aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--src/modules/commander/commander.cpp157
-rw-r--r--src/modules/commander/px4_custom_mode.h1
-rw-r--r--src/modules/commander/state_machine_helper.cpp6
-rw-r--r--src/modules/mavlink/mavlink.c2
-rw-r--r--src/modules/mc_att_control/mc_att_control_main.cpp99
-rw-r--r--src/modules/navigator/navigator_main.cpp16
-rw-r--r--src/modules/sensors/sensor_params.c3
-rw-r--r--src/modules/sensors/sensors.cpp29
-rw-r--r--src/modules/uORB/topics/manual_control_setpoint.h4
-rw-r--r--src/modules/uORB/topics/vehicle_status.h8
10 files changed, 193 insertions, 132 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 47053838c..7b69f2b76 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -411,42 +411,52 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
/* set main state */
transition_result_t main_res = TRANSITION_DENIED;
- if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
- /* use autopilot-specific mode */
- if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_MANUAL) {
- /* MANUAL */
- main_res = main_state_transition(status, MAIN_STATE_MANUAL);
-
- } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_SEATBELT) {
- /* SEATBELT */
- main_res = main_state_transition(status, MAIN_STATE_SEATBELT);
-
- } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_EASY) {
- /* EASY */
- main_res = main_state_transition(status, MAIN_STATE_EASY);
-
- } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
- /* AUTO */
- main_res = main_state_transition(status, MAIN_STATE_AUTO);
- }
+ if (status->rc_signal_lost) {
+ /* allow mode switching by command only if no RC signal */
+ if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
+ /* use autopilot-specific mode */
+ if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_MANUAL) {
+ /* MANUAL */
+ main_res = main_state_transition(status, MAIN_STATE_MANUAL);
- } else {
- /* use base mode */
- if (base_mode & MAV_MODE_FLAG_AUTO_ENABLED) {
- /* AUTO */
- main_res = main_state_transition(status, MAIN_STATE_AUTO);
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_SEATBELT) {
+ /* SEATBELT */
+ main_res = main_state_transition(status, MAIN_STATE_SEATBELT);
- } else if (base_mode & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED) {
- if (base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) {
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_EASY) {
/* EASY */
main_res = main_state_transition(status, MAIN_STATE_EASY);
- } else if (base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED) {
- /* MANUAL */
- main_res = main_state_transition(status, MAIN_STATE_MANUAL);
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
+ /* AUTO */
+ main_res = main_state_transition(status, MAIN_STATE_AUTO);
+
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_OFFBOARD) {
+ /* OFFBOARD */
+ main_res = main_state_transition(status, MAIN_STATE_OFFBOARD);
+ }
+
+ } else {
+ /* use base mode */
+ if (base_mode & MAV_MODE_FLAG_AUTO_ENABLED) {
+ /* AUTO */
+ main_res = main_state_transition(status, MAIN_STATE_AUTO);
+
+ } else if (base_mode & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED) {
+ if (base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) {
+ /* EASY */
+ main_res = main_state_transition(status, MAIN_STATE_EASY);
+
+ } else if (base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED) {
+ /* MANUAL */
+ main_res = main_state_transition(status, MAIN_STATE_MANUAL);
+ }
}
}
+ } else {
+ mavlink_log_info(mavlink_fd, "RC signal is valid, ignoring set mode cmd");
}
+
if (main_res == TRANSITION_CHANGED)
ret = true;
@@ -1410,6 +1420,17 @@ check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_sta
} else {
current_status->mission_switch = MISSION_SWITCH_MISSION;
}
+
+ /* offboard switch */
+ if (!isfinite(sp_man->offboard_switch)) {
+ current_status->offboard_switch = OFFBOARD_SWITCH_NONE;
+
+ } else if (sp_man->offboard_switch > STICK_ON_OFF_LIMIT) {
+ current_status->offboard_switch = OFFBOARD_SWITCH_OFFBOARD;
+
+ } else {
+ current_status->offboard_switch = OFFBOARD_SWITCH_ONBOARD;
+ }
}
transition_result_t
@@ -1418,56 +1439,62 @@ check_main_state_machine(struct vehicle_status_s *current_status)
/* evaluate the main state machine */
transition_result_t res = TRANSITION_DENIED;
- switch (current_status->mode_switch) {
- case MODE_SWITCH_MANUAL:
- res = main_state_transition(current_status, MAIN_STATE_MANUAL);
- // TRANSITION_DENIED is not possible here
- break;
+ if (current_status->offboard_switch == OFFBOARD_SWITCH_OFFBOARD) {
+ /* offboard switch overrides main switch */
+ res = main_state_transition(current_status, MAIN_STATE_OFFBOARD);
+
+ } else {
+ switch (current_status->mode_switch) {
+ case MODE_SWITCH_MANUAL:
+ res = main_state_transition(current_status, MAIN_STATE_MANUAL);
+ // TRANSITION_DENIED is not possible here
+ break;
- case MODE_SWITCH_ASSISTED:
- if (current_status->assisted_switch == ASSISTED_SWITCH_EASY) {
- res = main_state_transition(current_status, MAIN_STATE_EASY);
+ case MODE_SWITCH_ASSISTED:
+ if (current_status->assisted_switch == ASSISTED_SWITCH_EASY) {
+ res = main_state_transition(current_status, MAIN_STATE_EASY);
- if (res != TRANSITION_DENIED)
- break; // changed successfully or already in this state
+ if (res != TRANSITION_DENIED)
+ break; // changed successfully or already in this state
- // else fallback to SEATBELT
- print_reject_mode("EASY");
- }
+ // else fallback to SEATBELT
+ print_reject_mode("EASY");
+ }
- res = main_state_transition(current_status, MAIN_STATE_SEATBELT);
+ res = main_state_transition(current_status, MAIN_STATE_SEATBELT);
- if (res != TRANSITION_DENIED)
- break; // changed successfully or already in this mode
+ if (res != TRANSITION_DENIED)
+ break; // changed successfully or already in this mode
- if (current_status->assisted_switch != ASSISTED_SWITCH_EASY) // don't print both messages
- print_reject_mode("SEATBELT");
+ if (current_status->assisted_switch != ASSISTED_SWITCH_EASY) // don't print both messages
+ print_reject_mode("SEATBELT");
- // else fallback to MANUAL
- res = main_state_transition(current_status, MAIN_STATE_MANUAL);
- // TRANSITION_DENIED is not possible here
- break;
+ // else fallback to MANUAL
+ res = main_state_transition(current_status, MAIN_STATE_MANUAL);
+ // TRANSITION_DENIED is not possible here
+ break;
- case MODE_SWITCH_AUTO:
- res = main_state_transition(current_status, MAIN_STATE_AUTO);
+ case MODE_SWITCH_AUTO:
+ res = main_state_transition(current_status, MAIN_STATE_AUTO);
- if (res != TRANSITION_DENIED)
- break; // changed successfully or already in this state
+ if (res != TRANSITION_DENIED)
+ break; // changed successfully or already in this state
- // else fallback to SEATBELT (EASY likely will not work too)
- print_reject_mode("AUTO");
- res = main_state_transition(current_status, MAIN_STATE_SEATBELT);
+ // else fallback to SEATBELT (EASY likely will not work too)
+ print_reject_mode("AUTO");
+ res = main_state_transition(current_status, MAIN_STATE_SEATBELT);
- if (res != TRANSITION_DENIED)
- break; // changed successfully or already in this state
+ if (res != TRANSITION_DENIED)
+ break; // changed successfully or already in this state
- // else fallback to MANUAL
- res = main_state_transition(current_status, MAIN_STATE_MANUAL);
- // TRANSITION_DENIED is not possible here
- break;
+ // else fallback to MANUAL
+ res = main_state_transition(current_status, MAIN_STATE_MANUAL);
+ // TRANSITION_DENIED is not possible here
+ break;
- default:
- break;
+ default:
+ break;
+ }
}
return res;
diff --git a/src/modules/commander/px4_custom_mode.h b/src/modules/commander/px4_custom_mode.h
index b60a7e0b9..4843e72c3 100644
--- a/src/modules/commander/px4_custom_mode.h
+++ b/src/modules/commander/px4_custom_mode.h
@@ -13,6 +13,7 @@ enum PX4_CUSTOM_MAIN_MODE {
PX4_CUSTOM_MAIN_MODE_SEATBELT,
PX4_CUSTOM_MAIN_MODE_EASY,
PX4_CUSTOM_MAIN_MODE_AUTO,
+ PX4_CUSTOM_MAIN_MODE_OFFBOARD,
};
enum PX4_CUSTOM_SUB_MODE_AUTO {
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index 731e0e3ff..e5599e1c3 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -263,6 +263,12 @@ main_state_transition(struct vehicle_status_s *current_state, main_state_t new_m
}
break;
+
+ case MAIN_STATE_OFFBOARD:
+
+ ret = TRANSITION_CHANGED;
+
+ break;
}
if (ret == TRANSITION_CHANGED) {
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index 4f8091716..70229558c 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -231,6 +231,8 @@ get_mavlink_mode_and_state(uint8_t *mavlink_state, uint8_t *mavlink_base_mode, u
} else if (control_mode.nav_state == NAV_STATE_RTL) {
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_RTL;
}
+ } else if (v_status.main_state == MAIN_STATE_OFFBOARD) {
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_OFFBOARD;
}
*mavlink_custom_mode = custom_mode.data;
diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp
index 245ac024b..c4c6c0138 100644
--- a/src/modules/mc_att_control/mc_att_control_main.cpp
+++ b/src/modules/mc_att_control/mc_att_control_main.cpp
@@ -480,64 +480,73 @@ MulticopterAttitudeControl::task_main()
float yaw_sp_move_rate = 0.0f;
bool publish_att_sp = false;
- /* define which input is the dominating control input */
- if (_control_mode.flag_control_manual_enabled) {
- /* manual input */
- if (!_control_mode.flag_control_climb_rate_enabled) {
- /* pass throttle directly if not in altitude control mode */
- _att_sp.thrust = _manual.throttle;
- }
+ if (_control_mode.flag_control_offboard_enabled) {
+ /* offboard control */
+ // TODO set _att_sp or _rates_sp here depending on offboard control mode
+ // TODO _control_mode.flag_control_XXX flags are all false, set it according to ofboard control mode
+ // but it's not very beautiful, need to think how to do it better
- if (!_arming.armed) {
- /* reset yaw setpoint when disarmed */
- reset_yaw_sp = true;
- }
+ } else {
+ /* onboard control */
+ /* define which input is the dominating control input */
+ if (_control_mode.flag_control_manual_enabled) {
+ /* manual input */
+ if (!_control_mode.flag_control_climb_rate_enabled) {
+ /* pass throttle directly if not in altitude control mode */
+ _att_sp.thrust = _manual.throttle;
+ }
- if (_control_mode.flag_control_attitude_enabled) {
- /* control attitude, update attitude setpoint depending on mode */
+ if (!_arming.armed) {
+ /* reset yaw setpoint when disarmed */
+ reset_yaw_sp = true;
+ }
- if (_att_sp.thrust < 0.1f) {
- // TODO
- //if (_status.condition_landed) {
- /* reset yaw setpoint if on ground */
- // reset_yaw_sp = true;
- //}
- } else {
- if (_manual.yaw < -YAW_DEADZONE || YAW_DEADZONE < _manual.yaw) {
- /* move yaw setpoint */
- yaw_sp_move_rate = _manual.yaw;
- _att_sp.yaw_body = _wrap_pi(_att_sp.yaw_body + yaw_sp_move_rate * dt);
+ if (_control_mode.flag_control_attitude_enabled) {
+ /* control attitude, update attitude setpoint depending on mode */
+
+ if (_att_sp.thrust < 0.1f) {
+ // TODO
+ //if (_status.condition_landed) {
+ /* reset yaw setpoint if on ground */
+ // reset_yaw_sp = true;
+ //}
+ } else {
+ if (_manual.yaw < -YAW_DEADZONE || YAW_DEADZONE < _manual.yaw) {
+ /* move yaw setpoint */
+ yaw_sp_move_rate = _manual.yaw;
+ _att_sp.yaw_body = _wrap_pi(_att_sp.yaw_body + yaw_sp_move_rate * dt);
+ _att_sp.R_valid = false;
+ publish_att_sp = true;
+ }
+ }
+
+ /* reset yaw setpint to current position if needed */
+ if (reset_yaw_sp) {
+ reset_yaw_sp = false;
+ _att_sp.yaw_body = _att.yaw;
_att_sp.R_valid = false;
publish_att_sp = true;
}
- }
- /* reset yaw setpint to current position if needed */
- if (reset_yaw_sp) {
- reset_yaw_sp = false;
- _att_sp.yaw_body = _att.yaw;
- _att_sp.R_valid = false;
- publish_att_sp = true;
- }
+ if (!_control_mode.flag_control_velocity_enabled) {
+ /* update attitude setpoint if not in position control mode */
+ _att_sp.roll_body = _manual.roll;
+ _att_sp.pitch_body = _manual.pitch;
+ _att_sp.R_valid = false;
+ publish_att_sp = true;
+ }
- if (!_control_mode.flag_control_velocity_enabled) {
- /* update attitude setpoint if not in position control mode */
- _att_sp.roll_body = _manual.roll;
- _att_sp.pitch_body = _manual.pitch;
- _att_sp.R_valid = false;
- publish_att_sp = true;
+ } else {
+ /* manual rate inputs (ACRO) */
+ // TODO
+ /* reset yaw setpoint after ACRO */
+ reset_yaw_sp = true;
}
} else {
- /* manual rate inputs (ACRO) */
- // TODO
- /* reset yaw setpoint after ACRO */
+ /* reset yaw setpoint after non-manual control */
reset_yaw_sp = true;
}
-
- } else {
- /* reset yaw setpoint after non-manual control */
- reset_yaw_sp = true;
}
if (_att_sp.R_valid) {
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index ca5735509..7285e243e 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -1463,11 +1463,11 @@ Navigator::publish_control_mode()
_control_mode.flag_external_manual_override_ok = !_vstatus.is_rotary_wing;
_control_mode.flag_system_hil_enabled = _vstatus.hil_state == HIL_STATE_ON;
- _control_mode.flag_control_offboard_enabled = false;
_control_mode.flag_control_flighttermination_enabled = false;
switch (_vstatus.main_state) {
case MAIN_STATE_MANUAL:
+ _control_mode.flag_control_offboard_enabled = false;
_control_mode.flag_control_manual_enabled = true;
_control_mode.flag_control_rates_enabled = _vstatus.is_rotary_wing;
_control_mode.flag_control_attitude_enabled = _vstatus.is_rotary_wing;
@@ -1478,6 +1478,7 @@ Navigator::publish_control_mode()
break;
case MAIN_STATE_SEATBELT:
+ _control_mode.flag_control_offboard_enabled = false;
_control_mode.flag_control_manual_enabled = true;
_control_mode.flag_control_rates_enabled = true;
_control_mode.flag_control_attitude_enabled = true;
@@ -1488,6 +1489,7 @@ Navigator::publish_control_mode()
break;
case MAIN_STATE_EASY:
+ _control_mode.flag_control_offboard_enabled = false;
_control_mode.flag_control_manual_enabled = true;
_control_mode.flag_control_rates_enabled = true;
_control_mode.flag_control_attitude_enabled = true;
@@ -1498,6 +1500,7 @@ Navigator::publish_control_mode()
break;
case MAIN_STATE_AUTO:
+ _control_mode.flag_control_offboard_enabled = false;
_control_mode.flag_control_manual_enabled = false;
if (myState == NAV_STATE_READY) {
/* disable all controllers, armed but idle */
@@ -1517,6 +1520,17 @@ Navigator::publish_control_mode()
}
break;
+ case MAIN_STATE_OFFBOARD:
+ _control_mode.flag_control_offboard_enabled = true;
+ _control_mode.flag_control_manual_enabled = false;
+ _control_mode.flag_control_rates_enabled = false;
+ _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 = false;
+ _control_mode.flag_control_velocity_enabled = false;
+ break;
+
default:
break;
}
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index bbc84ef93..eb771382d 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -390,8 +390,7 @@ PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 5);
PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 0);
PARAM_DEFINE_INT32(RC_MAP_ASSIST_SW, 6);
PARAM_DEFINE_INT32(RC_MAP_MISSIO_SW, 0);
-
-//PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0);
+PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0);
PARAM_DEFINE_INT32(RC_MAP_FLAPS, 0);
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 5e8c5edbc..f87f2f282 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -246,8 +246,7 @@ private:
int rc_map_return_sw;
int rc_map_assisted_sw;
int rc_map_mission_sw;
-
-// int rc_map_offboard_ctrl_mode_sw;
+ int rc_map_offboard_sw;
int rc_map_flaps;
@@ -296,8 +295,7 @@ private:
param_t rc_map_return_sw;
param_t rc_map_assisted_sw;
param_t rc_map_mission_sw;
-
-// param_t rc_map_offboard_ctrl_mode_sw;
+ param_t rc_map_offboard_sw;
param_t rc_map_flaps;
@@ -515,8 +513,7 @@ Sensors::Sensors() :
/* optional mode switches, not mapped per default */
_parameter_handles.rc_map_assisted_sw = param_find("RC_MAP_ASSIST_SW");
_parameter_handles.rc_map_mission_sw = param_find("RC_MAP_MISSIO_SW");
-
-// _parameter_handles.rc_map_offboard_ctrl_mode_sw = param_find("RC_MAP_OFFB_SW");
+ _parameter_handles.rc_map_offboard_sw = param_find("RC_MAP_OFFB_SW");
_parameter_handles.rc_map_aux1 = param_find("RC_MAP_AUX1");
_parameter_handles.rc_map_aux2 = param_find("RC_MAP_AUX2");
@@ -669,14 +666,14 @@ Sensors::parameters_update()
warnx("Failed getting mission sw chan index");
}
+ if (param_get(_parameter_handles.rc_map_offboard_sw, &(_parameters.rc_map_offboard_sw)) != OK) {
+ warnx("Failed getting offboard sw chan index");
+ }
+
if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) {
warnx("Failed getting flaps chan index");
}
-// if (param_get(_parameter_handles.rc_map_offboard_ctrl_mode_sw, &(_parameters.rc_map_offboard_ctrl_mode_sw)) != OK) {
-// warnx("Failed getting offboard control mode sw chan index");
-// }
-
param_get(_parameter_handles.rc_map_aux1, &(_parameters.rc_map_aux1));
param_get(_parameter_handles.rc_map_aux2, &(_parameters.rc_map_aux2));
param_get(_parameter_handles.rc_map_aux3, &(_parameters.rc_map_aux3));
@@ -700,11 +697,10 @@ Sensors::parameters_update()
_rc.function[RETURN] = _parameters.rc_map_return_sw - 1;
_rc.function[ASSISTED] = _parameters.rc_map_assisted_sw - 1;
_rc.function[MISSION] = _parameters.rc_map_mission_sw - 1;
+ _rc.function[OFFBOARD_MODE] = _parameters.rc_map_offboard_sw - 1;
_rc.function[FLAPS] = _parameters.rc_map_flaps - 1;
-// _rc.function[OFFBOARD_MODE] = _parameters.rc_map_offboard_ctrl_mode_sw - 1;
-
_rc.function[AUX_1] = _parameters.rc_map_aux1 - 1;
_rc.function[AUX_2] = _parameters.rc_map_aux2 - 1;
_rc.function[AUX_3] = _parameters.rc_map_aux3 - 1;
@@ -1289,7 +1285,7 @@ Sensors::rc_poll()
manual_control.return_switch = NAN;
manual_control.assisted_switch = NAN;
manual_control.mission_switch = NAN;
-// manual_control.auto_offboard_input_switch = NAN;
+ manual_control.offboard_switch = NAN;
manual_control.flaps = NAN;
manual_control.aux1 = NAN;
@@ -1432,9 +1428,10 @@ Sensors::rc_poll()
manual_control.return_switch = limit_minus_one_to_one(_rc.chan[_rc.function[RETURN]].scaled);
}
-// if (_rc.function[OFFBOARD_MODE] >= 0) {
-// manual_control.auto_offboard_input_switch = limit_minus_one_to_one(_rc.chan[_rc.function[OFFBOARD_MODE]].scaled);
-// }
+ /* offboard switch input */
+ if (_rc.function[OFFBOARD_MODE] >= 0) {
+ manual_control.offboard_switch = limit_minus_one_to_one(_rc.chan[_rc.function[OFFBOARD_MODE]].scaled);
+ }
/* aux functions, only assign if valid mapping is present */
if (_rc.function[AUX_1] >= 0) {
diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h
index eac6d6e98..ab0c7a411 100644
--- a/src/modules/uORB/topics/manual_control_setpoint.h
+++ b/src/modules/uORB/topics/manual_control_setpoint.h
@@ -60,15 +60,13 @@ struct manual_control_setpoint_s {
float return_switch; /**< land 2 position switch (mandatory): land, no effect */
float assisted_switch; /**< assisted 2 position switch (optional): seatbelt, simple */
float mission_switch; /**< mission 2 position switch (optional): mission, loiter */
+ float offboard_switch; /**< offboard switch (optional): offboard, onboard */
/**
* Any of the channels below may not be available and be set to NaN
* to indicate that it does not contain valid data.
*/
- // XXX needed or parameter?
- //float auto_offboard_input_switch; /**< controller setpoint source (0 = onboard, 1 = offboard) */
-
float flaps; /**< flap position */
float aux1; /**< default function: camera yaw / azimuth */
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 1a9dec5f5..d74b696bb 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -64,6 +64,7 @@ typedef enum {
MAIN_STATE_SEATBELT,
MAIN_STATE_EASY,
MAIN_STATE_AUTO,
+ MAIN_STATE_OFFBOARD,
} main_state_t;
typedef enum {
@@ -109,6 +110,12 @@ typedef enum {
MISSION_SWITCH_MISSION
} mission_switch_pos_t;
+typedef enum {
+ OFFBOARD_SWITCH_NONE = 0,
+ OFFBOARD_SWITCH_OFFBOARD,
+ OFFBOARD_SWITCH_ONBOARD
+} offboard_switch_pos_t;
+
enum VEHICLE_MODE_FLAG {
VEHICLE_MODE_FLAG_SAFETY_ARMED = 128,
VEHICLE_MODE_FLAG_MANUAL_INPUT_ENABLED = 64,
@@ -184,6 +191,7 @@ struct vehicle_status_s
return_switch_pos_t return_switch;
assisted_switch_pos_t assisted_switch;
mission_switch_pos_t mission_switch;
+ offboard_switch_pos_t offboard_switch;
bool condition_battery_voltage_valid;
bool condition_system_in_air_restore; /**< true if we can restore in mid air */