mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Arducopter: Fix circle_WP
This commit is contained in:
parent
a28070e0e0
commit
d8ff5dcfab
@ -2404,8 +2404,11 @@ static void update_auto_yaw()
|
|||||||
if(wp_control == LOITER_MODE)
|
if(wp_control == LOITER_MODE)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
// this tracks a location so the copter is always pointing towards it.
|
if(control_mode == CIRCLE_MODE){
|
||||||
if(yaw_tracking == MAV_ROI_LOCATION){
|
auto_yaw = get_bearing(¤t_loc, &circle_WP);
|
||||||
|
|
||||||
|
}else if(yaw_tracking == MAV_ROI_LOCATION){
|
||||||
|
// this tracks a location so the copter is always pointing towards it.
|
||||||
auto_yaw = get_bearing(¤t_loc, &target_WP);
|
auto_yaw = get_bearing(¤t_loc, &target_WP);
|
||||||
|
|
||||||
}else if(yaw_tracking == MAV_ROI_WPNEXT){
|
}else if(yaw_tracking == MAV_ROI_WPNEXT){
|
||||||
|
@ -310,9 +310,6 @@ static void do_loiter_turns()
|
|||||||
{
|
{
|
||||||
wp_control = CIRCLE_MODE;
|
wp_control = CIRCLE_MODE;
|
||||||
|
|
||||||
// reset desired location
|
|
||||||
|
|
||||||
|
|
||||||
if(command_nav_queue.lat == 0){
|
if(command_nav_queue.lat == 0){
|
||||||
// allow user to specify just the altitude
|
// allow user to specify just the altitude
|
||||||
if(command_nav_queue.alt > 0){
|
if(command_nav_queue.alt > 0){
|
||||||
@ -323,6 +320,8 @@ static void do_loiter_turns()
|
|||||||
set_next_WP(&command_nav_queue);
|
set_next_WP(&command_nav_queue);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
circle_WP = next_WP;
|
||||||
|
|
||||||
loiter_total = command_nav_queue.p1 * 360;
|
loiter_total = command_nav_queue.p1 * 360;
|
||||||
loiter_sum = 0;
|
loiter_sum = 0;
|
||||||
old_target_bearing = target_bearing;
|
old_target_bearing = target_bearing;
|
||||||
|
Loading…
Reference in New Issue
Block a user