QuRT and POSIX changes - part 4

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
Mark Charlebois
2015-04-24 01:24:31 -07:00
parent c802beb3d7
commit 187f13cd70
11 changed files with 65 additions and 35 deletions
@@ -43,6 +43,7 @@
#include <px4_config.h>
#include <px4_defines.h>
#include <px4_posix.h>
#include <unistd.h>
#include <stdlib.h>
#include <stdio.h>
@@ -50,8 +51,6 @@
#include <poll.h>
#include <fcntl.h>
#include <float.h>
#include <sys/prctl.h>
#include <termios.h>
#include <errno.h>
#include <limits.h>
#include <math.h>
@@ -299,12 +298,12 @@ int attitude_estimator_ekf_thread_main(int argc, char *argv[])
/* Main loop*/
while (!thread_should_exit) {
struct pollfd fds[2];
px4_pollfd_struct_t fds[2];
fds[0].fd = sub_raw;
fds[0].events = POLLIN;
fds[1].fd = sub_params;
fds[1].events = POLLIN;
int ret = poll(fds, 2, 1000);
int ret = px4_poll(fds, 2, 1000);
if (ret < 0) {
/* XXX this is seriously bad - should be an emergency */
@@ -39,6 +39,8 @@
*/
#include <px4_defines.h>
#include <px4_posix.h>
#include <px4_time.h>
#include <stdio.h>
#include <unistd.h>
#include <math.h>
@@ -246,7 +248,7 @@ enum detect_orientation_return detect_orientation(int mavlink_fd, int accel_sub)
float accel_err_thr = 5.0f;
/* still time required in us */
hrt_abstime still_time = 2000000;
struct pollfd fds[1];
px4_pollfd_struct_t fds[1];
fds[0].fd = accel_sub;
fds[0].events = POLLIN;
@@ -262,7 +264,7 @@ enum detect_orientation_return detect_orientation(int mavlink_fd, int accel_sub)
while (true) {
/* wait blocking for new data */
int poll_ret = poll(fds, 1, 1000);
int poll_ret = px4_poll(fds, 1, 1000);
if (poll_ret) {
orb_copy(ORB_ID(sensor_accel), accel_sub, &sensor);
+8 -2
View File
@@ -43,6 +43,8 @@
*/
#include <px4_config.h>
#include <px4_posix.h>
#include <px4_time.h>
#include <pthread.h>
#include <stdio.h>
#include <stdlib.h>
@@ -54,7 +56,9 @@
#include <systemlib/err.h>
#include <systemlib/circuit_breaker.h>
//#include <debug.h>
#ifndef __PX4_QURT
#include <sys/prctl.h>
#endif
#include <sys/stat.h>
#include <string.h>
#include <math.h>
@@ -2571,8 +2575,10 @@ void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT resul
void *commander_low_prio_loop(void *arg)
{
#ifndef __PX4_QURT
/* Set thread name */
prctl(PR_SET_NAME, "commander_low_prio", getpid());
#endif
/* Subscribe to command topic */
int cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
@@ -2583,7 +2589,7 @@ void *commander_low_prio_loop(void *arg)
hrt_abstime need_param_autosave_timeout = 0;
/* wakeup source(s) */
struct pollfd fds[1];
px4_pollfd_struct_t fds[1];
/* use the gyro to pace output - XXX BROKEN if we are using the L3GD20 */
fds[0].fd = cmd_sub;
@@ -2591,7 +2597,7 @@ void *commander_low_prio_loop(void *arg)
while (!thread_should_exit) {
/* wait for up to 1000ms for data */
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 1000);
int pret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 1000);
/* timed out - periodic check for thread_should_exit, etc. */
if (pret == 0) {
@@ -46,6 +46,8 @@
#include <px4_config.h>
#include <px4_defines.h>
#include <px4_tasks.h>
#include <px4_posix.h>
#include <px4_time.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
@@ -230,10 +232,10 @@ AttitudePositionEstimatorEKF::AttitudePositionEstimatorEKF() :
for (unsigned s = 0; s < 3; s++) {
char str[30];
(void)sprintf(str, "%s%u", GYRO_BASE_DEVICE_PATH, s);
fd = open(str, O_RDONLY);
fd = px4_open(str, O_RDONLY);
if (fd >= 0) {
res = ioctl(fd, GYROIOCGSCALE, (long unsigned int)&_gyro_offsets[s]);
res = px4_ioctl(fd, GYROIOCGSCALE, (long unsigned int)&_gyro_offsets[s]);
close(fd);
if (res) {
@@ -242,11 +244,11 @@ AttitudePositionEstimatorEKF::AttitudePositionEstimatorEKF() :
}
(void)sprintf(str, "%s%u", ACCEL_BASE_DEVICE_PATH, s);
fd = open(str, O_RDONLY);
fd = px4_open(str, O_RDONLY);
if (fd >= 0) {
res = ioctl(fd, ACCELIOCGSCALE, (long unsigned int)&_accel_offsets[s]);
close(fd);
res = px4_ioctl(fd, ACCELIOCGSCALE, (long unsigned int)&_accel_offsets[s]);
px4_close(fd);
if (res) {
warnx("A%u SCALE FAIL", s);
@@ -254,11 +256,11 @@ AttitudePositionEstimatorEKF::AttitudePositionEstimatorEKF() :
}
(void)sprintf(str, "%s%u", MAG_BASE_DEVICE_PATH, s);
fd = open(str, O_RDONLY);
fd = px4_open(str, O_RDONLY);
if (fd >= 0) {
res = ioctl(fd, MAGIOCGSCALE, (long unsigned int)&_mag_offsets[s]);
close(fd);
res = px4_ioctl(fd, MAGIOCGSCALE, (long unsigned int)&_mag_offsets[s]);
px4_close(fd);
if (res) {
warnx("M%u SCALE FAIL", s);
@@ -520,7 +522,7 @@ void AttitudePositionEstimatorEKF::task_main()
parameters_update();
/* wakeup source(s) */
struct pollfd fds[2];
px4_pollfd_struct_t fds[2];
/* Setup of loop */
fds[0].fd = _params_sub;
@@ -538,7 +540,7 @@ void AttitudePositionEstimatorEKF::task_main()
while (!_task_should_exit) {
/* wait for up to 100ms for data */
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
int pret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
/* timed out - periodic check for _task_should_exit, etc. */
if (pret == 0) {
+7 -4
View File
@@ -36,10 +36,8 @@
#
SRCS = err.c \
hx_stream.c \
perf_counter.c \
param/param.c \
bson/tinybson.c \
conversions.c \
cpuload.c \
getopt_long.c \
@@ -52,14 +50,19 @@ SRCS = err.c \
otp.c \
board_serial.c \
pwm_limit/pwm_limit.c \
circuit_breaker.cpp \
circuit_breaker_params.c \
mcu_version.c
ifeq ($(PX4_TARGET_OS),nuttx)
SRCS += up_cxxinitialize.c
endif
ifneq ($(PX4_TARGET_OS),qurt)
SRCS += hx_stream.c \
circuit_breaker.cpp \
circuit_breaker_params.c \
bson/tinybson.c
endif
MAXOPTIMIZATION = -Os
EXTRACFLAGS = -Wno-sign-compare
+1 -1
View File
@@ -71,7 +71,7 @@ int val_read(void *dest, volatile const void *src, int bytes)
int write_otp(uint8_t id_type, uint32_t vid, uint32_t pid, char *signature)
{
warnx("write_otp: PX4 / %02X / %02X / %02X / ... etc \n", id_type, vid, pid);
warnx("write_otp: PX4 / %02X / %02lX / %02lX / ... etc \n", id_type, (unsigned long)vid, (unsigned long)pid);
int errors = 0;
+5 -1
View File
@@ -45,6 +45,10 @@
#include <math.h>
#include "perf_counter.h"
#ifdef __PX4_QURT
#define dprintf(...)
#endif
/**
* Header common to all counters.
*/
@@ -470,7 +474,7 @@ perf_print_latency(int fd)
{
dprintf(fd, "bucket : events\n");
for (int i = 0; i < latency_bucket_count; i++) {
printf(" %4i : %i\n", latency_buckets[i], latency_counters[i]);
printf(" %4i : %li\n", latency_buckets[i], (long int)latency_counters[i]);
}
// print the overflow bucket value
dprintf(fd, " >%4i : %i\n", latency_buckets[latency_bucket_count-1], latency_counters[latency_bucket_count]);
+1 -1
View File
@@ -40,7 +40,7 @@
#define _SYSTEMLIB_PERF_COUNTER_H value
#include <stdint.h>
#include <platforms/px4_defines.h>
#include <px4_defines.h>
/**
* Counter types.
+1
View File
@@ -38,6 +38,7 @@
*/
#include <px4_config.h>
#include <px4_time.h>
#include <stdio.h>
#include <unistd.h>
+1 -2
View File
@@ -51,7 +51,7 @@ public:
};
StateTable(Tran const *table, unsigned nStates, unsigned nSignals)
: myTable(table), myNsignals(nSignals), myNstates(nStates) {}
: myTable(table), myNsignals(nSignals) {}
#define NO_ACTION &StateTable::doNothing
#define ACTION(_target) StateTable::Action(_target)
@@ -76,7 +76,6 @@ protected:
private:
Tran const *myTable;
unsigned myNsignals;
unsigned myNstates;
};
#endif
+22 -8
View File
@@ -42,6 +42,7 @@
#include <px4_defines.h>
#include <stdint.h>
#include <sys/types.h>
#include <unistd.h>
#include <poll.h>
#include <semaphore.h>
@@ -52,13 +53,18 @@
#define PX4_DEBUG(...)
//#define PX4_DEBUG(...) printf(__VA_ARGS__)
__BEGIN_DECLS
#ifdef __PX4_NUTTX
extern int px4_errno;
#define px4_pollfd_struct_t struct pollfd
#define px4_open open
#define px4_close close
#define px4_ioctl ioctl
#define px4_write write
#define px4_read read
#define px4_poll poll
#ifndef __PX4_NUTTX
#else
typedef short pollevent_t;
#endif
typedef struct {
/* This part of the struct is POSIX-like */
@@ -71,15 +77,23 @@ typedef struct {
void *priv; /* For use by drivers */
} px4_pollfd_struct_t;
__BEGIN_DECLS
__EXPORT int px4_open(const char *path, int flags);
__EXPORT int px4_close(int fd);
__EXPORT ssize_t px4_read(int fd, void *buffer, size_t buflen);
__EXPORT ssize_t px4_write(int fd, const void *buffer, size_t buflen);
__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 void px4_show_devices(void);
__EXPORT void px4_show_topics(void);
__EXPORT const char * px4_get_device_names(unsigned int *handle);
__EXPORT const char * px4_get_topic_names(unsigned int *handle);
__END_DECLS
#endif
__BEGIN_DECLS
extern int px4_errno;
__EXPORT void px4_show_devices(void);
__EXPORT const char * px4_get_device_names(unsigned int *handle);
__EXPORT void px4_show_topics(void);
__EXPORT const char * px4_get_topic_names(unsigned int *handle);
__END_DECLS