aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mc_att_control
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-12-25 09:59:58 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-12-25 09:59:58 +0100
commitb376316fb19e497f76512a0353183936396e769d (patch)
tree428bcd6ee1926b57a64cc47d903273225fb56ba4 /src/modules/mc_att_control
parent25af4b266ca48b183a1ad375856396f67d6ab30f (diff)
parentd8eefa30538331fde7e5ce79fef4e04dc62664bc (diff)
downloadpx4-firmware-b376316fb19e497f76512a0353183936396e769d.tar.gz
px4-firmware-b376316fb19e497f76512a0353183936396e769d.tar.bz2
px4-firmware-b376316fb19e497f76512a0353183936396e769d.zip
Merge remote-tracking branch 'upstream/isvtol' into dev_ros
Conflicts: src/modules/mc_att_control/mc_att_control_main.cpp src/modules/uORB/topics/vehicle_status.h
Diffstat (limited to 'src/modules/mc_att_control')
-rw-r--r--src/modules/mc_att_control/mc_att_control.cpp17
-rw-r--r--src/modules/mc_att_control/mc_att_control.h2
2 files changed, 3 insertions, 16 deletions
diff --git a/src/modules/mc_att_control/mc_att_control.cpp b/src/modules/mc_att_control/mc_att_control.cpp
index 90a6c90fe..5dfe18cf2 100644
--- a/src/modules/mc_att_control/mc_att_control.cpp
+++ b/src/modules/mc_att_control/mc_att_control.cpp
@@ -97,17 +97,6 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() :
_params_handles.acro_roll_max = PX4_PARAM_INIT(MC_ACRO_R_MAX);
_params_handles.acro_pitch_max = PX4_PARAM_INIT(MC_ACRO_P_MAX);
_params_handles.acro_yaw_max = PX4_PARAM_INIT(MC_ACRO_Y_MAX);
- _params_handles.autostart_id = PX4_PARAM_INIT(SYS_AUTOSTART);
-
- /* fetch initial parameter values */
- parameters_update();
- /* set correct uORB ID, depending on if vehicle is VTOL or not */
- if (_params.autostart_id >= 13000 && _params.autostart_id <= 13999) { /* VTOL airframe?*/
- _is_vtol = true;
- }
- else {
- _is_vtol = false;
- }
/*
* do subscriptions
@@ -235,7 +224,7 @@ void MulticopterAttitudeControl::handle_vehicle_attitude(const PX4_TOPIC_T(vehi
if (_v_rates_sp_pub != nullptr) {
_v_rates_sp_pub->publish(_v_rates_sp_mod);
} else {
- if (_is_vtol) {
+ if (_v_status->get()._is_vtol) {
_v_rates_sp_pub = PX4_ADVERTISE(_n, mc_virtual_rates_setpoint);
} else {
_v_rates_sp_pub = PX4_ADVERTISE(_n, vehicle_rates_setpoint);
@@ -264,7 +253,7 @@ void MulticopterAttitudeControl::handle_vehicle_attitude(const PX4_TOPIC_T(vehi
_v_rates_sp_pub->publish(_v_rates_sp_mod);
} else {
- if (_is_vtol) {
+ if (_v_status->get()._is_vtol) {
_v_rates_sp_pub = PX4_ADVERTISE(_n, mc_virtual_rates_setpoint);
} else {
_v_rates_sp_pub = PX4_ADVERTISE(_n, vehicle_rates_setpoint);
@@ -295,7 +284,7 @@ void MulticopterAttitudeControl::handle_vehicle_attitude(const PX4_TOPIC_T(vehi
_actuators_0_pub->publish(_actuators);
} else {
- if (_is_vtol) {
+ if (_v_status()->get()._is_vtol) {
_actuators_0_pub = PX4_ADVERTISE(_n, actuator_controls_virtual_mc);
} else {
_actuators_0_pub = PX4_ADVERTISE(_n, actuator_controls_0);
diff --git a/src/modules/mc_att_control/mc_att_control.h b/src/modules/mc_att_control/mc_att_control.h
index 33552c269..bff5289fd 100644
--- a/src/modules/mc_att_control/mc_att_control.h
+++ b/src/modules/mc_att_control/mc_att_control.h
@@ -93,8 +93,6 @@ private:
px4::Publisher * _v_rates_sp_pub; /**< rate setpoint publication */
px4::Publisher * _actuators_0_pub; /**< attitude actuator controls publication */
- bool _is_vtol; /**< true if vehicle is vtol, to be replaced with global API */
-
px4::NodeHandle _n;
struct {