mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 20:28:37 +08:00
Merge remote-tracking branch 'upstream/master' into dev_ros
This commit is contained in:
@@ -301,7 +301,6 @@ then
|
|||||||
|
|
||||||
if [ $OUTPUT_MODE == io -o $OUTPUT_MODE == uavcan_esc ]
|
if [ $OUTPUT_MODE == io -o $OUTPUT_MODE == uavcan_esc ]
|
||||||
then
|
then
|
||||||
echo "[init] Use PX4IO PWM as primary output"
|
|
||||||
if px4io start
|
if px4io start
|
||||||
then
|
then
|
||||||
echo "[init] PX4IO started"
|
echo "[init] PX4IO started"
|
||||||
@@ -314,7 +313,6 @@ then
|
|||||||
|
|
||||||
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == ardrone ]
|
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == ardrone ]
|
||||||
then
|
then
|
||||||
echo "[init] Use FMU as primary output"
|
|
||||||
if fmu mode_$FMU_MODE
|
if fmu mode_$FMU_MODE
|
||||||
then
|
then
|
||||||
echo "[init] FMU mode_$FMU_MODE started"
|
echo "[init] FMU mode_$FMU_MODE started"
|
||||||
@@ -338,7 +336,6 @@ then
|
|||||||
|
|
||||||
if [ $OUTPUT_MODE == mkblctrl ]
|
if [ $OUTPUT_MODE == mkblctrl ]
|
||||||
then
|
then
|
||||||
echo "[init] Use MKBLCTRL as primary output"
|
|
||||||
set MKBLCTRL_ARG ""
|
set MKBLCTRL_ARG ""
|
||||||
if [ $MKBLCTRL_MODE == x ]
|
if [ $MKBLCTRL_MODE == x ]
|
||||||
then
|
then
|
||||||
@@ -361,7 +358,6 @@ then
|
|||||||
|
|
||||||
if [ $OUTPUT_MODE == hil ]
|
if [ $OUTPUT_MODE == hil ]
|
||||||
then
|
then
|
||||||
echo "[init] Use HIL as primary output"
|
|
||||||
if hil mode_port2_pwm8
|
if hil mode_port2_pwm8
|
||||||
then
|
then
|
||||||
echo "[init] HIL output started"
|
echo "[init] HIL output started"
|
||||||
@@ -380,7 +376,6 @@ then
|
|||||||
then
|
then
|
||||||
if px4io start
|
if px4io start
|
||||||
then
|
then
|
||||||
echo "[init] PX4IO started"
|
|
||||||
sh /etc/init.d/rc.io
|
sh /etc/init.d/rc.io
|
||||||
else
|
else
|
||||||
echo "[init] ERROR: PX4IO start failed"
|
echo "[init] ERROR: PX4IO start failed"
|
||||||
|
|||||||
@@ -24,6 +24,8 @@ MODULES += drivers/l3gd20
|
|||||||
MODULES += drivers/mpu6000
|
MODULES += drivers/mpu6000
|
||||||
MODULES += drivers/hmc5883
|
MODULES += drivers/hmc5883
|
||||||
MODULES += drivers/ms5611
|
MODULES += drivers/ms5611
|
||||||
|
#MODULES += drivers/ll40ls
|
||||||
|
MODULES += drivers/trone
|
||||||
#MODULES += drivers/mb12xx
|
#MODULES += drivers/mb12xx
|
||||||
MODULES += drivers/gps
|
MODULES += drivers/gps
|
||||||
MODULES += drivers/hil
|
MODULES += drivers/hil
|
||||||
|
|||||||
@@ -27,13 +27,14 @@ MODULES += drivers/l3gd20
|
|||||||
MODULES += drivers/hmc5883
|
MODULES += drivers/hmc5883
|
||||||
MODULES += drivers/ms5611
|
MODULES += drivers/ms5611
|
||||||
MODULES += drivers/mb12xx
|
MODULES += drivers/mb12xx
|
||||||
MODULES += drivers/sf0x
|
# MODULES += drivers/sf0x
|
||||||
MODULES += drivers/ll40ls
|
MODULES += drivers/ll40ls
|
||||||
|
# MODULES += drivers/trone
|
||||||
MODULES += drivers/gps
|
MODULES += drivers/gps
|
||||||
MODULES += drivers/hil
|
MODULES += drivers/hil
|
||||||
MODULES += drivers/hott/hott_telemetry
|
MODULES += drivers/hott/hott_telemetry
|
||||||
MODULES += drivers/hott/hott_sensors
|
MODULES += drivers/hott/hott_sensors
|
||||||
MODULES += drivers/blinkm
|
# MODULES += drivers/blinkm
|
||||||
MODULES += drivers/airspeed
|
MODULES += drivers/airspeed
|
||||||
MODULES += drivers/ets_airspeed
|
MODULES += drivers/ets_airspeed
|
||||||
MODULES += drivers/meas_airspeed
|
MODULES += drivers/meas_airspeed
|
||||||
|
|||||||
@@ -159,13 +159,15 @@ out:
|
|||||||
int
|
int
|
||||||
Airspeed::probe()
|
Airspeed::probe()
|
||||||
{
|
{
|
||||||
/* on initial power up the device needs more than one retry
|
/* on initial power up the device may need more than one retry
|
||||||
for detection. Once it is running then retries aren't
|
for detection. Once it is running the number of retries can
|
||||||
needed
|
be reduced
|
||||||
*/
|
*/
|
||||||
_retries = 4;
|
_retries = 4;
|
||||||
int ret = measure();
|
int ret = measure();
|
||||||
_retries = 0;
|
|
||||||
|
// drop back to 2 retries once initialised
|
||||||
|
_retries = 2;
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -1349,7 +1349,7 @@ HMC5883 *g_dev_ext = nullptr;
|
|||||||
void start(int bus, enum Rotation rotation);
|
void start(int bus, enum Rotation rotation);
|
||||||
void test(int bus);
|
void test(int bus);
|
||||||
void reset(int bus);
|
void reset(int bus);
|
||||||
void info(int bus);
|
int info(int bus);
|
||||||
int calibrate(int bus);
|
int calibrate(int bus);
|
||||||
void usage();
|
void usage();
|
||||||
|
|
||||||
@@ -1595,17 +1595,23 @@ reset(int bus)
|
|||||||
/**
|
/**
|
||||||
* Print a little info about the driver.
|
* Print a little info about the driver.
|
||||||
*/
|
*/
|
||||||
void
|
int
|
||||||
info(int bus)
|
info(int bus)
|
||||||
{
|
{
|
||||||
HMC5883 *g_dev = (bus == PX4_I2C_BUS_ONBOARD?g_dev_int:g_dev_ext);
|
int ret = 1;
|
||||||
if (g_dev == nullptr)
|
|
||||||
errx(1, "driver not running");
|
HMC5883 *g_dev = (bus == PX4_I2C_BUS_ONBOARD ? g_dev_int : g_dev_ext);
|
||||||
|
if (g_dev == nullptr) {
|
||||||
|
warnx("not running on bus %d", bus);
|
||||||
|
} else {
|
||||||
|
|
||||||
|
warnx("running on bus: %d (%s)\n", bus, ((PX4_I2C_BUS_ONBOARD) ? "onboard" : "offboard"));
|
||||||
|
|
||||||
printf("state @ %p\n", g_dev);
|
|
||||||
g_dev->print_info();
|
g_dev->print_info();
|
||||||
|
ret = 0;
|
||||||
|
}
|
||||||
|
|
||||||
exit(0);
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
@@ -1685,8 +1691,21 @@ hmc5883_main(int argc, char *argv[])
|
|||||||
/*
|
/*
|
||||||
* Print driver information.
|
* Print driver information.
|
||||||
*/
|
*/
|
||||||
if (!strcmp(verb, "info") || !strcmp(verb, "status"))
|
if (!strcmp(verb, "info") || !strcmp(verb, "status")) {
|
||||||
hmc5883::info(bus);
|
if (bus == -1) {
|
||||||
|
int ret = 0;
|
||||||
|
if (hmc5883::info(PX4_I2C_BUS_ONBOARD)) {
|
||||||
|
ret = 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (hmc5883::info(PX4_I2C_BUS_EXPANSION)) {
|
||||||
|
ret = 1;
|
||||||
|
}
|
||||||
|
exit(ret);
|
||||||
|
} else {
|
||||||
|
exit(hmc5883::info(bus));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Autocalibrate the scaling
|
* Autocalibrate the scaling
|
||||||
|
|||||||
+167
-110
@@ -1,6 +1,6 @@
|
|||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
*
|
*
|
||||||
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
|
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
@@ -73,15 +73,13 @@
|
|||||||
#include <board_config.h>
|
#include <board_config.h>
|
||||||
|
|
||||||
/* Configuration Constants */
|
/* Configuration Constants */
|
||||||
#define PX4FLOW_BUS PX4_I2C_BUS_EXPANSION
|
|
||||||
#define I2C_FLOW_ADDRESS 0x42 //* 7-bit address. 8-bit address is 0x84
|
#define I2C_FLOW_ADDRESS 0x42 //* 7-bit address. 8-bit address is 0x84
|
||||||
//range 0x42 - 0x49
|
//range 0x42 - 0x49
|
||||||
|
|
||||||
/* PX4FLOW Registers addresses */
|
/* PX4FLOW Registers addresses */
|
||||||
#define PX4FLOW_REG 0x00 /* Measure Register */
|
#define PX4FLOW_REG 0x16 /* Measure Register 22*/
|
||||||
|
|
||||||
#define PX4FLOW_CONVERSION_INTERVAL 8000 /* 8ms 125Hz */
|
|
||||||
|
|
||||||
|
#define PX4FLOW_CONVERSION_INTERVAL 20000 //in microseconds! 20000 = 50 Hz 100000 = 10Hz
|
||||||
/* oddly, ERROR is not defined for c++ */
|
/* oddly, ERROR is not defined for c++ */
|
||||||
#ifdef ERROR
|
#ifdef ERROR
|
||||||
# undef ERROR
|
# undef ERROR
|
||||||
@@ -92,28 +90,42 @@ static const int ERROR = -1;
|
|||||||
# error This requires CONFIG_SCHED_WORKQUEUE.
|
# error This requires CONFIG_SCHED_WORKQUEUE.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//struct i2c_frame
|
struct i2c_frame {
|
||||||
//{
|
uint16_t frame_count;
|
||||||
// uint16_t frame_count;
|
int16_t pixel_flow_x_sum;
|
||||||
// int16_t pixel_flow_x_sum;
|
int16_t pixel_flow_y_sum;
|
||||||
// int16_t pixel_flow_y_sum;
|
int16_t flow_comp_m_x;
|
||||||
// int16_t flow_comp_m_x;
|
int16_t flow_comp_m_y;
|
||||||
// int16_t flow_comp_m_y;
|
int16_t qual;
|
||||||
// int16_t qual;
|
int16_t gyro_x_rate;
|
||||||
// int16_t gyro_x_rate;
|
int16_t gyro_y_rate;
|
||||||
// int16_t gyro_y_rate;
|
int16_t gyro_z_rate;
|
||||||
// int16_t gyro_z_rate;
|
uint8_t gyro_range;
|
||||||
// uint8_t gyro_range;
|
uint8_t sonar_timestamp;
|
||||||
// uint8_t sonar_timestamp;
|
int16_t ground_distance;
|
||||||
// int16_t ground_distance;
|
};
|
||||||
//};
|
struct i2c_frame f;
|
||||||
//
|
|
||||||
//struct i2c_frame f;
|
|
||||||
|
|
||||||
class PX4FLOW : public device::I2C
|
typedef struct i2c_integral_frame {
|
||||||
|
uint16_t frame_count_since_last_readout;
|
||||||
|
int16_t pixel_flow_x_integral;
|
||||||
|
int16_t pixel_flow_y_integral;
|
||||||
|
int16_t gyro_x_rate_integral;
|
||||||
|
int16_t gyro_y_rate_integral;
|
||||||
|
int16_t gyro_z_rate_integral;
|
||||||
|
uint32_t integration_timespan;
|
||||||
|
uint32_t time_since_last_sonar_update;
|
||||||
|
uint16_t ground_distance;
|
||||||
|
int16_t gyro_temperature;
|
||||||
|
uint8_t qual;
|
||||||
|
} __attribute__((packed));
|
||||||
|
struct i2c_integral_frame f_integral;
|
||||||
|
|
||||||
|
|
||||||
|
class PX4FLOW: public device::I2C
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
PX4FLOW(int bus = PX4FLOW_BUS, int address = I2C_FLOW_ADDRESS);
|
PX4FLOW(int bus, int address = I2C_FLOW_ADDRESS);
|
||||||
virtual ~PX4FLOW();
|
virtual ~PX4FLOW();
|
||||||
|
|
||||||
virtual int init();
|
virtual int init();
|
||||||
@@ -180,7 +192,6 @@ private:
|
|||||||
*/
|
*/
|
||||||
static void cycle_trampoline(void *arg);
|
static void cycle_trampoline(void *arg);
|
||||||
|
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@@ -189,7 +200,7 @@ private:
|
|||||||
extern "C" __EXPORT int px4flow_main(int argc, char *argv[]);
|
extern "C" __EXPORT int px4flow_main(int argc, char *argv[]);
|
||||||
|
|
||||||
PX4FLOW::PX4FLOW(int bus, int address) :
|
PX4FLOW::PX4FLOW(int bus, int address) :
|
||||||
I2C("PX4FLOW", PX4FLOW_DEVICE_PATH, bus, address, 400000),//400khz
|
I2C("PX4FLOW", PX4FLOW_DEVICE_PATH, bus, address, 400000), //400khz
|
||||||
_reports(nullptr),
|
_reports(nullptr),
|
||||||
_sensor_ok(false),
|
_sensor_ok(false),
|
||||||
_measure_ticks(0),
|
_measure_ticks(0),
|
||||||
@@ -228,21 +239,12 @@ PX4FLOW::init()
|
|||||||
}
|
}
|
||||||
|
|
||||||
/* allocate basic report buffers */
|
/* allocate basic report buffers */
|
||||||
_reports = new RingBuffer(2, sizeof(struct optical_flow_s));
|
_reports = new RingBuffer(2, sizeof(optical_flow_s));
|
||||||
|
|
||||||
if (_reports == nullptr) {
|
if (_reports == nullptr) {
|
||||||
goto out;
|
goto out;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* get a publish handle on the px4flow topic */
|
|
||||||
struct optical_flow_s zero_report;
|
|
||||||
memset(&zero_report, 0, sizeof(zero_report));
|
|
||||||
_px4flow_topic = orb_advertise(ORB_ID(optical_flow), &zero_report);
|
|
||||||
|
|
||||||
if (_px4flow_topic < 0) {
|
|
||||||
warnx("failed to create px4flow object. Did you start uOrb?");
|
|
||||||
}
|
|
||||||
|
|
||||||
ret = OK;
|
ret = OK;
|
||||||
/* sensor is ok, but we don't really know if it is within range */
|
/* sensor is ok, but we don't really know if it is within range */
|
||||||
_sensor_ok = true;
|
_sensor_ok = true;
|
||||||
@@ -410,9 +412,6 @@ PX4FLOW::read(struct file *filp, char *buffer, size_t buflen)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* wait for it to complete */
|
|
||||||
usleep(PX4FLOW_CONVERSION_INTERVAL);
|
|
||||||
|
|
||||||
/* run the collection phase */
|
/* run the collection phase */
|
||||||
if (OK != collect()) {
|
if (OK != collect()) {
|
||||||
ret = -EIO;
|
ret = -EIO;
|
||||||
@@ -442,6 +441,7 @@ PX4FLOW::measure()
|
|||||||
|
|
||||||
if (OK != ret) {
|
if (OK != ret) {
|
||||||
perf_count(_comms_errors);
|
perf_count(_comms_errors);
|
||||||
|
debug("i2c::transfer returned %d", ret);
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -456,11 +456,17 @@ PX4FLOW::collect()
|
|||||||
int ret = -EIO;
|
int ret = -EIO;
|
||||||
|
|
||||||
/* read from the sensor */
|
/* read from the sensor */
|
||||||
uint8_t val[22] = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
|
uint8_t val[47] = { 0 };
|
||||||
|
|
||||||
perf_begin(_sample_perf);
|
perf_begin(_sample_perf);
|
||||||
|
|
||||||
ret = transfer(nullptr, 0, &val[0], 22);
|
if (PX4FLOW_REG == 0x00) {
|
||||||
|
ret = transfer(nullptr, 0, &val[0], 47); // read 47 bytes (22+25 : frame1 + frame2)
|
||||||
|
}
|
||||||
|
|
||||||
|
if (PX4FLOW_REG == 0x16) {
|
||||||
|
ret = transfer(nullptr, 0, &val[0], 25); // read 25 bytes (only frame2)
|
||||||
|
}
|
||||||
|
|
||||||
if (ret < 0) {
|
if (ret < 0) {
|
||||||
debug("error reading from sensor: %d", ret);
|
debug("error reading from sensor: %d", ret);
|
||||||
@@ -469,36 +475,74 @@ PX4FLOW::collect()
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
// f.frame_count = val[1] << 8 | val[0];
|
if (PX4FLOW_REG == 0) {
|
||||||
// f.pixel_flow_x_sum= val[3] << 8 | val[2];
|
f.frame_count = val[1] << 8 | val[0];
|
||||||
// f.pixel_flow_y_sum= val[5] << 8 | val[4];
|
f.pixel_flow_x_sum = val[3] << 8 | val[2];
|
||||||
// f.flow_comp_m_x= val[7] << 8 | val[6];
|
f.pixel_flow_y_sum = val[5] << 8 | val[4];
|
||||||
// f.flow_comp_m_y= val[9] << 8 | val[8];
|
f.flow_comp_m_x = val[7] << 8 | val[6];
|
||||||
// f.qual= val[11] << 8 | val[10];
|
f.flow_comp_m_y = val[9] << 8 | val[8];
|
||||||
// f.gyro_x_rate= val[13] << 8 | val[12];
|
f.qual = val[11] << 8 | val[10];
|
||||||
// f.gyro_y_rate= val[15] << 8 | val[14];
|
f.gyro_x_rate = val[13] << 8 | val[12];
|
||||||
// f.gyro_z_rate= val[17] << 8 | val[16];
|
f.gyro_y_rate = val[15] << 8 | val[14];
|
||||||
// f.gyro_range= val[18];
|
f.gyro_z_rate = val[17] << 8 | val[16];
|
||||||
// f.sonar_timestamp= val[19];
|
f.gyro_range = val[18];
|
||||||
// f.ground_distance= val[21] << 8 | val[20];
|
f.sonar_timestamp = val[19];
|
||||||
|
f.ground_distance = val[21] << 8 | val[20];
|
||||||
|
|
||||||
|
f_integral.frame_count_since_last_readout = val[23] << 8 | val[22];
|
||||||
|
f_integral.pixel_flow_x_integral = val[25] << 8 | val[24];
|
||||||
|
f_integral.pixel_flow_y_integral = val[27] << 8 | val[26];
|
||||||
|
f_integral.gyro_x_rate_integral = val[29] << 8 | val[28];
|
||||||
|
f_integral.gyro_y_rate_integral = val[31] << 8 | val[30];
|
||||||
|
f_integral.gyro_z_rate_integral = val[33] << 8 | val[32];
|
||||||
|
f_integral.integration_timespan = val[37] << 24 | val[36] << 16
|
||||||
|
| val[35] << 8 | val[34];
|
||||||
|
f_integral.time_since_last_sonar_update = val[41] << 24 | val[40] << 16
|
||||||
|
| val[39] << 8 | val[38];
|
||||||
|
f_integral.ground_distance = val[43] << 8 | val[42];
|
||||||
|
f_integral.gyro_temperature = val[45] << 8 | val[44];
|
||||||
|
f_integral.qual = val[46];
|
||||||
|
}
|
||||||
|
|
||||||
|
if (PX4FLOW_REG == 0x16) {
|
||||||
|
f_integral.frame_count_since_last_readout = val[1] << 8 | val[0];
|
||||||
|
f_integral.pixel_flow_x_integral = val[3] << 8 | val[2];
|
||||||
|
f_integral.pixel_flow_y_integral = val[5] << 8 | val[4];
|
||||||
|
f_integral.gyro_x_rate_integral = val[7] << 8 | val[6];
|
||||||
|
f_integral.gyro_y_rate_integral = val[9] << 8 | val[8];
|
||||||
|
f_integral.gyro_z_rate_integral = val[11] << 8 | val[10];
|
||||||
|
f_integral.integration_timespan = val[15] << 24 | val[14] << 16 | val[13] << 8 | val[12];
|
||||||
|
f_integral.time_since_last_sonar_update = val[19] << 24 | val[18] << 16 | val[17] << 8 | val[16];
|
||||||
|
f_integral.ground_distance = val[21] << 8 | val[20];
|
||||||
|
f_integral.gyro_temperature = val[23] << 8 | val[22];
|
||||||
|
f_integral.qual = val[24];
|
||||||
|
}
|
||||||
|
|
||||||
int16_t flowcx = val[7] << 8 | val[6];
|
|
||||||
int16_t flowcy = val[9] << 8 | val[8];
|
|
||||||
int16_t gdist = val[21] << 8 | val[20];
|
|
||||||
|
|
||||||
struct optical_flow_s report;
|
struct optical_flow_s report;
|
||||||
report.flow_comp_x_m = float(flowcx) / 1000.0f;
|
|
||||||
report.flow_comp_y_m = float(flowcy) / 1000.0f;
|
|
||||||
report.flow_raw_x = val[3] << 8 | val[2];
|
|
||||||
report.flow_raw_y = val[5] << 8 | val[4];
|
|
||||||
report.ground_distance_m = float(gdist) / 1000.0f;
|
|
||||||
report.quality = val[10];
|
|
||||||
report.sensor_id = 0;
|
|
||||||
report.timestamp = hrt_absolute_time();
|
report.timestamp = hrt_absolute_time();
|
||||||
|
report.pixel_flow_x_integral = static_cast<float>(f_integral.pixel_flow_x_integral) / 10000.0f;//convert to radians
|
||||||
|
report.pixel_flow_y_integral = static_cast<float>(f_integral.pixel_flow_y_integral) / 10000.0f;//convert to radians
|
||||||
|
report.frame_count_since_last_readout = f_integral.frame_count_since_last_readout;
|
||||||
|
report.ground_distance_m = static_cast<float>(f_integral.ground_distance) / 1000.0f;//convert to meters
|
||||||
|
report.quality = f_integral.qual; //0:bad ; 255 max quality
|
||||||
|
report.gyro_x_rate_integral = static_cast<float>(f_integral.gyro_x_rate_integral) / 10000.0f; //convert to radians
|
||||||
|
report.gyro_y_rate_integral = static_cast<float>(f_integral.gyro_y_rate_integral) / 10000.0f; //convert to radians
|
||||||
|
report.gyro_z_rate_integral = static_cast<float>(f_integral.gyro_z_rate_integral) / 10000.0f; //convert to radians
|
||||||
|
report.integration_timespan = f_integral.integration_timespan; //microseconds
|
||||||
|
report.time_since_last_sonar_update = f_integral.time_since_last_sonar_update;//microseconds
|
||||||
|
report.gyro_temperature = f_integral.gyro_temperature;//Temperature * 100 in centi-degrees Celsius
|
||||||
|
|
||||||
|
report.sensor_id = 0;
|
||||||
|
|
||||||
|
if (_px4flow_topic < 0) {
|
||||||
|
_px4flow_topic = orb_advertise(ORB_ID(optical_flow), &report);
|
||||||
|
|
||||||
|
} else {
|
||||||
/* publish it */
|
/* publish it */
|
||||||
orb_publish(ORB_ID(optical_flow), _px4flow_topic, &report);
|
orb_publish(ORB_ID(optical_flow), _px4flow_topic, &report);
|
||||||
|
}
|
||||||
|
|
||||||
/* post a report to the ring */
|
/* post a report to the ring */
|
||||||
if (_reports->force(&report)) {
|
if (_reports->force(&report)) {
|
||||||
@@ -558,8 +602,9 @@ PX4FLOW::cycle_trampoline(void *arg)
|
|||||||
void
|
void
|
||||||
PX4FLOW::cycle()
|
PX4FLOW::cycle()
|
||||||
{
|
{
|
||||||
/* collection phase? */
|
if (OK != measure()) {
|
||||||
if (_collect_phase) {
|
debug("measure error");
|
||||||
|
}
|
||||||
|
|
||||||
/* perform collection */
|
/* perform collection */
|
||||||
if (OK != collect()) {
|
if (OK != collect()) {
|
||||||
@@ -569,39 +614,9 @@ PX4FLOW::cycle()
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* next phase is measurement */
|
work_queue(HPWORK, &_work, (worker_t)&PX4FLOW::cycle_trampoline, this,
|
||||||
_collect_phase = false;
|
_measure_ticks);
|
||||||
|
|
||||||
/*
|
|
||||||
* Is there a collect->measure gap?
|
|
||||||
*/
|
|
||||||
if (_measure_ticks > USEC2TICK(PX4FLOW_CONVERSION_INTERVAL)) {
|
|
||||||
|
|
||||||
/* schedule a fresh cycle call when we are ready to measure again */
|
|
||||||
work_queue(HPWORK,
|
|
||||||
&_work,
|
|
||||||
(worker_t)&PX4FLOW::cycle_trampoline,
|
|
||||||
this,
|
|
||||||
_measure_ticks - USEC2TICK(PX4FLOW_CONVERSION_INTERVAL));
|
|
||||||
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/* measurement phase */
|
|
||||||
if (OK != measure()) {
|
|
||||||
debug("measure error");
|
|
||||||
}
|
|
||||||
|
|
||||||
/* next phase is collection */
|
|
||||||
_collect_phase = true;
|
|
||||||
|
|
||||||
/* schedule a fresh cycle call when the measurement is done */
|
|
||||||
work_queue(HPWORK,
|
|
||||||
&_work,
|
|
||||||
(worker_t)&PX4FLOW::cycle_trampoline,
|
|
||||||
this,
|
|
||||||
USEC2TICK(PX4FLOW_CONVERSION_INTERVAL));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
@@ -647,7 +662,29 @@ start()
|
|||||||
}
|
}
|
||||||
|
|
||||||
/* create the driver */
|
/* create the driver */
|
||||||
g_dev = new PX4FLOW(PX4FLOW_BUS);
|
g_dev = new PX4FLOW(PX4_I2C_BUS_EXPANSION);
|
||||||
|
|
||||||
|
if (g_dev == nullptr) {
|
||||||
|
goto fail;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (OK != g_dev->init()) {
|
||||||
|
|
||||||
|
#ifdef PX4_I2C_BUS_ESC
|
||||||
|
delete g_dev;
|
||||||
|
/* try 2nd bus */
|
||||||
|
g_dev = new PX4FLOW(PX4_I2C_BUS_ESC);
|
||||||
|
|
||||||
|
if (g_dev == nullptr) {
|
||||||
|
goto fail;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (OK != g_dev->init()) {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
delete g_dev;
|
||||||
|
/* try 3rd bus */
|
||||||
|
g_dev = new PX4FLOW(PX4_I2C_BUS_ONBOARD);
|
||||||
|
|
||||||
if (g_dev == nullptr) {
|
if (g_dev == nullptr) {
|
||||||
goto fail;
|
goto fail;
|
||||||
@@ -657,6 +694,11 @@ start()
|
|||||||
goto fail;
|
goto fail;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef PX4_I2C_BUS_ESC
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
/* set the poll rate to default, starts automatic data collection */
|
/* set the poll rate to default, starts automatic data collection */
|
||||||
fd = open(PX4FLOW_DEVICE_PATH, O_RDONLY);
|
fd = open(PX4FLOW_DEVICE_PATH, O_RDONLY);
|
||||||
|
|
||||||
@@ -683,7 +725,8 @@ fail:
|
|||||||
/**
|
/**
|
||||||
* Stop the driver
|
* Stop the driver
|
||||||
*/
|
*/
|
||||||
void stop()
|
void
|
||||||
|
stop()
|
||||||
{
|
{
|
||||||
if (g_dev != nullptr) {
|
if (g_dev != nullptr) {
|
||||||
delete g_dev;
|
delete g_dev;
|
||||||
@@ -714,6 +757,7 @@ test()
|
|||||||
err(1, "%s open failed (try 'px4flow start' if the driver is not running", PX4FLOW_DEVICE_PATH);
|
err(1, "%s open failed (try 'px4flow start' if the driver is not running", PX4FLOW_DEVICE_PATH);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/* do a simple demand read */
|
/* do a simple demand read */
|
||||||
sz = read(fd, &report, sizeof(report));
|
sz = read(fd, &report, sizeof(report));
|
||||||
|
|
||||||
@@ -723,18 +767,18 @@ test()
|
|||||||
}
|
}
|
||||||
|
|
||||||
warnx("single read");
|
warnx("single read");
|
||||||
warnx("flowx: %0.2f m/s", (double)report.flow_comp_x_m);
|
warnx("pixel_flow_x_integral: %i", f_integral.pixel_flow_x_integral);
|
||||||
warnx("flowy: %0.2f m/s", (double)report.flow_comp_y_m);
|
warnx("pixel_flow_y_integral: %i", f_integral.pixel_flow_y_integral);
|
||||||
warnx("time: %lld", report.timestamp);
|
warnx("framecount_integral: %u",
|
||||||
|
f_integral.frame_count_since_last_readout);
|
||||||
|
|
||||||
|
/* start the sensor polling at 10Hz */
|
||||||
/* start the sensor polling at 2Hz */
|
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 10)) {
|
||||||
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
|
errx(1, "failed to set 10Hz poll rate");
|
||||||
errx(1, "failed to set 2Hz poll rate");
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/* 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 < 10; i++) {
|
||||||
struct pollfd fds;
|
struct pollfd fds;
|
||||||
|
|
||||||
/* wait for data to be ready */
|
/* wait for data to be ready */
|
||||||
@@ -754,9 +798,22 @@ test()
|
|||||||
}
|
}
|
||||||
|
|
||||||
warnx("periodic read %u", i);
|
warnx("periodic read %u", i);
|
||||||
warnx("flowx: %0.2f m/s", (double)report.flow_comp_x_m);
|
|
||||||
warnx("flowy: %0.2f m/s", (double)report.flow_comp_y_m);
|
warnx("framecount_total: %u", f.frame_count);
|
||||||
warnx("time: %lld", report.timestamp);
|
warnx("framecount_integral: %u",
|
||||||
|
f_integral.frame_count_since_last_readout);
|
||||||
|
warnx("pixel_flow_x_integral: %i", f_integral.pixel_flow_x_integral);
|
||||||
|
warnx("pixel_flow_y_integral: %i", f_integral.pixel_flow_y_integral);
|
||||||
|
warnx("gyro_x_rate_integral: %i", f_integral.gyro_x_rate_integral);
|
||||||
|
warnx("gyro_y_rate_integral: %i", f_integral.gyro_y_rate_integral);
|
||||||
|
warnx("gyro_z_rate_integral: %i", f_integral.gyro_z_rate_integral);
|
||||||
|
warnx("integration_timespan [us]: %u", f_integral.integration_timespan);
|
||||||
|
warnx("ground_distance: %0.2f m",
|
||||||
|
(double) f_integral.ground_distance / 1000);
|
||||||
|
warnx("time since last sonar update [us]: %i",
|
||||||
|
f_integral.time_since_last_sonar_update);
|
||||||
|
warnx("quality integration average : %i", f_integral.qual);
|
||||||
|
warnx("quality : %i", f.qual);
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
+12
-10
@@ -1160,15 +1160,15 @@ PX4IO::io_set_arming_state()
|
|||||||
actuator_armed_s armed; ///< system armed state
|
actuator_armed_s armed; ///< system armed state
|
||||||
vehicle_control_mode_s control_mode; ///< vehicle_control_mode
|
vehicle_control_mode_s control_mode; ///< vehicle_control_mode
|
||||||
|
|
||||||
orb_copy(ORB_ID(actuator_armed), _t_actuator_armed, &armed);
|
int have_armed = orb_copy(ORB_ID(actuator_armed), _t_actuator_armed, &armed);
|
||||||
orb_copy(ORB_ID(vehicle_control_mode), _t_vehicle_control_mode, &control_mode);
|
int have_control_mode = orb_copy(ORB_ID(vehicle_control_mode), _t_vehicle_control_mode, &control_mode);
|
||||||
|
|
||||||
uint16_t set = 0;
|
uint16_t set = 0;
|
||||||
uint16_t clear = 0;
|
uint16_t clear = 0;
|
||||||
|
|
||||||
|
if (have_armed == OK) {
|
||||||
if (armed.armed) {
|
if (armed.armed) {
|
||||||
set |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
|
set |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
clear |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
|
clear |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
|
||||||
}
|
}
|
||||||
@@ -1200,13 +1200,15 @@ PX4IO::io_set_arming_state()
|
|||||||
} else {
|
} else {
|
||||||
clear |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
|
clear |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (have_control_mode == OK) {
|
||||||
if (control_mode.flag_external_manual_override_ok) {
|
if (control_mode.flag_external_manual_override_ok) {
|
||||||
set |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK;
|
set |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
clear |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK;
|
clear |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK;
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
return io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, clear, set);
|
return io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, clear, set);
|
||||||
}
|
}
|
||||||
@@ -2198,7 +2200,7 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
|
|||||||
struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
|
struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
|
||||||
if (pwm->channel_count > _max_actuators)
|
if (pwm->channel_count > _max_actuators)
|
||||||
/* fail with error */
|
/* fail with error */
|
||||||
return E2BIG;
|
return -E2BIG;
|
||||||
|
|
||||||
/* copy values to registers in IO */
|
/* copy values to registers in IO */
|
||||||
ret = io_reg_set(PX4IO_PAGE_FAILSAFE_PWM, 0, pwm->values, pwm->channel_count);
|
ret = io_reg_set(PX4IO_PAGE_FAILSAFE_PWM, 0, pwm->values, pwm->channel_count);
|
||||||
@@ -2217,7 +2219,7 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
|
|||||||
struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
|
struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
|
||||||
if (pwm->channel_count > _max_actuators)
|
if (pwm->channel_count > _max_actuators)
|
||||||
/* fail with error */
|
/* fail with error */
|
||||||
return E2BIG;
|
return -E2BIG;
|
||||||
|
|
||||||
/* copy values to registers in IO */
|
/* copy values to registers in IO */
|
||||||
ret = io_reg_set(PX4IO_PAGE_DISARMED_PWM, 0, pwm->values, pwm->channel_count);
|
ret = io_reg_set(PX4IO_PAGE_DISARMED_PWM, 0, pwm->values, pwm->channel_count);
|
||||||
@@ -2236,7 +2238,7 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
|
|||||||
struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
|
struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
|
||||||
if (pwm->channel_count > _max_actuators)
|
if (pwm->channel_count > _max_actuators)
|
||||||
/* fail with error */
|
/* fail with error */
|
||||||
return E2BIG;
|
return -E2BIG;
|
||||||
|
|
||||||
/* copy values to registers in IO */
|
/* copy values to registers in IO */
|
||||||
ret = io_reg_set(PX4IO_PAGE_CONTROL_MIN_PWM, 0, pwm->values, pwm->channel_count);
|
ret = io_reg_set(PX4IO_PAGE_CONTROL_MIN_PWM, 0, pwm->values, pwm->channel_count);
|
||||||
@@ -2255,7 +2257,7 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
|
|||||||
struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
|
struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
|
||||||
if (pwm->channel_count > _max_actuators)
|
if (pwm->channel_count > _max_actuators)
|
||||||
/* fail with error */
|
/* fail with error */
|
||||||
return E2BIG;
|
return -E2BIG;
|
||||||
|
|
||||||
/* copy values to registers in IO */
|
/* copy values to registers in IO */
|
||||||
ret = io_reg_set(PX4IO_PAGE_CONTROL_MAX_PWM, 0, pwm->values, pwm->channel_count);
|
ret = io_reg_set(PX4IO_PAGE_CONTROL_MAX_PWM, 0, pwm->values, pwm->channel_count);
|
||||||
@@ -2592,9 +2594,9 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
|
|||||||
on param_get()
|
on param_get()
|
||||||
*/
|
*/
|
||||||
struct pwm_output_rc_config* config = (struct pwm_output_rc_config*)arg;
|
struct pwm_output_rc_config* config = (struct pwm_output_rc_config*)arg;
|
||||||
if (config->channel >= _max_actuators) {
|
if (config->channel >= RC_INPUT_MAX_CHANNELS) {
|
||||||
/* fail with error */
|
/* fail with error */
|
||||||
return E2BIG;
|
return -E2BIG;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* copy values to registers in IO */
|
/* copy values to registers in IO */
|
||||||
|
|||||||
@@ -0,0 +1,44 @@
|
|||||||
|
############################################################################
|
||||||
|
#
|
||||||
|
# Copyright (c) 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.
|
||||||
|
#
|
||||||
|
############################################################################
|
||||||
|
|
||||||
|
#
|
||||||
|
# Makefile to build the TeraRanger One range finder driver
|
||||||
|
#
|
||||||
|
|
||||||
|
MODULE_COMMAND = trone
|
||||||
|
|
||||||
|
SRCS = trone.cpp
|
||||||
|
|
||||||
|
MODULE_STACKSIZE = 1200
|
||||||
|
|
||||||
|
MAXOPTIMIZATION = -Os
|
||||||
File diff suppressed because it is too large
Load Diff
@@ -308,8 +308,8 @@ int flow_position_estimator_thread_main(int argc, char *argv[])
|
|||||||
if (vehicle_liftoff || params.debug)
|
if (vehicle_liftoff || params.debug)
|
||||||
{
|
{
|
||||||
/* copy flow */
|
/* copy flow */
|
||||||
flow_speed[0] = flow.flow_comp_x_m;
|
flow_speed[0] = flow.pixel_flow_x_integral / (flow.integration_timespan / 1e6f) * flow.ground_distance_m;
|
||||||
flow_speed[1] = flow.flow_comp_y_m;
|
flow_speed[1] = flow.pixel_flow_y_integral / (flow.integration_timespan / 1e6f) * flow.ground_distance_m;
|
||||||
flow_speed[2] = 0.0f;
|
flow_speed[2] = 0.0f;
|
||||||
|
|
||||||
/* convert to bodyframe velocity */
|
/* convert to bodyframe velocity */
|
||||||
|
|||||||
@@ -1405,7 +1405,7 @@ Mavlink::task_main(int argc, char *argv[])
|
|||||||
configure_stream("POSITION_TARGET_GLOBAL_INT", 3.0f);
|
configure_stream("POSITION_TARGET_GLOBAL_INT", 3.0f);
|
||||||
configure_stream("ATTITUDE_TARGET", 3.0f);
|
configure_stream("ATTITUDE_TARGET", 3.0f);
|
||||||
configure_stream("DISTANCE_SENSOR", 0.5f);
|
configure_stream("DISTANCE_SENSOR", 0.5f);
|
||||||
configure_stream("OPTICAL_FLOW", 5.0f);
|
configure_stream("OPTICAL_FLOW_RAD", 5.0f);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAVLINK_MODE_ONBOARD:
|
case MAVLINK_MODE_ONBOARD:
|
||||||
|
|||||||
@@ -1834,33 +1834,32 @@ protected:
|
|||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
class MavlinkStreamOpticalFlowRad : public MavlinkStream
|
||||||
class MavlinkStreamOpticalFlow : public MavlinkStream
|
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
const char *get_name() const
|
const char *get_name() const
|
||||||
{
|
{
|
||||||
return MavlinkStreamOpticalFlow::get_name_static();
|
return MavlinkStreamOpticalFlowRad::get_name_static();
|
||||||
}
|
}
|
||||||
|
|
||||||
static const char *get_name_static()
|
static const char *get_name_static()
|
||||||
{
|
{
|
||||||
return "OPTICAL_FLOW";
|
return "OPTICAL_FLOW_RAD";
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t get_id()
|
uint8_t get_id()
|
||||||
{
|
{
|
||||||
return MAVLINK_MSG_ID_OPTICAL_FLOW;
|
return MAVLINK_MSG_ID_OPTICAL_FLOW_RAD;
|
||||||
}
|
}
|
||||||
|
|
||||||
static MavlinkStream *new_instance(Mavlink *mavlink)
|
static MavlinkStream *new_instance(Mavlink *mavlink)
|
||||||
{
|
{
|
||||||
return new MavlinkStreamOpticalFlow(mavlink);
|
return new MavlinkStreamOpticalFlowRad(mavlink);
|
||||||
}
|
}
|
||||||
|
|
||||||
unsigned get_size()
|
unsigned get_size()
|
||||||
{
|
{
|
||||||
return _flow_sub->is_published() ? (MAVLINK_MSG_ID_OPTICAL_FLOW_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0;
|
return _flow_sub->is_published() ? (MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
@@ -1868,11 +1867,11 @@ private:
|
|||||||
uint64_t _flow_time;
|
uint64_t _flow_time;
|
||||||
|
|
||||||
/* do not allow top copying this class */
|
/* do not allow top copying this class */
|
||||||
MavlinkStreamOpticalFlow(MavlinkStreamOpticalFlow &);
|
MavlinkStreamOpticalFlowRad(MavlinkStreamOpticalFlowRad &);
|
||||||
MavlinkStreamOpticalFlow& operator = (const MavlinkStreamOpticalFlow &);
|
MavlinkStreamOpticalFlowRad& operator = (const MavlinkStreamOpticalFlowRad &);
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
explicit MavlinkStreamOpticalFlow(Mavlink *mavlink) : MavlinkStream(mavlink),
|
explicit MavlinkStreamOpticalFlowRad(Mavlink *mavlink) : MavlinkStream(mavlink),
|
||||||
_flow_sub(_mavlink->add_orb_subscription(ORB_ID(optical_flow))),
|
_flow_sub(_mavlink->add_orb_subscription(ORB_ID(optical_flow))),
|
||||||
_flow_time(0)
|
_flow_time(0)
|
||||||
{}
|
{}
|
||||||
@@ -1882,18 +1881,23 @@ protected:
|
|||||||
struct optical_flow_s flow;
|
struct optical_flow_s flow;
|
||||||
|
|
||||||
if (_flow_sub->update(&_flow_time, &flow)) {
|
if (_flow_sub->update(&_flow_time, &flow)) {
|
||||||
mavlink_optical_flow_t msg;
|
mavlink_optical_flow_rad_t msg;
|
||||||
|
|
||||||
msg.time_usec = flow.timestamp;
|
msg.time_usec = flow.timestamp;
|
||||||
msg.sensor_id = flow.sensor_id;
|
msg.sensor_id = flow.sensor_id;
|
||||||
msg.flow_x = flow.flow_raw_x;
|
msg.integrated_x = flow.pixel_flow_x_integral;
|
||||||
msg.flow_y = flow.flow_raw_y;
|
msg.integrated_y = flow.pixel_flow_y_integral;
|
||||||
msg.flow_comp_m_x = flow.flow_comp_x_m;
|
msg.integrated_xgyro = flow.gyro_x_rate_integral;
|
||||||
msg.flow_comp_m_y = flow.flow_comp_y_m;
|
msg.integrated_ygyro = flow.gyro_y_rate_integral;
|
||||||
|
msg.integrated_zgyro = flow.gyro_z_rate_integral;
|
||||||
|
msg.distance = flow.ground_distance_m;
|
||||||
msg.quality = flow.quality;
|
msg.quality = flow.quality;
|
||||||
msg.ground_distance = flow.ground_distance_m;
|
msg.integration_time_us = flow.integration_timespan;
|
||||||
|
msg.sensor_id = flow.sensor_id;
|
||||||
|
msg.time_delta_distance_us = flow.time_since_last_sonar_update;
|
||||||
|
msg.temperature = flow.gyro_temperature;
|
||||||
|
|
||||||
_mavlink->send_message(MAVLINK_MSG_ID_OPTICAL_FLOW, &msg);
|
_mavlink->send_message(MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, &msg);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
@@ -2199,7 +2203,7 @@ StreamListItem *streams_list[] = {
|
|||||||
new StreamListItem(&MavlinkStreamAttitudeTarget::new_instance, &MavlinkStreamAttitudeTarget::get_name_static),
|
new StreamListItem(&MavlinkStreamAttitudeTarget::new_instance, &MavlinkStreamAttitudeTarget::get_name_static),
|
||||||
new StreamListItem(&MavlinkStreamRCChannelsRaw::new_instance, &MavlinkStreamRCChannelsRaw::get_name_static),
|
new StreamListItem(&MavlinkStreamRCChannelsRaw::new_instance, &MavlinkStreamRCChannelsRaw::get_name_static),
|
||||||
new StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static),
|
new StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static),
|
||||||
new StreamListItem(&MavlinkStreamOpticalFlow::new_instance, &MavlinkStreamOpticalFlow::get_name_static),
|
new StreamListItem(&MavlinkStreamOpticalFlowRad::new_instance, &MavlinkStreamOpticalFlowRad::get_name_static),
|
||||||
new StreamListItem(&MavlinkStreamAttitudeControls::new_instance, &MavlinkStreamAttitudeControls::get_name_static),
|
new StreamListItem(&MavlinkStreamAttitudeControls::new_instance, &MavlinkStreamAttitudeControls::get_name_static),
|
||||||
new StreamListItem(&MavlinkStreamNamedValueFloat::new_instance, &MavlinkStreamNamedValueFloat::get_name_static),
|
new StreamListItem(&MavlinkStreamNamedValueFloat::new_instance, &MavlinkStreamNamedValueFloat::get_name_static),
|
||||||
new StreamListItem(&MavlinkStreamCameraCapture::new_instance, &MavlinkStreamCameraCapture::get_name_static),
|
new StreamListItem(&MavlinkStreamCameraCapture::new_instance, &MavlinkStreamCameraCapture::get_name_static),
|
||||||
|
|||||||
@@ -144,8 +144,8 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
|
|||||||
handle_message_command_int(msg);
|
handle_message_command_int(msg);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_OPTICAL_FLOW:
|
case MAVLINK_MSG_ID_OPTICAL_FLOW_RAD:
|
||||||
handle_message_optical_flow(msg);
|
handle_message_optical_flow_rad(msg);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_SET_MODE:
|
case MAVLINK_MSG_ID_SET_MODE:
|
||||||
@@ -352,24 +352,27 @@ MavlinkReceiver::handle_message_command_int(mavlink_message_t *msg)
|
|||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
MavlinkReceiver::handle_message_optical_flow(mavlink_message_t *msg)
|
MavlinkReceiver::handle_message_optical_flow_rad(mavlink_message_t *msg)
|
||||||
{
|
{
|
||||||
/* optical flow */
|
/* optical flow */
|
||||||
mavlink_optical_flow_t flow;
|
mavlink_optical_flow_rad_t flow;
|
||||||
mavlink_msg_optical_flow_decode(msg, &flow);
|
mavlink_msg_optical_flow_rad_decode(msg, &flow);
|
||||||
|
|
||||||
struct optical_flow_s f;
|
struct optical_flow_s f;
|
||||||
memset(&f, 0, sizeof(f));
|
memset(&f, 0, sizeof(f));
|
||||||
|
|
||||||
f.timestamp = hrt_absolute_time();
|
f.timestamp = flow.time_usec;
|
||||||
f.flow_timestamp = flow.time_usec;
|
f.integration_timespan = flow.integration_time_us;
|
||||||
f.flow_raw_x = flow.flow_x;
|
f.pixel_flow_x_integral = flow.integrated_x;
|
||||||
f.flow_raw_y = flow.flow_y;
|
f.pixel_flow_y_integral = flow.integrated_y;
|
||||||
f.flow_comp_x_m = flow.flow_comp_m_x;
|
f.gyro_x_rate_integral = flow.integrated_xgyro;
|
||||||
f.flow_comp_y_m = flow.flow_comp_m_y;
|
f.gyro_y_rate_integral = flow.integrated_ygyro;
|
||||||
f.ground_distance_m = flow.ground_distance;
|
f.gyro_z_rate_integral = flow.integrated_zgyro;
|
||||||
|
f.time_since_last_sonar_update = flow.time_delta_distance_us;
|
||||||
|
f.ground_distance_m = flow.distance;
|
||||||
f.quality = flow.quality;
|
f.quality = flow.quality;
|
||||||
f.sensor_id = flow.sensor_id;
|
f.sensor_id = flow.sensor_id;
|
||||||
|
f.gyro_temperature = flow.temperature;
|
||||||
|
|
||||||
if (_flow_pub < 0) {
|
if (_flow_pub < 0) {
|
||||||
_flow_pub = orb_advertise(ORB_ID(optical_flow), &f);
|
_flow_pub = orb_advertise(ORB_ID(optical_flow), &f);
|
||||||
@@ -389,13 +392,18 @@ MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg)
|
|||||||
struct optical_flow_s f;
|
struct optical_flow_s f;
|
||||||
memset(&f, 0, sizeof(f));
|
memset(&f, 0, sizeof(f));
|
||||||
|
|
||||||
f.timestamp = hrt_absolute_time();
|
f.timestamp = hrt_absolute_time(); // XXX we rely on the system time for now and not flow.time_usec;
|
||||||
f.flow_timestamp = flow.time_usec;
|
f.integration_timespan = flow.integration_time_us;
|
||||||
f.flow_raw_x = flow.integrated_x;
|
f.pixel_flow_x_integral = flow.integrated_x;
|
||||||
f.flow_raw_y = flow.integrated_y;
|
f.pixel_flow_y_integral = flow.integrated_y;
|
||||||
|
f.gyro_x_rate_integral = flow.integrated_xgyro;
|
||||||
|
f.gyro_y_rate_integral = flow.integrated_ygyro;
|
||||||
|
f.gyro_z_rate_integral = flow.integrated_zgyro;
|
||||||
|
f.time_since_last_sonar_update = flow.time_delta_distance_us;
|
||||||
f.ground_distance_m = flow.distance;
|
f.ground_distance_m = flow.distance;
|
||||||
f.quality = flow.quality;
|
f.quality = flow.quality;
|
||||||
f.sensor_id = flow.sensor_id;
|
f.sensor_id = flow.sensor_id;
|
||||||
|
f.gyro_temperature = flow.temperature;
|
||||||
|
|
||||||
if (_flow_pub < 0) {
|
if (_flow_pub < 0) {
|
||||||
_flow_pub = orb_advertise(ORB_ID(optical_flow), &f);
|
_flow_pub = orb_advertise(ORB_ID(optical_flow), &f);
|
||||||
|
|||||||
@@ -112,7 +112,7 @@ private:
|
|||||||
void handle_message(mavlink_message_t *msg);
|
void handle_message(mavlink_message_t *msg);
|
||||||
void handle_message_command_long(mavlink_message_t *msg);
|
void handle_message_command_long(mavlink_message_t *msg);
|
||||||
void handle_message_command_int(mavlink_message_t *msg);
|
void handle_message_command_int(mavlink_message_t *msg);
|
||||||
void handle_message_optical_flow(mavlink_message_t *msg);
|
void handle_message_optical_flow_rad(mavlink_message_t *msg);
|
||||||
void handle_message_hil_optical_flow(mavlink_message_t *msg);
|
void handle_message_hil_optical_flow(mavlink_message_t *msg);
|
||||||
void handle_message_set_mode(mavlink_message_t *msg);
|
void handle_message_set_mode(mavlink_message_t *msg);
|
||||||
void handle_message_vicon_position_estimate(mavlink_message_t *msg);
|
void handle_message_vicon_position_estimate(mavlink_message_t *msg);
|
||||||
|
|||||||
@@ -296,7 +296,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
|||||||
float w_flow = 0.0f;
|
float w_flow = 0.0f;
|
||||||
|
|
||||||
float sonar_prev = 0.0f;
|
float sonar_prev = 0.0f;
|
||||||
hrt_abstime flow_prev = 0; // time of last flow measurement
|
//hrt_abstime flow_prev = 0; // time of last flow measurement
|
||||||
hrt_abstime sonar_time = 0; // time of last sonar measurement (not filtered)
|
hrt_abstime sonar_time = 0; // time of last sonar measurement (not filtered)
|
||||||
hrt_abstime sonar_valid_time = 0; // time of last sonar measurement used for correction (filtered)
|
hrt_abstime sonar_valid_time = 0; // time of last sonar measurement used for correction (filtered)
|
||||||
|
|
||||||
@@ -489,8 +489,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
|||||||
orb_copy(ORB_ID(optical_flow), optical_flow_sub, &flow);
|
orb_copy(ORB_ID(optical_flow), optical_flow_sub, &flow);
|
||||||
|
|
||||||
/* calculate time from previous update */
|
/* calculate time from previous update */
|
||||||
float flow_dt = flow_prev > 0 ? (flow.flow_timestamp - flow_prev) * 1e-6f : 0.1f;
|
// float flow_dt = flow_prev > 0 ? (flow.flow_timestamp - flow_prev) * 1e-6f : 0.1f;
|
||||||
flow_prev = flow.flow_timestamp;
|
// flow_prev = flow.flow_timestamp;
|
||||||
|
|
||||||
if ((flow.ground_distance_m > 0.31f) &&
|
if ((flow.ground_distance_m > 0.31f) &&
|
||||||
(flow.ground_distance_m < 4.0f) &&
|
(flow.ground_distance_m < 4.0f) &&
|
||||||
@@ -548,8 +548,9 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
|||||||
|
|
||||||
/* convert raw flow to angular flow (rad/s) */
|
/* convert raw flow to angular flow (rad/s) */
|
||||||
float flow_ang[2];
|
float flow_ang[2];
|
||||||
flow_ang[0] = flow.flow_raw_x * params.flow_k / 1000.0f / flow_dt;
|
//todo check direction of x und y axis
|
||||||
flow_ang[1] = flow.flow_raw_y * params.flow_k / 1000.0f / flow_dt;
|
flow_ang[0] = flow.pixel_flow_x_integral/(float)flow.integration_timespan*1000000.0f;//flow.flow_raw_x * params.flow_k / 1000.0f / flow_dt;
|
||||||
|
flow_ang[1] = flow.pixel_flow_y_integral/(float)flow.integration_timespan*1000000.0f;//flow.flow_raw_y * params.flow_k / 1000.0f / flow_dt;
|
||||||
/* flow measurements vector */
|
/* flow measurements vector */
|
||||||
float flow_m[3];
|
float flow_m[3];
|
||||||
flow_m[0] = -flow_ang[0] * flow_dist;
|
flow_m[0] = -flow_ang[0] * flow_dist;
|
||||||
|
|||||||
@@ -412,7 +412,6 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
|
|||||||
* text handling function.
|
* text handling function.
|
||||||
*/
|
*/
|
||||||
return mixer_handle_text(values, num_values * sizeof(*values));
|
return mixer_handle_text(values, num_values * sizeof(*values));
|
||||||
break;
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
/* avoid offset wrap */
|
/* avoid offset wrap */
|
||||||
@@ -584,10 +583,7 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case PX4IO_P_SETUP_REBOOT_BL:
|
case PX4IO_P_SETUP_REBOOT_BL:
|
||||||
// do not reboot if FMU is armed and IO's safety is off
|
if (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) {
|
||||||
// this state defines an active system.
|
|
||||||
if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) &&
|
|
||||||
(r_status_flags & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
|
|
||||||
// don't allow reboot while armed
|
// don't allow reboot while armed
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@@ -633,12 +629,9 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
|
|||||||
case PX4IO_PAGE_RC_CONFIG: {
|
case PX4IO_PAGE_RC_CONFIG: {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* do not allow a RC config change while outputs armed
|
* do not allow a RC config change while safety is off
|
||||||
* = FMU is armed and IO's safety is off
|
|
||||||
* this state defines an active system.
|
|
||||||
*/
|
*/
|
||||||
if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) &&
|
if (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) {
|
||||||
(r_status_flags & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -1518,11 +1518,14 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|||||||
/* --- FLOW --- */
|
/* --- FLOW --- */
|
||||||
if (copy_if_updated(ORB_ID(optical_flow), subs.flow_sub, &buf.flow)) {
|
if (copy_if_updated(ORB_ID(optical_flow), subs.flow_sub, &buf.flow)) {
|
||||||
log_msg.msg_type = LOG_FLOW_MSG;
|
log_msg.msg_type = LOG_FLOW_MSG;
|
||||||
log_msg.body.log_FLOW.flow_raw_x = buf.flow.flow_raw_x;
|
log_msg.body.log_FLOW.ground_distance_m = buf.flow.ground_distance_m;
|
||||||
log_msg.body.log_FLOW.flow_raw_y = buf.flow.flow_raw_y;
|
log_msg.body.log_FLOW.gyro_temperature = buf.flow.gyro_temperature;
|
||||||
log_msg.body.log_FLOW.flow_comp_x = buf.flow.flow_comp_x_m;
|
log_msg.body.log_FLOW.gyro_x_rate_integral = buf.flow.gyro_x_rate_integral;
|
||||||
log_msg.body.log_FLOW.flow_comp_y = buf.flow.flow_comp_y_m;
|
log_msg.body.log_FLOW.gyro_y_rate_integral = buf.flow.gyro_y_rate_integral;
|
||||||
log_msg.body.log_FLOW.distance = buf.flow.ground_distance_m;
|
log_msg.body.log_FLOW.gyro_z_rate_integral = buf.flow.gyro_z_rate_integral;
|
||||||
|
log_msg.body.log_FLOW.integration_timespan = buf.flow.integration_timespan;
|
||||||
|
log_msg.body.log_FLOW.pixel_flow_x_integral = buf.flow.pixel_flow_x_integral;
|
||||||
|
log_msg.body.log_FLOW.pixel_flow_y_integral = buf.flow.pixel_flow_y_integral;
|
||||||
log_msg.body.log_FLOW.quality = buf.flow.quality;
|
log_msg.body.log_FLOW.quality = buf.flow.quality;
|
||||||
log_msg.body.log_FLOW.sensor_id = buf.flow.sensor_id;
|
log_msg.body.log_FLOW.sensor_id = buf.flow.sensor_id;
|
||||||
LOGBUFFER_WRITE_AND_COUNT(FLOW);
|
LOGBUFFER_WRITE_AND_COUNT(FLOW);
|
||||||
|
|||||||
@@ -200,13 +200,19 @@ struct log_ARSP_s {
|
|||||||
/* --- FLOW - OPTICAL FLOW --- */
|
/* --- FLOW - OPTICAL FLOW --- */
|
||||||
#define LOG_FLOW_MSG 15
|
#define LOG_FLOW_MSG 15
|
||||||
struct log_FLOW_s {
|
struct log_FLOW_s {
|
||||||
int16_t flow_raw_x;
|
uint64_t timestamp;
|
||||||
int16_t flow_raw_y;
|
|
||||||
float flow_comp_x;
|
|
||||||
float flow_comp_y;
|
|
||||||
float distance;
|
|
||||||
uint8_t quality;
|
|
||||||
uint8_t sensor_id;
|
uint8_t sensor_id;
|
||||||
|
float pixel_flow_x_integral;
|
||||||
|
float pixel_flow_y_integral;
|
||||||
|
float gyro_x_rate_integral;
|
||||||
|
float gyro_y_rate_integral;
|
||||||
|
float gyro_z_rate_integral;
|
||||||
|
float ground_distance_m;
|
||||||
|
uint32_t integration_timespan;
|
||||||
|
uint32_t time_since_last_sonar_update;
|
||||||
|
uint16_t frame_count_since_last_readout;
|
||||||
|
int16_t gyro_temperature;
|
||||||
|
uint8_t quality;
|
||||||
};
|
};
|
||||||
|
|
||||||
/* --- GPOS - GLOBAL POSITION ESTIMATE --- */
|
/* --- GPOS - GLOBAL POSITION ESTIMATE --- */
|
||||||
|
|||||||
@@ -46,6 +46,7 @@
|
|||||||
#include "topics/vehicle_attitude_setpoint.h"
|
#include "topics/vehicle_attitude_setpoint.h"
|
||||||
#include "topics/vehicle_rates_setpoint.h"
|
#include "topics/vehicle_rates_setpoint.h"
|
||||||
#include "topics/actuator_outputs.h"
|
#include "topics/actuator_outputs.h"
|
||||||
|
#include "topics/actuator_direct.h"
|
||||||
#include "topics/encoders.h"
|
#include "topics/encoders.h"
|
||||||
#include "topics/tecs_status.h"
|
#include "topics/tecs_status.h"
|
||||||
#include "topics/rc_channels.h"
|
#include "topics/rc_channels.h"
|
||||||
@@ -77,6 +78,7 @@ template class __EXPORT Publication<vehicle_global_velocity_setpoint_s>;
|
|||||||
template class __EXPORT Publication<vehicle_attitude_setpoint_s>;
|
template class __EXPORT Publication<vehicle_attitude_setpoint_s>;
|
||||||
template class __EXPORT Publication<vehicle_rates_setpoint_s>;
|
template class __EXPORT Publication<vehicle_rates_setpoint_s>;
|
||||||
template class __EXPORT Publication<actuator_outputs_s>;
|
template class __EXPORT Publication<actuator_outputs_s>;
|
||||||
|
template class __EXPORT Publication<actuator_direct_s>;
|
||||||
template class __EXPORT Publication<encoders_s>;
|
template class __EXPORT Publication<encoders_s>;
|
||||||
template class __EXPORT Publication<tecs_status_s>;
|
template class __EXPORT Publication<tecs_status_s>;
|
||||||
template class __EXPORT Publication<rc_channels_s>;
|
template class __EXPORT Publication<rc_channels_s>;
|
||||||
|
|||||||
@@ -192,6 +192,9 @@ ORB_DEFINE(actuator_outputs_1, struct actuator_outputs_s);
|
|||||||
ORB_DEFINE(actuator_outputs_2, struct actuator_outputs_s);
|
ORB_DEFINE(actuator_outputs_2, struct actuator_outputs_s);
|
||||||
ORB_DEFINE(actuator_outputs_3, struct actuator_outputs_s);
|
ORB_DEFINE(actuator_outputs_3, struct actuator_outputs_s);
|
||||||
|
|
||||||
|
#include "topics/actuator_direct.h"
|
||||||
|
ORB_DEFINE(actuator_direct, struct actuator_direct_s);
|
||||||
|
|
||||||
#include "topics/multirotor_motor_limits.h"
|
#include "topics/multirotor_motor_limits.h"
|
||||||
ORB_DEFINE(multirotor_motor_limits, struct multirotor_motor_limits_s);
|
ORB_DEFINE(multirotor_motor_limits, struct multirotor_motor_limits_s);
|
||||||
|
|
||||||
|
|||||||
@@ -0,0 +1,69 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2012 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 actuator_direct.h
|
||||||
|
*
|
||||||
|
* Actuator direct values.
|
||||||
|
*
|
||||||
|
* Values published to this topic are the direct actuator values which
|
||||||
|
* should be passed to actuators, bypassing mixing
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef TOPIC_ACTUATOR_DIRECT_H
|
||||||
|
#define TOPIC_ACTUATOR_DIRECT_H
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include "../uORB.h"
|
||||||
|
|
||||||
|
#define NUM_ACTUATORS_DIRECT 16
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @addtogroup topics
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
struct actuator_direct_s {
|
||||||
|
uint64_t timestamp; /**< timestamp in us since system boot */
|
||||||
|
float values[NUM_ACTUATORS_DIRECT]; /**< actuator values, from -1 to 1 */
|
||||||
|
unsigned nvalues; /**< number of valid values */
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* actuator direct ORB */
|
||||||
|
ORB_DECLARE(actuator_direct);
|
||||||
|
|
||||||
|
#endif // TOPIC_ACTUATOR_DIRECT_H
|
||||||
@@ -56,15 +56,21 @@
|
|||||||
struct optical_flow_s {
|
struct optical_flow_s {
|
||||||
|
|
||||||
uint64_t timestamp; /**< in microseconds since system start */
|
uint64_t timestamp; /**< in microseconds since system start */
|
||||||
|
|
||||||
uint64_t flow_timestamp; /**< timestamp from flow sensor */
|
|
||||||
int16_t flow_raw_x; /**< flow in pixels in X direction, not rotation-compensated */
|
|
||||||
int16_t flow_raw_y; /**< flow in pixels in Y direction, not rotation-compensated */
|
|
||||||
float flow_comp_x_m; /**< speed over ground in meters, rotation-compensated */
|
|
||||||
float flow_comp_y_m; /**< speed over ground in meters, rotation-compensated */
|
|
||||||
float ground_distance_m; /**< Altitude / distance to ground in meters */
|
|
||||||
uint8_t quality; /**< Quality of the measurement, 0: bad quality, 255: maximum quality */
|
|
||||||
uint8_t sensor_id; /**< id of the sensor emitting the flow value */
|
uint8_t sensor_id; /**< id of the sensor emitting the flow value */
|
||||||
|
float pixel_flow_x_integral; /**< accumulated optical flow in radians around x axis */
|
||||||
|
float pixel_flow_y_integral; /**< accumulated optical flow in radians around y axis */
|
||||||
|
float gyro_x_rate_integral; /**< accumulated gyro value in radians around x axis */
|
||||||
|
float gyro_y_rate_integral; /**< accumulated gyro value in radians around y axis */
|
||||||
|
float gyro_z_rate_integral; /**< accumulated gyro value in radians around z axis */
|
||||||
|
float ground_distance_m; /**< Altitude / distance to ground in meters */
|
||||||
|
uint32_t integration_timespan; /**<accumulation timespan in microseconds */
|
||||||
|
uint32_t time_since_last_sonar_update;/**< time since last sonar update in microseconds */
|
||||||
|
uint16_t frame_count_since_last_readout;/**< number of accumulated frames in timespan */
|
||||||
|
int16_t gyro_temperature;/**< Temperature * 100 in centi-degrees Celsius */
|
||||||
|
uint8_t quality; /**< Average of quality of accumulated frames, 0: bad quality, 255: maximum quality */
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -76,7 +76,9 @@ int UavcanEscController::init()
|
|||||||
|
|
||||||
void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs)
|
void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs)
|
||||||
{
|
{
|
||||||
if ((outputs == nullptr) || (num_outputs > uavcan::equipment::esc::RawCommand::FieldTypes::cmd::MaxSize)) {
|
if ((outputs == nullptr) ||
|
||||||
|
(num_outputs > uavcan::equipment::esc::RawCommand::FieldTypes::cmd::MaxSize) ||
|
||||||
|
(num_outputs > CONNECTED_ESC_MAX)) {
|
||||||
perf_count(_perfcnt_invalid_input);
|
perf_count(_perfcnt_invalid_input);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@@ -101,10 +103,15 @@ void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs)
|
|||||||
for (unsigned i = 0; i < num_outputs; i++) {
|
for (unsigned i = 0; i < num_outputs; i++) {
|
||||||
if (_armed_mask & MOTOR_BIT(i)) {
|
if (_armed_mask & MOTOR_BIT(i)) {
|
||||||
float scaled = (outputs[i] + 1.0F) * 0.5F * cmd_max;
|
float scaled = (outputs[i] + 1.0F) * 0.5F * cmd_max;
|
||||||
if (scaled < 1.0F) {
|
// trim negative values back to 0. Previously
|
||||||
scaled = 1.0F; // Since we're armed, we don't want to stop it completely
|
// we set this to 0.1, which meant motors kept
|
||||||
|
// spinning when armed, but that should be a
|
||||||
|
// policy decision for a specific vehicle
|
||||||
|
// type, as it is not appropriate for all
|
||||||
|
// types of vehicles (eg. fixed wing).
|
||||||
|
if (scaled < 0.0F) {
|
||||||
|
scaled = 0.0F;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (scaled > cmd_max) {
|
if (scaled > cmd_max) {
|
||||||
scaled = cmd_max;
|
scaled = cmd_max;
|
||||||
perf_count(_perfcnt_scaling_error);
|
perf_count(_perfcnt_scaling_error);
|
||||||
|
|||||||
@@ -269,6 +269,24 @@ void UavcanNode::node_spin_once()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
add a fd to the list of polled events. This assumes you want
|
||||||
|
POLLIN for now.
|
||||||
|
*/
|
||||||
|
int UavcanNode::add_poll_fd(int fd)
|
||||||
|
{
|
||||||
|
int ret = _poll_fds_num;
|
||||||
|
if (_poll_fds_num >= UAVCAN_NUM_POLL_FDS) {
|
||||||
|
errx(1, "uavcan: too many poll fds, exiting");
|
||||||
|
}
|
||||||
|
_poll_fds[_poll_fds_num] = ::pollfd();
|
||||||
|
_poll_fds[_poll_fds_num].fd = fd;
|
||||||
|
_poll_fds[_poll_fds_num].events = POLLIN;
|
||||||
|
_poll_fds_num += 1;
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
int UavcanNode::run()
|
int UavcanNode::run()
|
||||||
{
|
{
|
||||||
(void)pthread_mutex_lock(&_node_mutex);
|
(void)pthread_mutex_lock(&_node_mutex);
|
||||||
@@ -280,9 +298,9 @@ int UavcanNode::run()
|
|||||||
|
|
||||||
_armed_sub = orb_subscribe(ORB_ID(actuator_armed));
|
_armed_sub = orb_subscribe(ORB_ID(actuator_armed));
|
||||||
_test_motor_sub = orb_subscribe(ORB_ID(test_motor));
|
_test_motor_sub = orb_subscribe(ORB_ID(test_motor));
|
||||||
|
_actuator_direct_sub = orb_subscribe(ORB_ID(actuator_direct));
|
||||||
|
|
||||||
actuator_outputs_s outputs;
|
memset(&_outputs, 0, sizeof(_outputs));
|
||||||
memset(&outputs, 0, sizeof(outputs));
|
|
||||||
|
|
||||||
const int busevent_fd = ::open(uavcan_stm32::BusEvent::DevName, 0);
|
const int busevent_fd = ::open(uavcan_stm32::BusEvent::DevName, 0);
|
||||||
if (busevent_fd < 0)
|
if (busevent_fd < 0)
|
||||||
@@ -304,11 +322,15 @@ int UavcanNode::run()
|
|||||||
* the value returned from poll() to detect whether actuator control has timed out or not.
|
* the value returned from poll() to detect whether actuator control has timed out or not.
|
||||||
* Instead, all ORB events need to be checked individually (see below).
|
* Instead, all ORB events need to be checked individually (see below).
|
||||||
*/
|
*/
|
||||||
_poll_fds_num = 0;
|
add_poll_fd(busevent_fd);
|
||||||
_poll_fds[_poll_fds_num] = ::pollfd();
|
|
||||||
_poll_fds[_poll_fds_num].fd = busevent_fd;
|
/*
|
||||||
_poll_fds[_poll_fds_num].events = POLLIN;
|
* setup poll to look for actuator direct input if we are
|
||||||
_poll_fds_num += 1;
|
* subscribed to the topic
|
||||||
|
*/
|
||||||
|
if (_actuator_direct_sub != -1) {
|
||||||
|
_actuator_direct_poll_fd_num = add_poll_fd(_actuator_direct_sub);
|
||||||
|
}
|
||||||
|
|
||||||
while (!_task_should_exit) {
|
while (!_task_should_exit) {
|
||||||
// update actuator controls subscriptions if needed
|
// update actuator controls subscriptions if needed
|
||||||
@@ -326,6 +348,8 @@ int UavcanNode::run()
|
|||||||
|
|
||||||
node_spin_once(); // Non-blocking
|
node_spin_once(); // Non-blocking
|
||||||
|
|
||||||
|
bool new_output = false;
|
||||||
|
|
||||||
// this would be bad...
|
// this would be bad...
|
||||||
if (poll_ret < 0) {
|
if (poll_ret < 0) {
|
||||||
log("poll error %d", errno);
|
log("poll error %d", errno);
|
||||||
@@ -333,24 +357,39 @@ int UavcanNode::run()
|
|||||||
} else {
|
} else {
|
||||||
// get controls for required topics
|
// get controls for required topics
|
||||||
bool controls_updated = false;
|
bool controls_updated = false;
|
||||||
unsigned poll_id = 1;
|
|
||||||
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
|
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
|
||||||
if (_control_subs[i] > 0) {
|
if (_control_subs[i] > 0) {
|
||||||
if (_poll_fds[poll_id].revents & POLLIN) {
|
if (_poll_fds[_poll_ids[i]].revents & POLLIN) {
|
||||||
controls_updated = true;
|
controls_updated = true;
|
||||||
orb_copy(_control_topics[i], _control_subs[i], &_controls[i]);
|
orb_copy(_control_topics[i], _control_subs[i], &_controls[i]);
|
||||||
}
|
}
|
||||||
poll_id++;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
see if we have any direct actuator updates
|
||||||
|
*/
|
||||||
|
if (_actuator_direct_sub != -1 &&
|
||||||
|
(_poll_fds[_actuator_direct_poll_fd_num].revents & POLLIN) &&
|
||||||
|
orb_copy(ORB_ID(actuator_direct), _actuator_direct_sub, &_actuator_direct) == OK &&
|
||||||
|
!_test_in_progress) {
|
||||||
|
if (_actuator_direct.nvalues > NUM_ACTUATOR_OUTPUTS) {
|
||||||
|
_actuator_direct.nvalues = NUM_ACTUATOR_OUTPUTS;
|
||||||
|
}
|
||||||
|
memcpy(&_outputs.output[0], &_actuator_direct.values[0],
|
||||||
|
_actuator_direct.nvalues*sizeof(float));
|
||||||
|
_outputs.noutputs = _actuator_direct.nvalues;
|
||||||
|
new_output = true;
|
||||||
|
}
|
||||||
|
|
||||||
// can we mix?
|
// can we mix?
|
||||||
if (_test_in_progress) {
|
if (_test_in_progress) {
|
||||||
float test_outputs[NUM_ACTUATOR_OUTPUTS] = {};
|
memset(&_outputs, 0, sizeof(_outputs));
|
||||||
test_outputs[_test_motor.motor_number] = _test_motor.value*2.0f-1.0f;
|
if (_test_motor.motor_number < NUM_ACTUATOR_OUTPUTS) {
|
||||||
|
_outputs.output[_test_motor.motor_number] = _test_motor.value*2.0f-1.0f;
|
||||||
// Output to the bus
|
_outputs.noutputs = _test_motor.motor_number+1;
|
||||||
_esc_controller.update_outputs(test_outputs, NUM_ACTUATOR_OUTPUTS);
|
}
|
||||||
|
new_output = true;
|
||||||
} else if (controls_updated && (_mixers != nullptr)) {
|
} else if (controls_updated && (_mixers != nullptr)) {
|
||||||
|
|
||||||
// XXX one output group has 8 outputs max,
|
// XXX one output group has 8 outputs max,
|
||||||
@@ -358,39 +397,41 @@ int UavcanNode::run()
|
|||||||
unsigned num_outputs_max = 8;
|
unsigned num_outputs_max = 8;
|
||||||
|
|
||||||
// Do mixing
|
// Do mixing
|
||||||
outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs_max);
|
_outputs.noutputs = _mixers->mix(&_outputs.output[0], num_outputs_max);
|
||||||
outputs.timestamp = hrt_absolute_time();
|
|
||||||
|
|
||||||
// iterate actuators
|
new_output = true;
|
||||||
for (unsigned i = 0; i < outputs.noutputs; i++) {
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (new_output) {
|
||||||
|
// iterate actuators, checking for valid values
|
||||||
|
for (uint8_t i = 0; i < _outputs.noutputs; i++) {
|
||||||
// last resort: catch NaN, INF and out-of-band errors
|
// last resort: catch NaN, INF and out-of-band errors
|
||||||
if (!isfinite(outputs.output[i])) {
|
if (!isfinite(_outputs.output[i])) {
|
||||||
/*
|
/*
|
||||||
* Value is NaN, INF or out of band - set to the minimum value.
|
* Value is NaN, INF or out of band - set to the minimum value.
|
||||||
* This will be clearly visible on the servo status and will limit the risk of accidentally
|
* This will be clearly visible on the servo status and will limit the risk of accidentally
|
||||||
* spinning motors. It would be deadly in flight.
|
* spinning motors. It would be deadly in flight.
|
||||||
*/
|
*/
|
||||||
outputs.output[i] = -1.0f;
|
_outputs.output[i] = -1.0f;
|
||||||
}
|
}
|
||||||
|
|
||||||
// limit outputs to valid range
|
|
||||||
|
|
||||||
// never go below min
|
// never go below min
|
||||||
if (outputs.output[i] < -1.0f) {
|
if (_outputs.output[i] < -1.0f) {
|
||||||
outputs.output[i] = -1.0f;
|
_outputs.output[i] = -1.0f;
|
||||||
}
|
}
|
||||||
|
|
||||||
// never go below max
|
// never go above max
|
||||||
if (outputs.output[i] > 1.0f) {
|
if (_outputs.output[i] > 1.0f) {
|
||||||
outputs.output[i] = 1.0f;
|
_outputs.output[i] = 1.0f;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Output to the bus
|
// Output to the bus
|
||||||
_esc_controller.update_outputs(outputs.output, outputs.noutputs);
|
_outputs.timestamp = hrt_absolute_time();
|
||||||
}
|
_esc_controller.update_outputs(_outputs.output, _outputs.noutputs);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Check motor test state
|
// Check motor test state
|
||||||
bool updated = false;
|
bool updated = false;
|
||||||
orb_check(_test_motor_sub, &updated);
|
orb_check(_test_motor_sub, &updated);
|
||||||
@@ -459,7 +500,6 @@ UavcanNode::subscribe()
|
|||||||
uint32_t sub_groups = _groups_required & ~_groups_subscribed;
|
uint32_t sub_groups = _groups_required & ~_groups_subscribed;
|
||||||
uint32_t unsub_groups = _groups_subscribed & ~_groups_required;
|
uint32_t unsub_groups = _groups_subscribed & ~_groups_required;
|
||||||
// the first fd used by CAN
|
// the first fd used by CAN
|
||||||
_poll_fds_num = 1;
|
|
||||||
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
|
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
|
||||||
if (sub_groups & (1 << i)) {
|
if (sub_groups & (1 << i)) {
|
||||||
warnx("subscribe to actuator_controls_%d", i);
|
warnx("subscribe to actuator_controls_%d", i);
|
||||||
@@ -472,9 +512,7 @@ UavcanNode::subscribe()
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (_control_subs[i] > 0) {
|
if (_control_subs[i] > 0) {
|
||||||
_poll_fds[_poll_fds_num].fd = _control_subs[i];
|
_poll_ids[i] = add_poll_fd(_control_subs[i]);
|
||||||
_poll_fds[_poll_fds_num].events = POLLIN;
|
|
||||||
_poll_fds_num++;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -572,6 +610,14 @@ UavcanNode::print_info()
|
|||||||
(unsigned)_groups_subscribed, (unsigned)_groups_required, _poll_fds_num);
|
(unsigned)_groups_subscribed, (unsigned)_groups_required, _poll_fds_num);
|
||||||
printf("ESC mixer: %s\n", (_mixers == nullptr) ? "NONE" : "OK");
|
printf("ESC mixer: %s\n", (_mixers == nullptr) ? "NONE" : "OK");
|
||||||
|
|
||||||
|
if (_outputs.noutputs != 0) {
|
||||||
|
printf("ESC output: ");
|
||||||
|
for (uint8_t i=0; i<_outputs.noutputs; i++) {
|
||||||
|
printf("%d ", (int)(_outputs.output[i]*1000));
|
||||||
|
}
|
||||||
|
printf("\n");
|
||||||
|
}
|
||||||
|
|
||||||
// Sensor bridges
|
// Sensor bridges
|
||||||
auto br = _sensor_bridges.getHead();
|
auto br = _sensor_bridges.getHead();
|
||||||
while (br != nullptr) {
|
while (br != nullptr) {
|
||||||
@@ -590,7 +636,7 @@ UavcanNode::print_info()
|
|||||||
static void print_usage()
|
static void print_usage()
|
||||||
{
|
{
|
||||||
warnx("usage: \n"
|
warnx("usage: \n"
|
||||||
"\tuavcan {start|status|stop}");
|
"\tuavcan {start|status|stop|arm|disarm}");
|
||||||
}
|
}
|
||||||
|
|
||||||
extern "C" __EXPORT int uavcan_main(int argc, char *argv[]);
|
extern "C" __EXPORT int uavcan_main(int argc, char *argv[]);
|
||||||
@@ -637,6 +683,16 @@ int uavcan_main(int argc, char *argv[])
|
|||||||
::exit(0);
|
::exit(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (!std::strcmp(argv[1], "arm")) {
|
||||||
|
inst->arm_actuators(true);
|
||||||
|
::exit(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!std::strcmp(argv[1], "disarm")) {
|
||||||
|
inst->arm_actuators(false);
|
||||||
|
::exit(0);
|
||||||
|
}
|
||||||
|
|
||||||
if (!std::strcmp(argv[1], "stop")) {
|
if (!std::strcmp(argv[1], "stop")) {
|
||||||
delete inst;
|
delete inst;
|
||||||
::exit(0);
|
::exit(0);
|
||||||
|
|||||||
@@ -42,6 +42,7 @@
|
|||||||
#include <uORB/topics/actuator_outputs.h>
|
#include <uORB/topics/actuator_outputs.h>
|
||||||
#include <uORB/topics/actuator_armed.h>
|
#include <uORB/topics/actuator_armed.h>
|
||||||
#include <uORB/topics/test_motor.h>
|
#include <uORB/topics/test_motor.h>
|
||||||
|
#include <uORB/topics/actuator_direct.h>
|
||||||
|
|
||||||
#include "actuators/esc.hpp"
|
#include "actuators/esc.hpp"
|
||||||
#include "sensors/sensor_bridge.hpp"
|
#include "sensors/sensor_bridge.hpp"
|
||||||
@@ -57,6 +58,9 @@
|
|||||||
#define NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN 4
|
#define NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN 4
|
||||||
#define UAVCAN_DEVICE_PATH "/dev/uavcan/esc"
|
#define UAVCAN_DEVICE_PATH "/dev/uavcan/esc"
|
||||||
|
|
||||||
|
// we add two to allow for actuator_direct and busevent
|
||||||
|
#define UAVCAN_NUM_POLL_FDS (NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN+2)
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* A UAVCAN node.
|
* A UAVCAN node.
|
||||||
*/
|
*/
|
||||||
@@ -97,6 +101,8 @@ private:
|
|||||||
int init(uavcan::NodeID node_id);
|
int init(uavcan::NodeID node_id);
|
||||||
void node_spin_once();
|
void node_spin_once();
|
||||||
int run();
|
int run();
|
||||||
|
int add_poll_fd(int fd); ///< add a fd to poll list, returning index into _poll_fds[]
|
||||||
|
|
||||||
|
|
||||||
int _task = -1; ///< handle to the OS task
|
int _task = -1; ///< handle to the OS task
|
||||||
bool _task_should_exit = false; ///< flag to indicate to tear down the CAN driver
|
bool _task_should_exit = false; ///< flag to indicate to tear down the CAN driver
|
||||||
@@ -125,6 +131,15 @@ private:
|
|||||||
int _control_subs[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {};
|
int _control_subs[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {};
|
||||||
actuator_controls_s _controls[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {};
|
actuator_controls_s _controls[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {};
|
||||||
orb_id_t _control_topics[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {};
|
orb_id_t _control_topics[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {};
|
||||||
pollfd _poll_fds[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN + 1] = {}; ///< +1 for /dev/uavcan/busevent
|
pollfd _poll_fds[UAVCAN_NUM_POLL_FDS] = {};
|
||||||
unsigned _poll_fds_num = 0;
|
unsigned _poll_fds_num = 0;
|
||||||
|
|
||||||
|
int _actuator_direct_sub = -1; ///< uORB subscription of the actuator_direct topic
|
||||||
|
uint8_t _actuator_direct_poll_fd_num;
|
||||||
|
actuator_direct_s _actuator_direct;
|
||||||
|
|
||||||
|
actuator_outputs_s _outputs;
|
||||||
|
|
||||||
|
// index into _poll_fds for each _control_subs handle
|
||||||
|
uint8_t _poll_ids[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN];
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -59,9 +59,10 @@ __EXPORT int motor_test_main(int argc, char *argv[]);
|
|||||||
static void motor_test(unsigned channel, float value);
|
static void motor_test(unsigned channel, float value);
|
||||||
static void usage(const char *reason);
|
static void usage(const char *reason);
|
||||||
|
|
||||||
|
static orb_advert_t _test_motor_pub;
|
||||||
|
|
||||||
void motor_test(unsigned channel, float value)
|
void motor_test(unsigned channel, float value)
|
||||||
{
|
{
|
||||||
orb_advert_t _test_motor_pub;
|
|
||||||
struct test_motor_s _test_motor;
|
struct test_motor_s _test_motor;
|
||||||
|
|
||||||
_test_motor.motor_number = channel;
|
_test_motor.motor_number = channel;
|
||||||
|
|||||||
@@ -0,0 +1,41 @@
|
|||||||
|
############################################################################
|
||||||
|
#
|
||||||
|
# Copyright (c) 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.
|
||||||
|
#
|
||||||
|
############################################################################
|
||||||
|
|
||||||
|
#
|
||||||
|
# Dump file utility
|
||||||
|
#
|
||||||
|
|
||||||
|
MODULE_COMMAND = reflect
|
||||||
|
SRCS = reflect.c
|
||||||
|
|
||||||
|
MAXOPTIMIZATION = -Os
|
||||||
@@ -0,0 +1,111 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (c) 2014 Andrew Tridgell. 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 reflect.c
|
||||||
|
*
|
||||||
|
* simple data reflector for load testing terminals (especially USB)
|
||||||
|
*
|
||||||
|
* @author Andrew Tridgell
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <nuttx/config.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <assert.h>
|
||||||
|
#include <systemlib/err.h>
|
||||||
|
|
||||||
|
__EXPORT int reflect_main(int argc, char *argv[]);
|
||||||
|
|
||||||
|
// memory corruption checking
|
||||||
|
#define MAX_BLOCKS 1000
|
||||||
|
static uint32_t nblocks;
|
||||||
|
struct block {
|
||||||
|
uint32_t v[256];
|
||||||
|
};
|
||||||
|
static struct block *blocks[MAX_BLOCKS];
|
||||||
|
|
||||||
|
#define VALUE(i) ((i*7) ^ 0xDEADBEEF)
|
||||||
|
|
||||||
|
static void allocate_blocks(void)
|
||||||
|
{
|
||||||
|
while (nblocks < MAX_BLOCKS) {
|
||||||
|
blocks[nblocks] = calloc(1, sizeof(struct block));
|
||||||
|
if (blocks[nblocks] == NULL) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
for (uint32_t i=0; i<sizeof(blocks[nblocks]->v)/sizeof(uint32_t); i++) {
|
||||||
|
blocks[nblocks]->v[i] = VALUE(i);
|
||||||
|
}
|
||||||
|
nblocks++;
|
||||||
|
}
|
||||||
|
printf("Allocated %u blocks\n", nblocks);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void check_blocks(void)
|
||||||
|
{
|
||||||
|
for (uint32_t n=0; n<nblocks; n++) {
|
||||||
|
for (uint32_t i=0; i<sizeof(blocks[nblocks]->v)/sizeof(uint32_t); i++) {
|
||||||
|
assert(blocks[n]->v[i] == VALUE(i));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int
|
||||||
|
reflect_main(int argc, char *argv[])
|
||||||
|
{
|
||||||
|
uint32_t total = 0;
|
||||||
|
printf("Starting reflector\n");
|
||||||
|
|
||||||
|
allocate_blocks();
|
||||||
|
|
||||||
|
while (true) {
|
||||||
|
char buf[128];
|
||||||
|
ssize_t n = read(0, buf, sizeof(buf));
|
||||||
|
if (n < 0) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
if (n > 0) {
|
||||||
|
write(1, buf, n);
|
||||||
|
}
|
||||||
|
total += n;
|
||||||
|
if (total > 1024000) {
|
||||||
|
check_blocks();
|
||||||
|
total = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return OK;
|
||||||
|
}
|
||||||
Reference in New Issue
Block a user