mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Arducopter: WP_radius
Switching to stored WP_radius in meters, just like Arduplane
This commit is contained in:
parent
32e6a6ba8d
commit
9de2c00d93
@ -1980,7 +1980,7 @@ static void update_navigation()
|
||||
static void update_nav_RTL()
|
||||
{
|
||||
// Have we have reached Home?
|
||||
if(wp_distance <= g.waypoint_radius){
|
||||
if(wp_distance <= (g.waypoint_radius * 100)){
|
||||
// if loiter_timer value > 0, we are set to trigger auto_land or approach
|
||||
set_mode(LOITER);
|
||||
|
||||
|
@ -454,7 +454,7 @@ static bool verify_nav_wp()
|
||||
}
|
||||
|
||||
// Did we pass the WP? // Distance checking
|
||||
if((wp_distance <= g.waypoint_radius) || check_missed_wp()){
|
||||
if((wp_distance <= (g.waypoint_radius * 100)) || check_missed_wp()){
|
||||
|
||||
// if we have a distance calc error, wp_distance may be less than 0
|
||||
if(wp_distance > 0){
|
||||
@ -505,7 +505,7 @@ static bool verify_loiter_time()
|
||||
return true;
|
||||
}
|
||||
}
|
||||
if(wp_control == WP_MODE && wp_distance <= g.waypoint_radius){
|
||||
if(wp_control == WP_MODE && wp_distance <= (g.waypoint_radius * 100)){
|
||||
// reset our loiter time
|
||||
loiter_time = millis();
|
||||
// switch to position hold
|
||||
@ -534,7 +534,7 @@ static bool verify_RTL()
|
||||
wp_control = WP_MODE;
|
||||
|
||||
// Did we pass the WP? // Distance checking
|
||||
if((wp_distance <= g.waypoint_radius) || check_missed_wp()){
|
||||
if((wp_distance <= (g.waypoint_radius * 100)) || check_missed_wp()){
|
||||
wp_control = LOITER_MODE;
|
||||
|
||||
//gcs_send_text_P(SEVERITY_LOW,PSTR("Reached home"));
|
||||
|
@ -257,7 +257,7 @@ static int16_t calc_desired_speed(int16_t max_speed, bool _slow)
|
||||
// limit the ramp up of the speed
|
||||
// waypoint_speed_gov is reset to 0 at each new WP command
|
||||
if(max_speed > waypoint_speed_gov){
|
||||
waypoint_speed_gov += (int)(200.0 * dTnav); // increase at .5/ms
|
||||
waypoint_speed_gov += (int)(100.0 * dTnav); // increase at .5/ms
|
||||
max_speed = waypoint_speed_gov;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user