mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
APM_Control: updates for new AP_Param API
This commit is contained in:
parent
95d4cc2ce9
commit
5a9ba4aeb4
@ -9,6 +9,10 @@
|
|||||||
|
|
||||||
class AP_PitchController {
|
class AP_PitchController {
|
||||||
public:
|
public:
|
||||||
|
AP_PitchController() {
|
||||||
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
|
}
|
||||||
|
|
||||||
void set_ahrs(AP_AHRS *ahrs) { _ahrs = ahrs; }
|
void set_ahrs(AP_AHRS *ahrs) { _ahrs = ahrs; }
|
||||||
|
|
||||||
int32_t get_servo_out(int32_t angle, float scaler = 1.0, bool stabilize = false);
|
int32_t get_servo_out(int32_t angle, float scaler = 1.0, bool stabilize = false);
|
||||||
|
@ -9,6 +9,10 @@
|
|||||||
|
|
||||||
class AP_RollController {
|
class AP_RollController {
|
||||||
public:
|
public:
|
||||||
|
AP_RollController() {
|
||||||
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
|
}
|
||||||
|
|
||||||
void set_ahrs(AP_AHRS *ahrs) { _ahrs = ahrs; }
|
void set_ahrs(AP_AHRS *ahrs) { _ahrs = ahrs; }
|
||||||
|
|
||||||
int32_t get_servo_out(int32_t angle, float scaler=1.0, bool stabilize=false);
|
int32_t get_servo_out(int32_t angle, float scaler=1.0, bool stabilize=false);
|
||||||
|
@ -9,6 +9,10 @@
|
|||||||
|
|
||||||
class AP_YawController {
|
class AP_YawController {
|
||||||
public:
|
public:
|
||||||
|
AP_YawController() {
|
||||||
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
|
}
|
||||||
|
|
||||||
void set_ahrs(AP_AHRS *ahrs) {
|
void set_ahrs(AP_AHRS *ahrs) {
|
||||||
_ahrs = ahrs;
|
_ahrs = ahrs;
|
||||||
_ins = _ahrs->get_ins();
|
_ins = _ahrs->get_ins();
|
||||||
|
Loading…
Reference in New Issue
Block a user