From 7582c882e6216be1f48ac94cfcbb756dae3f2561 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 13 Dec 2012 08:52:23 +1100 Subject: [PATCH] Motors: updates for new AP_Param API --- libraries/AP_Motors/AP_MotorsHeli.h | 1 + libraries/AP_Motors/AP_Motors_Class.cpp | 2 ++ 2 files changed, 3 insertions(+) diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 3497febee7..0651a2fb29 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -60,6 +60,7 @@ public: _servo_4(yaw_servo), _rc_8(rc_8) { + AP_Param::setup_object_defaults(this, var_info); throttle_mid = 0; _roll_scaler = 1; _pitch_scaler = 1; diff --git a/libraries/AP_Motors/AP_Motors_Class.cpp b/libraries/AP_Motors/AP_Motors_Class.cpp index 495d1c37c6..25d8706bdb 100644 --- a/libraries/AP_Motors/AP_Motors_Class.cpp +++ b/libraries/AP_Motors/AP_Motors_Class.cpp @@ -55,6 +55,8 @@ AP_Motors::AP_Motors( uint8_t APM_version, RC_Channel* rc_roll, RC_Channel* rc_p { uint8_t i; + AP_Param::setup_object_defaults(this, var_info); + top_bottom_ratio = AP_MOTORS_TOP_BOTTOM_RATIO; // initialise motor map