mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Copter: integrate AttControl feel param
This commit is contained in:
parent
25ee5d5dc8
commit
429e8d5e50
@ -51,7 +51,7 @@ static void stabilize_run()
|
|||||||
attitude_control.init_targets();
|
attitude_control.init_targets();
|
||||||
}else{
|
}else{
|
||||||
// call attitude controller
|
// call attitude controller
|
||||||
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate);
|
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, g.rc_feel_rp);
|
||||||
|
|
||||||
// body-frame rate controller is run directly from 100hz loop
|
// body-frame rate controller is run directly from 100hz loop
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user