vehicle constraints: remove landing gear

- landing_gear: refactor state name
- Add the keep state to the landing gear message
- Adapt FlightTaskManual, FlightTaskAutoMapper, mc_pos_control,
to review message definition
This commit is contained in:
Simone Guscetti
2018-11-01 18:00:27 +01:00
committed by Dennis Mannhart
parent 6dbed6636d
commit de185726b3
7 changed files with 24 additions and 27 deletions
@@ -415,9 +415,9 @@ MulticopterAttitudeControl::get_landing_gear_state()
if (_vehicle_land_detected.landed) {
_gear_state_initialized = false;
}
float landing_gear = landing_gear_s::LANDING_GEAR_DOWN; // default to down
float landing_gear = landing_gear_s::GEAR_DOWN; // default to down
if (_manual_control_sp.gear_switch == manual_control_setpoint_s::SWITCH_POS_ON && _gear_state_initialized) {
landing_gear = landing_gear_s::LANDING_GEAR_UP;
landing_gear = landing_gear_s::GEAR_UP;
} else if (_manual_control_sp.gear_switch == manual_control_setpoint_s::SWITCH_POS_OFF) {
// Switching the gear off does put it into a safe defined state
@@ -691,6 +691,7 @@ MulticopterPositionControl::run()
update_avoidance_waypoint_desired(_states, setpoint);
vehicle_constraints_s constraints = _flight_tasks.getConstraints();
landing_gear_s gear = _flight_tasks.getGear();
// check if all local states are valid and map accordingly
set_vehicle_states(setpoint.vz);
@@ -732,7 +733,7 @@ MulticopterPositionControl::run()
setpoint.vx = setpoint.vy = setpoint.vz = NAN;
setpoint.yawspeed = NAN;
setpoint.yaw = _states.yaw;
constraints.landing_gear = vehicle_constraints_s::GEAR_KEEP;
gear.landing_gear = landing_gear_s::GEAR_KEEP;
// reactivate the task which will reset the setpoint to current state
_flight_tasks.reActivate();
}
@@ -801,11 +802,11 @@ MulticopterPositionControl::run()
// they might conflict with each other such as in offboard attitude control.
publish_attitude();
// if theres any change in landing gear setpoint publish it
if (_old_landing_gear_position != constraints.landing_gear
&& constraints.landing_gear != vehicle_constraints_s::GEAR_KEEP) {
// if there's any change in landing gear setpoint publish it
if (gear.landing_gear != _old_landing_gear_position
&& gear.landing_gear != landing_gear_s::GEAR_KEEP) {
_landing_gear.landing_gear = constraints.landing_gear;
_landing_gear.landing_gear = gear.landing_gear;
_landing_gear.timestamp = hrt_absolute_time();
if (_landing_gear_pub != nullptr) {
@@ -816,7 +817,7 @@ MulticopterPositionControl::run()
}
}
_old_landing_gear_position = constraints.landing_gear;
_old_landing_gear_position = gear.landing_gear;
} else {
// no flighttask is active: set attitude setpoint to idle