mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -04:00
ArduPlane: use shared param info defines
This commit is contained in:
parent
13818eac99
commit
4e00a460fb
ArduPlane
@ -5,12 +5,6 @@
|
||||
*
|
||||
*/
|
||||
|
||||
#define GSCALAR(v, name, def) { plane.g.v.vtype, name, Parameters::k_param_ ## v, &plane.g.v, {def_value : def} }
|
||||
#define ASCALAR(v, name, def) { plane.aparm.v.vtype, name, Parameters::k_param_ ## v, (const void *)&plane.aparm.v, {def_value : def} }
|
||||
#define GGROUP(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &plane.g.v, {group_info : class::var_info} }
|
||||
#define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&plane.v, {group_info : class::var_info} }
|
||||
#define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, (const void *)&plane.v, {group_info : class::var_info} }
|
||||
|
||||
const AP_Param::Info Plane::var_info[] = {
|
||||
// @Param: FORMAT_VERSION
|
||||
// @DisplayName: Eeprom format version number
|
||||
@ -801,9 +795,9 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
#if HAL_QUADPLANE_ENABLED
|
||||
// @Group: Q_A_
|
||||
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../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 },
|
||||
{ "Q_A_", (const void *)&plane.quadplane.attitude_control,
|
||||
{group_info : AC_AttitudeControl_Multi::var_info}, AP_PARAM_FLAG_POINTER,
|
||||
Parameters::k_param_q_attitude_control, AP_PARAM_GROUP },
|
||||
#endif
|
||||
|
||||
// @Group: RLL
|
||||
@ -990,7 +984,7 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
|
||||
// @Group:
|
||||
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
|
||||
{ AP_PARAM_GROUP, "", Parameters::k_param_vehicle, (const void *)&plane, {group_info : AP_Vehicle::var_info} },
|
||||
PARAM_VEHICLE_INFO,
|
||||
|
||||
AP_VAREND
|
||||
};
|
||||
|
@ -1,5 +1,7 @@
|
||||
#pragma once
|
||||
|
||||
#define AP_PARAM_VEHICLE_NAME plane
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Gripper/AP_Gripper.h>
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user