ArduCopter: use shared param info defines
This commit is contained in:
parent
1ea8a0c1a0
commit
13818eac99
@ -20,14 +20,6 @@
|
||||
*
|
||||
*/
|
||||
|
||||
#define GSCALAR(v, name, def) { copter.g.v.vtype, name, Parameters::k_param_ ## v, &copter.g.v, {def_value : def} }
|
||||
#define ASCALAR(v, name, def) { copter.aparm.v.vtype, name, Parameters::k_param_ ## v, (const void *)&copter.aparm.v, {def_value : def} }
|
||||
#define GGROUP(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &copter.g.v, {group_info : class::var_info} }
|
||||
#define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&copter.v, {group_info : class::var_info} }
|
||||
#define GOBJECTPTR(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&copter.v, {group_info : class::var_info}, AP_PARAM_FLAG_POINTER }
|
||||
#define GOBJECTVARPTR(v, name, var_info_ptr) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&copter.v, {group_info_ptr : var_info_ptr}, AP_PARAM_FLAG_POINTER | AP_PARAM_FLAG_INFO_POINTER }
|
||||
#define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, (const void *)&copter.v, {group_info : class::var_info} }
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// 6 here is AP_Motors::MOTOR_FRAME_HELI
|
||||
#define DEFAULT_FRAME_CLASS 6
|
||||
@ -725,7 +717,7 @@ const AP_Param::Info Copter::var_info[] = {
|
||||
|
||||
// @Group:
|
||||
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
|
||||
{ AP_PARAM_GROUP, "", Parameters::k_param_vehicle, (const void *)&copter, {group_info : AP_Vehicle::var_info} },
|
||||
PARAM_VEHICLE_INFO,
|
||||
|
||||
AP_VAREND
|
||||
};
|
||||
|
@ -1,5 +1,7 @@
|
||||
#pragma once
|
||||
|
||||
#define AP_PARAM_VEHICLE_NAME copter
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include "RC_Channel.h"
|
||||
#include <AP_Proximity/AP_Proximity.h>
|
||||
|
Loading…
Reference in New Issue
Block a user