mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Copter: remove unused get_acro_pitch and roll
This commit is contained in:
parent
f6688582a6
commit
13ee672eae
@ -95,24 +95,6 @@ get_stabilize_yaw(int32_t target_angle)
|
||||
set_yaw_rate_target(target_rate, EARTH_FRAME);
|
||||
}
|
||||
|
||||
static void
|
||||
get_acro_roll(int32_t target_rate)
|
||||
{
|
||||
target_rate = target_rate * g.acro_rp_p;
|
||||
|
||||
// set targets for rate controller
|
||||
set_roll_rate_target(target_rate, BODY_FRAME);
|
||||
}
|
||||
|
||||
static void
|
||||
get_acro_pitch(int32_t target_rate)
|
||||
{
|
||||
target_rate = target_rate * g.acro_rp_p;
|
||||
|
||||
// set targets for rate controller
|
||||
set_pitch_rate_target(target_rate, BODY_FRAME);
|
||||
}
|
||||
|
||||
static void
|
||||
get_acro_yaw(int32_t target_rate)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user