mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AC_WPNav: integrate AC_PosControl::get_roll_cd rename
This commit is contained in:
parent
b17042078a
commit
ccf06f66f7
@ -192,8 +192,8 @@ public:
|
|||||||
///
|
///
|
||||||
|
|
||||||
/// get desired roll, pitch which should be fed into stabilize controllers
|
/// get desired roll, pitch which should be fed into stabilize controllers
|
||||||
float get_roll() const { return _pos_control.get_roll(); }
|
float get_roll() const { return _pos_control.get_roll_cd(); }
|
||||||
float get_pitch() const { return _pos_control.get_pitch(); }
|
float get_pitch() const { return _pos_control.get_pitch_cd(); }
|
||||||
Vector3f get_thrust_vector() const { return _pos_control.get_thrust_vector(); }
|
Vector3f get_thrust_vector() const { return _pos_control.get_thrust_vector(); }
|
||||||
|
|
||||||
/// advance_wp_target_along_track - move target location along track from origin to destination
|
/// advance_wp_target_along_track - move target location along track from origin to destination
|
||||||
|
Loading…
Reference in New Issue
Block a user