Browse Source

Rover: remove unused update_navigation

master
Randy Mackay 8 years ago
parent
commit
b4af441eb9
  1. 5
      APMrover2/APMrover2.cpp
  2. 1
      APMrover2/Rover.h
  3. 4
      APMrover2/navigation.cpp

5
APMrover2/APMrover2.cpp

@ -408,9 +408,4 @@ void Rover::update_current_mode(void) @@ -408,9 +408,4 @@ void Rover::update_current_mode(void)
control_mode->update();
}
void Rover::update_navigation()
{
control_mode->update_navigation();
}
AP_HAL_MAIN_CALLBACKS(&rover);

1
APMrover2/Rover.h

@ -431,7 +431,6 @@ private: @@ -431,7 +431,6 @@ private:
void update_GPS_50Hz(void);
void update_GPS_10Hz(void);
void update_current_mode(void);
void update_navigation();
void send_heartbeat(mavlink_channel_t chan);
void send_attitude(mavlink_channel_t chan);
void update_sensor_status_flags(void);

4
APMrover2/navigation.cpp

@ -18,10 +18,6 @@ void Rover::navigate() @@ -18,10 +18,6 @@ void Rover::navigate()
// waypoint distance from rover
// ----------------------------
wp_distance = get_distance(current_loc, next_WP);
// control mode specific updates to nav_bearing
// --------------------------------------------
update_navigation();
}

Loading…
Cancel
Save