From 5a9ba4aeb45c888eda18ae96f96f7bcfd570e584 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 13 Dec 2012 08:41:12 +1100 Subject: [PATCH] APM_Control: updates for new AP_Param API --- libraries/APM_Control/AP_PitchController.h | 4 ++++ libraries/APM_Control/AP_RollController.h | 4 ++++ libraries/APM_Control/AP_YawController.h | 4 ++++ 3 files changed, 12 insertions(+) diff --git a/libraries/APM_Control/AP_PitchController.h b/libraries/APM_Control/AP_PitchController.h index c3264e2afb..4ea2bae675 100644 --- a/libraries/APM_Control/AP_PitchController.h +++ b/libraries/APM_Control/AP_PitchController.h @@ -9,6 +9,10 @@ class AP_PitchController { public: + AP_PitchController() { + AP_Param::setup_object_defaults(this, var_info); + } + void set_ahrs(AP_AHRS *ahrs) { _ahrs = ahrs; } int32_t get_servo_out(int32_t angle, float scaler = 1.0, bool stabilize = false); diff --git a/libraries/APM_Control/AP_RollController.h b/libraries/APM_Control/AP_RollController.h index 2565d08333..48a9ed0ae4 100644 --- a/libraries/APM_Control/AP_RollController.h +++ b/libraries/APM_Control/AP_RollController.h @@ -9,6 +9,10 @@ class AP_RollController { public: + AP_RollController() { + AP_Param::setup_object_defaults(this, var_info); + } + void set_ahrs(AP_AHRS *ahrs) { _ahrs = ahrs; } int32_t get_servo_out(int32_t angle, float scaler=1.0, bool stabilize=false); diff --git a/libraries/APM_Control/AP_YawController.h b/libraries/APM_Control/AP_YawController.h index b735cadb9a..4510796bd6 100644 --- a/libraries/APM_Control/AP_YawController.h +++ b/libraries/APM_Control/AP_YawController.h @@ -9,6 +9,10 @@ class AP_YawController { public: + AP_YawController() { + AP_Param::setup_object_defaults(this, var_info); + } + void set_ahrs(AP_AHRS *ahrs) { _ahrs = ahrs; _ins = _ahrs->get_ins();