mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_WPNav: remove unused function
This commit is contained in:
parent
7b60ace18b
commit
00b44ff6c8
@ -365,26 +365,6 @@ bool AC_WPNav::set_wp_destination_next_NED(const Vector3f& destination_NED)
|
||||
return set_wp_destination_next(Vector3f(destination_NED.x * 100.0f, destination_NED.y * 100.0f, -destination_NED.z * 100.0f), false);
|
||||
}
|
||||
|
||||
/// shift_wp_origin_to_current_pos - shifts the origin and destination so the origin starts at the current position
|
||||
/// used to reset the position just before takeoff
|
||||
/// relies on set_wp_destination or set_wp_origin_and_destination having been called first
|
||||
void AC_WPNav::shift_wp_origin_to_current_pos()
|
||||
{
|
||||
// get current and target locations
|
||||
const Vector3f &curr_pos = _inav.get_position();
|
||||
const Vector3f pos_target = _pos_control.get_pos_target();
|
||||
|
||||
// calculate difference between current position and target
|
||||
Vector3f pos_diff = curr_pos - pos_target;
|
||||
|
||||
// shift origin and destination
|
||||
_origin += pos_diff;
|
||||
_destination += pos_diff;
|
||||
|
||||
// move pos controller target and disable feed forward
|
||||
_pos_control.set_pos_target(curr_pos);
|
||||
}
|
||||
|
||||
/// shifts the origin and destination horizontally to the current position
|
||||
/// used to reset the track when taking off without horizontal position control
|
||||
/// relies on set_wp_destination or set_wp_origin_and_destination having been called first
|
||||
|
@ -116,11 +116,6 @@ public:
|
||||
bool set_wp_destination_NED(const Vector3f& destination_NED);
|
||||
bool set_wp_destination_next_NED(const Vector3f& destination_NED);
|
||||
|
||||
/// shift_wp_origin_to_current_pos - shifts the origin and destination so the origin starts at the current position
|
||||
/// used to reset the position just before takeoff
|
||||
/// relies on set_wp_destination or set_wp_origin_and_destination having been called first
|
||||
void shift_wp_origin_to_current_pos();
|
||||
|
||||
/// shifts the origin and destination horizontally to the current position
|
||||
/// used to reset the track when taking off without horizontal position control
|
||||
/// relies on set_wp_destination or set_wp_origin_and_destination having been called first
|
||||
|
Loading…
Reference in New Issue
Block a user