mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
Plane: fixed up parameters for quadplane
this fixes quadplane parameters for the new AP_Motors code
This commit is contained in:
parent
0530af93aa
commit
dd6c4d6225
@ -1106,6 +1106,12 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
// @Path: quadplane.cpp
|
||||
GOBJECT(quadplane, "Q_", QuadPlane),
|
||||
|
||||
// @Group: Q_A_
|
||||
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp
|
||||
{ AP_PARAM_GROUP, "Q_A_", Parameters::k_param_q_attitude_control,
|
||||
(const void *)&plane.quadplane.attitude_control,
|
||||
{group_info : AC_AttitudeControl_Multi::var_info}, AP_PARAM_FLAG_POINTER },
|
||||
|
||||
// RC channel
|
||||
//-----------
|
||||
// @Group: RC1_
|
||||
|
@ -152,6 +152,7 @@ public:
|
||||
k_param_fence_retalt = 105,
|
||||
k_param_fence_autoenable,
|
||||
k_param_fence_ret_rally,
|
||||
k_param_q_attitude_control,
|
||||
|
||||
// 110: Telemetry control
|
||||
//
|
||||
|
@ -17,10 +17,6 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
|
||||
|
||||
// 3 ~ 8 were used by quadplane attitude control PIDs
|
||||
|
||||
// @Group: ATC_
|
||||
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp
|
||||
AP_SUBGROUPPTR(attitude_control, "A_", 9, QuadPlane, AC_AttitudeControl_Multi),
|
||||
|
||||
// @Param: ANGLE_MAX
|
||||
// @DisplayName: Angle Max
|
||||
// @Description: Maximum lean angle in all flight modes
|
||||
|
Loading…
Reference in New Issue
Block a user