mirror of
https://github.com/ArduPilot/ardupilot.git
synced 2026-02-07 13:07:26 +08:00
Sub: replace smoothing gain with AC_AttitudeControl::set_input_tc
This commit is contained in:
@@ -1,12 +1,5 @@
|
||||
#include "Sub.h"
|
||||
|
||||
// get_smoothing_gain - returns smoothing gain to be passed into attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw
|
||||
// result is a number from 2 to 12 with 2 being very sluggish and 12 being very crisp
|
||||
float Sub::get_smoothing_gain()
|
||||
{
|
||||
return (2.0f + (float)g.rc_feel_rp/10.0f);
|
||||
}
|
||||
|
||||
// get_pilot_desired_angle - transform pilot's roll or pitch input into a desired lean angle
|
||||
// returns desired angle in centi-degrees
|
||||
void Sub::get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out, float angle_max)
|
||||
|
||||
Reference in New Issue
Block a user