本节主要记录自己在ardupilot多旋翼无人机代码中添加一个新的参数,并显示到地面站上;同时实现美国手与日本手切换的过程。欢迎批评指正!!!
增加一个新的参数网址
参数既可以是主代码的一部分,也可以是库的一部分。
1.增加一个参数到主代码
第1步:在这个文件(Parameters.h)中找到参数类的枚举的备用间隙,并添加新参数(也就是找个没有被占用的枚举数据,添加自己的参数),如下面所示的红色。
enum {
// Misc
//
k_param_log_bitmask = 20,
k_param_log_last_filenumber, // *** Deprecated - remove
// with next eeprom number
// change
k_param_toy_yaw_rate, // THOR The memory
// location for the
// Yaw Rate 1 = fast,
// 2 = med, 3 = slow
k_param_crosstrack_min_distance, // deprecated - remove with next eeprom number change
k_param_rssi_pin,
k_param_throttle_accel_enabled, // deprecated - remove
k_param_wp_yaw_behavior,
k_param_acro_trainer,
k_param_pilot_velocity_z_max,
k_param_circle_rate,
k_param_sonar_gain,
k_param_ch8_option,
k_param_arming_check_enabled,
k_param_sprayer,
k_param_angle_max,
k_param_gps_hdop_good, // 35
//新增加的参数:这里为什么要这样写后面会讲解,一定要这样写,不然会报错。一定要k_param_开头,当然这个代码已经比较古老了,可以看下怎么添加最新的,我也贴出自己添加的参数
k_param_my_new_parameter, // 36
官网上的文档太古老了,这里重新写个代码(直接使用254,最后一个枚举数)
enum {
// Layout version number, always key zero.
//
k_param_format_version = 0,
k_param_software_type,
k_param_ins_old, // *** Deprecated, remove with next eeprom number change
k_param_ins, // libraries/AP_InertialSensor variables
k_param_NavEKF2_old, // deprecated - remove
k_param_NavEKF2,
k_param_g2, // 2nd block of parameters
k_param_NavEKF3,
// simulation
k_param_sitl = 10,
// barometer object (needed for SITL)
k_param_barometer,
// scheduler object (for debugging)
k_param_scheduler,
// relay object
k_param_relay,
// (old) EPM object
k_param_epm_unused,
// BoardConfig object
k_param_BoardConfig,
// GPS object
k_param_gps,
// Parachute object
k_param_parachute,
// Landing gear object
k_param_landinggear, // 18
// Input Management object
k_param_input_manager, // 19
// Misc
//
k_param_log_bitmask_old = 20, // Deprecated
k_param_log_last_filenumber, // *** Deprecated - remove
// with next eeprom number
// change
k_param_toy_yaw_rate, // deprecated - remove
k_param_crosstrack_min_distance, // deprecated - remove with next eeprom number change
k_param_rssi_pin, // unused, replaced by rssi_ library parameters
k_param_throttle_accel_enabled, // deprecated - remove
k_param_wp_yaw_behavior,
k_param_acro_trainer,
k_param_pilot_speed_up,
k_param_circle_rate, // deprecated - remove
k_param_rangefinder_gain,
k_param_ch8_option,
k_param_arming_check_old, // deprecated - remove
k_param_sprayer,
k_param_angle_max,
k_param_gps_hdop_good,
k_param_battery,
k_param_fs_batt_mah,
k_param_angle_rate_max, // remove
k_param_rssi_range, // unused, replaced by rssi_ library parameters
k_param_rc_feel_rp,
k_param_NavEKF, // deprecated - remove
k_param_mission, // mission library
k_param_rc_13_old,
k_param_rc_14_old,
k_param_rally,
k_param_poshold_brake_rate,
k_param_poshold_brake_angle_max,
k_param_pilot_accel_z,
k_param_serial0_baud, // deprecated - remove
k_param_serial1_baud, // deprecated - remove
k_param_serial2_baud, // deprecated - remove
k_param_land_repositioning,
k_param_rangefinder, // rangefinder object
k_param_fs_ekf_thresh,
k_param_terrain,
k_param_acro_rp_expo,
k_param_throttle_deadzone,
k_param_optflow,
k_param_dcmcheck_thresh, // deprecated - remove
k_param_log_bitmask,
k_param_cli_enabled,
k_param_throttle_filt,
k_param_throttle_behavior,
k_param_pilot_takeoff_alt, // 64
// 65: AP_Limits Library
k_param_limits = 65, // deprecated - remove
k_param_gpslock_limit, // deprecated - remove
k_param_geofence_limit, // deprecated - remove
k_param_altitude_limit, // deprecated - remove
k_param_fence,
k_param_gps_glitch, // deprecated
k_param_baro_glitch, // 71 - deprecated
// AP_ADSB Library
k_param_adsb, // 72
k_param_notify, // 73
// 74: precision landing object
k_param_precland = 74,
//
// 75: Singlecopter, CoaxCopter
//
k_param_single_servo_1 = 75, // remove
k_param_single_servo_2, // remove
k_param_single_servo_3, // remove
k_param_single_servo_4, // 78 - remove
//
// 80: Heli
//
k_param_heli_servo_1 = 80, // remove
k_param_heli_servo_2, // remove
k_param_heli_servo_3, // remove
k_param_heli_servo_4, // remove
k_param_heli_pitch_ff, // remove
k_param_heli_roll_ff, // remove
k_param_heli_yaw_ff, // remove
k_param_heli_stab_col_min, // remove
k_param_heli_stab_col_max, // remove
k_param_heli_servo_rsc, // 89 = full! - remove
//
// 90: misc2
//
k_param_motors = 90,
k_param_disarm_delay,
k_param_fs_crash_check,
k_param_throw_motor_start,
k_param_terrain_follow, // 94
k_param_avoid,
k_param_avoidance_adsb,
// 97: RSSI
k_param_rssi = 97,
//
// 100: Inertial Nav
//
k_param_inertial_nav = 100, // deprecated
k_param_wp_nav,
k_param_attitude_control,
k_param_pos_control,
k_param_circle_nav, // 104
k_param_loiter_nav, // 105
// 110: Telemetry control
//
k_param_gcs0 = 110,
k_param_gcs1,
k_param_sysid_this_mav,
k_param_sysid_my_gcs,
k_param_serial1_baud_old, // deprecated
k_param_telem_delay,
k_param_gcs2,
k_param_serial2_baud_old, // deprecated
k_param_serial2_protocol, // deprecated
k_param_serial_manager,
k_param_ch9_option,
k_param_ch10_option,
k_param_ch11_option,
k_param_ch12_option,
k_param_takeoff_trigger_dz,
k_param_gcs3,
k_param_gcs_pid_mask, // 126
//
// 135 : reserved for Solo until features merged with master
//
k_param_rtl_speed_cms = 135,
k_param_fs_batt_curr_rtl,
k_param_rtl_cone_slope, // 137
//
// 140: Sensor parameters
//
k_param_imu = 140, // deprecated - can be deleted
k_param_battery_monitoring = 141, // deprecated - can be deleted
k_param_volt_div_ratio, // deprecated - can be deleted
k_param_curr_amp_per_volt, // deprecated - can be deleted
k_param_input_voltage, // deprecated - can be deleted
k_param_pack_capacity, // deprecated - can be deleted
k_param_compass_enabled,
k_param_compass,
k_param_rangefinder_enabled_old, // deprecated
k_param_frame_type,
k_param_optflow_enabled, // deprecated
k_param_fs_batt_voltage,
k_param_ch7_option,
k_param_auto_slew_rate, // deprecated - can be deleted
k_param_rangefinder_type_old, // deprecated
k_param_super_simple = 155,
k_param_axis_enabled = 157, // deprecated - remove with next eeprom number change
k_param_copter_leds_mode, // deprecated - remove with next eeprom number change
k_param_ahrs, // AHRS group // 159
//
// 160: Navigation parameters
//
k_param_rtl_altitude = 160,
k_param_crosstrack_gain, // deprecated - remove with next eeprom number change
k_param_rtl_loiter_time,
k_param_rtl_alt_final,
k_param_tilt_comp, //164 deprecated - remove with next eeprom number change
//
// Camera and mount parameters
//
k_param_camera = 165,
k_param_camera_mount,
k_param_camera_mount2, // deprecated
//
// Batery monitoring parameters
//
k_param_battery_volt_pin = 168, // deprecated - can be deleted
k_param_battery_curr_pin, // 169 deprecated - can be deleted
//
// 170: Radio settings
//
k_param_rc_1_old = 170,
k_param_rc_2_old,
k_param_rc_3_old,
k_param_rc_4_old,
k_param_rc_5_old,
k_param_rc_6_old,
k_param_rc_7_old,
k_param_rc_8_old,
k_param_rc_10_old,
k_param_rc_11_old,
k_param_throttle_min, // remove
k_param_throttle_max, // remove
k_param_failsafe_throttle,
k_param_throttle_fs_action, // remove
k_param_failsafe_throttle_value,
k_param_throttle_trim, // remove
k_param_esc_calibrate,
k_param_radio_tuning,
k_param_radio_tuning_high,
k_param_radio_tuning_low,
k_param_rc_speed = 192,
k_param_failsafe_battery_enabled,
k_param_throttle_mid, // remove
k_param_failsafe_gps_enabled, // remove
k_param_rc_9_old,
k_param_rc_12_old,
k_param_failsafe_gcs,
k_param_rcmap, // 199
//
// 200: flight modes
//
k_param_flight_mode1 = 200,
k_param_flight_mode2,
k_param_flight_mode3,
k_param_flight_mode4,
k_param_flight_mode5,
k_param_flight_mode6,
k_param_simple_modes,
//
// 210: Waypoint data
//
k_param_waypoint_mode = 210, // remove
k_param_command_total, // remove
k_param_command_index, // remove
k_param_command_nav_index, // remove
k_param_waypoint_radius, // remove
k_param_circle_radius, // remove
k_param_waypoint_speed_max, // remove
k_param_land_speed,
k_param_auto_velocity_z_min, // remove
k_param_auto_velocity_z_max, // remove - 219
k_param_land_speed_high,
//
// 220: PI/D Controllers
//
k_param_acro_rp_p = 221,
k_param_axis_lock_p, // remove
k_param_pid_rate_roll, // remove
k_param_pid_rate_pitch, // remove
k_param_pid_rate_yaw, // remove
k_param_p_stabilize_roll, // remove
k_param_p_stabilize_pitch, // remove
k_param_p_stabilize_yaw, // remove
k_param_p_pos_xy,
k_param_p_loiter_lon, // remove
k_param_pid_loiter_rate_lat, // remove
k_param_pid_loiter_rate_lon, // remove
k_param_pid_nav_lat, // remove
k_param_pid_nav_lon, // remove
k_param_p_alt_hold,
k_param_p_vel_z,
k_param_pid_optflow_roll, // remove
k_param_pid_optflow_pitch, // remove
k_param_acro_balance_roll_old, // remove
k_param_acro_balance_pitch_old, // remove
k_param_pid_accel_z,
k_param_acro_balance_roll,
k_param_acro_balance_pitch,
k_param_acro_yaw_p,
k_param_autotune_axis_bitmask,
k_param_autotune_aggressiveness,
k_param_pi_vel_xy,
k_param_fs_ekf_action,
k_param_rtl_climb_min,
k_param_rpm_sensor,
k_param_autotune_min_d, // 251
k_param_arming, // 252 - AP_Arming
k_param_DataFlash = 253, // 253 - Logging Group
/********************这里是我自己添加的参数****************/
k_param_radio_mode = 254, // 254 - radio mode American or japan arm
/********************这里是我自己添加的参数****************/
// the k_param_* space is 9-bits in size
// 511: reserved
};
需要注意的:
(1)尽量在执行类似功能的参数区域添加新的参数,或者最坏的情形下就是在“Misc(混合)”区域的末尾添加。(个人建议可以在最后添加好点)
2)确保你添加的参数区域中还可以有编号添加新的参数。检查是否能继续添加参数的方法是:检查参数的计数,确保你所要添加的参数的上一个元素编号要小于你的下一部分代码的编号。比如,Misc部分的第一个参数起始于#20,。my_new_parameter是#36。如果下一部分参数开始于#36,那么我们就不能在这里添加这个新参数。
3)不要在一个代码块的中间添加新的参数,那样容易造成现存参数对应的信息的改变。
4)不要在参数旁边用“弃用(deprecated)”或“移除(remove)”做注解,这是因为一些使用者将此注释用作在eeprom上的旧的参数的默认注解,如果你添加的新参数也是这样注解,那么就让人就会看起来很奇怪和疑惑。
第2步:
在枚举变量后面的参数类中声明上面枚举变种提到的参数。可使用的类型包括
AP_Int8,AP_Int16,AP_Float,AP_Int32,AP_Vector3
(目前还不支持unsigned integer无符号整型)。新的枚举变量的名称应该保持一致,只是去掉了前缀k_param_。
// 254,255: reserved
};
AP_Int16 format_version;
AP_Int8 software_type;
// Telemetry control
//
AP_Int16 sysid_this_mav;
AP_Int16 sysid_my_gcs;
AP_Int8 serial3_baud;
AP_Int8 telem_delay;
AP_Int16 rtl_altitude;
AP_Int8 sonar_enabled;
AP_Int8 sonar_type; // 0 = XL, 1 = LV,
// 2 = XLL (XL with 10m range)
// 3 = HRLV
AP_Float sonar_gain;
AP_Int8 battery_monitoring; // 0=disabled, 3=voltage only,
// 4=voltage and current
AP_Float volt_div_ratio;
AP_Float curr_amp_per_volt;
AP_Int16 pack_capacity; // Battery pack capacity less reserve
AP_Int8 failsafe_battery_enabled; // battery failsafe enabled
AP_Int8 failsafe_gps_enabled; // gps failsafe enabled
AP_Int8 failsafe_gcs; // ground station failsafe behavior
AP_Int16 gps_hdop_good; // GPS Hdop value below which represent a good position
//注意这里是官网上添加的参数,我现在还是按自己的添加
AP_Int16 my_new_parameter; // my new parameter's description goes here
我自己添加的参数
AP_Int16 format_version;
AP_Int8 software_type;
// Telemetry control
//
AP_Int16 sysid_this_mav;
AP_Int16 sysid_my_gcs;
AP_Int8 telem_delay;
#if CLI_ENABLED == ENABLED
AP_Int8 cli_enabled;
#endif
AP_Float throttle_filt;
AP_Int16 throttle_behavior;
AP_Int16 takeoff_trigger_dz;
AP_Float pilot_takeoff_alt;
AP_Int16 rtl_altitude;
AP_Int16 rtl_speed_cms;
AP_Float rtl_cone_slope;
AP_Float rangefinder_gain;
AP_Int8 failsafe_battery_enabled; // battery failsafe enabled
AP_Float fs_batt_voltage; // battery voltage below which failsafe will be triggered
AP_Float fs_batt_mah; // battery capacity (in mah) below which failsafe will be triggered
AP_Int8 failsafe_gcs; // ground station failsafe behavior
AP_Int16 gps_hdop_good; // GPS Hdop value at or below this value represent a good position
AP_Int8 compass_enabled;
AP_Int8 super_simple;
AP_Int16 rtl_alt_final;
AP_Int16 rtl_climb_min; // rtl minimum climb in cm
AP_Int8 wp_yaw_behavior; // controls how the autopilot controls yaw during missions
//AP_Int8 rc_feel_rp; // controls vehicle response to user input with 0 being extremely soft and 100 begin extremely crisp
AP_Int16 poshold_brake_rate; // PosHold flight mode's rotation rate during braking in deg/sec
AP_Int16 poshold_brake_angle_max; // PosHold flight mode's max lean angle during braking in centi-degrees
// Waypoints
//
AP_Int32 rtl_loiter_time;
AP_Int16 land_speed;
AP_Int16 land_speed_high;
AP_Int16 pilot_speed_up; // rename pilot_speed_up maximum vertical velocity the pilot may request
AP_Int16 pilot_accel_z; // vertical acceleration the pilot may request
// Throttle
//
AP_Int8 failsafe_throttle;
AP_Int16 failsafe_throttle_value;
AP_Int16 throttle_deadzone;
// Flight modes
//
AP_Int8 flight_mode1;
AP_Int8 flight_mode2;
AP_Int8 flight_mode3;
AP_Int8 flight_mode4;
AP_Int8 flight_mode5;
AP_Int8 flight_mode6;
AP_Int8 simple_modes;
// Misc
//
AP_Int32 log_bitmask;
AP_Int8 esc_calibrate;
AP_Int8 radio_tuning;
AP_Int16 radio_tuning_high;
AP_Int16 radio_tuning_low;
AP_Int8 frame_type;
AP_Int8 ch7_option;
AP_Int8 ch8_option;
AP_Int8 ch9_option;
AP_Int8 ch10_option;
AP_Int8 ch11_option;
AP_Int8 ch12_option;
AP_Int8 disarm_delay;
AP_Int8 land_repositioning;
AP_Int8 fs_ekf_action;
AP_Int8 fs_crash_check;
AP_Float fs_ekf_thresh;
AP_Int16 gcs_pid_mask;
AP_Int8 throw_motor_start;
AP_Int8 terrain_follow;
AP_Int16 rc_speed; // speed of fast RC Channels in Hz
// Acro parameters
AP_Float acro_rp_p;
AP_Float acro_yaw_p;
AP_Float acro_balance_roll;
AP_Float acro_balance_pitch;
AP_Int8 acro_trainer;
AP_Float acro_rp_expo;
// Autotune
AP_Int8 autotune_axis_bitmask;
AP_Float autotune_aggressiveness;
AP_Float autotune_min_d;
AP_Int32 Zigzag_time;
AP_Int8 Zigzag_width;
AP_Int8 radio_type;
//增加新的遥控器类型参数
AP_Int8 radio_mode ;
第3步:
将变量声明添加到Parameters.cpp的var_info表中
// @Param: MY_NEW_PARAMETER
// @DisplayName: My New Parameter
// @Description: A description of my new parameter goes here
// @Range: -32768 32767
// @User: Advanced
GSCALAR(my_new_parameter, "MY_NEW_PARAMETER", MY_NEW_PARAMETER_DEFAULT),
自己添加代码
// @Group:
// @Path: Parameters.cpp
GOBJECT(g2, "", ParametersG2),
//增加遥控器模式参数
GSCALAR(radio_mode, "radio_mode", RADIO_MODE),
AP_VAREND
地面站(如Mission Planner)中将使用@Param ~ @User的注释信息向使用者说明用户所设置的变量的范围等。
第4步:
在config.h中添加你的新参数。
#ifndef MY_NEW_PARAMETER_DEFAULT
# define MY_NEW_PARAMETER_DEFAULT 100 // default value for my new parameter
#endif
自己添加代码
#ifndef RADIO_MODE
# define RADIO_MODE 2
#endif
最后在地面站可以看到参数
向主执行代码添加参数的工作就完成了!添加到主代码中(并非库中)的参数就可以通过诸如g.my_new_parameter这样来使用。
2.增加一个参数到库
同样可以使用下列步骤向库中添加新的参数。以AP_Compass库为例:
第一步:
首先在库代码的.h((如Compass.h))头文件添加新的类变量。可使用的类型包括AP_Int8,AP_Int16,AP_Float,AP_Int32,AP_Vector3f。然后可以添加你想要的参数的默认值(我们将在Step #2中使用)。
#define MY_NEW_PARAM_DEFAULT 100
class Compass
{
public:
int16_t product_id; /// product id
int16_t mag_x; ///< magnetic field strength along the X axis
int16_t mag_y; ///< magnetic field strength along the Y axis
int16_t mag_z; ///< magnetic field strength along the Z axis
uint32_t last_update; ///< micros() time of last update
bool healthy; ///< true if last read OK
/// Constructor
///
Compass();
protected:
AP_Int8 _orientation;
AP_Vector3f _offset;
AP_Float _declination;
AP_Int8 _use_for_yaw; ///
AP_Int8 _auto_declination; ///
//这里是增加的变量
AP_Int16 _my_new_lib_parameter; /// description of my new parameter
};
自己添加代码
(第一步)
class AP_Proximity
{
public:
..............................
//增加参数
AP_Int8 MY_DATA;
..............................
private:
Proximity_State state[PROXIMITY_MAX_INSTANCES];
AP_Proximity_Backend *drivers[PROXIMITY_MAX_INSTANCES];
const RangeFinder *_rangefinder;
uint8_t primary_instance:3;
uint8_t num_instances:3;
AP_SerialManager &serial_manager;
// parameters for all instances
AP_Int8 _type[PROXIMITY_MAX_INSTANCES];
AP_Int8 _orientation[PROXIMITY_MAX_INSTANCES];
AP_Int16 _yaw_correction[PROXIMITY_MAX_INSTANCES];
AP_Int16 _ignore_angle_deg[PROXIMITY_MAX_IGNORE]; // angle (in degrees) of area that should be ignored by sensor (i.e. leg shows up)
AP_Int8 _ignore_width_deg[PROXIMITY_MAX_IGNORE]; // width of beam (in degrees) that should be ignored
void detect_instance(uint8_t instance);
void update_instance(uint8_t instance);
};
第二步:
然后在.cpp文件(如Compass.cpp)中添加变量包含有@Param ~ @Increment的var_info表信息,以便允许GCS向用户显示来自地面站的关于该参数值的范围设定。当添加新参数时应注意:
(1)自己添加的代码编号(下面的编号9)一定要比之前变量的大。
(2)参数的名称(如MY_NEW_P)包括对象自动添加的前缀要少于16个字符。比如罗盘对象的前缀为“COMPASS_”。//这里要注意,起的名字不能太长!!!
const AP_Param::GroupInfo Compass::var_info[] = {
// index 0 was used for the old orientation matrix
// @Param: OFS_X
// @DisplayName: Compass offsets on the X axis
// @Description: Offset to be added to the compass x-axis values to compensate for metal in the frame
// @Range: -400 400
// @Increment: 1
// @Param: ORIENT
// @DisplayName: Compass orientation
// @Description: The orientation of the compass relative to the autopilot board.
// @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180
AP_GROUPINFO("ORIENT", 8, Compass, _orientation, ROTATION_NONE),
// @Param: MY_NEW_P
// @DisplayName: My New Library Parameter
// @Description: The new library parameter description goes here
// @Range: -32768 32767
// @User: Advanced
//注意这里是增加的名字
AP_GROUPINFO("MY_NEW_P", 9, Compass, _my_new_lib_parameter, MY_NEW_PARAM_DEFAULT),
AP_GROUPEND
};
这样,新添加的参数将以_my_new_lib_parameter包含在库中。需要指明的是:protected保护类型的参数是不能够在类外被访问的。如果我们将其变为public类型,那么我们就可以在主代码中使用compass._my_new_lib_parameter参数了。
第三步:
除了compass.cpp文件中的定义之外,还将var_info的声明添加到新库类的compass.h文件的公共部分:
static const struct AP_Param::GroupInfo var_info[];
第四步:
前面提到的是在已经存在的类(比如AP_Compass)中定义一个新的变量。如果你重新定义了一个新类,在这个新类中添加参数。添加参数的方法如第二步。不过你还有一个工作要做,就是将这个新类,添加到Parameters.cpp文件的var_info 数组列表中去。下面加粗的红色罗盘类代码就是一个示例。
const AP_Param::Info var_info[] = {
// @Param: SYSID_SW_MREV
// @DisplayName: Eeprom format version number
// @Description: This value is incremented when changes are made to the eeprom format
// @User: Advanced
GSCALAR(format_version, "SYSID_SW_MREV", 0),
// @Group: COMPASS_
// @Path: ../libraries/AP_Compass/Compass.cpp
//注意这里
GOBJECT(compass, "COMPASS_", Compass),
// @Group: INS_
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
GOBJECT(ins, "INS_", AP_InertialSensor),
AP_VAREND
};
第五步:
如果所添加的类是一个完全新添加的代码,那么还要将k_param_my_new_lib添加到Parameters.h中的枚举中,其中my_new_lib是Parameters.cpp.中的GOBJECT声明的第一个参数。读取枚举上的注释,以了解在何处放置新的值,这是因为放置的顺序很重要,(只能使用不占用的枚举数据,一般放在相关的类后面,或者放在最后面。
到这里官网上的注释就结束了!!!
下面进行动手讲解怎么添加一个新参数到新建的库中,这里以adrc库实现为例;
(1)首先增加AC_ADRC库,包含(AC_ADRC.cpp和AC_ADRC.h)在AC_ADRC.h定义变量类*
#ifndef AC_ADRC_H_
#define AC_ADRC_H_
#include
#include
class AC_ADRC {
public:
...............此处省略..............
static const struct AP_Param::GroupInfo var_info[];
protected:
//中间省略
AP_Float _kp, _kd;
//中间省略
};
#endif
(2)首先增加数据表:var_info[]
const AP_Param::GroupInfo AC_ADRC::var_info[] =
{
// @Param: P
// @DisplayName: PID Proportional Gain
// @Description: P Gain which produces an output value that is proportional to the current error value
AP_GROUPINFO("P", 0, AC_ADRC, _kp, 0),
// @Param: D
// @DisplayName: PID Derivative Gain
// @Description: D Gain which produces an output that is proportional to the rate of change of the error
AP_GROUPINFO("D", 1, AC_ADRC, _kd, 0),
AP_GROUPEND
};
(3)在AC_ADRC.h中声明var_info[]
class AC_ADRC {
public:
...............此处省略..............
//注意是说的这个定义
static const struct AP_Param::GroupInfo var_info[];
//注意是说的这个定义
protected:
//中间省略
AP_Float _kp, _kd;
//中间省略
};
第四步:在Parameters.cpp中增加参数声明
const AP_Param::Info Copter::var_info[] = {
#if FRAME_CONFIG == HELI_FRAME
GOBJECTPTR(attitude_control, "ATC_", AC_AttitudeControl_Heli),
#else
GOBJECTPTR(attitude_control, "ATC_", AC_AttitudeControl_Multi),
#endif
};
//继续在AC_AttitudeControl_Multi.cpp和AC_AttitudeControl_Multi.h中安装添加
const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = {
AP_SUBGROUPINFO(_adrc_rate_roll, "ADRC_R_", 15, AC_AttitudeControl_Multi, AC_ADRC),
AP_SUBGROUPINFO(_adrc_rate_pitch, "ADRC_P_", 16, AC_AttitudeControl_Multi, AC_ADRC),
AP_SUBGROUPINFO(_adrc_rate_yaw, "ADRC_Y_", 17, AC_AttitudeControl_Multi, AC_ADRC),
}
到这基本完成,如果还不会,可以随便找一个库,自己抄袭一遍就知道怎么添加了。
1.为什么Parameters.h中的enum文件必须按照下面那样写?
enum {
// Layout version number, always key zero.
//
k_param_format_version = 0,
k_param_software_type,
k_param_ins_old, // *** Deprecated, remove with next eeprom number change
k_param_ins, // libraries/AP_InertialSensor variables
k_param_NavEKF2_old, // deprecated - remove
k_param_NavEKF2,
k_param_g2, // 2nd block of parameters
k_param_NavEKF3,
// simulation
k_param_sitl = 10,
// barometer object (needed for SITL)
k_param_barometer,
// scheduler object (for debugging)
k_param_scheduler,
// relay object
k_param_relay,
// (old) EPM object
k_param_epm_unused,
// BoardConfig object
k_param_BoardConfig,
/*****************后面省略****************/
}
重点在这:
#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} }
其实一个类中的enum变量名字可以任意定义,只要按照枚举顺序就可以,关键在于其他地方调用这个枚举变量,是其他地方对这个有要求,所以我们需要按照这种方式去定义。
(1)分析重要函数
#define GSCALAR(v, name, def) { copter.g.v.vtype, name, Parameters::k_param_ ## v, &copter.g.v, {def_value : def} }
v是变量类对象
name是名称,可以随便起,但是还是要靠谱点,方便识别
def是定义