mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-23 15:07:34 +08:00
Simplify use of pitch_min
This commit is contained in:
committed by
Lorenz Meier
parent
9821499113
commit
eaae1abdaf
@@ -900,6 +900,11 @@ MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t *
|
||||
mission_item->altitude_is_relative = true;
|
||||
}
|
||||
|
||||
/* this field is shared with pitch_min in memory and
|
||||
* exclusive in the MAVLink spec. Set it to 0 first
|
||||
* and then set minimum pitch later only for the
|
||||
* corresponding item
|
||||
*/
|
||||
mission_item->time_inside = 0.0f;
|
||||
|
||||
switch (mavlink_mission_item->command) {
|
||||
|
||||
@@ -127,7 +127,6 @@ DataLinkLoss::set_dll_item()
|
||||
_mission_item.nav_cmd = NAV_CMD_LOITER_TIME_LIMIT;
|
||||
_mission_item.acceptance_radius = _navigator->get_acceptance_radius();
|
||||
_mission_item.time_inside = _param_commsholdwaittime.get() < 0.0f ? 0.0f : _param_commsholdwaittime.get();
|
||||
_mission_item.pitch_min = 0.0f;
|
||||
_mission_item.autocontinue = true;
|
||||
_mission_item.origin = ORIGIN_ONBOARD;
|
||||
|
||||
@@ -144,7 +143,6 @@ DataLinkLoss::set_dll_item()
|
||||
_mission_item.nav_cmd = NAV_CMD_LOITER_TIME_LIMIT;
|
||||
_mission_item.time_inside = _param_airfieldhomewaittime.get() < 0.0f ? 0.0f : _param_airfieldhomewaittime.get();
|
||||
_mission_item.acceptance_radius = _navigator->get_acceptance_radius();
|
||||
_mission_item.pitch_min = 0.0f;
|
||||
_mission_item.autocontinue = true;
|
||||
_mission_item.origin = ORIGIN_ONBOARD;
|
||||
|
||||
|
||||
@@ -115,7 +115,6 @@ EngineFailure::set_ef_item()
|
||||
_mission_item.loiter_radius = _navigator->get_loiter_radius();
|
||||
_mission_item.nav_cmd = NAV_CMD_LOITER_UNLIMITED;
|
||||
_mission_item.acceptance_radius = _navigator->get_acceptance_radius();
|
||||
_mission_item.pitch_min = 0.0f;
|
||||
_mission_item.autocontinue = true;
|
||||
_mission_item.origin = ORIGIN_ONBOARD;
|
||||
|
||||
|
||||
@@ -575,7 +575,6 @@ MissionBlock::set_loiter_item(struct mission_item_s *item, float min_clearance)
|
||||
item->loiter_radius = _navigator->get_loiter_radius();
|
||||
item->acceptance_radius = _navigator->get_acceptance_radius();
|
||||
item->time_inside = 0.0f;
|
||||
item->pitch_min = 0.0f;
|
||||
item->autocontinue = false;
|
||||
item->origin = ORIGIN_ONBOARD;
|
||||
}
|
||||
@@ -610,7 +609,6 @@ MissionBlock::set_follow_target_item(struct mission_item_s *item, float min_clea
|
||||
item->loiter_radius = _navigator->get_loiter_radius();
|
||||
item->acceptance_radius = _navigator->get_acceptance_radius();
|
||||
item->time_inside = 0.0f;
|
||||
item->pitch_min = 0.0f;
|
||||
item->autocontinue = false;
|
||||
item->origin = ORIGIN_ONBOARD;
|
||||
}
|
||||
@@ -629,7 +627,6 @@ MissionBlock::set_takeoff_item(struct mission_item_s *item, float abs_altitude,
|
||||
|
||||
item->yaw = NAN;
|
||||
item->loiter_radius = _navigator->get_loiter_radius();
|
||||
item->time_inside = 0.0f;
|
||||
item->pitch_min = min_pitch;
|
||||
item->autocontinue = false;
|
||||
item->origin = ORIGIN_ONBOARD;
|
||||
@@ -672,7 +669,6 @@ MissionBlock::set_land_item(struct mission_item_s *item, bool at_current_locatio
|
||||
item->loiter_radius = _navigator->get_loiter_radius();
|
||||
item->acceptance_radius = _navigator->get_acceptance_radius();
|
||||
item->time_inside = 0.0f;
|
||||
item->pitch_min = 0.0f;
|
||||
item->autocontinue = true;
|
||||
item->origin = ORIGIN_ONBOARD;
|
||||
}
|
||||
@@ -689,7 +685,6 @@ MissionBlock::set_current_position_item(struct mission_item_s *item)
|
||||
item->loiter_radius = _navigator->get_loiter_radius();
|
||||
item->acceptance_radius = _navigator->get_acceptance_radius();
|
||||
item->time_inside = 0.0f;
|
||||
item->pitch_min = 0.0f;
|
||||
item->autocontinue = true;
|
||||
item->origin = ORIGIN_ONBOARD;
|
||||
}
|
||||
@@ -706,7 +701,6 @@ MissionBlock::set_idle_item(struct mission_item_s *item)
|
||||
item->loiter_radius = _navigator->get_loiter_radius();
|
||||
item->acceptance_radius = _navigator->get_acceptance_radius();
|
||||
item->time_inside = 0.0f;
|
||||
item->pitch_min = 0.0f;
|
||||
item->autocontinue = true;
|
||||
item->origin = ORIGIN_ONBOARD;
|
||||
}
|
||||
|
||||
@@ -117,7 +117,6 @@ RCLoss::set_rcl_item()
|
||||
_mission_item.nav_cmd = NAV_CMD_LOITER_TIME_LIMIT;
|
||||
_mission_item.acceptance_radius = _navigator->get_acceptance_radius();
|
||||
_mission_item.time_inside = _param_loitertime.get() < 0.0f ? 0.0f : _param_loitertime.get();
|
||||
_mission_item.pitch_min = 0.0f;
|
||||
_mission_item.autocontinue = true;
|
||||
_mission_item.origin = ORIGIN_ONBOARD;
|
||||
|
||||
|
||||
@@ -158,7 +158,6 @@ RTL::set_rtl_item()
|
||||
_mission_item.nav_cmd = NAV_CMD_WAYPOINT;
|
||||
_mission_item.acceptance_radius = _navigator->get_acceptance_radius();
|
||||
_mission_item.time_inside = 0.0f;
|
||||
_mission_item.pitch_min = 0.0f;
|
||||
_mission_item.autocontinue = true;
|
||||
_mission_item.origin = ORIGIN_ONBOARD;
|
||||
|
||||
@@ -199,7 +198,6 @@ RTL::set_rtl_item()
|
||||
_mission_item.nav_cmd = NAV_CMD_WAYPOINT;
|
||||
_mission_item.acceptance_radius = _navigator->get_acceptance_radius();
|
||||
_mission_item.time_inside = 0.0f;
|
||||
_mission_item.pitch_min = 0.0f;
|
||||
_mission_item.autocontinue = true;
|
||||
_mission_item.origin = ORIGIN_ONBOARD;
|
||||
|
||||
@@ -245,7 +243,6 @@ RTL::set_rtl_item()
|
||||
_mission_item.nav_cmd = NAV_CMD_WAYPOINT;
|
||||
_mission_item.acceptance_radius = _navigator->get_acceptance_radius();
|
||||
_mission_item.time_inside = 0.0f;
|
||||
_mission_item.pitch_min = 0.0f;
|
||||
_mission_item.autocontinue = false;
|
||||
_mission_item.origin = ORIGIN_ONBOARD;
|
||||
|
||||
@@ -269,7 +266,6 @@ RTL::set_rtl_item()
|
||||
_mission_item.nav_cmd = autoland ? NAV_CMD_LOITER_TIME_LIMIT : NAV_CMD_LOITER_UNLIMITED;
|
||||
_mission_item.acceptance_radius = _navigator->get_acceptance_radius();
|
||||
_mission_item.time_inside = _param_land_delay.get() < 0.0f ? 0.0f : _param_land_delay.get();
|
||||
_mission_item.pitch_min = 0.0f;
|
||||
_mission_item.autocontinue = autoland;
|
||||
_mission_item.origin = ORIGIN_ONBOARD;
|
||||
|
||||
|
||||
Reference in New Issue
Block a user