mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: fix example sketch
Also minor formatting fix Thanks to OXINARF for spotting this
This commit is contained in:
parent
ffa6d1a5b9
commit
037e411e35
|
@ -59,8 +59,7 @@ void setup()
|
||||||
|
|
||||||
// motor initialisation
|
// motor initialisation
|
||||||
motors.set_update_rate(490);
|
motors.set_update_rate(490);
|
||||||
motors.set_frame_class_and_type(AP_Motors::MOTOR_FRAME_QUAD, AP_Motors::MOTOR_FRAME_TYPE_X);
|
motors.init(AP_Motors::MOTOR_FRAME_QUAD, AP_Motors::MOTOR_FRAME_TYPE_X);
|
||||||
motors.Init();
|
|
||||||
#if HELI_TEST == 0
|
#if HELI_TEST == 0
|
||||||
motors.set_throttle_range(1000,2000);
|
motors.set_throttle_range(1000,2000);
|
||||||
motors.set_throttle_avg_max(0.5f);
|
motors.set_throttle_avg_max(0.5f);
|
||||||
|
@ -69,7 +68,7 @@ void setup()
|
||||||
motors.output_min();
|
motors.output_min();
|
||||||
|
|
||||||
// setup radio
|
// setup radio
|
||||||
rc3.set_radio_min(1000);
|
rc3.set_radio_min(1000);
|
||||||
rc3.set_radio_max(2000);
|
rc3.set_radio_max(2000);
|
||||||
|
|
||||||
// set rc channel ranges
|
// set rc channel ranges
|
||||||
|
|
Loading…
Reference in New Issue