mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: implement get_rate_bf_targets method
This commit is contained in:
parent
cd1a62b7bc
commit
7d13582913
@ -725,6 +725,13 @@ bool Copter::get_wp_crosstrack_error_m(float &xtrack_error) const
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// get the target body-frame angular velocities in rad/s (Z-axis component used by some gimbals)
|
||||||
|
bool Copter::get_rate_bf_targets(Vector3f& rate_bf_targets) const
|
||||||
|
{
|
||||||
|
rate_bf_targets = attitude_control->rate_bf_targets();
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
constructor for main Copter class
|
constructor for main Copter class
|
||||||
*/
|
*/
|
||||||
|
@ -676,6 +676,7 @@ private:
|
|||||||
bool get_wp_distance_m(float &distance) const override;
|
bool get_wp_distance_m(float &distance) const override;
|
||||||
bool get_wp_bearing_deg(float &bearing) const override;
|
bool get_wp_bearing_deg(float &bearing) const override;
|
||||||
bool get_wp_crosstrack_error_m(float &xtrack_error) const override;
|
bool get_wp_crosstrack_error_m(float &xtrack_error) const override;
|
||||||
|
bool get_rate_bf_targets(Vector3f& rate_bf_targets) const override;
|
||||||
|
|
||||||
// Attitude.cpp
|
// Attitude.cpp
|
||||||
void update_throttle_hover();
|
void update_throttle_hover();
|
||||||
|
Loading…
Reference in New Issue
Block a user