mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
ArduCopter: remove unused get_stabilize_rate_yaw
This commit is contained in:
parent
849fd9a234
commit
14cbe37d3e
@ -111,15 +111,6 @@ get_stabilize_yaw(int32_t target_angle)
|
||||
set_yaw_rate_target(target_rate+i_term, EARTH_FRAME);
|
||||
}
|
||||
|
||||
static void
|
||||
get_stabilize_rate_yaw(int32_t target_rate)
|
||||
{
|
||||
target_rate = g.pi_stabilize_yaw.get_p(target_rate);
|
||||
|
||||
// set targets for rate controller
|
||||
set_yaw_rate_target(target_rate, EARTH_FRAME);
|
||||
}
|
||||
|
||||
static void
|
||||
get_acro_roll(int32_t target_rate)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user