aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander/commander.cpp
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-07-03 14:42:59 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-07-03 14:46:25 +0200
commit839710daf841a9528a58e915f8b04484bf54e7dc (patch)
tree997f95813e3a5cdf8af393323398e841f29c0fae /src/modules/commander/commander.cpp
parent57f707af56be0d9281a95aebf64baf63ef022267 (diff)
downloadpx4-firmware-839710daf841a9528a58e915f8b04484bf54e7dc.tar.gz
px4-firmware-839710daf841a9528a58e915f8b04484bf54e7dc.tar.bz2
px4-firmware-839710daf841a9528a58e915f8b04484bf54e7dc.zip
Update offboard control uorb topic
Work towards supporting the new external setpoint mavlink messages
Diffstat (limited to 'src/modules/commander/commander.cpp')
-rw-r--r--src/modules/commander/commander.cpp16
1 files changed, 6 insertions, 10 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 38297745d..7185eebc4 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -946,7 +946,7 @@ int commander_thread_main(int argc, char *argv[])
}
/* Perform system checks (again) once params are loaded and MAVLink is up. */
- if (!system_checked && mavlink_fd &&
+ if (!system_checked && mavlink_fd &&
(telemetry.heartbeat_time > 0) &&
(hrt_elapsed_time(&telemetry.heartbeat_time) < 1 * 1000 * 1000)) {
@@ -1847,21 +1847,17 @@ set_control_mode()
control_mode.flag_control_position_enabled = false;
control_mode.flag_control_velocity_enabled = false;
break;
- case OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY:
- control_mode.flag_control_rates_enabled = true;
- control_mode.flag_control_attitude_enabled = true;
- control_mode.flag_control_altitude_enabled = true; /* XXX: hack for now */
- control_mode.flag_control_climb_rate_enabled = true;
- control_mode.flag_control_position_enabled = true; /* XXX: hack for now */
- control_mode.flag_control_velocity_enabled = true;
- break;
- case OFFBOARD_CONTROL_MODE_DIRECT_POSITION:
+ case OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED:
+ case OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_OFFSET_NED:
+ case OFFBOARD_CONTROL_MODE_DIRECT_BODY_NED:
+ case OFFBOARD_CONTROL_MODE_DIRECT_BODY_OFFSET_NED:
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;
+ //XXX: the flags could depend on sp_offboard.ignore
break;
default:
control_mode.flag_control_rates_enabled = false;