AC_WPNav: Support Thrust Vector Control

This commit is contained in:
Leonard Hall 2021-04-13 13:52:56 +09:30 committed by Randy Mackay
parent bb46f7a947
commit 939d8e3ed4
3 changed files with 3 additions and 0 deletions

View File

@ -66,6 +66,7 @@ public:
/// get desired roll, pitch which should be fed into stabilize controllers
float get_roll() const { return _pos_control.get_roll(); }
float get_pitch() const { return _pos_control.get_pitch(); }
Vector3f get_thrust_vector() const { return _pos_control.get_thrust_vector(); }
float get_yaw() const { return _yaw; }
/// returns true if update has been run recently

View File

@ -53,6 +53,7 @@ public:
/// get desired roll, pitch which should be fed into stabilize controllers
float get_roll() const { return _pos_control.get_roll(); }
float get_pitch() const { return _pos_control.get_pitch(); }
Vector3f get_thrust_vector() const { return _pos_control.get_thrust_vector(); }
static const struct AP_Param::GroupInfo var_info[];

View File

@ -200,6 +200,7 @@ public:
/// get desired roll, pitch which should be fed into stabilize controllers
float get_roll() const { return _pos_control.get_roll(); }
float get_pitch() const { return _pos_control.get_pitch(); }
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
bool advance_wp_target_along_track(float dt);