diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2013-10-15 08:39:57 +0200 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2013-10-15 08:39:57 +0200 |
commit | 3dcd5dbd0e25432049e5ba6971851931764ae043 (patch) | |
tree | 22bcca8a6c2593fe4b6d0585015473c24821dd51 | |
parent | 16efc0d2d9437c44142503265553e8413f3f9cb3 (diff) | |
download | px4-firmware-3dcd5dbd0e25432049e5ba6971851931764ae043.tar.gz px4-firmware-3dcd5dbd0e25432049e5ba6971851931764ae043.tar.bz2 px4-firmware-3dcd5dbd0e25432049e5ba6971851931764ae043.zip |
Piping through manual control channels
-rw-r--r-- | src/modules/fw_att_control/fw_att_control_main.cpp | 4 | ||||
-rw-r--r-- | src/modules/multirotor_att_control/multirotor_att_control_main.c | 6 | ||||
-rw-r--r-- | src/modules/sensors/sensors.cpp | 22 |
3 files changed, 32 insertions, 0 deletions
diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp index ae9aaa2da..eb67874db 100644 --- a/src/modules/fw_att_control/fw_att_control_main.cpp +++ b/src/modules/fw_att_control/fw_att_control_main.cpp @@ -683,6 +683,10 @@ FixedwingAttitudeControl::task_main() _actuators.control[4] = _manual.flaps; } + _actuators.control[5] = _manual.aux1; + _actuators.control[6] = _manual.aux2; + _actuators.control[7] = _manual.aux3; + /* lazily publish the setpoint only once available */ _actuators.timestamp = hrt_absolute_time(); diff --git a/src/modules/multirotor_att_control/multirotor_att_control_main.c b/src/modules/multirotor_att_control/multirotor_att_control_main.c index 44f8f664b..60a211817 100644 --- a/src/modules/multirotor_att_control/multirotor_att_control_main.c +++ b/src/modules/multirotor_att_control/multirotor_att_control_main.c @@ -368,6 +368,12 @@ mc_thread_main(int argc, char *argv[]) actuators.control[3] = 0.0f; } + /* fill in manual control values */ + actuators.control[4] = manual.flaps; + actuators.control[5] = manual.aux1; + actuators.control[6] = manual.aux2; + actuators.control[7] = manual.aux3; + actuators.timestamp = hrt_absolute_time(); orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators); diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 3fcacaf8f..630131e1e 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -74,6 +74,7 @@ #include <uORB/topics/sensor_combined.h> #include <uORB/topics/rc_channels.h> #include <uORB/topics/manual_control_setpoint.h> +#include <uORB/topics/actuator_controls.h> #include <uORB/topics/vehicle_control_mode.h> #include <uORB/topics/parameter_update.h> #include <uORB/topics/battery_status.h> @@ -264,6 +265,7 @@ private: orb_advert_t _sensor_pub; /**< combined sensor data topic */ orb_advert_t _manual_control_pub; /**< manual control signal topic */ + orb_advert_t _actuator_group_3_pub; /**< manual control as actuator topic */ orb_advert_t _rc_pub; /**< raw r/c control topic */ orb_advert_t _battery_pub; /**< battery status */ orb_advert_t _airspeed_pub; /**< airspeed */ @@ -519,6 +521,7 @@ Sensors::Sensors() : /* publications */ _sensor_pub(-1), _manual_control_pub(-1), + _actuator_group_3_pub(-1), _rc_pub(-1), _battery_pub(-1), _airspeed_pub(-1), @@ -1318,6 +1321,7 @@ Sensors::rc_poll() orb_copy(ORB_ID(input_rc), _rc_sub, &rc_input); struct manual_control_setpoint_s manual_control; + struct actuator_controls_s actuator_group_3; /* initialize to default values */ manual_control.roll = NAN; @@ -1485,6 +1489,16 @@ Sensors::rc_poll() manual_control.aux5 = limit_minus_one_to_one(_rc.chan[_rc.function[AUX_5]].scaled); } + /* copy from mapped manual control to control group 3 */ + actuator_group_3.control[0] = manual_control.roll; + actuator_group_3.control[1] = manual_control.pitch; + actuator_group_3.control[2] = manual_control.yaw; + actuator_group_3.control[3] = manual_control.throttle; + actuator_group_3.control[4] = manual_control.flaps; + actuator_group_3.control[5] = manual_control.aux1; + actuator_group_3.control[6] = manual_control.aux2; + actuator_group_3.control[7] = manual_control.aux3; + /* check if ready for publishing */ if (_rc_pub > 0) { orb_publish(ORB_ID(rc_channels), _rc_pub, &_rc); @@ -1501,6 +1515,14 @@ Sensors::rc_poll() } else { _manual_control_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual_control); } + + /* check if ready for publishing */ + if (_actuator_group_3_pub > 0) { + orb_publish(ORB_ID(actuator_controls_3), _actuator_group_3_pub, &actuator_group_3); + + } else { + _actuator_group_3_pub = orb_advertise(ORB_ID(actuator_controls_3), &actuator_group_3); + } } } |