mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Vehicle: add get_rate_bf_targets method
This commit is contained in:
parent
0975da6068
commit
c19d5391d9
@ -292,6 +292,11 @@ public:
|
||||
virtual void get_osd_roll_pitch_rad(float &roll, float &pitch) const;
|
||||
#endif
|
||||
|
||||
/*
|
||||
get the target body-frame angular velocities in rad/s (Z-axis component used by some gimbals)
|
||||
*/
|
||||
virtual bool get_rate_bf_targets(Vector3f& rate_bf_targets) const { return false; }
|
||||
|
||||
protected:
|
||||
|
||||
virtual void init_ardupilot() = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user