QuRT and POSIX changes

Partial commit of the changes for QuRT and related changes for POSIX

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
Mark Charlebois
2015-04-24 00:52:44 -07:00
parent a4c33f5173
commit 3336fce1f4
25 changed files with 919 additions and 2435 deletions
+1 -2
View File
@@ -35,6 +35,5 @@
# #
MODULES += \ MODULES += \
platforms/common \ platforms/common
platforms/qurt/px4_layer
+25 -25
View File
@@ -10,17 +10,17 @@
# #
# Board support modules # Board support modules
# #
#MODULES += drivers/device MODULES += drivers/device
#MODULES += drivers/blinkm MODULES += drivers/blinkm
#MODULES += drivers/hil MODULES += drivers/hil
#MODULES += drivers/rgbled MODULES += drivers/rgbled
#MODULES += modules/sensors MODULES += modules/sensors
#MODULES += drivers/ms5611 #MODULES += drivers/ms5611
# #
# System commands # System commands
# #
#MODULES += systemcmds/param MODULES += systemcmds/param
# #
# General system control # General system control
@@ -30,8 +30,8 @@
# #
# Estimation modules (EKF/ SO3 / other filters) # Estimation modules (EKF/ SO3 / other filters)
# #
#MODULES += modules/attitude_estimator_ekf MODULES += modules/attitude_estimator_ekf
#MODULES += modules/ekf_att_pos_estimator MODULES += modules/ekf_att_pos_estimator
# #
# Vehicle Control # Vehicle Control
@@ -41,37 +41,37 @@
# #
# Library modules # Library modules
# #
#MODULES += modules/systemlib MODULES += modules/systemlib
#MODULES += modules/systemlib/mixer MODULES += modules/systemlib/mixer
#MODULES += modules/uORB MODULES += modules/uORB
#MODULES += modules/dataman #MODULES += modules/dataman
#MODULES += modules/sdlog2 #MODULES += modules/sdlog2
#MODULES += modules/simulator MODULES += modules/simulator
#MODULES += modules/commander MODULES += modules/commander
# #
# Libraries # Libraries
# #
#MODULES += lib/mathlib MODULES += lib/mathlib
#MODULES += lib/mathlib/math/filter MODULES += lib/mathlib/math/filter
#MODULES += lib/geo MODULES += lib/geo
#MODULES += lib/geo_lookup MODULES += lib/geo_lookup
#MODULES += lib/conversion MODULES += lib/conversion
# #
# QuRT port # QuRT port
# #
MODULES += platforms/qurt/px4_layer MODULES += platforms/qurt/px4_layer
#MODULES += platforms/linux/drivers/accelsim MODULES += platforms/posix/drivers/accelsim
#MODULES += platforms/linux/drivers/gyrosim MODULES += platforms/posix/drivers/gyrosim
#MODULES += platforms/linux/drivers/adcsim MODULES += platforms/posix/drivers/adcsim
#MODULES += platforms/linux/drivers/barosim MODULES += platforms/posix/drivers/barosim
# #
# Unit tests # Unit tests
# #
MODULES += platforms/qurt/tests/hello MODULES += platforms/qurt/tests/hello
#MODULES += platforms/linux/tests/vcdev_test #MODULES += platforms/posix/tests/vcdev_test
#MODULES += platforms/linux/tests/hrt_test #MODULES += platforms/posix/tests/hrt_test
#MODULES += platforms/linux/tests/wqueue #MODULES += platforms/posix/tests/wqueue
+6 -2
View File
@@ -68,7 +68,7 @@ endif
# XXX this is pulled pretty directly from the fmu Make.defs - needs cleanup # XXX this is pulled pretty directly from the fmu Make.defs - needs cleanup
MAXOPTIMIZATION ?= -O2 MAXOPTIMIZATION ?= -Os
# Base CPU flags for each of the supported architectures. # Base CPU flags for each of the supported architectures.
# #
@@ -81,10 +81,11 @@ ifeq ($(CONFIG_BOARD),)
$(error Board config does not define CONFIG_BOARD) $(error Board config does not define CONFIG_BOARD)
endif endif
ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) \ ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) \
-D__PX4_QURT \ -D__PX4_QURT -D__PX4_POSIX \
-D__EXPORT= \ -D__EXPORT= \
-Dnoreturn_function= \ -Dnoreturn_function= \
-Drestrict= \ -Drestrict= \
-I/opt/6.4.05/gnu/hexagon/include \
-I$(PX4_BASE)/src/lib/eigen \ -I$(PX4_BASE)/src/lib/eigen \
-I$(PX4_BASE)/src/platforms/qurt/include \ -I$(PX4_BASE)/src/platforms/qurt/include \
-I$(PX4_BASE)/../dspal/include \ -I$(PX4_BASE)/../dspal/include \
@@ -116,7 +117,9 @@ ARCHWARNINGS = -Wall \
-Wextra \ -Wextra \
-Werror \ -Werror \
-Wno-unused-parameter \ -Wno-unused-parameter \
-Wno-unused-function \
-Wno-unused-variable \ -Wno-unused-variable \
-Wno-gnu-array-member-paren-init \
-Wno-cast-align \ -Wno-cast-align \
-Wno-missing-braces \ -Wno-missing-braces \
-Wno-strict-aliasing -Wno-strict-aliasing
@@ -206,6 +209,7 @@ DEP_INCLUDES = $(subst .o,.d,$(OBJS))
define COMPILE define COMPILE
@$(ECHO) "CC: $1" @$(ECHO) "CC: $1"
@$(MKDIR) -p $(dir $2) @$(MKDIR) -p $(dir $2)
@echo $(Q) $(CCACHE) $(CC) -MD -c $(CFLAGS) $(abspath $1) -o $2
$(Q) $(CCACHE) $(CC) -MD -c $(CFLAGS) $(abspath $1) -o $2 $(Q) $(CCACHE) $(CC) -MD -c $(CFLAGS) $(abspath $1) -o $2
endef endef
+2 -1
View File
@@ -37,7 +37,8 @@
* POSIX-like API for virtual character device * POSIX-like API for virtual character device
*/ */
#include "px4_posix.h" #include <px4_posix.h>
#include <px4_time.h>
#include "device.h" #include "device.h"
#include <stdlib.h> #include <stdlib.h>
+5 -2
View File
@@ -50,6 +50,8 @@
#include <px4_config.h> #include <px4_config.h>
#include <px4_tasks.h> #include <px4_tasks.h>
#include <px4_time.h>
#include <px4_common.h>
#include <sys/types.h> #include <sys/types.h>
#include <stdint.h> #include <stdint.h>
@@ -61,7 +63,8 @@
#include <poll.h> #include <poll.h>
#include <errno.h> #include <errno.h>
#include <stdio.h> #include <stdio.h>
#include <math.h> #include <string.h>
#include <cmath>
#include <unistd.h> #include <unistd.h>
#include <drivers/device/device.h> #include <drivers/device/device.h>
@@ -409,7 +412,7 @@ HIL::task_main()
/* last resort: catch NaN, INF and out-of-band errors */ /* last resort: catch NaN, INF and out-of-band errors */
if (i < outputs.noutputs && if (i < outputs.noutputs &&
isfinite(outputs.output[i]) && PX4_ISFINITE(outputs.output[i]) &&
outputs.output[i] >= -1.0f && outputs.output[i] >= -1.0f &&
outputs.output[i] <= 1.0f) { outputs.output[i] <= 1.0f) {
/* scale for PWM output 900 - 2100us */ /* scale for PWM output 900 - 2100us */
@@ -49,6 +49,7 @@
#include <px4_config.h> #include <px4_config.h>
#include <px4_tasks.h> #include <px4_tasks.h>
#include <px4_posix.h> #include <px4_posix.h>
#include <px4_time.h>
#include <fcntl.h> #include <fcntl.h>
#include <poll.h> #include <poll.h>
@@ -62,6 +63,7 @@
#include <mathlib/mathlib.h> #include <mathlib/mathlib.h>
#include <px4_adc.h> #include <px4_adc.h>
//#include <nuttx/analog/adc.h>
#include <drivers/drv_hrt.h> #include <drivers/drv_hrt.h>
#include <drivers/drv_accel.h> #include <drivers/drv_accel.h>
@@ -113,7 +115,7 @@
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
#define ADC_BATTERY_VOLTAGE_CHANNEL 10 #define ADC_BATTERY_VOLTAGE_CHANNEL 10
#define ADC_BATTERY_CURRENT_CHANNEL -1 #define ADC_BATTERY_CURRENT_CHANNEL ((uint8_t)(-1))
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 11 #define ADC_AIRSPEED_VOLTAGE_CHANNEL 11
#endif #endif
@@ -126,8 +128,8 @@
#ifdef CONFIG_ARCH_BOARD_AEROCORE #ifdef CONFIG_ARCH_BOARD_AEROCORE
#define ADC_BATTERY_VOLTAGE_CHANNEL 10 #define ADC_BATTERY_VOLTAGE_CHANNEL 10
#define ADC_BATTERY_CURRENT_CHANNEL -1 #define ADC_BATTERY_CURRENT_CHANNEL ((uint8_t)(-1))
#define ADC_AIRSPEED_VOLTAGE_CHANNEL -1 #define ADC_AIRSPEED_VOLTAGE_CHANNEL ((uint8_t)(-1))
#endif #endif
#define BATT_V_LOWPASS 0.001f #define BATT_V_LOWPASS 0.001f
@@ -147,7 +149,7 @@
#endif #endif
static const int ERROR = -1; static const int ERROR = -1;
#define CAL_FAILED_APPLY_CAL_MSG "FAILED APPLYING SENSOR CAL" #define CAL_FAILED_APPLY_CAL_MSG "FAILED APPLYING %s CAL #%u"
/** /**
* Sensor app start / stop handling function * Sensor app start / stop handling function
@@ -225,7 +227,7 @@ private:
int _rc_sub; /**< raw rc channels data subscription */ int _rc_sub; /**< raw rc channels data subscription */
int _baro_sub; /**< raw baro data subscription */ int _baro_sub; /**< raw baro data subscription */
int _baro1_sub; /**< raw baro data subscription */ int _baro1_sub; /**< raw baro data subscription */
int _airspeed_sub; /**< airspeed subscription */ //int _airspeed_sub; /**< airspeed subscription */
int _diff_pres_sub; /**< raw differential pressure subscription */ int _diff_pres_sub; /**< raw differential pressure subscription */
int _vcontrol_mode_sub; /**< vehicle control mode subscription */ int _vcontrol_mode_sub; /**< vehicle control mode subscription */
int _params_sub; /**< notification of parameter updates */ int _params_sub; /**< notification of parameter updates */
@@ -671,11 +673,7 @@ Sensors::parameters_update()
tmpRevFactor = tmpScaleFactor * _parameters.rev[i]; tmpRevFactor = tmpScaleFactor * _parameters.rev[i];
/* handle blowup in the scaling factor calculation */ /* handle blowup in the scaling factor calculation */
#ifdef __PX4_NUTTX if (!PX4_ISFINITE(tmpScaleFactor) ||
if (!isfinite(tmpScaleFactor) ||
#else
if (!std::isfinite(tmpScaleFactor) ||
#endif
(tmpRevFactor < 0.000001f) || (tmpRevFactor < 0.000001f) ||
(tmpRevFactor > 0.2f)) { (tmpRevFactor > 0.2f)) {
warnx("RC chan %u not sane, scaling: %8.6f, rev: %d", i, (double)tmpScaleFactor, (int)(_parameters.rev[i])); warnx("RC chan %u not sane, scaling: %8.6f, rev: %d", i, (double)tmpScaleFactor, (int)(_parameters.rev[i]));
@@ -855,7 +853,7 @@ Sensors::parameters_update()
barofd = px4_open(BARO0_DEVICE_PATH, 0); barofd = px4_open(BARO0_DEVICE_PATH, 0);
if (barofd < 0) { if (barofd < 0) {
warnx("ERROR: no barometer found on %s", BARO0_DEVICE_PATH); warnx("ERROR: no barometer foundon %s", BARO0_DEVICE_PATH);
return ERROR; return ERROR;
} else { } else {
@@ -1021,6 +1019,7 @@ Sensors::accel_poll(struct sensor_combined_s &raw)
raw.accelerometer_timestamp = accel_report.timestamp; raw.accelerometer_timestamp = accel_report.timestamp;
raw.accelerometer_errcount = accel_report.error_count; raw.accelerometer_errcount = accel_report.error_count;
raw.accelerometer_temp = accel_report.temperature;
} }
orb_check(_accel1_sub, &accel_updated); orb_check(_accel1_sub, &accel_updated);
@@ -1043,6 +1042,7 @@ Sensors::accel_poll(struct sensor_combined_s &raw)
raw.accelerometer1_timestamp = accel_report.timestamp; raw.accelerometer1_timestamp = accel_report.timestamp;
raw.accelerometer1_errcount = accel_report.error_count; raw.accelerometer1_errcount = accel_report.error_count;
raw.accelerometer1_temp = accel_report.temperature;
} }
orb_check(_accel2_sub, &accel_updated); orb_check(_accel2_sub, &accel_updated);
@@ -1065,6 +1065,7 @@ Sensors::accel_poll(struct sensor_combined_s &raw)
raw.accelerometer2_timestamp = accel_report.timestamp; raw.accelerometer2_timestamp = accel_report.timestamp;
raw.accelerometer2_errcount = accel_report.error_count; raw.accelerometer2_errcount = accel_report.error_count;
raw.accelerometer2_temp = accel_report.temperature;
} }
} }
@@ -1092,6 +1093,7 @@ Sensors::gyro_poll(struct sensor_combined_s &raw)
raw.timestamp = gyro_report.timestamp; raw.timestamp = gyro_report.timestamp;
raw.gyro_errcount = gyro_report.error_count; raw.gyro_errcount = gyro_report.error_count;
raw.gyro_temp = gyro_report.temperature;
} }
orb_check(_gyro1_sub, &gyro_updated); orb_check(_gyro1_sub, &gyro_updated);
@@ -1114,6 +1116,7 @@ Sensors::gyro_poll(struct sensor_combined_s &raw)
raw.gyro1_timestamp = gyro_report.timestamp; raw.gyro1_timestamp = gyro_report.timestamp;
raw.gyro1_errcount = gyro_report.error_count; raw.gyro1_errcount = gyro_report.error_count;
raw.gyro1_temp = gyro_report.temperature;
} }
orb_check(_gyro2_sub, &gyro_updated); orb_check(_gyro2_sub, &gyro_updated);
@@ -1136,6 +1139,7 @@ Sensors::gyro_poll(struct sensor_combined_s &raw)
raw.gyro2_timestamp = gyro_report.timestamp; raw.gyro2_timestamp = gyro_report.timestamp;
raw.gyro2_errcount = gyro_report.error_count; raw.gyro2_errcount = gyro_report.error_count;
raw.gyro2_temp = gyro_report.temperature;
} }
} }
@@ -1164,6 +1168,7 @@ Sensors::mag_poll(struct sensor_combined_s &raw)
raw.magnetometer_timestamp = mag_report.timestamp; raw.magnetometer_timestamp = mag_report.timestamp;
raw.magnetometer_errcount = mag_report.error_count; raw.magnetometer_errcount = mag_report.error_count;
raw.magnetometer_temp = mag_report.temperature;
} }
orb_check(_mag1_sub, &mag_updated); orb_check(_mag1_sub, &mag_updated);
@@ -1187,6 +1192,7 @@ Sensors::mag_poll(struct sensor_combined_s &raw)
raw.magnetometer1_timestamp = mag_report.timestamp; raw.magnetometer1_timestamp = mag_report.timestamp;
raw.magnetometer1_errcount = mag_report.error_count; raw.magnetometer1_errcount = mag_report.error_count;
raw.magnetometer1_temp = mag_report.temperature;
} }
orb_check(_mag2_sub, &mag_updated); orb_check(_mag2_sub, &mag_updated);
@@ -1210,6 +1216,7 @@ Sensors::mag_poll(struct sensor_combined_s &raw)
raw.magnetometer2_timestamp = mag_report.timestamp; raw.magnetometer2_timestamp = mag_report.timestamp;
raw.magnetometer2_errcount = mag_report.error_count; raw.magnetometer2_errcount = mag_report.error_count;
raw.magnetometer2_temp = mag_report.temperature;
} }
} }
@@ -1379,14 +1386,13 @@ Sensors::parameter_update_poll(bool forced)
failed = failed || (OK != param_get(param_find(str), &gscale.z_scale)); failed = failed || (OK != param_get(param_find(str), &gscale.z_scale));
if (failed) { if (failed) {
warnx("%s: gyro #%u", CAL_FAILED_APPLY_CAL_MSG, gyro_count); warnx(CAL_FAILED_APPLY_CAL_MSG, "gyro", i);
} else { } else {
/* apply new scaling and offsets */ /* apply new scaling and offsets */
res = px4_ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale); res = px4_ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale);
if (res) { if (res) {
warnx(CAL_FAILED_APPLY_CAL_MSG); warnx(CAL_FAILED_APPLY_CAL_MSG, "gyro", i);
} else { } else {
gyro_count++;
config_ok = true; config_ok = true;
} }
} }
@@ -1394,11 +1400,11 @@ Sensors::parameter_update_poll(bool forced)
} }
} }
px4_close(fd); if (config_ok) {
gyro_count++;
if (!config_ok) {
warnx("NO CONFIG FOR GYRO #%u", s);
} }
px4_close(fd);
} }
/* run through all accel sensors */ /* run through all accel sensors */
@@ -1446,14 +1452,13 @@ Sensors::parameter_update_poll(bool forced)
failed = failed || (OK != param_get(param_find(str), &gscale.z_scale)); failed = failed || (OK != param_get(param_find(str), &gscale.z_scale));
if (failed) { if (failed) {
warnx("%s: acc #%u", CAL_FAILED_APPLY_CAL_MSG, accel_count); warnx(CAL_FAILED_APPLY_CAL_MSG, "accel", i);
} else { } else {
/* apply new scaling and offsets */ /* apply new scaling and offsets */
res = px4_ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&gscale); res = px4_ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&gscale);
if (res) { if (res) {
warnx(CAL_FAILED_APPLY_CAL_MSG); warnx(CAL_FAILED_APPLY_CAL_MSG, "accel", i);
} else { } else {
accel_count++;
config_ok = true; config_ok = true;
} }
} }
@@ -1461,11 +1466,11 @@ Sensors::parameter_update_poll(bool forced)
} }
} }
px4_close(fd); if (config_ok) {
accel_count++;
if (!config_ok) {
warnx("NO CONFIG FOR ACCEL #%u", s);
} }
px4_close(fd);
} }
/* run through all mag sensors */ /* run through all mag sensors */
@@ -1477,9 +1482,16 @@ Sensors::parameter_update_poll(bool forced)
int fd = px4_open(str, 0); int fd = px4_open(str, 0);
if (fd < 0) { if (fd < 0) {
/* the driver is not running, abort */
continue; continue;
} }
/* set a valid default rotation (same as board).
* if the mag is configured, this might be replaced
* in the section below.
*/
_mag_rotation[s] = _board_rotation;
bool config_ok = false; bool config_ok = false;
/* run through all stored calibrations */ /* run through all stored calibrations */
@@ -1563,14 +1575,13 @@ Sensors::parameter_update_poll(bool forced)
} }
if (failed) { if (failed) {
warnx("%s: mag #%u", CAL_FAILED_APPLY_CAL_MSG, mag_count); warnx(CAL_FAILED_APPLY_CAL_MSG, "mag", i);
} else { } else {
/* apply new scaling and offsets */ /* apply new scaling and offsets */
res = px4_ioctl(fd, MAGIOCSSCALE, (long unsigned int)&gscale); res = px4_ioctl(fd, MAGIOCSSCALE, (long unsigned int)&gscale);
if (res) { if (res) {
warnx(CAL_FAILED_APPLY_CAL_MSG); warnx(CAL_FAILED_APPLY_CAL_MSG, "mag", i);
} else { } else {
mag_count++;
config_ok = true; config_ok = true;
} }
} }
@@ -1578,11 +1589,11 @@ Sensors::parameter_update_poll(bool forced)
} }
} }
px4_close(fd); if (config_ok) {
mag_count++;
if (!config_ok) {
warnx("NO CONFIG FOR MAG #%u", s);
} }
px4_close(fd);
} }
int fd = px4_open(AIRSPEED0_DEVICE_PATH, 0); int fd = px4_open(AIRSPEED0_DEVICE_PATH, 0);
@@ -1602,7 +1613,7 @@ Sensors::parameter_update_poll(bool forced)
px4_close(fd); px4_close(fd);
} }
warnx("config: %u gyros, %u mags, %u accels", gyro_count, mag_count, accel_count); warnx("valid configs: %u gyros, %u mags, %u accels", gyro_count, mag_count, accel_count);
} }
} }
@@ -1947,11 +1958,7 @@ Sensors::rc_poll()
_rc.channels[i] *= _parameters.rev[i]; _rc.channels[i] *= _parameters.rev[i];
/* handle any parameter-induced blowups */ /* handle any parameter-induced blowups */
#ifdef __PX4_NUTTX if (!PX4_ISFINITE(_rc.channels[i])) {
if (!isfinite(_rc.channels[i])) {
#else
if (!std::isfinite(_rc.channels[i])) {
#endif
_rc.channels[i] = 0.0f; _rc.channels[i] = 0.0f;
} }
} }
@@ -2152,12 +2159,8 @@ Sensors::task_main()
/* advertise the sensor_combined topic and make the initial publication */ /* advertise the sensor_combined topic and make the initial publication */
_sensor_pub = orb_advertise(ORB_ID(sensor_combined), &raw); _sensor_pub = orb_advertise(ORB_ID(sensor_combined), &raw);
if (_sensor_pub < 0) {
warnx("Sensors::task_main ERROR - uORB not started");
}
/* wakeup source(s) */ /* 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 */ /* use the gyro to pace output - XXX BROKEN if we are using the L3GD20 */
fds[0].fd = _gyro_sub; fds[0].fd = _gyro_sub;
@@ -2168,7 +2171,7 @@ Sensors::task_main()
while (!_task_should_exit) { while (!_task_should_exit) {
/* wait for up to 50ms for data */ /* wait for up to 50ms for data */
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 50); int pret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 50);
/* if pret == 0 it timed out - periodic check for _task_should_exit, etc. */ /* if pret == 0 it timed out - periodic check for _task_should_exit, etc. */
File diff suppressed because it is too large Load Diff
+9 -2
View File
@@ -37,13 +37,15 @@
*/ */
#include <px4_tasks.h> #include <px4_tasks.h>
#include <err.h> #include <systemlib/err.h>
#include <errno.h> #include <errno.h>
#include <stdio.h> #include <stdio.h>
#include <string.h> #include <string.h>
#include <sys/types.h> #include <sys/types.h>
#ifndef __PX4_QURT
#include <sys/socket.h> #include <sys/socket.h>
#include <netinet/in.h> #include <netinet/in.h>
#endif
#include "simulator.h" #include "simulator.h"
using namespace simulator; using namespace simulator;
@@ -76,8 +78,11 @@ int Simulator::start(int argc, char *argv[])
{ {
int ret = 0; int ret = 0;
_instance = new Simulator(); _instance = new Simulator();
if (_instance) if (_instance) {
#ifndef __PX4_QURT
_instance->updateSamples(); _instance->updateSamples();
#endif
}
else { else {
printf("Simulator creation failed\n"); printf("Simulator creation failed\n");
ret = 1; ret = 1;
@@ -86,6 +91,7 @@ int Simulator::start(int argc, char *argv[])
} }
#ifndef __PX4_QURT
void Simulator::updateSamples() void Simulator::updateSamples()
{ {
// get samples from external provider // get samples from external provider
@@ -133,6 +139,7 @@ void Simulator::updateSamples()
} }
} }
} }
#endif
static void usage() static void usage()
{ {
+2
View File
@@ -148,7 +148,9 @@ private:
Simulator() : _accel(1), _mpu(1), _baro(1) {} Simulator() : _accel(1), _mpu(1), _baro(1) {}
~Simulator() { _instance=NULL; } ~Simulator() { _instance=NULL; }
#ifndef __PX4_QURT
void updateSamples(); void updateSamples();
#endif
static Simulator *_instance; static Simulator *_instance;
+1
View File
@@ -37,6 +37,7 @@
*/ */
#include <px4_config.h> #include <px4_config.h>
#include <px4_time.h>
#include <drivers/device/device.h> #include <drivers/device/device.h>
@@ -41,6 +41,7 @@
*/ */
#include <px4_config.h> #include <px4_config.h>
#include <px4_time.h>
#include <px4_adc.h> #include <px4_adc.h>
#include <board_config.h> #include <board_config.h>
#include <drivers/device/device.h> #include <drivers/device/device.h>
@@ -89,8 +90,6 @@ private:
unsigned _channel_count; unsigned _channel_count;
adc_msg_s *_samples; /**< sample buffer */ adc_msg_s *_samples; /**< sample buffer */
orb_advert_t _to_system_power;
/** work trampoline */ /** work trampoline */
static void _tick_trampoline(void *arg); static void _tick_trampoline(void *arg);
@@ -114,8 +113,7 @@ ADCSIM::ADCSIM(uint32_t channels) :
VDev("adcsim", ADCSIM0_DEVICE_PATH), VDev("adcsim", ADCSIM0_DEVICE_PATH),
_sample_perf(perf_alloc(PC_ELAPSED, "adc_samples")), _sample_perf(perf_alloc(PC_ELAPSED, "adc_samples")),
_channel_count(0), _channel_count(0),
_samples(nullptr), _samples(nullptr)
_to_system_power(0)
{ {
//_debug_enabled = true; //_debug_enabled = true;
@@ -259,7 +257,7 @@ test(void)
unsigned channels = count / sizeof(data[0]); unsigned channels = count / sizeof(data[0]);
for (unsigned j = 0; j < channels; j++) { for (unsigned j = 0; j < channels; j++) {
printf ("%d: %u ", data[j].am_channel, data[j].am_data); printf ("%d: %lu ", data[j].am_channel, (unsigned long)data[j].am_data);
} }
printf("\n"); printf("\n");
@@ -0,0 +1,407 @@
/****************************************************************************
*
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file ets_airspeed.cpp
* @author Simon Wilks
*
* Driver for the Eagle Tree Airspeed V3 connected via I2C.
*/
#include <px4_config.h>
#include <drivers/device/i2c.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdlib.h>
#include <stdbool.h>
#include <semaphore.h>
#include <string.h>
#include <fcntl.h>
#include <poll.h>
#include <errno.h>
#include <stdio.h>
#include <math.h>
#include <unistd.h>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
#include <arch/board/board.h>
#include <systemlib/airspeed.h>
#include <systemlib/err.h>
#include <systemlib/param/param.h>
#include <systemlib/perf_counter.h>
#include <drivers/drv_airspeed.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/ringbuffer.h>
#include <uORB/uORB.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/subsystem_info.h>
#include <drivers/airspeed/airspeed.h>
AirspeedSim::AirspeedSim(int bus, int address, unsigned conversion_interval, const char* path) :
I2C("Airspeed", path, bus, address),
_reports(nullptr),
_buffer_overflows(perf_alloc(PC_COUNT, "airspeed_buffer_overflows")),
_max_differential_pressure_pa(0),
_sensor_ok(false),
_last_published_sensor_ok(true), /* initialize differently to force publication */
_measure_ticks(0),
_collect_phase(false),
_diff_pres_offset(0.0f),
_airspeed_pub(-1),
_subsys_pub(-1),
_class_instance(-1),
_conversion_interval(conversion_interval),
_sample_perf(perf_alloc(PC_ELAPSED, "airspeed_read")),
_comms_errors(perf_alloc(PC_COUNT, "airspeed_comms_errors"))
{
// enable debug() calls
_debug_enabled = false;
// work_cancel in the dtor will explode if we don't do this...
memset(&_work, 0, sizeof(_work));
}
AirspeedSim::~AirspeedSim()
{
/* make sure we are truly inactive */
stop();
if (_class_instance != -1)
unregister_class_devname(AIRSPEED_BASE_DEVICE_PATH, _class_instance);
/* free any existing reports */
if (_reports != nullptr)
delete _reports;
// free perf counters
perf_free(_sample_perf);
perf_free(_comms_errors);
perf_free(_buffer_overflows);
}
int
AirspeedSim::init()
{
int ret = ERROR;
/* do I2C init (and probe) first */
if (I2C::init() != OK)
goto out;
/* allocate basic report buffers */
_reports = new RingBuffer(2, sizeof(differential_pressure_s));
if (_reports == nullptr)
goto out;
/* register alternate interfaces if we have to */
_class_instance = register_class_devname(AIRSPEED_BASE_DEVICE_PATH);
/* publication init */
if (_class_instance == CLASS_DEVICE_PRIMARY) {
/* advertise sensor topic, measure manually to initialize valid report */
struct differential_pressure_s arp;
measure();
_reports->get(&arp);
/* measurement will have generated a report, publish */
_airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &arp);
if (_airspeed_pub < 0)
warnx("uORB started?");
}
ret = OK;
out:
return ret;
}
int
AirspeedSim::probe()
{
/* on initial power up the device may need more than one retry
for detection. Once it is running the number of retries can
be reduced
*/
_retries = 4;
int ret = measure();
// drop back to 2 retries once initialised
_retries = 2;
return ret;
}
int
AirspeedSim::ioctl(px4_dev_handle_t *handlep, int cmd, unsigned long arg)
{
switch (cmd) {
case SENSORIOCSPOLLRATE: {
switch (arg) {
/* switching to manual polling */
case SENSOR_POLLRATE_MANUAL:
stop();
_measure_ticks = 0;
return OK;
/* external signalling (DRDY) not supported */
case SENSOR_POLLRATE_EXTERNAL:
/* zero would be bad */
case 0:
return -EINVAL;
/* set default/max polling rate */
case SENSOR_POLLRATE_MAX:
case SENSOR_POLLRATE_DEFAULT: {
/* do we need to start internal polling? */
bool want_start = (_measure_ticks == 0);
/* set interval for next measurement to minimum legal value */
_measure_ticks = USEC2TICK(_conversion_interval);
/* if we need to start the poll state machine, do it */
if (want_start)
start();
return OK;
}
/* adjust to a legal polling interval in Hz */
default: {
/* do we need to start internal polling? */
bool want_start = (_measure_ticks == 0);
/* convert hz to tick interval via microseconds */
unsigned ticks = USEC2TICK(1000000 / arg);
/* check against maximum rate */
if (ticks < USEC2TICK(_conversion_interval))
return -EINVAL;
/* update interval for next measurement */
_measure_ticks = ticks;
/* if we need to start the poll state machine, do it */
if (want_start)
start();
return OK;
}
}
}
case SENSORIOCGPOLLRATE:
if (_measure_ticks == 0)
return SENSOR_POLLRATE_MANUAL;
return (1000 / _measure_ticks);
case SENSORIOCSQUEUEDEPTH: {
/* lower bound is mandatory, upper bound is a sanity check */
if ((arg < 1) || (arg > 100))
return -EINVAL;
irqstate_t flags = irqsave();
if (!_reports->resize(arg)) {
irqrestore(flags);
return -ENOMEM;
}
irqrestore(flags);
return OK;
}
case SENSORIOCGQUEUEDEPTH:
return _reports->size();
case SENSORIOCRESET:
/* XXX implement this */
return -EINVAL;
case AIRSPEEDIOCSSCALE: {
struct airspeed_scale *s = (struct airspeed_scale*)arg;
_diff_pres_offset = s->offset_pa;
return OK;
}
case AIRSPEEDIOCGSCALE: {
struct airspeed_scale *s = (struct airspeed_scale*)arg;
s->offset_pa = _diff_pres_offset;
s->scale = 1.0f;
return OK;
}
default:
/* give it to the superclass */
return I2C::ioctl(handlep, cmd, arg);
}
}
ssize_t
AirspeedSim::read(px4_dev_handle_t *handlep, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(differential_pressure_s);
differential_pressure_s *abuf = reinterpret_cast<differential_pressure_s *>(buffer);
int ret = 0;
/* buffer must be large enough */
if (count < 1)
return -ENOSPC;
/* if automatic measurement is enabled */
if (_measure_ticks > 0) {
/*
* While there is space in the caller's buffer, and reports, copy them.
* Note that we may be pre-empted by the workq thread while we are doing this;
* we are careful to avoid racing with them.
*/
while (count--) {
if (_reports->get(abuf)) {
ret += sizeof(*abuf);
abuf++;
}
}
/* if there was no data, warn the caller */
return ret ? ret : -EAGAIN;
}
/* manual measurement - run one conversion */
do {
_reports->flush();
/* trigger a measurement */
if (OK != measure()) {
ret = -EIO;
break;
}
/* wait for it to complete */
usleep(_conversion_interval);
/* run the collection phase */
if (OK != collect()) {
ret = -EIO;
break;
}
/* state machine will have generated a report, copy it out */
if (_reports->get(abuf)) {
ret = sizeof(*abuf);
}
} while (0);
return ret;
}
void
AirspeedSim::start()
{
/* reset the report ring and state machine */
_collect_phase = false;
_reports->flush();
/* schedule a cycle to start things */
work_queue(HPWORK, &_work, (worker_t)&AirspeedSim::cycle_trampoline, this, 1);
}
void
AirspeedSim::stop()
{
work_cancel(HPWORK, &_work);
}
void
AirspeedSim::update_status()
{
if (_sensor_ok != _last_published_sensor_ok) {
/* notify about state change */
struct subsystem_info_s info = {
true,
true,
_sensor_ok,
SUBSYSTEM_TYPE_DIFFPRESSURE
};
if (_subsys_pub > 0) {
orb_publish(ORB_ID(subsystem_info), _subsys_pub, &info);
} else {
_subsys_pub = orb_advertise(ORB_ID(subsystem_info), &info);
}
_last_published_sensor_ok = _sensor_ok;
}
}
void
AirspeedSim::cycle_trampoline(void *arg)
{
Airspeed *dev = (Airspeed *)arg;
dev->cycle();
// XXX we do not know if this is
// really helping - do not update the
// subsys state right now
//dev->update_status();
}
void
AirspeedSim::print_info()
{
perf_print_counter(_sample_perf);
perf_print_counter(_comms_errors);
perf_print_counter(_buffer_overflows);
warnx("poll interval: %u ticks", _measure_ticks);
_reports->print_info("report queue");
}
void
AirspeedSim::new_report(const differential_pressure_s &report)
{
if (!_reports->force(&report))
perf_count(_buffer_overflows);
}
@@ -0,0 +1,187 @@
/****************************************************************************
*
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file airspeed.h
* @author Simon Wilks
*
* Generic driver for airspeed sensors connected via I2C.
*/
#include <px4_config.h>
#include <drivers/device/i2c.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdlib.h>
#include <stdbool.h>
#include <semaphore.h>
#include <string.h>
#include <fcntl.h>
#include <poll.h>
#include <errno.h>
#include <stdio.h>
#include <math.h>
#include <unistd.h>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
#include <arch/board/board.h>
#include <systemlib/airspeed.h>
#include <systemlib/err.h>
#include <systemlib/param/param.h>
#include <systemlib/perf_counter.h>
#include <drivers/drv_airspeed.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/ringbuffer.h>
#include <uORB/uORB.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/subsystem_info.h>
/* Default I2C bus */
#define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION
/* Oddly, ERROR is not defined for C++ */
#ifdef ERROR
# undef ERROR
#endif
static const int ERROR = -1;
#ifndef CONFIG_SCHED_WORKQUEUE
# error This requires CONFIG_SCHED_WORKQUEUE.
#endif
class __EXPORT AirspeedSim : public device::I2C
{
public:
AirspeedSim(int bus, int address, unsigned conversion_interval, const char *path);
virtual ~AirspeedSim();
virtual int init();
virtual ssize_t read(px4_dev_handle_t *handlep, char *buffer, size_t buflen);
virtual int ioctl(px4_dev_handle_t *handlep, int cmd, unsigned long arg);
/**
* Diagnostics - print some basic information about the driver.
*/
virtual void print_info();
private:
RingBuffer *_reports;
perf_counter_t _buffer_overflows;
/* this class has pointer data members and should not be copied */
AirspeedSim(const AirspeedSim &);
AirspeedSim &operator=(const AirspeedSim &);
protected:
virtual int probe();
/**
* Perform a poll cycle; collect from the previous measurement
* and start a new one.
*/
virtual void cycle() = 0;
virtual int measure() = 0;
virtual int collect() = 0;
/**
* Update the subsystem status
*/
void update_status();
work_s _work;
float _max_differential_pressure_pa;
bool _sensor_ok;
bool _last_published_sensor_ok;
int _measure_ticks;
bool _collect_phase;
float _diff_pres_offset;
orb_advert_t _airspeed_pub;
orb_advert_t _subsys_pub;
int _class_instance;
unsigned _conversion_interval;
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
/**
* Test whether the device supported by the driver is present at a
* specific address.
*
* @param address The I2C bus address to probe.
* @return True if the device is present.
*/
int probe_address(uint8_t address);
/**
* Initialise the automatic measurement state machine and start it.
*
* @note This function is called at open and error time. It might make sense
* to make it more aggressive about resetting the bus in case of errors.
*/
void start();
/**
* Stop the automatic measurement state machine.
*/
void stop();
/**
* Static trampoline from the workq context; because we don't have a
* generic workq wrapper yet.
*
* @param arg Instance pointer for the driver that is polling.
*/
static void cycle_trampoline(void *arg);
/**
* add a new report to the reports queue
*
* @param report differential_pressure_s report
*/
void new_report(const differential_pressure_s &report);
};
@@ -0,0 +1,40 @@
############################################################################
#
# Copyright (c) 2013 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Makefile to build the generic airspeed driver.
#
SRCS = airspeedsim.cpp
MAXOPTIMIZATION = -Os
+9 -8
View File
@@ -38,6 +38,7 @@
#include <px4_config.h> #include <px4_config.h>
#include <px4_defines.h> #include <px4_defines.h>
#include <px4_time.h>
#include <px4_getopt.h> #include <px4_getopt.h>
#include <sys/types.h> #include <sys/types.h>
@@ -755,7 +756,7 @@ BAROSIM::print_info()
perf_print_counter(_buffer_overflows); perf_print_counter(_buffer_overflows);
printf("poll interval: %u ticks\n", _measure_ticks); printf("poll interval: %u ticks\n", _measure_ticks);
_reports->print_info("report queue"); _reports->print_info("report queue");
printf("TEMP: %d\n", _TEMP); printf("TEMP: %ld\n", (long)_TEMP);
printf("SENS: %lld\n", (long long)_SENS); printf("SENS: %lld\n", (long long)_SENS);
printf("OFF: %lld\n", (long long)_OFF); printf("OFF: %lld\n", (long long)_OFF);
printf("P: %.3f\n", (double)_P); printf("P: %.3f\n", (double)_P);
@@ -964,12 +965,12 @@ test()
/* read the sensor 5x and report each value */ /* read the sensor 5x and report each value */
for (unsigned i = 0; i < 5; i++) { for (unsigned i = 0; i < 5; i++) {
struct pollfd fds; px4_pollfd_struct_t fds;
/* wait for data to be ready */ /* wait for data to be ready */
fds.fd = fd; fds.fd = fd;
fds.events = POLLIN; fds.events = POLLIN;
ret = poll(&fds, 1, 2000); ret = px4_poll(&fds, 1, 2000);
if (ret != 1) { if (ret != 1) {
warnx("timed out waiting for sensor data"); warnx("timed out waiting for sensor data");
@@ -990,7 +991,7 @@ test()
warnx("time: %lld", (long long)report.timestamp); warnx("time: %lld", (long long)report.timestamp);
} }
close(fd); px4_close(fd);
warnx("PASS"); warnx("PASS");
return 0; return 0;
} }
@@ -1004,7 +1005,7 @@ reset()
struct barosim_bus_option &bus = bus_options[0]; struct barosim_bus_option &bus = bus_options[0];
int fd; int fd;
fd = open(bus.devpath, O_RDONLY); fd = px4_open(bus.devpath, O_RDONLY);
if (fd < 0) { if (fd < 0) {
warn("failed "); warn("failed ");
return 1; return 1;
@@ -1068,14 +1069,14 @@ calibrate(unsigned altitude)
pressure = 0.0f; pressure = 0.0f;
for (unsigned i = 0; i < 20; i++) { for (unsigned i = 0; i < 20; i++) {
struct pollfd fds; px4_pollfd_struct_t fds;
int ret; int ret;
ssize_t sz; ssize_t sz;
/* wait for data to be ready */ /* wait for data to be ready */
fds.fd = fd; fds.fd = fd;
fds.events = POLLIN; fds.events = POLLIN;
ret = poll(&fds, 1, 1000); ret = px4_poll(&fds, 1, 1000);
if (ret != 1) { if (ret != 1) {
warnx("timed out waiting for sensor data"); warnx("timed out waiting for sensor data");
@@ -1116,7 +1117,7 @@ calibrate(unsigned altitude)
return 1; return 1;
} }
close(fd); px4_close(fd);
return 0; return 0;
} }
@@ -69,7 +69,7 @@ public:
virtual int transfer(const uint8_t *send, unsigned send_len, virtual int transfer(const uint8_t *send, unsigned send_len,
uint8_t *recv, unsigned recv_len); uint8_t *recv, unsigned recv_len);
private: private:
barosim::prom_u &_prom; //barosim::prom_u &_prom;
/** /**
* Send a reset command to the barometer simulator. * Send a reset command to the barometer simulator.
@@ -101,8 +101,7 @@ BAROSIM_sim_interface(barosim::prom_u &prom_buf, uint8_t busnum)
} }
BARO_SIM::BARO_SIM(uint8_t bus, barosim::prom_u &prom) : BARO_SIM::BARO_SIM(uint8_t bus, barosim::prom_u &prom) :
SIM("BARO_SIM", "/dev/BARO_SIM", bus, 0), SIM("BARO_SIM", "/dev/BARO_SIM", bus, 0)
_prom(prom)
{ {
} }
@@ -57,7 +57,6 @@
#include <stdio.h> #include <stdio.h>
#include <math.h> #include <math.h>
#include <unistd.h> #include <unistd.h>
#include <getopt.h>
#include <simulator/simulator.h> #include <simulator/simulator.h>
+8
View File
@@ -0,0 +1,8 @@
#pragma once
#ifdef __PX4_QURT
#include <types.h>
size_t strnlen(const char *s, size_t maxlen);
//inline bool isfinite(int x) { return true; }
#endif
+31
View File
@@ -0,0 +1,31 @@
#pragma once
#include <sys/types.h>
#include <time.h>
#ifdef __PX4_LINUX
#define px4_clock_gettime clock_gettime
#define px4_clock_settime clock_settime
#elif defined(__PX4_QURT)
#define CLOCK_REALTIME 1
__BEGIN_DECLS
#if !defined(__cplusplus)
struct timespec
{
time_t tv_sec;
long tv_nsec;
};
#endif
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
#endif
+43
View File
@@ -0,0 +1,43 @@
/****************************************************************************
* include/nuttx/i2c.h
*
* Copyright(C) 2009-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES(INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
struct i2c_msg_s
{
uint16_t addr; /* Slave address */
uint16_t flags; /* See I2C_M_* definitions */
uint8_t *buffer;
int length;
};
+37
View File
@@ -1,3 +1,40 @@
/****************************************************************************
* include/poll.h
*
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once #pragma once
typedef unsigned int nfds_t; typedef unsigned int nfds_t;
#define POLLIN (0x01)
+3
View File
@@ -0,0 +1,3 @@
#pragma once
#define _IO(x,y) (x+y)
+26 -21
View File
@@ -49,25 +49,29 @@
//typedef int (*px4_main_t)(int argc, char *argv[]); //typedef int (*px4_main_t)(int argc, char *argv[]);
#include "apps.h" #include "apps.h"
//#include "px4_middleware.h" #include "px4_middleware.h"
static const char *commands = "hello start\n"; static const char *commands = "hello start\n"
"list_tasks";
static void run_cmd(const vector<string> &appargs) { static void run_cmd(const vector<string> &appargs) {
// command is appargs[0] // command is appargs[0]
string command = appargs[0]; string command = appargs[0];
printf("Looking for %s\n", command.c_str()); printf("Looking for %s\n", command.c_str());
if (apps.find(command) != apps.end()) { if (apps.find(command) != apps.end()) {
const char *arg[appargs.size()+2]; const char *arg[2+1];
unsigned int i = 0; unsigned int i = 0;
while (i < appargs.size() && appargs[i] != "") { printf("size = %d\n", appargs.size());
while (i < appargs.size() && appargs[i].c_str()[0] != '\0') {
arg[i] = (char *)appargs[i].c_str(); arg[i] = (char *)appargs[i].c_str();
printf(" arg = '%s'\n", arg[i]); printf(" arg = '%s'\n", arg[i]);
++i; ++i;
} }
arg[i] = (char *)0; arg[i] = (char *)0;
//printf("BEFORE argc = %d %s %s %p\n", i, arg[0], arg[1], arg[2]);
apps[command](i,(char **)arg); apps[command](i,(char **)arg);
//printf("AFTER argc = %d %s %s %p\n", i, arg[0], arg[1], arg[2]);
} }
else else
{ {
@@ -76,35 +80,39 @@ static void run_cmd(const vector<string> &appargs) {
} }
} }
void eat_whitespace(const char *&b, int &i)
{
// Eat whitespace
while (b[i] == ' ' || b[i] == '\t') { ++i; }
b = &b[i];
i=0;
}
static void process_commands(const char *cmds) static void process_commands(const char *cmds)
{ {
vector<string> appargs(5); vector<string> appargs;
int i=0; int i=0;
int j=0;
const char *b = cmds; const char *b = cmds;
bool found_first_char = false; bool found_first_char = false;
char arg[20]; char arg[20];
// Eat leading whitespace // Eat leading whitespace
while (b[i] == ' ') { ++i; }; eat_whitespace(b, i);
b = &b[i];
for(;;) { for(;;) {
// End of command line // End of command line
if (b[i] == '\n' || b[i] == '\0') { if (b[i] == '\n' || b[i] == '\0') {
strncpy(arg, b, i); strncpy(arg, b, i);
arg[i] = '\0'; arg[i] = '\0';
appargs[j] = arg; appargs.push_back(arg);
// If we have a command to run // If we have a command to run
if (i > 0 || j > 0) if (appargs.size() > 0) {
run_cmd(appargs); run_cmd(appargs);
j=0; }
appargs.clear();
if (b[i] == '\n') { if (b[i] == '\n') {
// Eat whitespace eat_whitespace(b, ++i);
while (b[++i] == ' ');
b = &b[i];
i=0;
continue; continue;
} }
else { else {
@@ -115,12 +123,8 @@ static void process_commands(const char *cmds)
else if (b[i] == ' ') { else if (b[i] == ' ') {
strncpy(arg, b, i); strncpy(arg, b, i);
arg[i] = '\0'; arg[i] = '\0';
appargs[j] = arg; appargs.push_back(arg);
j++; eat_whitespace(b, ++i);
// Eat whitespace
while (b[++i] == ' ');
b = &b[i];
i=0;
continue; continue;
} }
++i; ++i;
@@ -129,6 +133,7 @@ static void process_commands(const char *cmds)
int main(int argc, char **argv) int main(int argc, char **argv)
{ {
px4::init(argc, argv, "mainapp");
process_commands(commands); process_commands(commands);
for (;;) {} for (;;) {}
} }
+24 -13
View File
@@ -79,14 +79,17 @@ typedef struct
static void entry_adapter ( void *ptr ) static void entry_adapter ( void *ptr )
{ {
pthdata_t *data; pthdata_t *data = (pthdata_t *) ptr;
data = (pthdata_t *) ptr;
data->entry(data->argc, data->argv); printf("TEST3\n");
free(ptr); #if 0
//data->entry(data->argc, data->argv);
printf("TEST4\n");
printf("Before px4_task_exit\n"); printf("Before px4_task_exit\n");
px4_task_exit(0); px4_task_exit(0);
//free(ptr);
printf("After px4_task_exit\n"); printf("After px4_task_exit\n");
#endif
} }
void void
@@ -95,7 +98,7 @@ px4_systemreset(bool to_bootloader)
printf("Called px4_system_reset\n"); printf("Called px4_system_reset\n");
} }
px4_task_t px4_task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, px4_main_t entry, char * const argv[]) px4_task_t px4_task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, px4_main_t entry, char * const *argv)
{ {
int rv; int rv;
int argc = 0; int argc = 0;
@@ -105,14 +108,18 @@ px4_task_t px4_task_spawn_cmd(const char *name, int scheduler, int priority, int
unsigned long structsize; unsigned long structsize;
char * p; char * p;
//printf("arg %d %s %s %p\n", argc, argv[0], argv[1], argv[2]);
printf("arg %d %p\n", argc, argv);
// Calculate argc // Calculate argc
for(;;) { if (argv) {
p = argv[argc]; for(;;) {
printf("arg %d %s\n", argc, argv[argc]); p = argv[argc];
if (p == (char *)0) if (p == (char *)0)
break; break;
++argc; printf("arg %d %s\n", argc, argv[argc]);
len += strlen(p)+1; ++argc;
len += strlen(p)+1;
}
} }
structsize = sizeof(pthdata_t)+(argc+1)*sizeof(char *); structsize = sizeof(pthdata_t)+(argc+1)*sizeof(char *);
pthdata_t *taskdata; pthdata_t *taskdata;
@@ -125,6 +132,7 @@ px4_task_t px4_task_spawn_cmd(const char *name, int scheduler, int priority, int
taskdata->argc = argc; taskdata->argc = argc;
for (i=0; i<argc; i++) { for (i=0; i<argc; i++) {
printf("TEST\n");
printf("arg %d %s\n", i, argv[i]); printf("arg %d %s\n", i, argv[i]);
taskdata->argv[i] = (char *)offset; taskdata->argv[i] = (char *)offset;
strcpy((char *)offset, argv[i]); strcpy((char *)offset, argv[i]);
@@ -138,10 +146,11 @@ px4_task_t px4_task_spawn_cmd(const char *name, int scheduler, int priority, int
taskmap[i].pid = i+1; taskmap[i].pid = i+1;
taskmap[i].name = name; taskmap[i].name = name;
taskmap[i].isused = true; taskmap[i].isused = true;
taskmap[i].sp = malloc(stack_size);; taskmap[i].sp = malloc(stack_size);
break; break;
} }
} }
printf("TEST2\n");
thread_create(entry_adapter, taskmap[i].sp, i+1, (void *) taskdata); thread_create(entry_adapter, taskmap[i].sp, i+1, (void *) taskdata);
return i+1; return i+1;
@@ -156,6 +165,8 @@ int px4_task_delete(px4_task_t id)
void px4_task_exit(int ret) void px4_task_exit(int ret)
{ {
thread_stop(); thread_stop();
// Free stack
} }
void px4_killall(void) void px4_killall(void)
@@ -56,7 +56,7 @@ static void usage()
} }
int hello_main(int argc, char *argv[]) int hello_main(int argc, char *argv[])
{ {
printf("argc = %d %s %s\n", argc, argv[0], argv[1]); printf("argc = %d %s %s %p\n", argc, argv[0], argv[1], argv[2]);
if (argc < 2) { if (argc < 2) {
usage(); usage();
return 1; return 1;