Browse Source

QuRT: Changes to enable qurt target to build

QuRT doesn't support unlink and does not provide getpid().
The DSPAL layer provides access to usleep so an implementation is
no longer needed.

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
sbg
Mark Charlebois 10 years ago
parent
commit
cb231e89f6
  1. 4
      makefiles/qurt/toolchain_hexagon.mk
  2. 2
      src/modules/mavlink/mavlink_main.h
  3. 4
      src/modules/uORB/uORBDevices_posix.cpp
  4. 10
      src/platforms/px4_log.h
  5. 7
      src/platforms/px4_posix.h
  6. 1
      src/platforms/px4_time.h
  7. 7
      src/platforms/qurt/px4_layer/px4_qurt_impl.cpp
  8. 14
      src/platforms/qurt/px4_layer/px4_qurt_tasks.cpp
  9. 2
      src/systemcmds/param/param.c

4
makefiles/qurt/toolchain_hexagon.mk

@ -38,9 +38,7 @@ @@ -38,9 +38,7 @@
# Toolchain commands. Normally only used inside this file.
#
HEXAGON_TOOLS_ROOT = /opt/6.4.05
#HEXAGON_SDK_ROOT = /opt/Hexagon_SDK/2.0
HEXAGON_SDK_ROOT = /prj/atlanticus/users/rkintada/Hexagon_SDK/2.0
#V_ARCH = v4
HEXAGON_SDK_ROOT = /opt/Hexagon_SDK/2.0
V_ARCH = v5
CROSSDEV = hexagon-
HEXAGON_BIN = $(addsuffix /gnu/bin,$(HEXAGON_TOOLS_ROOT))

2
src/modules/mavlink/mavlink_main.h

@ -395,12 +395,14 @@ private: @@ -395,12 +395,14 @@ private:
float _rate_txerr;
float _rate_rx;
#ifdef __PX4_POSIX
int _socket_fd;
struct sockaddr_in _myaddr;
struct sockaddr_in _src_addr;
Protocol _protocol;
unsigned short _udp_port;
#endif
struct telemetry_status_s _rstatus; ///< receive status

4
src/modules/uORB/uORBDevices_posix.cpp

@ -91,7 +91,7 @@ uORB::DeviceNode::open(device::file_t *filp) @@ -91,7 +91,7 @@ uORB::DeviceNode::open(device::file_t *filp)
lock();
if (_publisher == 0) {
_publisher = getpid();
_publisher = px4_getpid();
ret = PX4_OK;
} else {
@ -153,7 +153,7 @@ uORB::DeviceNode::close(device::file_t *filp) @@ -153,7 +153,7 @@ uORB::DeviceNode::close(device::file_t *filp)
{
//warnx("uORB::DeviceNode::close fd = %d", filp->fd);
/* is this the publisher closing? */
if (getpid() == _publisher) {
if (px4_getpid() == _publisher) {
_publisher = 0;
} else {

10
src/platforms/px4_log.h

@ -52,7 +52,7 @@ @@ -52,7 +52,7 @@
}
#if defined(__PX4_QURT)
#include <stdio.h>
#include "HAP_farf.h"
#define FARF printf
#define __FARF_omit(level, ...) { }
#define __FARF_log(level, ...) { \
@ -66,10 +66,10 @@ @@ -66,10 +66,10 @@
FARF(" (file %s line %d)\n", __FILE__, __LINE__);\
}
#define PX4_DEBUG(...) __FARF_omit(HIGH, __VA_ARGS__)
#define PX4_INFO(...) __FARF_log(HIGH, __VA_ARGS__)
#define PX4_WARN(...) __FARF_log_verbose(HIGH, __VA_ARGS__)
#define PX4_ERR(...) __FARF_log_verbose(HIGH, __VA_ARGS__)
#define PX4_DEBUG(...) __FARF_omit("DEBUG", __VA_ARGS__)
#define PX4_INFO(...) __FARF_log("INFO", __VA_ARGS__)
#define PX4_WARN(...) __FARF_log_verbose("WARN", __VA_ARGS__)
#define PX4_ERR(...) __FARF_log_verbose("ERROR", __VA_ARGS__)
#elif defined(__PX4_LINUX)
#include <stdio.h>

7
src/platforms/px4_posix.h

@ -68,6 +68,7 @@ typedef struct pollfd px4_pollfd_struct_t; @@ -68,6 +68,7 @@ typedef struct pollfd px4_pollfd_struct_t;
#define px4_poll _GLOBAL poll
#define px4_fsync _GLOBAL fsync
#define px4_access _GLOBAL access
#define px4_getpid _GLOBAL getpid
#elif defined(__PX4_POSIX)
@ -98,6 +99,12 @@ __EXPORT int px4_ioctl(int fd, int cmd, unsigned long arg); @@ -98,6 +99,12 @@ __EXPORT int px4_ioctl(int fd, int cmd, unsigned long arg);
__EXPORT int px4_poll(px4_pollfd_struct_t *fds, nfds_t nfds, int timeout);
__EXPORT int px4_fsync(int fd);
__EXPORT int px4_access(const char *pathname, int mode);
#ifdef __PX4_QURT
typedef int pid_t;
__EXPORT int px4_getpid(void);
#else
#define px4_getpid getpid
#endif
__END_DECLS
#else

1
src/platforms/px4_time.h

@ -28,7 +28,6 @@ struct timespec @@ -28,7 +28,6 @@ struct timespec
int px4_clock_gettime(clockid_t clk_id, struct timespec *tp);
int px4_clock_settime(clockid_t clk_id, struct timespec *tp);
__EXPORT int usleep(useconds_t usec);
__EXPORT unsigned int sleep(unsigned int sec);
__END_DECLS

7
src/platforms/qurt/px4_layer/px4_qurt_impl.cpp

@ -48,7 +48,6 @@ @@ -48,7 +48,6 @@
#include <errno.h>
#include <unistd.h>
#include <semaphore.h>
#include <qurt.h>
#include "systemlib/param/param.h"
@ -57,14 +56,10 @@ __BEGIN_DECLS @@ -57,14 +56,10 @@ __BEGIN_DECLS
// FIXME - sysconf(_SC_CLK_TCK) not supported
long PX4_TICKS_PER_SEC = 1000;
void usleep(useconds_t usec) {
qurt_timer_sleep(usec);
}
unsigned int sleep(unsigned int sec)
{
for (unsigned int i=0; i< sec; i++)
qurt_timer_sleep(1000000);
usleep(1000000);
return 0;
}

14
src/platforms/qurt/px4_layer/px4_qurt_tasks.cpp

@ -245,6 +245,20 @@ int px4_task_kill(px4_task_t id, int sig) @@ -245,6 +245,20 @@ int px4_task_kill(px4_task_t id, int sig)
return rv;
}
pid_t px4_getpid()
{
pthread_t pid = pthread_self();
// Get pthread ID from the opaque ID
for (int i=0; i<PX4_MAX_TASKS; ++i) {
if (taskmap[i].pid == pid) {
return i;
}
}
PX4_ERR("px4_getpid() called from non-thread context!");
return -EINVAL;
}
void px4_show_tasks()
{
int idx;

2
src/systemcmds/param/param.c

@ -213,7 +213,9 @@ do_save(const char *param_file_name) @@ -213,7 +213,9 @@ do_save(const char *param_file_name)
close(fd);
if (result < 0) {
#ifndef __PX4_QURT
(void)unlink(param_file_name);
#endif
warnx("error exporting to '%s'", param_file_name);
return 1;
}

Loading…
Cancel
Save