Merge branch 'px4dev_new_param' of github.com:PX4/Firmware into px4dev_new_param

This commit is contained in:
Lorenz Meier
2012-08-22 20:58:12 +02:00
33 changed files with 917 additions and 323 deletions
+23
View File
@@ -73,6 +73,29 @@ document showheap
. Prints the contents of the malloc heap(s).
end
################################################################################
# Task file listing
################################################################################
define showfiles
set $task = (struct _TCB *)$arg0
set $nfiles = sizeof((*(struct filelist*)0).fl_files) / sizeof(struct file)
printf "%d files\n", $nfiles
set $index = 0
while $index < $nfiles
set $file = &($task->filelist->fl_files[$index])
printf "%d: inode %p f_priv %p\n", $index, $file->f_inode, $file->f_priv
if $file->f_inode != 0
printf " i_name %s i_private %p\n", &$file->f_inode->i_name[0], $file->f_inode->i_private
end
set $index = $index + 1
end
end
document showfiles
. showfiles <TCB pointer>
. Prints the files opened by a task.
################################################################################
# Task display
################################################################################
+3 -2
View File
@@ -7,8 +7,9 @@
# Start sensor drivers here.
#
#ms5611 start
#mpu6000 start
ms5611 start
mpu6000 start
hmc5883 start
#
# Start the sensor collection task.
+4
View File
@@ -31,6 +31,8 @@ else
echo "[init] no microSD card found"
fi
usleep 500
#
# Look for an init script on the microSD card.
#
@@ -82,6 +84,7 @@ else
if [ -f /etc/init.d/rc.PX4IOAR ]
then
echo "[init] reading /etc/init.d/rc.PX4IOAR"
usleep 500
sh /etc/init.d/rc.PX4IOAR
fi
else
@@ -97,6 +100,7 @@ else
if [ -f /etc/init.d/rc.PX4IO ]
then
echo "[init] reading /etc/init.d/rc.PX4IO"
usleep 500
sh /etc/init.d/rc.PX4IO
fi
else
@@ -138,7 +138,7 @@ int attitude_estimator_ekf_main(int argc, char *argv[])
/* subscribe to raw data */
int sub_raw = orb_subscribe(ORB_ID(sensor_combined));
/* advertise attitude */
int pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att);
orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att);
int loopcounter = 0;
+2 -2
View File
@@ -96,8 +96,8 @@ static int leds;
static int buzzer;
static int mavlink_fd;
static bool commander_initialized = false;
static struct vehicle_status_s current_status; /**< Main state machine */
static int stat_pub;
static struct vehicle_status_s current_status; /**< Main state machine */
static orb_advert_t stat_pub;
static uint16_t nofix_counter = 0;
static uint16_t gotfix_counter = 0;
+8
View File
@@ -48,6 +48,8 @@
/**
* mag report structure. Reads from the device must be in multiples of this
* structure.
*
* Output values are in gauss.
*/
struct mag_report {
float x;
@@ -99,4 +101,10 @@ ORB_DECLARE(sensor_mag);
/** set the mag scaling constants to the structure pointed to by (arg) */
#define MAGIOCSSCALE _MAGIOC(5)
/** copy the mag scaling constants to the structure pointed to by (arg) */
#define MAGIOCGSCALE _MAGIOC(6)
/** perform self-calibration, update scale factors to canonical units */
#define MAGIOCCALIBRATE _MAGIOC(7)
#endif /* _DRV_MAG_H */
+3
View File
@@ -81,4 +81,7 @@
/** Set the minimum interval at which the topic can be seen to be updated for this subscription */
#define ORBIOCSETINTERVAL _ORBIOC(12)
/** Get the global advertiser handle for the topic */
#define ORBIOCGADVERTISER _ORBIOC(13)
#endif /* _DRV_UORB_H */
+93 -30
View File
@@ -43,6 +43,7 @@
#include <sys/types.h>
#include <stdint.h>
#include <stdlib.h>
#include <stdbool.h>
#include <semaphore.h>
#include <string.h>
@@ -63,7 +64,6 @@
#include <drivers/drv_mag.h>
/*
* HMC5883 internal constants and data structures.
*/
@@ -137,17 +137,17 @@ protected:
virtual int probe();
private:
struct work_s _work;
work_s _work;
unsigned _measure_ticks;
unsigned _num_reports;
volatile unsigned _next_report;
volatile unsigned _oldest_report;
struct mag_report *_reports;
mag_report *_reports;
mag_scale _scale;
bool _collect_phase;
int _mag_topic;
orb_advert_t _mag_topic;
unsigned _reads;
unsigned _measure_errors;
@@ -257,6 +257,7 @@ HMC5883::HMC5883(int bus) :
_next_report(0),
_oldest_report(0),
_reports(nullptr),
_mag_topic(-1),
_reads(0),
_measure_errors(0),
_read_errors(0),
@@ -266,6 +267,14 @@ HMC5883::HMC5883(int bus) :
// enable debug() calls
_debug_enabled = true;
// default scaling
_scale.x_offset = 0;
_scale.x_scale = 1.0f / 1090.0f; /* default range scale from counts to gauss */
_scale.y_offset = 0;
_scale.y_scale = 1.0f / 1090.0f; /* default range scale from counts to gauss */
_scale.z_offset = 0;
_scale.z_scale = 1.0f / 1090.0f; /* default range scale from counts to gauss */
// work_cancel in the dtor will explode if we don't do this...
_work.worker = nullptr;
}
@@ -287,21 +296,10 @@ HMC5883::init()
/* do I2C init (and probe) first */
ret = I2C::init();
if (ret != OK)
goto out;
/* assuming we're good, advertise the object */
struct mag_report m;
/* if this fails (e.g. no object in the system) that's OK */
memset(&m, 0, sizeof(m));
_mag_topic = orb_advertise(ORB_ID(sensor_mag), &m);
if (_mag_topic < 0) {
debug("failed to create sensor_baro object");
} else {
ret = 0;
}
out:
return ret;
}
@@ -340,7 +338,6 @@ HMC5883::close_last(struct file *filp)
int
HMC5883::probe()
{
uint8_t cmd[] = { ADDR_STATUS };
uint8_t data[3];
if (read_reg(ADDR_ID_A, data[0]) ||
@@ -348,7 +345,7 @@ HMC5883::probe()
read_reg(ADDR_ID_C, data[2]))
debug("read_reg fail");
if ((data[0] != ID_A_WHO_AM_I) ||
if ((data[0] != ID_A_WHO_AM_I) ||
(data[1] != ID_B_WHO_AM_I) ||
(data[2] != ID_C_WHO_AM_I)) {
debug("ID byte mismatch (%02x,%02x,%02x)", data[0], data[1], data[2]);
@@ -434,7 +431,7 @@ HMC5883::ioctl(struct file *filp, int cmd, unsigned long arg)
_measure_ticks = 0;
return OK;
/* external signalling not supported */
/* external signalling (DRDY) not supported */
case MAG_POLLRATE_EXTERNAL:
/* zero would be bad */
@@ -486,7 +483,30 @@ HMC5883::ioctl(struct file *filp, int cmd, unsigned long arg)
return OK;
}
case MAGIOCSSCALE:
/* set new scale factors */
memcpy(&_scale, (mag_scale *)arg, sizeof(_scale));
return 0;
case MAGIOCGSCALE:
/* copy out scale factors */
memcpy((mag_scale *)arg, &_scale, sizeof(_scale));
return 0;
case MAGIOCCALIBRATE:
/* XXX perform auto-calibration */
return -EINVAL;
case MAGIOCSSAMPLERATE:
/* not supported, always 1 sample per poll */
return -EINVAL;
case MAGIOCSLOWPASS:
/* not supported, no internal filtering */
return -EINVAL;
case MAGIOCSREPORTFORMAT:
/* not supported, no custom report format */
return -EINVAL;
default:
@@ -526,6 +546,25 @@ HMC5883::cycle_trampoline(void *arg)
void
HMC5883::cycle()
{
/*
* We have to publish the mag topic in the context of the workq
* in order to ensure that the descriptor is valid when we go to publish.
*
* @bug We can't really ever be torn down and restarted, since this
* descriptor will never be closed and on the restart we will be
* unable to re-advertise.
*/
if (_mag_topic == -1) {
struct mag_report m;
/* if this fails (e.g. no object in the system) we will cope */
memset(&m, 0, sizeof(m));
_mag_topic = orb_advertise(ORB_ID(sensor_mag), &m);
if (_mag_topic < 0)
debug("failed to create sensor_mag object");
}
/* collection phase? */
if (_collect_phase) {
@@ -579,6 +618,7 @@ HMC5883::measure()
* Send the command to begin a measurement.
*/
ret = write_reg(ADDR_MODE, MODE_REG_SINGLE_MODE);
if (OK != ret)
_measure_errors++;
@@ -591,33 +631,56 @@ HMC5883::collect()
#pragma pack(push, 1)
struct { /* status register and data as read back from the device */
uint8_t x[2];
uint8_t z[2];
uint8_t y[2];
uint8_t status;
uint8_t z[2];
} hmc_report;
#pragma pack(pop)
struct {
int16_t x, y, z;
} report;
int ret = -EIO;
uint8_t cmd[1];
uint8_t cmd;
perf_begin(_sample_perf);
/* this should be fairly close to the end of the measurement, so the best approximation of the time */
_reports[_next_report].timestamp = hrt_absolute_time();
/*
* @note We could read the status register here, which could tell us that
* we were too early and that the output registers are still being
* written. In the common case that would just slow us down, and
* we're better off just never being early.
*/
/* get measurements from the device */
cmd[0] = ADDR_DATA_OUT_X_MSB;
ret = transfer(&cmd[0], 1, &hmc_report.x[0], sizeof(hmc_report));
cmd = ADDR_DATA_OUT_X_MSB;
ret = transfer(&cmd, 1, (uint8_t *)&hmc_report, sizeof(hmc_report));
if (ret != OK) {
debug("data/status read error");
goto out;
}
/* XXX check status? */
/* swap the data we just received */
report.x = ((int16_t)hmc_report.x[0] << 8) + hmc_report.x[1];
report.y = ((int16_t)hmc_report.y[0] << 8) + hmc_report.y[1];
report.z = ((int16_t)hmc_report.z[0] << 8) + hmc_report.z[1];
/* XXX scaling */
_reports[_next_report].x = meas_to_float(hmc_report.x);
_reports[_next_report].y = meas_to_float(hmc_report.y);
_reports[_next_report].z = meas_to_float(hmc_report.z);
/*
* If any of the values are -4096, there was an internal math error in the sensor.
* Generalise this to a simple range check that will also catch some bit errors.
*/
if ((abs(report.x) > 2048) ||
(abs(report.y) > 2048) ||
(abs(report.z) > 2048))
goto out;
/* scale values for output */
_reports[_next_report].x = report.x * _scale.x_scale + _scale.x_offset;
_reports[_next_report].y = report.y * _scale.y_scale + _scale.y_offset;
_reports[_next_report].z = report.z * _scale.z_scale + _scale.z_offset;
/* publish it */
orb_publish(ORB_ID(sensor_mag), _mag_topic, &_reports[_next_report]);
+9 -8
View File
@@ -181,12 +181,12 @@ private:
struct accel_report _accel_report;
struct accel_scale _accel_scale;
float _accel_range_scale;
int _accel_topic;
orb_advert_t _accel_topic;
struct gyro_report _gyro_report;
struct gyro_scale _gyro_scale;
float _gyro_range_scale;
int _gyro_topic;
orb_advert_t _gyro_topic;
unsigned _reads;
perf_counter_t _sample_perf;
@@ -288,9 +288,9 @@ MPU6000::MPU6000(int bus, spi_dev_e device) :
_gyro(new MPU6000_gyro(this)),
_product(0),
_call_interval(0),
_accel_range_scale(1.0f),
_accel_range_scale(0.02f),
_accel_topic(-1),
_gyro_range_scale(1.0f),
_gyro_range_scale(0.02f),
_gyro_topic(-1),
_reads(0),
_sample_perf(perf_alloc(PC_ELAPSED, "mpu6000_read"))
@@ -826,7 +826,7 @@ test()
fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
if (fd < 0) {
reason = "can't open driver";
reason = "can't open driver, use <mpu6000 start> first";
break;
}
@@ -841,9 +841,10 @@ test()
printf("single read\n");
fflush(stdout);
printf("time: %lld\n", report.timestamp);
printf("x: %f\n", report.x);
printf("y: %f\n", report.y);
printf("z: %f\n", report.z);
printf("x: %5.2f\n", (double)report.x);
printf("y: %5.2f\n", (double)report.y);
printf("z: %5.2f\n", (double)report.z);
printf("test: %8.4f\n", 1.5);
} while (0);
+21 -13
View File
@@ -125,7 +125,7 @@ private:
int32_t _dT;
int64_t _temp64;
int _baro_topic;
orb_advert_t _baro_topic;
unsigned _reads;
unsigned _measure_errors;
@@ -246,6 +246,7 @@ MS5611::MS5611(int bus) :
_measure_phase(0),
_dT(0),
_temp64(0),
_baro_topic(-1),
_reads(0),
_measure_errors(0),
_read_errors(0),
@@ -277,18 +278,6 @@ MS5611::init()
/* do I2C init (and probe) first */
ret = I2C::init();
/* assuming we're good, advertise the object */
if (ret == OK) {
struct baro_report b;
/* if this fails (e.g. no object in the system) that's OK */
memset(&b, 0, sizeof(b));
_baro_topic = orb_advertise(ORB_ID(sensor_baro), &b);
if (_baro_topic < 0)
debug("failed to create sensor_baro object");
}
return ret;
}
@@ -538,6 +527,25 @@ MS5611::cycle_trampoline(void *arg)
void
MS5611::cycle()
{
/*
* We have to publish the baro topic in the context of the workq
* in order to ensure that the descriptor is valid when we go to publish.
*
* @bug We can't really ever be torn down and restarted, since this
* descriptor will never be closed and on the restart we will be
* unable to re-advertise.
*/
if (_baro_topic == -1) {
struct baro_report b;
/* if this fails (e.g. no object in the system) we will cope */
memset(&b, 0, sizeof(b));
_baro_topic = orb_advertise(ORB_ID(sensor_baro), &b);
if (_baro_topic < 0)
debug("failed to create sensor_baro object");
}
/* collection phase? */
if (_collect_phase) {
@@ -59,7 +59,7 @@ int px4_simple_app_main(int argc, char *argv[])
/* advertise attitude topic */
struct vehicle_attitude_s att;
memset(&att, 0, sizeof(att));
int att_pub_fd = orb_advertise(ORB_ID(vehicle_attitude), &att);
orb_advert_t att_pub = orb_advertise(ORB_ID(vehicle_attitude), &att);
/* one could wait for multiple topics with this technique, just using one here */
struct pollfd fds[] = {
@@ -103,7 +103,7 @@ int px4_simple_app_main(int argc, char *argv[])
att.roll = raw.accelerometer_m_s2[0];
att.pitch = raw.accelerometer_m_s2[1];
att.yaw = raw.accelerometer_m_s2[2];
orb_publish(ORB_ID(vehicle_attitude), att_pub_fd, &att);
orb_publish(ORB_ID(vehicle_attitude), att_pub, &att);
}
/* there could be more file descriptors here, in the form like:
* if (fds[1..n].revents & POLLIN) {}
+1 -1
View File
@@ -683,7 +683,7 @@ int fixedwing_control_main(int argc, char *argv[])
/* Set up to publish fixed wing control messages */
struct fixedwing_control_s control;
int fixedwing_control_pub = orb_advertise(ORB_ID(fixedwing_control), &control);
orb_advert_t fixedwing_control_pub = orb_advertise(ORB_ID(fixedwing_control), &control);
/* Subscribe to global position, attitude and rc */
struct vehicle_global_position_s global_pos;
+1 -1
View File
@@ -311,7 +311,7 @@ void *mtk_loop(void *arg)
/* advertise GPS topic */
struct vehicle_gps_position_s mtk_gps_d;
mtk_gps = &mtk_gps_d;
int gps_handle = orb_advertise(ORB_ID(vehicle_gps_position), &mtk_gps);
orb_advert_t gps_handle = orb_advertise(ORB_ID(vehicle_gps_position), &mtk_gps);
while (1) {
/* Parse a message from the gps receiver */
+1 -1
View File
@@ -176,7 +176,7 @@ void *nmea_loop(void *arg)
/* advertise GPS topic */
struct vehicle_gps_position_s nmea_gps_d = {0};
nmea_gps = &nmea_gps_d;
int gps_handle = orb_advertise(ORB_ID(vehicle_gps_position), nmea_gps);
orb_advert_t gps_handle = orb_advertise(ORB_ID(vehicle_gps_position), nmea_gps);
while (1) {
/* Parse a message from the gps receiver */
+1 -1
View File
@@ -842,7 +842,7 @@ void *ubx_loop(void *arg)
ubx_gps = &ubx_gps_d;
int gps_pub = orb_advertise(ORB_ID(vehicle_gps_position), &ubx_gps);
orb_advert_t gps_pub = orb_advertise(ORB_ID(vehicle_gps_position), &ubx_gps);
while (1) {
/* Parse a message from the gps receiver */
+255 -44
View File
@@ -73,6 +73,8 @@
#include <uORB/topics/vehicle_global_position_setpoint.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/manual_control_setpoint.h>
#include "waypoints.h"
#include "mavlink_log.h"
@@ -113,7 +115,7 @@ static struct vehicle_status_s v_status;
static struct rc_channels_s rc;
/* HIL publishers */
static int pub_hil_attitude = -1;
static orb_advert_t pub_hil_attitude = -1;
/** HIL attitude */
static struct vehicle_attitude_s hil_attitude;
@@ -126,16 +128,13 @@ static struct ardrone_motors_setpoint_s ardrone_motors;
static struct vehicle_command_s vcmd;
static int pub_hil_global_pos = -1;
static int ardrone_motors_pub = -1;
static int cmd_pub = -1;
static int sensor_sub = -1;
static int att_sub = -1;
static int global_pos_sub = -1;
static orb_advert_t pub_hil_global_pos = -1;
static orb_advert_t ardrone_motors_pub = -1;
static orb_advert_t cmd_pub = -1;
static int local_pos_sub = -1;
static int flow_pub = -1;
static int global_position_setpoint_pub = -1;
static int local_position_setpoint_pub = -1;
static orb_advert_t flow_pub = -1;
static orb_advert_t global_position_setpoint_pub = -1;
static orb_advert_t local_position_setpoint_pub = -1;
static bool mavlink_hil_enabled = false;
static char mavlink_message_string[51] = {0};
@@ -146,6 +145,30 @@ static enum {
MAVLINK_INTERFACE_MODE_ONBOARD
} mavlink_link_mode = MAVLINK_INTERFACE_MODE_OFFBOARD;
static struct mavlink_subscriptions {
int sensor_sub;
int att_sub;
int global_pos_sub;
int act_0_sub;
int act_1_sub;
int act_2_sub;
int act_3_sub;
int gps_sub;
int man_control_sp_sub;
bool initialized;
} mavlink_subs = {
.sensor_sub = 0,
.att_sub = 0,
.global_pos_sub = 0,
.act_0_sub = 0,
.act_1_sub = 0,
.act_2_sub = 0,
.act_3_sub = 0,
.gps_sub = 0,
.man_control_sp_sub = 0,
.initialized = false
};
/* 3: Define waypoint helper functions */
void mavlink_wpm_send_message(mavlink_message_t *msg);
@@ -459,23 +482,33 @@ static void *receiveloop(void *arg)
return NULL;
}
static int set_mavlink_interval_limit(int mavlink_msg_id, int min_interval)
static int set_mavlink_interval_limit(struct mavlink_subscriptions *subs, int mavlink_msg_id, int min_interval)
{
int ret = OK;
switch (mavlink_msg_id) {
case MAVLINK_MSG_ID_SCALED_IMU:
/* senser sub triggers scaled IMU */
orb_set_interval(sensor_sub, min_interval);
if (subs->sensor_sub) orb_set_interval(subs->sensor_sub, min_interval);
break;
case MAVLINK_MSG_ID_RAW_IMU:
/* senser sub triggers RAW IMU */
orb_set_interval(sensor_sub, min_interval);
if (subs->sensor_sub) orb_set_interval(subs->sensor_sub, min_interval);
break;
case MAVLINK_MSG_ID_ATTITUDE:
/* attitude sub triggers attitude */
orb_set_interval(att_sub, min_interval);
if (subs->att_sub) orb_set_interval(subs->att_sub, min_interval);
break;
case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
/* actuator_outputs triggers this message */
if (subs->act_0_sub) orb_set_interval(subs->act_0_sub, min_interval);
if (subs->act_1_sub) orb_set_interval(subs->act_1_sub, min_interval);
if (subs->act_2_sub) orb_set_interval(subs->act_2_sub, min_interval);
if (subs->act_3_sub) orb_set_interval(subs->act_3_sub, min_interval);
break;
case MAVLINK_MSG_ID_MANUAL_CONTROL:
/* manual_control_setpoint triggers this message */
if (subs->man_control_sp_sub) orb_set_interval(subs->man_control_sp_sub, min_interval);
default:
/* not found */
ret = ERROR;
@@ -494,13 +527,16 @@ static int set_mavlink_interval_limit(int mavlink_msg_id, int min_interval)
*/
static void *uorb_receiveloop(void *arg)
{
/* obtain reference to task's subscriptions */
struct mavlink_subscriptions *subs = (struct mavlink_subscriptions *)arg;
/* Set thread name */
prctl(PR_SET_NAME, "mavlink uORB", getpid());
/* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */
/* number of messages */
const ssize_t fdsc = 15;
const ssize_t fdsc = 25;
/* Sanity check variable and index */
ssize_t fdsc_count = 0;
/* file descriptors to wait for */
@@ -515,28 +551,30 @@ static void *uorb_receiveloop(void *arg)
struct vehicle_local_position_setpoint_s local_sp;
struct vehicle_global_position_setpoint_s global_sp;
struct vehicle_attitude_setpoint_s att_sp;
struct actuator_outputs_s act_outputs;
struct manual_control_setpoint_s man_control;
} buf;
/* --- SENSORS RAW VALUE --- */
/* subscribe to ORB for sensors raw */
sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
fds[fdsc_count].fd = sensor_sub;
subs->sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
fds[fdsc_count].fd = subs->sensor_sub;
fds[fdsc_count].events = POLLIN;
fdsc_count++;
/* --- ATTITUDE VALUE --- */
/* subscribe to ORB for attitude */
att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
orb_set_interval(att_sub, 100);
fds[fdsc_count].fd = att_sub;
subs->att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
orb_set_interval(subs->att_sub, 100);
fds[fdsc_count].fd = subs->att_sub;
fds[fdsc_count].events = POLLIN;
fdsc_count++;
/* --- GPS VALUE --- */
/* subscribe to ORB for attitude */
int gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
orb_set_interval(gps_sub, 1000); /* 1Hz updates */
fds[fdsc_count].fd = gps_sub;
subs->gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
orb_set_interval(subs->gps_sub, 1000); /* 1Hz updates */
fds[fdsc_count].fd = subs->gps_sub;
fds[fdsc_count].events = POLLIN;
fdsc_count++;
@@ -577,7 +615,7 @@ static void *uorb_receiveloop(void *arg)
/* --- GLOBAL POS VALUE --- */
/* struct already globally allocated and topic already subscribed */
fds[fdsc_count].fd = global_pos_sub;
fds[fdsc_count].fd = subs->global_pos_sub;
fds[fdsc_count].events = POLLIN;
fdsc_count++;
@@ -608,12 +646,39 @@ static void *uorb_receiveloop(void *arg)
/* --- ATTITUDE SETPOINT VALUE --- */
/* subscribe to ORB for attitude setpoint */
/* struct already allocated */
int spa_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint));
int spa_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
orb_set_interval(spa_sub, 2000); /* 0.5 Hz updates */
fds[fdsc_count].fd = spa_sub;
fds[fdsc_count].events = POLLIN;
fdsc_count++;
/** --- ACTUATOR OUTPUTS --- */
subs->act_0_sub = orb_subscribe(ORB_ID(actuator_outputs_0));
fds[fdsc_count].fd = subs->act_0_sub;
fds[fdsc_count].events = POLLIN;
fdsc_count++;
subs->act_1_sub = orb_subscribe(ORB_ID(actuator_outputs_1));
fds[fdsc_count].fd = subs->act_1_sub;
fds[fdsc_count].events = POLLIN;
fdsc_count++;
subs->act_2_sub = orb_subscribe(ORB_ID(actuator_outputs_2));
fds[fdsc_count].fd = subs->act_2_sub;
fds[fdsc_count].events = POLLIN;
fdsc_count++;
subs->act_3_sub = orb_subscribe(ORB_ID(actuator_outputs_3));
fds[fdsc_count].fd = subs->act_3_sub;
fds[fdsc_count].events = POLLIN;
fdsc_count++;
/** --- MAPPED MANUAL CONTROL INPUTS --- */
subs->man_control_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
fds[fdsc_count].fd = subs->man_control_sp_sub;
fds[fdsc_count].events = POLLIN;
fdsc_count++;
/* all subscriptions initialized, return success */
subs->initialized = true;
unsigned int sensors_raw_counter = 0;
unsigned int attitude_counter = 0;
unsigned int gps_counter = 0;
@@ -651,7 +716,7 @@ static void *uorb_receiveloop(void *arg)
if (fds[ifds++].revents & POLLIN) {
/* copy sensors raw data into local buffer */
orb_copy(ORB_ID(sensor_combined), sensor_sub, &buf.raw);
orb_copy(ORB_ID(sensor_combined), subs->sensor_sub, &buf.raw);
/* send raw imu data */
mavlink_msg_raw_imu_send(MAVLINK_COMM_0, buf.raw.timestamp, buf.raw.accelerometer_raw[0], buf.raw.accelerometer_raw[1], buf.raw.accelerometer_raw[2], buf.raw.gyro_raw[0], buf.raw.gyro_raw[1], buf.raw.gyro_raw[2], buf.raw.magnetometer_raw[0], buf.raw.magnetometer_raw[1], buf.raw.magnetometer_raw[2]);
@@ -667,7 +732,7 @@ static void *uorb_receiveloop(void *arg)
if (fds[ifds++].revents & POLLIN) {
/* copy attitude data into local buffer */
orb_copy(ORB_ID(vehicle_attitude), att_sub, &buf.att);
orb_copy(ORB_ID(vehicle_attitude), subs->att_sub, &buf.att);
/* send sensor values */
mavlink_msg_attitude_send(MAVLINK_COMM_0, buf.att.timestamp / 1000, buf.att.roll, buf.att.pitch, buf.att.yaw, buf.att.rollspeed, buf.att.pitchspeed, buf.att.yawspeed);
@@ -678,7 +743,7 @@ static void *uorb_receiveloop(void *arg)
/* --- GPS VALUE --- */
if (fds[ifds++].revents & POLLIN) {
/* copy gps data into local buffer */
orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &buf.gps);
orb_copy(ORB_ID(vehicle_gps_position), subs->gps_sub, &buf.gps);
/* GPS position */
mavlink_msg_gps_raw_int_send(MAVLINK_COMM_0, buf.gps.timestamp, buf.gps.fix_type, buf.gps.lat, buf.gps.lon, buf.gps.alt, buf.gps.eph, buf.gps.epv, buf.gps.vel, buf.gps.cog, buf.gps.satellites_visible);
@@ -801,7 +866,7 @@ static void *uorb_receiveloop(void *arg)
/* --- VEHICLE GLOBAL POSITION --- */
if (fds[ifds++].revents & POLLIN) {
/* copy global position data into local buffer */
orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos);
orb_copy(ORB_ID(vehicle_global_position), subs->global_pos_sub, &global_pos);
uint64_t timestamp = global_pos.timestamp;
int32_t lat = global_pos.lat;
int32_t lon = global_pos.lon;
@@ -845,6 +910,126 @@ static void *uorb_receiveloop(void *arg)
orb_copy(ORB_ID(vehicle_attitude_setpoint), spa_sub, &buf.att_sp);
mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(MAVLINK_COMM_0, buf.att_sp.timestamp/1000, buf.att_sp.roll_tait_bryan, buf.att_sp.pitch_tait_bryan, buf.att_sp.yaw_tait_bryan, buf.att_sp.thrust);
}
/* --- ACTUATOR OUTPUTS 0 --- */
if (fds[ifds++].revents & POLLIN) {
/* copy actuator data into local buffer */
orb_copy(ORB_ID(actuator_outputs_0), subs->act_0_sub, &buf.act_outputs);
mavlink_msg_servo_output_raw_send(MAVLINK_COMM_0, hrt_absolute_time(),
0 /* port 0 */,
buf.act_outputs.output[0],
buf.act_outputs.output[1],
buf.act_outputs.output[2],
buf.act_outputs.output[3],
buf.act_outputs.output[4],
buf.act_outputs.output[5],
buf.act_outputs.output[6],
buf.act_outputs.output[7]);
// if (NUM_ACTUATOR_OUTPUTS > 8 && NUM_ACTUATOR_OUTPUTS <= 16) {
// mavlink_msg_servo_output_raw_send(MAVLINK_COMM_0, hrt_absolute_time(),
// 1 /* port 1 */,
// buf.act_outputs.output[ 8],
// buf.act_outputs.output[ 9],
// buf.act_outputs.output[10],
// buf.act_outputs.output[11],
// buf.act_outputs.output[12],
// buf.act_outputs.output[13],
// buf.act_outputs.output[14],
// buf.act_outputs.output[15]);
// }
}
/* --- ACTUATOR OUTPUTS 1 --- */
if (fds[ifds++].revents & POLLIN) {
/* copy actuator data into local buffer */
orb_copy(ORB_ID(actuator_outputs_1), subs->act_1_sub, &buf.act_outputs);
mavlink_msg_servo_output_raw_send(MAVLINK_COMM_0, hrt_absolute_time(),
(NUM_ACTUATOR_OUTPUTS > 8 && NUM_ACTUATOR_OUTPUTS <= 16) ? 2 : 1 /* port 2 or 1*/,
buf.act_outputs.output[0],
buf.act_outputs.output[1],
buf.act_outputs.output[2],
buf.act_outputs.output[3],
buf.act_outputs.output[4],
buf.act_outputs.output[5],
buf.act_outputs.output[6],
buf.act_outputs.output[7]);
if (NUM_ACTUATOR_OUTPUTS > 8 && NUM_ACTUATOR_OUTPUTS <= 16) {
mavlink_msg_servo_output_raw_send(MAVLINK_COMM_0, hrt_absolute_time(),
3 /* port 3 */,
buf.act_outputs.output[ 8],
buf.act_outputs.output[ 9],
buf.act_outputs.output[10],
buf.act_outputs.output[11],
buf.act_outputs.output[12],
buf.act_outputs.output[13],
buf.act_outputs.output[14],
buf.act_outputs.output[15]);
}
}
/* --- ACTUATOR OUTPUTS 2 --- */
if (fds[ifds++].revents & POLLIN) {
/* copy actuator data into local buffer */
orb_copy(ORB_ID(actuator_outputs_2), subs->act_2_sub, &buf.act_outputs);
mavlink_msg_servo_output_raw_send(MAVLINK_COMM_0, hrt_absolute_time(),
(NUM_ACTUATOR_OUTPUTS > 8 && NUM_ACTUATOR_OUTPUTS <= 16) ? 4 : 2 /* port 4 or 2 */,
buf.act_outputs.output[0],
buf.act_outputs.output[1],
buf.act_outputs.output[2],
buf.act_outputs.output[3],
buf.act_outputs.output[4],
buf.act_outputs.output[5],
buf.act_outputs.output[6],
buf.act_outputs.output[7]);
if (NUM_ACTUATOR_OUTPUTS > 8 && NUM_ACTUATOR_OUTPUTS <= 16) {
mavlink_msg_servo_output_raw_send(MAVLINK_COMM_0, hrt_absolute_time(),
5 /* port 5 */,
buf.act_outputs.output[ 8],
buf.act_outputs.output[ 9],
buf.act_outputs.output[10],
buf.act_outputs.output[11],
buf.act_outputs.output[12],
buf.act_outputs.output[13],
buf.act_outputs.output[14],
buf.act_outputs.output[15]);
}
}
/* --- ACTUATOR OUTPUTS 3 --- */
if (fds[ifds++].revents & POLLIN) {
/* copy actuator data into local buffer */
orb_copy(ORB_ID(actuator_outputs_3), subs->act_3_sub, &buf.act_outputs);
mavlink_msg_servo_output_raw_send(MAVLINK_COMM_0, hrt_absolute_time(),
(NUM_ACTUATOR_OUTPUTS > 8 && NUM_ACTUATOR_OUTPUTS <= 16) ? 6 : 3 /* port 6 or 3 */,
buf.act_outputs.output[0],
buf.act_outputs.output[1],
buf.act_outputs.output[2],
buf.act_outputs.output[3],
buf.act_outputs.output[4],
buf.act_outputs.output[5],
buf.act_outputs.output[6],
buf.act_outputs.output[7]);
if (NUM_ACTUATOR_OUTPUTS > 8 && NUM_ACTUATOR_OUTPUTS <= 16) {
mavlink_msg_servo_output_raw_send(MAVLINK_COMM_0, hrt_absolute_time(),
7 /* port 7 */,
buf.act_outputs.output[ 8],
buf.act_outputs.output[ 9],
buf.act_outputs.output[10],
buf.act_outputs.output[11],
buf.act_outputs.output[12],
buf.act_outputs.output[13],
buf.act_outputs.output[14],
buf.act_outputs.output[15]);
}
}
/* --- MAPPED MANUAL CONTROL INPUTS --- */
if (fds[ifds++].revents & POLLIN) {
/* copy local position data into local buffer */
orb_copy(ORB_ID(manual_control_setpoint), subs->man_control_sp_sub, &buf.man_control);
mavlink_msg_manual_control_send(MAVLINK_COMM_0, mavlink_system.sysid, buf.man_control.roll,
buf.man_control.pitch, buf.man_control.yaw, buf.man_control.throttle, 1, 1, 1, 1);
}
}
}
@@ -891,7 +1076,8 @@ void handleMessage(mavlink_message_t *msg)
mavlink_command_long_t cmd_mavlink;
mavlink_msg_command_long_decode(msg, &cmd_mavlink);
if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid) || (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) {
if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid)
|| (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) {
//check for MAVLINK terminate command
if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) {
/* This is the link shutdown command, terminate mavlink */ //TODO: check what happens with global_data buffers that are read by the mavlink app
@@ -1299,8 +1485,8 @@ int mavlink_thread_main(int argc, char *argv[])
/* topics to subscribe globally */
/* subscribe to ORB for global position */
global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
orb_set_interval(global_pos_sub, 1000); /* 1Hz active updates */
mavlink_subs.global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
orb_set_interval(mavlink_subs.global_pos_sub, 1000); /* 1Hz active updates */
/* subscribe to ORB for local position */
local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));
orb_set_interval(local_pos_sub, 1000); /* 1Hz active updates */
@@ -1315,7 +1501,7 @@ int mavlink_thread_main(int argc, char *argv[])
pthread_attr_init(&uorb_attr);
/* Set stack size, needs more than 4000 bytes */
pthread_attr_setstacksize(&uorb_attr, 4096);
pthread_create(&uorb_receive_thread, &uorb_attr, uorb_receiveloop, NULL);
pthread_create(&uorb_receive_thread, &uorb_attr, uorb_receiveloop, &mavlink_subs);
/* initialize waypoint manager */
mavlink_wpm_init(wpm);
@@ -1323,27 +1509,52 @@ int mavlink_thread_main(int argc, char *argv[])
uint16_t counter = 0;
int lowspeed_counter = 0;
/* make sure all threads have registered their subscriptions */
while (!mavlink_subs.initialized) {
usleep(500);
}
/* all subscriptions are now active, set up initial guess about rate limits */
if (baudrate >= 921600) {
/* 500 Hz / 2 ms */
set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 2);
set_mavlink_interval_limit(MAVLINK_MSG_ID_ATTITUDE, 2);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SCALED_IMU, 2);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_ATTITUDE, 2);
/* 200 Hz / 5 ms */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 5);
/* 5 Hz */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 200);
} else if (baudrate >= 460800) {
/* 250 Hz / 4 ms */
set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 5);
set_mavlink_interval_limit(MAVLINK_MSG_ID_ATTITUDE, 5);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SCALED_IMU, 5);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_ATTITUDE, 5);
/* 50 Hz / 20 ms */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 20);
/* 2 Hz */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 500);
} else if (baudrate >= 115200) {
/* 50 Hz / 20 ms */
set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 50);
set_mavlink_interval_limit(MAVLINK_MSG_ID_ATTITUDE, 50);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SCALED_IMU, 50);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_ATTITUDE, 50);
/* 10 Hz / 100 ms */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 100);
/* 1 Hz */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 1000);
} else if (baudrate >= 57600) {
/* 10 Hz / 100 ms */
set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 100);
set_mavlink_interval_limit(MAVLINK_MSG_ID_ATTITUDE, 100);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SCALED_IMU, 100);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_ATTITUDE, 100);
/* 5 Hz / 200 ms */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 200);
/* 0.2 Hz */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 5000);
} else {
/* very low baud rate, limit to 1 Hz / 1000 ms */
set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 1000);
set_mavlink_interval_limit(MAVLINK_MSG_ID_ATTITUDE, 1000);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SCALED_IMU, 1000);
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_ATTITUDE, 1000);
/* 0.5 Hz */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 2000);
/* 0.1 Hz */
set_mavlink_interval_limit(&mavlink_subs, MAVLINK_MSG_ID_MANUAL_CONTROL, 10000);
}
while (!thread_should_exit) {
@@ -1351,7 +1562,7 @@ int mavlink_thread_main(int argc, char *argv[])
if (mavlink_exit_requested) break;
/* get local and global position */
orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos);
orb_copy(ORB_ID(vehicle_global_position), mavlink_subs.global_pos_sub, &global_pos);
orb_copy(ORB_ID(vehicle_local_position), local_pos_sub, &local_pos);
/* check if waypoint has been reached against the last positions */
@@ -78,13 +78,11 @@ static enum {
static bool thread_should_exit;
static int mc_task;
static bool motor_test_mode = false;
static int
mc_thread_main(int argc, char *argv[])
{
bool motor_test_mode = false;
/* structures */
/* declare and safely initialize all structs */
struct vehicle_status_s state;
memset(&state, 0, sizeof(state));
@@ -109,7 +107,7 @@ mc_thread_main(int argc, char *argv[])
int att_setpoint_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
int state_sub = orb_subscribe(ORB_ID(vehicle_status));
int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
int sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
//int sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
// int setpoint_sub = orb_subscribe(ORB_ID(ardrone_motors_setpoint));
/* rate-limit the attitude subscription to 200Hz to pace our loop */
@@ -119,9 +117,10 @@ mc_thread_main(int argc, char *argv[])
/* publish actuator controls */
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++)
actuators.control[i] = 0.0f;
int actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators);
armed.armed = true;
int armed_pub = orb_advertise(ORB_ID(actuator_armed), &armed);
orb_advert_t actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators);
armed.armed = false;
orb_advert_t armed_pub = orb_advertise(ORB_ID(actuator_armed), &armed);
orb_advert_t att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp);
/* register the perf counter */
perf_counter_t mc_loop_perf = perf_alloc(PC_ELAPSED, "multirotor_att_control");
@@ -136,6 +135,8 @@ mc_thread_main(int argc, char *argv[])
perf_begin(mc_loop_perf);
/* get a local copy of system state */
orb_copy(ORB_ID(vehicle_status), state_sub, &state);
/* get a local copy of manual setpoint */
orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &manual);
/* get a local copy of attitude */
@@ -150,7 +151,7 @@ mc_thread_main(int argc, char *argv[])
att_sp.roll_body = 0.0f;
att_sp.pitch_body = 0.0f;
att_sp.yaw_body = 0.0f;
att_sp.thrust = 0.3f;
att_sp.thrust = 0.1f;
} else {
if (state.state_machine == SYSTEM_STATE_MANUAL ||
state.state_machine == SYSTEM_STATE_GROUND_READY ||
@@ -159,28 +160,30 @@ mc_thread_main(int argc, char *argv[])
state.state_machine == SYSTEM_STATE_MISSION_ABORT ||
state.state_machine == SYSTEM_STATE_EMCY_LANDING) {
att_sp.thrust = manual.throttle;
armed.armed = true;
} else if (state.state_machine == SYSTEM_STATE_EMCY_CUTOFF) {
/* immediately cut off motors */
att_sp.thrust = 0.0f;
armed.armed = false;
} else {
/* limit motor throttle to zero for an unknown mode */
att_sp.thrust = 0.0f;
armed.armed = false;
}
}
multirotor_control_attitude(&att_sp, &att, &state, &actuator_controls, motor_test_mode);
//ardrone_mixing_and_output(ardrone_write, &actuator_controls, motor_test_mode);
/* publish the result */
orb_publish(ORB_ID(actuator_armed), armed_pub, &armed);
orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
perf_end(mc_loop_perf);
}
printf("[multirotor att control] stopping.\n");
printf("[multirotor att control] stopping, disarming motors.\n");
/* kill all outputs */
armed.armed = false;
@@ -208,8 +211,9 @@ usage(const char *reason)
{
if (reason)
fprintf(stderr, "%s\n", reason);
fprintf(stderr, "usage: multirotor_att_control [-m <mode>] {start|stop}\n");
fprintf(stderr, "usage: multirotor_att_control [-m <mode>] [-t] {start|stop}\n");
fprintf(stderr, " <mode> is 'rates' or 'attitude'\n");
fprintf(stderr, " -t enables motor test mode with 10%% thrust\n");
exit(1);
}
@@ -220,7 +224,7 @@ int multirotor_att_control_main(int argc, char *argv[])
control_mode = CONTROL_MODE_RATES;
unsigned int optioncount = 0;
while ((ch = getopt(argc, argv, "m:")) != EOF) {
while ((ch = getopt(argc, argv, "tm:")) != EOF) {
switch (ch) {
case 'm':
if (!strcmp(optarg, "rates")) {
@@ -231,24 +235,33 @@ int multirotor_att_control_main(int argc, char *argv[])
usage("unrecognized -m value");
}
optioncount += 2;
break;
case 't':
motor_test_mode = true;
optioncount += 1;
break;
case ':':
usage("missing parameter");
break;
default:
fprintf(stderr, "option: -%c\n", ch);
usage("unrecognized option");
}
}
argc -= optioncount;
argv += optioncount;
//argv += optioncount;
if (argc < 1)
usage("missing command");
if (!strcmp(argv[1], "start")) {
if (!strcmp(argv[1+optioncount], "start")) {
thread_should_exit = false;
mc_task = task_create("multirotor_att_control", SCHED_PRIORITY_MAX - 15, 2048, mc_thread_main, NULL);
exit(0);
}
if (!strcmp(argv[1], "stop")) {
if (!strcmp(argv[1+optioncount], "stop")) {
thread_should_exit = true;
exit(0);
}
@@ -239,4 +239,6 @@ void multirotor_control_attitude(const struct vehicle_attitude_setpoint_s *att_s
actuators->control[1] = pitch_control;
actuators->control[2] = yaw_rate_control;
actuators->control[3] = motor_thrust;
motor_skip_counter++;
}
@@ -89,7 +89,7 @@ mpc_thread_main(int argc, char *argv[])
int local_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint));
/* publish attitude setpoint */
int att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp);
orb_advert_t att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp);
while (1) {
/* get a local copy of the vehicle state */
@@ -297,7 +297,7 @@ int position_estimator_main(int argc, char *argv[])
.lon = lon_current * 1e7,
.alt = gps.alt
};
int global_pos_pub = orb_advertise(ORB_ID(vehicle_global_position), &global_pos);
orb_advert_t global_pos_pub = orb_advertise(ORB_ID(vehicle_global_position), &global_pos);
printf("[multirotor position estimator] initialized projection with: lat: %.10f, lon:%.10f\n", lat_current, lon_current);
@@ -96,16 +96,16 @@ int attitude_estimator_bm_update(struct sensor_combined_s *raw, float_vect3 *eul
mag_values.y = raw->magnetometer_ga[1]*456.0f;
mag_values.z = raw->magnetometer_ga[2]*456.0f;
static int i = 0;
// static int i = 0;
if (i == 500) {
printf("gyro: %8.4f\t%8.4f\t%8.4f\t accel: %8.4f\t%8.4f\t%8.4f\t mag: %8.4f\t%8.4f\t%8.4f\t\n",
gyro_values.x, gyro_values.y, gyro_values.z,
accel_values.x, accel_values.y, accel_values.z,
mag_values.x, mag_values.y, mag_values.z);
i = 0;
}
i++;
// if (i == 500) {
// printf("[att estim bm] gyro: %8.4f\t%8.4f\t%8.4f\t accel: %8.4f\t%8.4f\t%8.4f\t mag: %8.4f\t%8.4f\t%8.4f\t\n",
// gyro_values.x, gyro_values.y, gyro_values.z,
// accel_values.x, accel_values.y, accel_values.z,
// mag_values.x, mag_values.y, mag_values.z);
// i = 0;
// }
// i++;
attitude_blackmagic(&accel_values, &mag_values, &gyro_values);
@@ -154,7 +154,7 @@ int attitude_estimator_bm_main(int argc, char *argv[])
bool publishing = false;
/* advertise attitude */
int pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att);
orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att);
publishing = true;
struct pollfd fds[] = {
+28 -28
View File
@@ -64,6 +64,7 @@
#include <arch/board/up_pwm_servo.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_outputs.h>
class FMUServo : public device::CDev
@@ -88,6 +89,7 @@ private:
int _task;
int _t_actuators;
int _t_armed;
orb_advert_t _t_outputs;
unsigned _num_outputs;
volatile bool _task_should_exit;
@@ -98,15 +100,12 @@ private:
actuator_controls_s _controls;
static void task_main_trampoline(int argc, char *argv[]);
void task_main();
void task_main() __attribute__((noreturn));
static int control_callback_trampoline(uintptr_t handle,
static int control_callback(uintptr_t handle,
uint8_t control_group,
uint8_t control_index,
float &input);
int control_callback(uint8_t control_group,
uint8_t control_index,
float &input);
};
namespace
@@ -212,6 +211,11 @@ FMUServo::task_main()
_t_armed = orb_subscribe(ORB_ID(actuator_armed));
orb_set_interval(_t_armed, 100); /* 10Hz update rate */
/* advertise the mixed control outputs */
struct actuator_outputs_s outputs;
memset(&outputs, 0, sizeof(outputs));
_t_outputs = orb_advertise(ORB_ID_VEHICLE_CONTROLS, &outputs);
struct pollfd fds[2];
fds[0].fd = _t_actuators;
fds[0].events = POLLIN;
@@ -237,7 +241,6 @@ FMUServo::task_main()
/* do we have a control update? */
if (fds[0].revents & POLLIN) {
float outputs[num_outputs];
/* get controls - must always do this to avoid spinning */
orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, _t_actuators, &_controls);
@@ -246,14 +249,20 @@ FMUServo::task_main()
if (_mixers != nullptr) {
/* do mixing */
_mixers->mix(&outputs[0], num_outputs);
_mixers->mix(&outputs.output[0], num_outputs);
/* iterate actuators */
for (unsigned i = 0; i < num_outputs; i++) {
/* scale for PWM output 900 - 2100us */
up_pwm_servo_set(i, 1500 + (600 * outputs[i]));
outputs.output[i] = 1500 + (600 * outputs.output[i]);
/* output to the servo */
up_pwm_servo_set(i, outputs.output[i]);
}
/* and publish for anyone that cares to see */
orb_publish(ORB_ID_VEHICLE_CONTROLS, _t_outputs, &outputs);
}
}
@@ -264,13 +273,14 @@ FMUServo::task_main()
/* get new value */
orb_copy(ORB_ID(actuator_armed), _t_armed, &aa);
/* update PMW servo armed status */
/* update PWM servo armed status */
up_pwm_servo_arm(aa.armed);
}
}
::close(_t_actuators);
::close(_t_armed);
::close(_t_outputs);
/* make sure servos are off */
up_pwm_servo_deinit();
@@ -285,24 +295,14 @@ FMUServo::task_main()
}
int
FMUServo::control_callback_trampoline(uintptr_t handle,
FMUServo::control_callback(uintptr_t handle,
uint8_t control_group,
uint8_t control_index,
float &input)
{
return ((FMUServo *)handle)->control_callback(control_group, control_index, input);
}
const actuator_controls_s *controls = (actuator_controls_s *)handle;
int
FMUServo::control_callback(uint8_t control_group,
uint8_t control_index,
float &input)
{
/* XXX currently only supporting group zero */
if ((control_group != 0) || (control_index > NUM_ACTUATOR_CONTROLS))
return -1;
input = _controls.control[control_index];
input = controls->control[control_index];
return 0;
}
@@ -377,7 +377,8 @@ FMUServo::ioctl(struct file *filp, int cmd, unsigned long arg)
case MIXERIOCADDSIMPLE: {
mixer_simple_s *mixinfo = (mixer_simple_s *)arg;
SimpleMixer *mixer = new SimpleMixer(control_callback_trampoline, (uintptr_t)this, mixinfo);
SimpleMixer *mixer = new SimpleMixer(control_callback,
(uintptr_t)&_controls, mixinfo);
if (mixer->check()) {
delete mixer;
@@ -385,7 +386,8 @@ FMUServo::ioctl(struct file *filp, int cmd, unsigned long arg)
} else {
if (_mixers == nullptr)
_mixers = new MixerGroup(control_callback_trampoline, (uintptr_t)this);
_mixers = new MixerGroup(control_callback,
(uintptr_t)&_controls);
_mixers->add_mixer(mixer);
}
@@ -406,7 +408,7 @@ FMUServo::ioctl(struct file *filp, int cmd, unsigned long arg)
_mixers = nullptr;
}
_mixers = new MixerGroup(control_callback_trampoline, (uintptr_t)this);
_mixers = new MixerGroup(control_callback, (uintptr_t)&_controls);
if (_mixers->load_from_file(path) != 0) {
delete _mixers;
@@ -564,15 +566,13 @@ fake(int argc, char *argv[])
ac.control[3] = strtol(argv[4], 0, 0) / 100.0f;
int handle = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &ac);
orb_advert_t handle = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &ac);
if (handle < 0) {
puts("advertise failed");
exit(1);
}
close(handle);
exit(0);
}
+1 -1
View File
@@ -99,7 +99,7 @@ protected:
void set_channels(unsigned count, const servo_position_t *data);
private:
int _publication;
orb_advert_t _publication;
struct rc_input_values _input;
};
+1 -1
View File
@@ -37,6 +37,6 @@
APPNAME = tests
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 8096
STACKSIZE = 12000
include $(APPDIR)/mk/app.mk
+8 -5
View File
@@ -90,11 +90,11 @@ struct {
const char *path;
int (* test)(int argc, char *argv[]);
} sensors[] = {
{"l3gd20", "/dev/l3gd20", l3gd20},
{"bma180", "/dev/bma180", bma180},
{"mpu6000", "/dev/accel", mpu6000},
{"l3gd20", "/dev/l3gd20", l3gd20},
{"hmc5883l", "/dev/hmc5883l", hmc5883l},
{"ms5611", "/dev/ms5611", ms5611},
{"mpu6000", "/dev/accel", mpu6000},
// {"lis331", "/dev/lis331", lis331},
{NULL, NULL, NULL}
};
@@ -253,6 +253,9 @@ l3gd20(int argc, char *argv[])
static int
bma180(int argc, char *argv[])
{
// XXX THIS SENSOR IS OBSOLETE
// TEST REMAINS, BUT ALWAYS RETURNS OK
printf("\tBMA180: test start\n");
fflush(stdout);
@@ -264,7 +267,7 @@ bma180(int argc, char *argv[])
if (fd < 0) {
printf("\tBMA180: open fail\n");
return ERROR;
return OK;
}
// if (ioctl(fd, LIS331_SETRATE, LIS331_RATE_50Hz) ||
@@ -283,7 +286,7 @@ bma180(int argc, char *argv[])
if (ret != sizeof(buf)) {
printf("\tBMA180: read1 fail (%d)\n", ret);
close(fd);
return ERROR;
return OK;
} else {
printf("\tBMA180 values: x:%d\ty:%d\tz:%d\n", buf[0], buf[1], buf[2]);
@@ -297,7 +300,7 @@ bma180(int argc, char *argv[])
if (ret != sizeof(buf)) {
printf("\tBMA180: read2 fail (%d)\n", ret);
close(fd);
return ERROR;
return OK;
} else {
printf("\tBMA180: x:%d\ty:%d\tz:%d\n", buf[0], buf[1], buf[2]);
+1 -2
View File
@@ -37,7 +37,6 @@
APPNAME = sensors
PRIORITY = SCHED_PRIORITY_MAX-5
# Reduce to 4096 on next occasion
STACKSIZE = 8000
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk
+244 -111
View File
File diff suppressed because it is too large Load Diff
+1 -1
View File
@@ -34,7 +34,7 @@
/**
* @file tinybson.h
*
* A simple subset SAX-style BSON parser and generator.
* A simple subset SAX-style BSON parser and generator. See http://bsonspec.org
*
* Some types and defines taken from the standalone BSON parser/generator
* in the Mongo C connector.
+11 -6
View File
@@ -91,6 +91,9 @@ UT_icd param_icd = {sizeof(struct param_wbuf_s), NULL, NULL, NULL};
/** parameter update topic */
ORB_DEFINE(parameter_update, struct parameter_update_s);
/** parameter update topic handle */
static orb_advert_t param_topic = -1;
/** lock the parameter store */
static void
param_lock(void)
@@ -390,13 +393,15 @@ out:
struct parameter_update_s pup = { .timestamp = hrt_absolute_time() };
/*
* Because we're a library, we can't keep a persistent advertisement
* around, so if we succeed in updating the topic, we have to toss
* the descriptor straight away.
* If we don't have a handle to our topic, create one now; otherwise
* just publish.
*/
int param_topic = orb_advertise(ORB_ID(parameter_update), &pup);
if (param_topic != -1)
close(param_topic);
if (param_topic == -1) {
param_topic = orb_advertise(ORB_ID(parameter_update), &pup);
} else {
orb_publish(ORB_ID(parameter_update), param_topic, &pup);
}
}
return result;
+6
View File
@@ -114,3 +114,9 @@ ORB_DEFINE(actuator_controls_1, struct actuator_controls_s);
ORB_DEFINE(actuator_controls_2, struct actuator_controls_s);
ORB_DEFINE(actuator_controls_3, struct actuator_controls_s);
ORB_DEFINE(actuator_armed, struct actuator_armed_s);
#include "topics/actuator_outputs.h"
ORB_DEFINE(actuator_outputs_0, struct actuator_outputs_s);
ORB_DEFINE(actuator_outputs_1, struct actuator_outputs_s);
ORB_DEFINE(actuator_outputs_2, struct actuator_outputs_s);
ORB_DEFINE(actuator_outputs_3, struct actuator_outputs_s);
+68
View File
@@ -0,0 +1,68 @@
/****************************************************************************
*
* 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_outputs.h
*
* Actuator output values.
*
* Values published to these topics are the outputs of the control mixing
* system as sent to the actuators (servos, motors, etc.) that operate
* the vehicle.
*
* Each topic can be published by a single output driver.
*/
#ifndef TOPIC_ACTUATOR_OUTPUTS_H
#define TOPIC_ACTUATOR_OUTPUTS_H
#include <stdint.h>
#include "../uORB.h"
#define NUM_ACTUATOR_OUTPUTS 16
#define NUM_ACTUATOR_OUTPUT_GROUPS 4 /**< for sanity checking */
struct actuator_outputs_s {
float output[NUM_ACTUATOR_OUTPUTS];
};
/* actuator output sets; this list can be expanded as more drivers emerge */
ORB_DECLARE(actuator_outputs_0);
ORB_DECLARE(actuator_outputs_1);
ORB_DECLARE(actuator_outputs_2);
ORB_DECLARE(actuator_outputs_3);
/* output sets with pre-defined applications */
#define ORB_ID_VEHICLE_CONTROLS ORB_ID(actuator_outputs_0)
#endif
+58 -30
View File
@@ -112,6 +112,8 @@ public:
virtual ssize_t write(struct file *filp, const char *buffer, size_t buflen);
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
static ssize_t publish(const orb_metadata *meta, orb_advert_t handle, const void *data);
protected:
virtual pollevent_t poll_state(struct file *filp);
virtual void poll_notify_one(struct pollfd *fds, pollevent_t events);
@@ -298,6 +300,8 @@ ORBDevNode::write(struct file *filp, const char *buffer, size_t buflen)
*
* Writes outside interrupt context will allocate the object
* if it has not yet been allocated.
*
* Note that filp will usually be NULL.
*/
if (nullptr == _data) {
if (!up_interrupt_context()) {
@@ -353,12 +357,42 @@ ORBDevNode::ioctl(struct file *filp, int cmd, unsigned long arg)
sd->update_interval = arg;
return OK;
case ORBIOCGADVERTISER:
*(uintptr_t *)arg = (uintptr_t)this;
return OK;
default:
/* give it to the superclass */
return CDev::ioctl(filp, cmd, arg);
}
}
ssize_t
ORBDevNode::publish(const orb_metadata *meta, orb_advert_t handle, const void *data)
{
ORBDevNode *devnode = (ORBDevNode *)handle;
int ret;
/* this is a bit risky, since we are trusting the handle in order to deref it */
if (devnode->_meta != meta) {
errno = EINVAL;
return ERROR;
}
/* call the devnode write method with no file pointer */
ret = devnode->write(nullptr, (const char *)data, meta->o_size);
if (ret < 0)
return ERROR;
if (ret != (int)meta->o_size) {
errno = EIO;
return ERROR;
}
return OK;
}
pollevent_t
ORBDevNode::poll_state(struct file *filp)
{
@@ -614,7 +648,7 @@ test()
if (pfd < 0)
return test_fail("advertise failed: %d", errno);
test_note("publish fd %d", pfd);
test_note("publish handle 0x%08x", pfd);
sfd = orb_subscribe(ORB_ID(orb_test));
if (sfd < 0)
@@ -877,29 +911,35 @@ node_open(Flavor f, const struct orb_metadata *meta, const void *data, bool adve
return ERROR;
}
/* the advertiser must perform an initial publish to initialise the object */
if (advertiser) {
ret = orb_publish(meta, fd, data);
if (ret != OK) {
/* save errno across the close */
ret = errno;
close(fd);
errno = ret;
return ERROR;
}
}
/* everything has been OK, we can return the handle now */
return fd;
}
} // namespace
int
orb_advert_t
orb_advertise(const struct orb_metadata *meta, const void *data)
{
return node_open(PUBSUB, meta, data, true);
int result, fd;
orb_advert_t advertiser;
/* open the node as an advertiser */
fd = node_open(PUBSUB, meta, data, true);
if (fd == ERROR)
return ERROR;
/* get the advertiser handle and close the node */
result = ioctl(fd, ORBIOCGADVERTISER, (unsigned long)&advertiser);
close(fd);
if (result == ERROR)
return ERROR;
/* the advertiser must perform an initial publish to initialise the object */
result= orb_publish(meta, advertiser, data);
if (result == ERROR)
return ERROR;
return advertiser;
}
int
@@ -915,21 +955,9 @@ orb_unsubscribe(int handle)
}
int
orb_publish(const struct orb_metadata *meta, int handle, const void *data)
orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data)
{
int ret;
ret = write(handle, data, meta->o_size);
if (ret < 0)
return ERROR;
if (ret != (int)meta->o_size) {
errno = EIO;
return ERROR;
}
return OK;
return ORBDevNode::publish(meta, handle, data);
}
int
+18 -3
View File
@@ -105,12 +105,27 @@ struct orb_metadata {
__BEGIN_DECLS
/**
* ORB topic advertiser handle.
*
* Advertiser handles are global; once obtained they can be shared freely
* and do not need to be closed or released.
*
* This permits publication from interrupt context and other contexts where
* a file-descriptor-based handle would not otherwise be in scope for the
* publisher.
*/
typedef intptr_t orb_advert_t;
/**
* Advertise as the publisher of a topic.
*
* This performs the initial advertisement of a topic; it creates the topic
* node in /obj if required and publishes the initial data.
*
* Any number of advertisers may publish to a topic; publications are atomic
* but co-ordination between publishers is not provided by the ORB.
*
* @param meta The uORB metadata (usually from the ORB_ID() macro)
* for the topic.
* @param data A pointer to the initial data to be published.
@@ -122,7 +137,7 @@ __BEGIN_DECLS
* ORB_DEFINE with no corresponding ORB_DECLARE)
* this function will return -1 and set errno to ENOENT.
*/
extern int orb_advertise(const struct orb_metadata *meta, const void *data) __EXPORT;
extern orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data) __EXPORT;
/**
* Publish new data to a topic.
@@ -131,13 +146,13 @@ extern int orb_advertise(const struct orb_metadata *meta, const void *data) __EX
* will be notified. Subscribers that are not waiting can check the topic
* for updates using orb_check and/or orb_stat.
*
* @handle The handle returned from orb_advertise.
* @param meta The uORB metadata (usually from the ORB_ID() macro)
* for the topic.
* @handle The handle returned from orb_advertise.
* @param data A pointer to the data to be published.
* @return OK on success, ERROR otherwise with errno set accordingly.
*/
extern int orb_publish(const struct orb_metadata *meta, int handle, const void *data) __EXPORT;
extern int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data) __EXPORT;
/**
* Subscribe to a topic.