mirror of https://github.com/ArduPilot/ardupilot
AP_Vehicle: replace get_rate_bf_targets with get_rate_ef_targets
This commit is contained in:
parent
fa77792d69
commit
2616afc5c8
|
@ -296,9 +296,9 @@ public:
|
|||
virtual void get_osd_roll_pitch_rad(float &roll, float &pitch) const;
|
||||
|
||||
/*
|
||||
get the target body-frame angular velocities in rad/s (Z-axis component used by some gimbals)
|
||||
get the target earth-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; }
|
||||
virtual bool get_rate_ef_targets(Vector3f& rate_ef_targets) const { return false; }
|
||||
|
||||
protected:
|
||||
|
||||
|
|
Loading…
Reference in New Issue