Browse Source

Arducopter: WP_radius

Switching to stored WP_radius in meters, just like Arduplane
mission-4.1.18
Jason Short 13 years ago
parent
commit
3048d2f9b4
  1. 2
      ArduCopter/ArduCopter.pde
  2. 6
      ArduCopter/commands_logic.pde
  3. 2
      ArduCopter/navigation.pde

2
ArduCopter/ArduCopter.pde

@ -1980,7 +1980,7 @@ static void update_navigation() @@ -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);

6
ArduCopter/commands_logic.pde

@ -454,7 +454,7 @@ static bool verify_nav_wp() @@ -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() @@ -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() @@ -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"));

2
ArduCopter/navigation.pde

@ -257,7 +257,7 @@ static int16_t calc_desired_speed(int16_t max_speed, bool _slow) @@ -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…
Cancel
Save