aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2013-06-14 13:53:26 +0200
committerJulian Oes <julian@oes.ch>2013-06-14 13:53:26 +0200
commit90f5e30f2a177bed2ac08e76699ec3029292d640 (patch)
tree25752b2843f573e3affe42b7e20b8fc06c457290 /src/drivers
parent236053a600f5708aee0e5849f4fefc2380e7d101 (diff)
downloadpx4-firmware-90f5e30f2a177bed2ac08e76699ec3029292d640.tar.gz
px4-firmware-90f5e30f2a177bed2ac08e76699ec3029292d640.tar.bz2
px4-firmware-90f5e30f2a177bed2ac08e76699ec3029292d640.zip
Introduced new actuator_safety topic
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/ardrone_interface/ardrone_interface.c15
-rw-r--r--src/drivers/blinkm/blinkm.cpp21
-rw-r--r--src/drivers/hil/hil.cpp17
-rw-r--r--src/drivers/mkblctrl/mkblctrl.cpp19
-rw-r--r--src/drivers/px4fmu/fmu.cpp27
-rw-r--r--src/drivers/px4io/px4io.cpp41
6 files changed, 80 insertions, 60 deletions
diff --git a/src/drivers/ardrone_interface/ardrone_interface.c b/src/drivers/ardrone_interface/ardrone_interface.c
index 264041e65..4a6f30a4f 100644
--- a/src/drivers/ardrone_interface/ardrone_interface.c
+++ b/src/drivers/ardrone_interface/ardrone_interface.c
@@ -55,6 +55,7 @@
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/actuator_safety.h>
#include <systemlib/systemlib.h>
@@ -247,13 +248,13 @@ int ardrone_interface_thread_main(int argc, char *argv[])
memset(&state, 0, sizeof(state));
struct actuator_controls_s actuator_controls;
memset(&actuator_controls, 0, sizeof(actuator_controls));
- struct actuator_armed_s armed;
- armed.armed = false;
+ struct actuator_safety_s safety;
+ safety.armed = false;
/* subscribe to attitude, motor setpoints and system state */
int actuator_controls_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS);
int state_sub = orb_subscribe(ORB_ID(vehicle_status));
- int armed_sub = orb_subscribe(ORB_ID(actuator_armed));
+ int safety_sub = orb_subscribe(ORB_ID(actuator_safety));
printf("[ardrone_interface] Motors initialized - ready.\n");
fflush(stdout);
@@ -322,18 +323,14 @@ int ardrone_interface_thread_main(int argc, char *argv[])
} else {
/* MAIN OPERATION MODE */
- /* get a local copy of the vehicle state */
- orb_copy(ORB_ID(vehicle_status), state_sub, &state);
/* get a local copy of the actuator controls */
orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_controls_sub, &actuator_controls);
- orb_copy(ORB_ID(actuator_armed), armed_sub, &armed);
+ orb_copy(ORB_ID(actuator_safety), safety_sub, &safety);
/* for now only spin if armed and immediately shut down
* if in failsafe
*/
- //XXX fix this
- //if (armed.armed && !armed.lockdown) {
- if (state.flag_fmu_armed) {
+ if (safety.armed && !safety.lockdown) {
ardrone_mixing_and_output(ardrone_write, &actuator_controls);
} else {
diff --git a/src/drivers/blinkm/blinkm.cpp b/src/drivers/blinkm/blinkm.cpp
index 7a64b72a4..1cfdcfbed 100644
--- a/src/drivers/blinkm/blinkm.cpp
+++ b/src/drivers/blinkm/blinkm.cpp
@@ -116,6 +116,7 @@
#include <poll.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_safety.h>
#include <uORB/topics/vehicle_gps_position.h>
static const float MAX_CELL_VOLTAGE = 4.3f;
@@ -376,6 +377,7 @@ BlinkM::led()
static int vehicle_status_sub_fd;
static int vehicle_gps_position_sub_fd;
+ static int actuator_safety_sub_fd;
static int num_of_cells = 0;
static int detected_cells_runcount = 0;
@@ -386,6 +388,7 @@ BlinkM::led()
static int led_interval = 1000;
static int no_data_vehicle_status = 0;
+ static int no_data_actuator_safety = 0;
static int no_data_vehicle_gps_position = 0;
static bool topic_initialized = false;
@@ -398,6 +401,9 @@ BlinkM::led()
vehicle_status_sub_fd = orb_subscribe(ORB_ID(vehicle_status));
orb_set_interval(vehicle_status_sub_fd, 1000);
+ actuator_safety_sub_fd = orb_subscribe(ORB_ID(actuator_safety));
+ orb_set_interval(actuator_safety_sub_fd, 1000);
+
vehicle_gps_position_sub_fd = orb_subscribe(ORB_ID(vehicle_gps_position));
orb_set_interval(vehicle_gps_position_sub_fd, 1000);
@@ -452,12 +458,14 @@ BlinkM::led()
if (led_thread_runcount == 15) {
/* obtained data for the first file descriptor */
struct vehicle_status_s vehicle_status_raw;
+ struct actuator_safety_s actuator_safety;
struct vehicle_gps_position_s vehicle_gps_position_raw;
memset(&vehicle_status_raw, 0, sizeof(vehicle_status_raw));
memset(&vehicle_gps_position_raw, 0, sizeof(vehicle_gps_position_raw));
bool new_data_vehicle_status;
+ bool new_data_actuator_safety;
bool new_data_vehicle_gps_position;
orb_check(vehicle_status_sub_fd, &new_data_vehicle_status);
@@ -471,6 +479,17 @@ BlinkM::led()
no_data_vehicle_status = 3;
}
+ orb_check(actuator_safety_sub_fd, &new_data_actuator_safety);
+
+ if (new_data_actuator_safety) {
+ orb_copy(ORB_ID(actuator_safety), actuator_safety_sub_fd, &actuator_safety);
+ no_data_actuator_safety = 0;
+ } else {
+ no_data_actuator_safety++;
+ if(no_data_vehicle_status >= 3)
+ no_data_vehicle_status = 3;
+ }
+
orb_check(vehicle_gps_position_sub_fd, &new_data_vehicle_gps_position);
if (new_data_vehicle_gps_position) {
@@ -530,7 +549,7 @@ BlinkM::led()
} else {
/* no battery warnings here */
- if(vehicle_status_raw.flag_fmu_armed == false) {
+ if(actuator_safety.armed == false) {
/* system not armed */
led_color_1 = LED_RED;
led_color_2 = LED_RED;
diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp
index d9aa772d4..e851d8a52 100644
--- a/src/drivers/hil/hil.cpp
+++ b/src/drivers/hil/hil.cpp
@@ -75,6 +75,7 @@
#include <systemlib/mixer/mixer.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/actuator_safety.h>
#include <uORB/topics/actuator_outputs.h>
#include <systemlib/err.h>
@@ -108,7 +109,7 @@ private:
int _current_update_rate;
int _task;
int _t_actuators;
- int _t_armed;
+ int _t_safety;
orb_advert_t _t_outputs;
unsigned _num_outputs;
bool _primary_pwm_device;
@@ -161,7 +162,7 @@ HIL::HIL() :
_current_update_rate(0),
_task(-1),
_t_actuators(-1),
- _t_armed(-1),
+ _t_safety(-1),
_t_outputs(0),
_num_outputs(0),
_primary_pwm_device(false),
@@ -321,8 +322,8 @@ HIL::task_main()
/* force a reset of the update rate */
_current_update_rate = 0;
- _t_armed = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(_t_armed, 200); /* 5Hz update rate */
+ _t_safety = orb_subscribe(ORB_ID(actuator_safety));
+ orb_set_interval(_t_safety, 200); /* 5Hz update rate */
/* advertise the mixed control outputs */
actuator_outputs_s outputs;
@@ -334,7 +335,7 @@ HIL::task_main()
pollfd fds[2];
fds[0].fd = _t_actuators;
fds[0].events = POLLIN;
- fds[1].fd = _t_armed;
+ fds[1].fd = _t_safety;
fds[1].events = POLLIN;
unsigned num_outputs;
@@ -426,15 +427,15 @@ HIL::task_main()
/* how about an arming update? */
if (fds[1].revents & POLLIN) {
- actuator_armed_s aa;
+ actuator_safety_s aa;
/* get new value */
- orb_copy(ORB_ID(actuator_armed), _t_armed, &aa);
+ orb_copy(ORB_ID(actuator_safety), _t_safety, &aa);
}
}
::close(_t_actuators);
- ::close(_t_armed);
+ ::close(_t_safety);
/* make sure servos are off */
// up_pwm_servo_deinit();
diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp
index c67276f8a..093b53d42 100644
--- a/src/drivers/mkblctrl/mkblctrl.cpp
+++ b/src/drivers/mkblctrl/mkblctrl.cpp
@@ -74,6 +74,7 @@
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_outputs.h>
+#include <uORB/topics/actuator_safety.h>
#include <systemlib/err.h>
@@ -132,7 +133,7 @@ private:
int _current_update_rate;
int _task;
int _t_actuators;
- int _t_armed;
+ int _t_actuator_safety;
unsigned int _motor;
int _px4mode;
int _frametype;
@@ -240,7 +241,7 @@ MK::MK(int bus) :
_update_rate(50),
_task(-1),
_t_actuators(-1),
- _t_armed(-1),
+ _t_actuator_safety(-1),
_t_outputs(0),
_t_actuators_effective(0),
_num_outputs(0),
@@ -496,8 +497,8 @@ MK::task_main()
/* force a reset of the update rate */
_current_update_rate = 0;
- _t_armed = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(_t_armed, 200); /* 5Hz update rate */
+ _t_actuator_safety = orb_subscribe(ORB_ID(actuator_safety));
+ orb_set_interval(_t_actuator_safety, 200); /* 5Hz update rate */
/* advertise the mixed control outputs */
actuator_outputs_s outputs;
@@ -519,7 +520,7 @@ MK::task_main()
pollfd fds[2];
fds[0].fd = _t_actuators;
fds[0].events = POLLIN;
- fds[1].fd = _t_armed;
+ fds[1].fd = _t_actuator_safety;
fds[1].events = POLLIN;
log("starting");
@@ -625,13 +626,13 @@ MK::task_main()
/* how about an arming update? */
if (fds[1].revents & POLLIN) {
- actuator_armed_s aa;
+ actuator_safety_s as;
/* get new value */
- orb_copy(ORB_ID(actuator_armed), _t_armed, &aa);
+ orb_copy(ORB_ID(actuator_safety), _t_actuator_safety, &as);
/* update PWM servo armed status if armed and not locked down */
- mk_servo_arm(aa.armed && !aa.lockdown);
+ mk_servo_arm(as.armed && !as.lockdown);
}
@@ -639,7 +640,7 @@ MK::task_main()
::close(_t_actuators);
::close(_t_actuators_effective);
- ::close(_t_armed);
+ ::close(_t_actuator_safety);
/* make sure servos are off */
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index bf72892eb..db4c87ddc 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -69,6 +69,7 @@
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_outputs.h>
+#include <uORB/topics/actuator_safety.h>
#include <systemlib/err.h>
#include <systemlib/ppm_decode.h>
@@ -104,7 +105,7 @@ private:
unsigned _current_update_rate;
int _task;
int _t_actuators;
- int _t_armed;
+ int _t_actuator_safety;
orb_advert_t _t_outputs;
orb_advert_t _t_actuators_effective;
unsigned _num_outputs;
@@ -174,7 +175,7 @@ PX4FMU::PX4FMU() :
_current_update_rate(0),
_task(-1),
_t_actuators(-1),
- _t_armed(-1),
+ _t_actuator_safety(-1),
_t_outputs(0),
_t_actuators_effective(0),
_num_outputs(0),
@@ -376,8 +377,8 @@ PX4FMU::task_main()
/* force a reset of the update rate */
_current_update_rate = 0;
- _t_armed = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(_t_armed, 200); /* 5Hz update rate */
+ _t_actuator_safety = orb_subscribe(ORB_ID(actuator_safety));
+ orb_set_interval(_t_actuator_safety, 200); /* 5Hz update rate */
/* advertise the mixed control outputs */
actuator_outputs_s outputs;
@@ -396,7 +397,7 @@ PX4FMU::task_main()
pollfd fds[2];
fds[0].fd = _t_actuators;
fds[0].events = POLLIN;
- fds[1].fd = _t_armed;
+ fds[1].fd = _t_actuator_safety;
fds[1].events = POLLIN;
unsigned num_outputs = (_mode == MODE_2PWM) ? 2 : 4;
@@ -499,13 +500,13 @@ PX4FMU::task_main()
/* how about an arming update? */
if (fds[1].revents & POLLIN) {
- actuator_armed_s aa;
+ actuator_safety_s as;
/* get new value */
- orb_copy(ORB_ID(actuator_armed), _t_armed, &aa);
+ orb_copy(ORB_ID(actuator_safety), _t_actuator_safety, &as);
/* update PWM servo armed status if armed and not locked down */
- bool set_armed = aa.armed && !aa.lockdown;
+ bool set_armed = as.armed && !as.lockdown;
if (set_armed != _armed) {
_armed = set_armed;
up_pwm_servo_arm(set_armed);
@@ -535,7 +536,7 @@ PX4FMU::task_main()
::close(_t_actuators);
::close(_t_actuators_effective);
- ::close(_t_armed);
+ ::close(_t_actuator_safety);
/* make sure servos are off */
up_pwm_servo_deinit();
@@ -1021,12 +1022,12 @@ fake(int argc, char *argv[])
if (handle < 0)
errx(1, "advertise failed");
- actuator_armed_s aa;
+ actuator_safety_s as;
- aa.armed = true;
- aa.lockdown = false;
+ as.armed = true;
+ as.lockdown = false;
- handle = orb_advertise(ORB_ID(actuator_armed), &aa);
+ handle = orb_advertise(ORB_ID(actuator_safety), &as);
if (handle < 0)
errx(1, "advertise failed 2");
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 962a91c7f..28a3eb917 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -75,6 +75,7 @@
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_outputs.h>
+#include <uORB/topics/actuator_safety.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/rc_channels.h>
@@ -152,7 +153,7 @@ private:
/* subscribed topics */
int _t_actuators; ///< actuator controls topic
- int _t_armed; ///< system armed control topic
+ int _t_actuator_safety; ///< system armed control topic
int _t_vstatus; ///< system / vehicle status
int _t_param; ///< parameter update topic
@@ -327,7 +328,7 @@ PX4IO::PX4IO() :
_status(0),
_alarms(0),
_t_actuators(-1),
- _t_armed(-1),
+ _t_actuator_safety(-1),
_t_vstatus(-1),
_t_param(-1),
_to_input_rc(0),
@@ -433,20 +434,20 @@ PX4IO::init()
* remains untouched (so manual override is still available).
*/
- int vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
+ int safety_sub = orb_subscribe(ORB_ID(actuator_safety));
/* fill with initial values, clear updated flag */
- vehicle_status_s status;
+ struct actuator_safety_s armed;
uint64_t try_start_time = hrt_absolute_time();
bool updated = false;
- /* keep checking for an update, ensure we got a recent state,
+ /* keep checking for an update, ensure we got a arming information,
not something that was published a long time ago. */
do {
- orb_check(vstatus_sub, &updated);
+ orb_check(safety_sub, &updated);
if (updated) {
/* got data, copy and exit loop */
- orb_copy(ORB_ID(vehicle_status), vstatus_sub, &status);
+ orb_copy(ORB_ID(actuator_safety), safety_sub, &armed);
break;
}
@@ -472,10 +473,10 @@ PX4IO::init()
cmd.param6 = 0;
cmd.param7 = 0;
cmd.command = VEHICLE_CMD_COMPONENT_ARM_DISARM;
- cmd.target_system = status.system_id;
- cmd.target_component = status.component_id;
- cmd.source_system = status.system_id;
- cmd.source_component = status.component_id;
+ // cmd.target_system = status.system_id;
+ // cmd.target_component = status.component_id;
+ // cmd.source_system = status.system_id;
+ // cmd.source_component = status.component_id;
/* ask to confirm command */
cmd.confirmation = 1;
@@ -484,10 +485,10 @@ PX4IO::init()
/* spin here until IO's state has propagated into the system */
do {
- orb_check(vstatus_sub, &updated);
+ orb_check(safety_sub, &updated);
if (updated) {
- orb_copy(ORB_ID(vehicle_status), vstatus_sub, &status);
+ orb_copy(ORB_ID(actuator_safety), safety_sub, &armed);
}
/* wait 10 ms */
@@ -500,7 +501,7 @@ PX4IO::init()
}
/* keep waiting for state change for 10 s */
- } while (!status.flag_fmu_armed);
+ } while (!armed.armed);
/* regular boot, no in-air restart, init IO */
} else {
@@ -564,8 +565,8 @@ PX4IO::task_main()
ORB_ID(actuator_controls_1));
orb_set_interval(_t_actuators, 20); /* default to 50Hz */
- _t_armed = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(_t_armed, 200); /* 5Hz update rate */
+ _t_actuator_safety = orb_subscribe(ORB_ID(actuator_safety));
+ orb_set_interval(_t_actuator_safety, 200); /* 5Hz update rate */
_t_vstatus = orb_subscribe(ORB_ID(vehicle_status));
orb_set_interval(_t_vstatus, 200); /* 5Hz update rate max. */
@@ -577,7 +578,7 @@ PX4IO::task_main()
pollfd fds[4];
fds[0].fd = _t_actuators;
fds[0].events = POLLIN;
- fds[1].fd = _t_armed;
+ fds[1].fd = _t_actuator_safety;
fds[1].events = POLLIN;
fds[2].fd = _t_vstatus;
fds[2].events = POLLIN;
@@ -713,16 +714,16 @@ PX4IO::set_failsafe_values(const uint16_t *vals, unsigned len)
int
PX4IO::io_set_arming_state()
{
- actuator_armed_s armed; ///< system armed state
+ actuator_safety_s safety; ///< system armed state
vehicle_status_s vstatus; ///< overall system state
- orb_copy(ORB_ID(actuator_armed), _t_armed, &armed);
+ orb_copy(ORB_ID(actuator_safety), _t_actuator_safety, &safety);
orb_copy(ORB_ID(vehicle_status), _t_vstatus, &vstatus);
uint16_t set = 0;
uint16_t clear = 0;
- if (armed.armed && !armed.lockdown) {
+ if (safety.armed && !safety.lockdown) {
set |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
} else {
clear |= PX4IO_P_SETUP_ARMING_FMU_ARMED;