From de5130fa1371b1e57c3718444c4ebe1a4bb6a2aa Mon Sep 17 00:00:00 2001 From: skyscraper Date: Mon, 9 May 2016 09:04:20 +0100 Subject: [PATCH] AP_Motors: RC_Channel refactor More fixing up of RC_Channel change access to data members to functions --- .../AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp | 6 +++--- 1 file changed, 3 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 1a6987815d..c80c46a7a9 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 @@ -74,8 +74,8 @@ void setup() motors.output_min(); // setup radio - rc3.radio_min = 1000; - rc3.radio_max = 2000; + rc3.set_radio_min(1000); + rc3.set_radio_max(2000); // set rc channel ranges rc1.set_angle(4500); @@ -139,7 +139,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.radio_min,(int)rc3.radio_max); + hal.console->printf("\nTesting stability patch\nThrottle Min:%d Max:%d\n",(int)rc3.get_radio_min(),(int)rc3.get_radio_max()); // arm motors motors.armed(true);