mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
changed define to a param for throttle_min and throttle_max
This commit is contained in:
parent
e8510faf5d
commit
efdf0a7fc8
@ -26,7 +26,7 @@ static void init_rc_in()
|
||||
// we do not want to limit the movment of the heli's swash plate
|
||||
g.rc_3.set_range(0, 1000);
|
||||
#else
|
||||
g.rc_3.set_range(MINIMUM_THROTTLE, MAXIMUM_THROTTLE);
|
||||
g.rc_3.set_range(g.throttle_min, g.throttle_max);
|
||||
#endif
|
||||
g.rc_4.set_angle(4500);
|
||||
|
||||
@ -54,8 +54,8 @@ static void init_rc_out()
|
||||
#endif
|
||||
motors.set_frame_orientation(g.frame_orientation);
|
||||
motors.Init(); // motor initialisation
|
||||
motors.set_min_throttle(MINIMUM_THROTTLE);
|
||||
motors.set_max_throttle(MAXIMUM_THROTTLE);
|
||||
motors.set_min_throttle(g.throttle_min);
|
||||
motors.set_max_throttle(g.throttle_max);
|
||||
|
||||
// this is the camera pitch5 and roll6
|
||||
APM_RC.OutputCh(CH_CAM_PITCH, 1500);
|
||||
|
Loading…
Reference in New Issue
Block a user