mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed loiter mode when Q_GUIDED_MODE=1
This fixes the fixed wing behaviour of LOITER mode whne Q_GUIDED_MODE=1. Many thanks to the PertUAV team for finding and reporting this bug
This commit is contained in:
parent
0f000efc6f
commit
4e017bf5b3
|
@ -173,8 +173,7 @@ void Plane::update_loiter(uint16_t radius)
|
||||||
}
|
}
|
||||||
|
|
||||||
if (loiter.start_time_ms != 0 &&
|
if (loiter.start_time_ms != 0 &&
|
||||||
quadplane.available() &&
|
quadplane.guided_mode_enabled()) {
|
||||||
quadplane.guided_mode != 0) {
|
|
||||||
if (!auto_state.vtol_loiter) {
|
if (!auto_state.vtol_loiter) {
|
||||||
auto_state.vtol_loiter = true;
|
auto_state.vtol_loiter = true;
|
||||||
// reset loiter start time, so we don't consider the point
|
// reset loiter start time, so we don't consider the point
|
||||||
|
@ -202,8 +201,7 @@ void Plane::update_loiter(uint16_t radius)
|
||||||
// starting a loiter in GUIDED means we just reached the target point
|
// starting a loiter in GUIDED means we just reached the target point
|
||||||
gcs_send_mission_item_reached_message(0);
|
gcs_send_mission_item_reached_message(0);
|
||||||
}
|
}
|
||||||
if (quadplane.available() &&
|
if (quadplane.guided_mode_enabled()) {
|
||||||
quadplane.guided_mode != 0) {
|
|
||||||
quadplane.guided_start();
|
quadplane.guided_start();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -2037,3 +2037,18 @@ void QuadPlane::afs_terminate(void)
|
||||||
motors->output();
|
motors->output();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
return true if we should do guided mode loitering using VTOL motors
|
||||||
|
*/
|
||||||
|
bool QuadPlane::guided_mode_enabled(void)
|
||||||
|
{
|
||||||
|
if (!available()) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
// only use quadplane guided when in AUTO or GUIDED mode
|
||||||
|
if (plane.control_mode != GUIDED && plane.control_mode != AUTO) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return guided_mode != 0;
|
||||||
|
}
|
||||||
|
|
|
@ -347,6 +347,7 @@ private:
|
||||||
void tilt_compensate(float *thrust, uint8_t num_motors);
|
void tilt_compensate(float *thrust, uint8_t num_motors);
|
||||||
|
|
||||||
void afs_terminate(void);
|
void afs_terminate(void);
|
||||||
|
bool guided_mode_enabled(void);
|
||||||
|
|
||||||
public:
|
public:
|
||||||
void motor_test_output();
|
void motor_test_output();
|
||||||
|
|
Loading…
Reference in New Issue