diff options
author | t0ni0 <azntonio789@gmail.com> | 2014-06-03 23:38:18 -0400 |
---|---|---|
committer | t0ni0 <azntonio789@gmail.com> | 2014-06-03 23:38:18 -0400 |
commit | e12d3af503c5ebc105e5b3c3ef8e51bd75959329 (patch) | |
tree | 7123f6e539ce2e4e9da545601a791f30394c243e /src/modules/commander | |
parent | ce1251fcc8119b2c4e8c9a3b5e7f0e0104fc975f (diff) | |
download | px4-firmware-e12d3af503c5ebc105e5b3c3ef8e51bd75959329.tar.gz px4-firmware-e12d3af503c5ebc105e5b3c3ef8e51bd75959329.tar.bz2 px4-firmware-e12d3af503c5ebc105e5b3c3ef8e51bd75959329.zip |
Added support for offboard velocity control & fixed position control flags
Diffstat (limited to 'src/modules/commander')
-rw-r--r-- | src/modules/commander/commander.cpp | 22 |
1 files changed, 15 insertions, 7 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 29a5f0b4a..3da43a792 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1809,12 +1809,12 @@ set_control_mode() control_mode.flag_control_offboard_enabled = true; switch (sp_offboard.mode) { - case OFFBOARD_CONTROL_MODE_DIRECT_POSITION: - control_mode.flag_control_rates_enabled = false; + case OFFBOARD_CONTROL_MODE_DIRECT_RATES: + control_mode.flag_control_rates_enabled = true; control_mode.flag_control_attitude_enabled = false; control_mode.flag_control_altitude_enabled = false; control_mode.flag_control_climb_rate_enabled = false; - control_mode.flag_control_position_enabled = true; + control_mode.flag_control_position_enabled = false; control_mode.flag_control_velocity_enabled = false; break; case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE: @@ -1825,13 +1825,21 @@ set_control_mode() control_mode.flag_control_position_enabled = false; control_mode.flag_control_velocity_enabled = false; break; - case OFFBOARD_CONTROL_MODE_DIRECT_RATES: + case OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY: control_mode.flag_control_rates_enabled = true; - control_mode.flag_control_attitude_enabled = false; + control_mode.flag_control_attitude_enabled = true; control_mode.flag_control_altitude_enabled = false; - control_mode.flag_control_climb_rate_enabled = false; + control_mode.flag_control_climb_rate_enabled = true; control_mode.flag_control_position_enabled = false; - control_mode.flag_control_velocity_enabled = false; + control_mode.flag_control_velocity_enabled = true; + break; + case OFFBOARD_CONTROL_MODE_DIRECT_POSITION: + control_mode.flag_control_rates_enabled = true; + control_mode.flag_control_attitude_enabled = true; + control_mode.flag_control_altitude_enabled = true; + control_mode.flag_control_climb_rate_enabled = true; + control_mode.flag_control_position_enabled = true; + control_mode.flag_control_velocity_enabled = true; break; default: control_mode.flag_control_rates_enabled = false; |