px4_custom_mode: add custom sub mode orbit

This commit is contained in:
Matthias Grob 2018-12-06 17:00:18 +01:00
parent 1cee90d42f
commit d4a40f5d99
2 changed files with 13 additions and 0 deletions

View File

@ -66,6 +66,11 @@ enum PX4_CUSTOM_SUB_MODE_AUTO {
PX4_CUSTOM_SUB_MODE_AUTO_PRECLAND
};
enum PX4_CUSTOM_SUB_MODE_POSCTL {
PX4_CUSTOM_SUB_MODE_POSCTL_POSCTL = 0,
PX4_CUSTOM_SUB_MODE_POSCTL_ORBIT
};
union px4_custom_mode {
struct {
uint16_t reserved;

View File

@ -186,6 +186,14 @@ void get_mavlink_navigation_mode(const struct vehicle_status_s *const status, ui
custom_mode->main_mode = PX4_CUSTOM_MAIN_MODE_POSCTL;
break;
case vehicle_status_s::NAVIGATION_STATE_ORBIT:
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED
| MAV_MODE_FLAG_STABILIZE_ENABLED
| MAV_MODE_FLAG_GUIDED_ENABLED;
custom_mode->main_mode = PX4_CUSTOM_MAIN_MODE_POSCTL;
custom_mode->sub_mode = PX4_CUSTOM_SUB_MODE_POSCTL_ORBIT;
break;
case vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF:
*mavlink_base_mode |= auto_mode_flags;
custom_mode->main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;