From aa6f66f29b33b30c30101725eff8a1d7b6cfdd8c Mon Sep 17 00:00:00 2001 From: "Hiroshi Takey (hiro2233)" Date: Sun, 24 Dec 2017 16:41:22 -0400 Subject: [PATCH] AP_Motors: Updated Motor example. --- .../AP_Motors_test/AP_Motors_test.cpp | 20 +++++++++---------- .../AP_Motors/examples/AP_Motors_test/wscript | 3 --- 2 files changed, 10 insertions(+), 13 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 1a9a7c0af9..1d495a5e17 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 @@ -29,6 +29,7 @@ #include #include #include +#include #include const AP_HAL::HAL& hal = AP_HAL::get_HAL(); @@ -43,8 +44,7 @@ void update_motors(); #define HELI_TEST 0 // set to 1 to test helicopters #define NUM_OUTPUTS 4 // set to 6 for hexacopter, 8 for octacopter and heli -RC_Channel rc1(0), rc2(1), rc3(2), rc4(3); -RC_Channel rc7(6), rsc(8), h1(0), h2(1), h3(2), h4(3); +SRV_Channels srvs; // uncomment the row below depending upon what frame you are using //AP_MotorsTri motors(400); @@ -68,14 +68,14 @@ void setup() motors.output_min(); // setup radio - rc3.set_radio_min(1000); - rc3.set_radio_max(2000); + SRV_Channels::srv_channel(2)->set_output_min(1000); + SRV_Channels::srv_channel(2)->set_output_max(2000); // set rc channel ranges - rc1.set_angle(4500); - rc2.set_angle(4500); - rc3.set_range(1000); - rc4.set_angle(4500); + SRV_Channels::srv_channel(0)->set_angle(4500); + SRV_Channels::srv_channel(1)->set_angle(4500); + SRV_Channels::srv_channel(2)->set_range(1000); + SRV_Channels::srv_channel(3)->set_angle(4500); hal.scheduler->delay(1000); } @@ -133,7 +133,7 @@ void stability_test() int16_t rpy_tests[] = {0, 1000, 2000, 3000, 4500, -1000, -2000, -3000, -4500}; uint8_t rpy_tests_num = sizeof(rpy_tests) / sizeof(int16_t); - hal.console->printf("\nTesting stability patch\nThrottle Min:%d Max:%d\n",(int)rc3.get_radio_min(),(int)rc3.get_radio_max()); + hal.console->printf("\nTesting stability patch\nThrottle Min:%d Max:%d\n",(int)SRV_Channels::srv_channel(2)->get_output_min(),(int)SRV_Channels::srv_channel(2)->get_output_max()); // arm motors motors.armed(true); @@ -211,7 +211,7 @@ void stability_test() void update_motors() { // call update motors 1000 times to get any ramp limiting complete - for (uint16_t i=0; i<4000; i++) { + for (uint16_t i=0; i<1000; i++) { motors.output(); } } diff --git a/libraries/AP_Motors/examples/AP_Motors_test/wscript b/libraries/AP_Motors/examples/AP_Motors_test/wscript index cce0a8aab5..719ec151ba 100644 --- a/libraries/AP_Motors/examples/AP_Motors_test/wscript +++ b/libraries/AP_Motors/examples/AP_Motors_test/wscript @@ -2,9 +2,6 @@ # encoding: utf-8 def build(bld): - # TODO: Test code doesn't build. Fix or delete the test. - return - bld.ap_example( use='ap', )