forked from Archive/PX4-Autopilot
vehicle_status delete engine_failure_cmd
This commit is contained in:
parent
17e17d79dd
commit
fc7c8b4b89
|
@ -63,7 +63,6 @@ uint8 rc_input_mode # set to 1 to disable the RC input, 2 to enable manual co
|
|||
bool data_link_lost # datalink to GCS lost
|
||||
uint8 data_link_lost_counter # counts unique data link lost events
|
||||
bool engine_failure # Set to true if an engine failure is detected
|
||||
bool engine_failure_cmd # Set to true if an engine failure mode is commanded
|
||||
bool mission_failure # Set to true if mission could not continue/finish
|
||||
|
||||
# see SYS_STATUS mavlink message for the following
|
||||
|
|
|
@ -957,17 +957,9 @@ Commander::handle_command(vehicle_status_s *status_local, const safety_s *safety
|
|||
armed_local->force_failsafe = true;
|
||||
warnx("forcing failsafe (termination)");
|
||||
|
||||
/* param2 is currently used for other failsafe modes */
|
||||
status_local->engine_failure_cmd = false;
|
||||
|
||||
if ((int)cmd->param2 <= 0) {
|
||||
/* reset all commanded failure modes */
|
||||
warnx("reset all non-flighttermination failsafe commands");
|
||||
|
||||
} else if ((int)cmd->param2 == 1) {
|
||||
/* trigger engine failure mode */
|
||||
status_local->engine_failure_cmd = true;
|
||||
warnx("engine failure mode commanded");
|
||||
}
|
||||
|
||||
} else {
|
||||
|
|
|
@ -668,11 +668,7 @@ bool set_nav_state(struct vehicle_status_s *status,
|
|||
* - if we have vtol transition failure
|
||||
* - depending on datalink, RC and if the mission is finished */
|
||||
|
||||
/* first look at the commands */
|
||||
if (status->engine_failure_cmd) {
|
||||
status->nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_LANDENGFAIL;
|
||||
|
||||
} else if (status_flags->gps_failure) {
|
||||
if (status_flags->gps_failure) {
|
||||
if (status->is_rotary_wing) {
|
||||
status->nav_state = vehicle_status_s::NAVIGATION_STATE_DESCEND;
|
||||
|
||||
|
|
|
@ -1125,10 +1125,8 @@ FixedwingAttitudeControl::task_main()
|
|||
}
|
||||
|
||||
/* throttle passed through if it is finite and if no engine failure was detected */
|
||||
_actuators.control[actuator_controls_s::INDEX_THROTTLE] = (PX4_ISFINITE(throttle_sp) &&
|
||||
!(_vehicle_status.engine_failure ||
|
||||
_vehicle_status.engine_failure_cmd)) ?
|
||||
throttle_sp : 0.0f;
|
||||
_actuators.control[actuator_controls_s::INDEX_THROTTLE] = (PX4_ISFINITE(throttle_sp)
|
||||
&& !_vehicle_status.engine_failure) ? throttle_sp : 0.0f;
|
||||
|
||||
/* scale effort by battery status */
|
||||
if (_parameters.bat_scale_en && _battery_status.scale > 0.0f &&
|
||||
|
@ -1169,10 +1167,7 @@ FixedwingAttitudeControl::task_main()
|
|||
_actuators.control[actuator_controls_s::INDEX_YAW] = (PX4_ISFINITE(yaw_u)) ? yaw_u + _parameters.trim_yaw :
|
||||
_parameters.trim_yaw;
|
||||
|
||||
_actuators.control[actuator_controls_s::INDEX_THROTTLE] = (PX4_ISFINITE(throttle_sp) &&
|
||||
//!(_vehicle_status.engine_failure ||
|
||||
!_vehicle_status.engine_failure_cmd) ?
|
||||
throttle_sp : 0.0f;
|
||||
_actuators.control[actuator_controls_s::INDEX_THROTTLE] = PX4_ISFINITE(throttle_sp) ? throttle_sp : 0.0f;
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -1786,7 +1786,7 @@ FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float airspee
|
|||
_reinitialize_tecs = false;
|
||||
}
|
||||
|
||||
if (_vehicle_status.engine_failure || _vehicle_status.engine_failure_cmd) {
|
||||
if (_vehicle_status.engine_failure) {
|
||||
/* Force the slow downwards spiral */
|
||||
pitch_min_rad = M_DEG_TO_RAD_F * -1.0f;
|
||||
pitch_max_rad = M_DEG_TO_RAD_F * 5.0f;
|
||||
|
|
Loading…
Reference in New Issue