mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-21 06:27:35 +08:00
updated some message severities and clarified reset in pos controller
This commit is contained in:
@@ -908,9 +908,10 @@ MulticopterPositionControl::cross_sphere_line(const math::Vector<3> &sphere_c, f
|
||||
|
||||
void MulticopterPositionControl::control_auto(float dt)
|
||||
{
|
||||
/* reset position setpoint on AUTO mode activation or when reentering MC mode */
|
||||
if (!_mode_auto || _vehicle_status.in_transition_mode || !_vehicle_status.is_rotary_wing) {
|
||||
_mode_auto = true;
|
||||
/* reset position setpoint on AUTO mode activation */
|
||||
|
||||
if (_vehicle_status.in_transition_mode || !_vehicle_status.is_rotary_wing) {
|
||||
_reset_pos_sp = true;
|
||||
_reset_alt_sp = true;
|
||||
|
||||
@@ -432,7 +432,7 @@ Mission::set_mission_items()
|
||||
|
||||
float takeoff_alt = calculate_takeoff_altitude(&_mission_item);
|
||||
|
||||
mavlink_log_critical(_navigator->get_mavlink_fd(), "takeoff to %.1f meters above home", (double)(takeoff_alt - _navigator->get_home_position()->alt));
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(), "takeoff to %.1f meters above home", (double)(takeoff_alt - _navigator->get_home_position()->alt));
|
||||
|
||||
_mission_item.nav_cmd = NAV_CMD_TAKEOFF;
|
||||
_mission_item.lat = _navigator->get_global_position()->lat;
|
||||
@@ -875,7 +875,7 @@ Mission::read_mission_item(bool onboard, int offset, struct mission_item_s *miss
|
||||
|
||||
} else {
|
||||
if (offset == 0) {
|
||||
mavlink_log_critical(_navigator->get_mavlink_fd(),
|
||||
mavlink_log_info(_navigator->get_mavlink_fd(),
|
||||
"DO JUMP repetitions completed");
|
||||
}
|
||||
/* no more DO_JUMPS, therefore just try to continue with next mission item */
|
||||
|
||||
Reference in New Issue
Block a user