From 037e411e35c65c01c1ff85eafafb76a90085e31a Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 15 Dec 2016 10:35:58 +0900 Subject: [PATCH] AP_Motors: fix example sketch Also minor formatting fix Thanks to OXINARF for spotting this --- .../AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp index 44bb7a4f39..780c0479b1 100644 --- a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp +++ b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp @@ -59,8 +59,7 @@ void setup() // motor initialisation motors.set_update_rate(490); - motors.set_frame_class_and_type(AP_Motors::MOTOR_FRAME_QUAD, AP_Motors::MOTOR_FRAME_TYPE_X); - motors.Init(); + motors.init(AP_Motors::MOTOR_FRAME_QUAD, AP_Motors::MOTOR_FRAME_TYPE_X); #if HELI_TEST == 0 motors.set_throttle_range(1000,2000); motors.set_throttle_avg_max(0.5f); @@ -69,7 +68,7 @@ void setup() motors.output_min(); // setup radio - rc3.set_radio_min(1000); + rc3.set_radio_min(1000); rc3.set_radio_max(2000); // set rc channel ranges