diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 83e7966e79406d..ca3b32a07c3366 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -692,6 +692,18 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Path: mode_circle.cpp AP_SUBGROUPINFO(mode_circle, "CIRC", 57, ParametersG2, ModeCircle), + // @Group: RLL + // @Path: ../libraries/APM_Control/AP_RollController.cpp + AP_SUBGROUPINFO(rollController, "RLL", 58, ParametersG2, AP_RollController), + + // @Group: PTCH + // @Path: ../libraries/APM_Control/AP_PitchController.cpp + AP_SUBGROUPINFO(pitchController, "PTCH", 59, ParametersG2, AP_PitchController), + + // @Group: YAW + // @Path: ../libraries/APM_Control/AP_YawController.cpp + AP_SUBGROUPINFO(yawController, "YAW", 60, ParametersG2, AP_YawController), + AP_GROUPEND }; diff --git a/Rover/Parameters.h b/Rover/Parameters.h index e176a72f0cb842..dbfcb1bae01e6f 100644 --- a/Rover/Parameters.h +++ b/Rover/Parameters.h @@ -15,6 +15,10 @@ #include "AP_Torqeedo/AP_Torqeedo.h" #include +#include +#include +#include + #define AP_PARAM_VEHICLE_NAME rover // Global parameter class. @@ -434,6 +438,14 @@ class ParametersG2 { AP_Float fs_gcs_timeout; class ModeCircle mode_circle; + + // key aircraft parameters passed to multiple libraries + AP_FixedWing aparm; + + // Attitude to servo controllers + AP_RollController rollController{aparm}; + AP_PitchController pitchController{aparm}; + AP_YawController yawController{aparm}; }; extern const AP_Param::Info var_info[]; diff --git a/Rover/Rover.h b/Rover/Rover.h index 0db95d23b3997d..af193fdd403e48 100644 --- a/Rover/Rover.h +++ b/Rover/Rover.h @@ -121,6 +121,14 @@ class Rover : public AP_Vehicle { // variables AP_Param param_loader; + // key aircraft parameters passed to multiple libraries + AP_FixedWing aparm; + + // Attitude to servo controllers + AP_RollController rollController{aparm}; + AP_PitchController pitchController{aparm}; + AP_YawController yawController{aparm}; + // all settable parameters Parameters g; ParametersG2 g2;