mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_L1_Control: move get_bearing_cd to Location and rename to get_bearing_to
This commit is contained in:
parent
1abe8c04f2
commit
2efe32e4b1
@ -224,7 +224,7 @@ void AP_L1_Control::update_waypoint(const struct Location &prev_WP, const struct
|
|||||||
Vector2f _groundspeed_vector = _ahrs.groundspeed_vector();
|
Vector2f _groundspeed_vector = _ahrs.groundspeed_vector();
|
||||||
|
|
||||||
// update _target_bearing_cd
|
// update _target_bearing_cd
|
||||||
_target_bearing_cd = get_bearing_cd(_current_loc, next_WP);
|
_target_bearing_cd = _current_loc.get_bearing_to(next_WP);
|
||||||
|
|
||||||
//Calculate groundspeed
|
//Calculate groundspeed
|
||||||
float groundSpeed = _groundspeed_vector.length();
|
float groundSpeed = _groundspeed_vector.length();
|
||||||
@ -360,7 +360,7 @@ void AP_L1_Control::update_loiter(const struct Location ¢er_WP, float radius
|
|||||||
|
|
||||||
|
|
||||||
// update _target_bearing_cd
|
// update _target_bearing_cd
|
||||||
_target_bearing_cd = get_bearing_cd(_current_loc, center_WP);
|
_target_bearing_cd = _current_loc.get_bearing_to(center_WP);
|
||||||
|
|
||||||
|
|
||||||
// Calculate time varying control parameters
|
// Calculate time varying control parameters
|
||||||
|
@ -18,6 +18,7 @@
|
|||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <AP_Navigation/AP_Navigation.h>
|
#include <AP_Navigation/AP_Navigation.h>
|
||||||
#include <AP_SpdHgtControl/AP_SpdHgtControl.h>
|
#include <AP_SpdHgtControl/AP_SpdHgtControl.h>
|
||||||
|
#include <AP_Common/Location.h>
|
||||||
|
|
||||||
class AP_L1_Control : public AP_Navigation {
|
class AP_L1_Control : public AP_Navigation {
|
||||||
public:
|
public:
|
||||||
|
Loading…
Reference in New Issue
Block a user