mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter WPNav: remove unused variable
This commit is contained in:
parent
5e2fc32410
commit
89bbf5844f
@ -357,12 +357,10 @@ void AC_WPNav::advance_target_along_track(float dt)
|
|||||||
float track_desired_max;
|
float track_desired_max;
|
||||||
float track_desired_temp = _track_desired;
|
float track_desired_temp = _track_desired;
|
||||||
float track_extra_max;
|
float track_extra_max;
|
||||||
float curr_delta_length;
|
|
||||||
|
|
||||||
// get current location
|
// get current location
|
||||||
Vector3f curr_pos = _inav->get_position();
|
Vector3f curr_pos = _inav->get_position();
|
||||||
Vector3f curr_delta = curr_pos - _origin;
|
Vector3f curr_delta = curr_pos - _origin;
|
||||||
curr_delta_length = curr_delta.length();
|
|
||||||
|
|
||||||
// calculate how far along the track we are
|
// calculate how far along the track we are
|
||||||
track_covered = curr_delta.x * _pos_delta_unit.x + curr_delta.y * _pos_delta_unit.y + curr_delta.z * _pos_delta_unit.z;
|
track_covered = curr_delta.x * _pos_delta_unit.x + curr_delta.y * _pos_delta_unit.y + curr_delta.z * _pos_delta_unit.z;
|
||||||
|
Loading…
Reference in New Issue
Block a user