Plane: change param prefixes for roll/pitch controllers

This commit is contained in:
Andrew Tridgell 2021-02-27 21:29:49 +11:00
parent 7b98ab0f12
commit a35d8e584d
2 changed files with 7 additions and 4 deletions

View File

@ -848,13 +848,13 @@ const AP_Param::Info Plane::var_info[] = {
(const void *)&plane.quadplane.attitude_control,
{group_info : AC_AttitudeControl_Multi::var_info}, AP_PARAM_FLAG_POINTER },
// @Group: RLL2SRV_
// @Group: RLL
// @Path: ../libraries/APM_Control/AP_RollController.cpp
GOBJECT(rollController, "RLL2SRV_", AP_RollController),
GOBJECT(rollController, "RLL", AP_RollController),
// @Group: PTCH2SRV_
// @Group: PTCH
// @Path: ../libraries/APM_Control/AP_PitchController.cpp
GOBJECT(pitchController, "PTCH2SRV_", AP_PitchController),
GOBJECT(pitchController, "PTCH", AP_PitchController),
// @Group: YAW2SRV_
// @Path: ../libraries/APM_Control/AP_YawController.cpp

View File

@ -38,6 +38,9 @@ void Plane::init_ardupilot()
can_mgr.init();
#endif
rollController.convert_pid();
pitchController.convert_pid();
// initialise rc channels including setting mode
rc().init();