convert libraries to new typesafe macros

This commit is contained in:
Andrew Tridgell 2012-02-12 18:23:19 +11:00
parent b6ee5ca982
commit dff75dba96
5 changed files with 22 additions and 26 deletions

View File

@ -2,10 +2,10 @@
#include "Compass.h" #include "Compass.h"
const AP_Param::GroupInfo Compass::var_info[] PROGMEM = { const AP_Param::GroupInfo Compass::var_info[] PROGMEM = {
{ AP_PARAM_MATRIX3F, "", VAROFFSET(Compass, _orientation_matrix) }, AP_GROUPINFO("ORIENT", Compass, _orientation_matrix),
{ AP_PARAM_VECTOR3F, "", VAROFFSET(Compass, _offset) }, AP_GROUPINFO("OFS", Compass, _offset),
{ AP_PARAM_VECTOR3F, "DEC", VAROFFSET(Compass, _declination) }, AP_GROUPINFO("DEC", Compass, _declination),
{ AP_PARAM_NONE, "" } AP_GROUPEND
}; };
// Default constructor. // Default constructor.

View File

@ -22,8 +22,8 @@
#include "AP_IMU_INS.h" #include "AP_IMU_INS.h"
const AP_Param::GroupInfo AP_IMU_INS::var_info[] PROGMEM = { const AP_Param::GroupInfo AP_IMU_INS::var_info[] PROGMEM = {
{ AP_PARAM_VECTOR3F, "", VAROFFSET(AP_IMU_INS, _sensor_cal) }, AP_GROUPINFO("CAL", AP_IMU_INS, _sensor_cal),
{ AP_PARAM_NONE, "" } AP_GROUPEND
}; };
void void

View File

@ -8,11 +8,11 @@
#include "PID.h" #include "PID.h"
const AP_Param::GroupInfo PID::var_info[] PROGMEM = { const AP_Param::GroupInfo PID::var_info[] PROGMEM = {
{ AP_PARAM_FLOAT, "P", VAROFFSET(PID, _kp) }, AP_GROUPINFO("P", PID, _kp),
{ AP_PARAM_FLOAT, "I", VAROFFSET(PID, _ki) }, AP_GROUPINFO("I", PID, _ki),
{ AP_PARAM_FLOAT, "D", VAROFFSET(PID, _kd) }, AP_GROUPINFO("D", PID, _kd),
{ AP_PARAM_INT16, "IMAX", VAROFFSET(PID, _imax) }, AP_GROUPINFO("IMAX", PID, _imax),
{ AP_PARAM_NONE, "" } AP_GROUPEND
}; };
long long

View File

@ -25,12 +25,12 @@
APM_RC_Class *RC_Channel::_apm_rc; APM_RC_Class *RC_Channel::_apm_rc;
const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = { const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = {
{ AP_PARAM_INT16, "MIN", VAROFFSET(RC_Channel, radio_min) }, AP_GROUPINFO("MIN", RC_Channel, radio_min),
{ AP_PARAM_INT16, "TRIM", VAROFFSET(RC_Channel, radio_trim) }, AP_GROUPINFO("TRIM", RC_Channel, radio_trim),
{ AP_PARAM_INT16, "MAX", VAROFFSET(RC_Channel, radio_max) }, AP_GROUPINFO("MAX", RC_Channel, radio_max),
{ AP_PARAM_INT8, "REV", VAROFFSET(RC_Channel, _reverse) }, AP_GROUPINFO("REV", RC_Channel, _reverse),
{ AP_PARAM_INT16, "DZ", VAROFFSET(RC_Channel, _dead_zone) }, AP_GROUPINFO("DZ", RC_Channel, _dead_zone),
{ AP_PARAM_NONE, "" } AP_GROUPEND
}; };
// setup the control preferences // setup the control preferences

View File

@ -4,15 +4,11 @@
#include "RC_Channel_aux.h" #include "RC_Channel_aux.h"
const AP_Param::GroupInfo RC_Channel_aux::var_info[] PROGMEM = { const AP_Param::GroupInfo RC_Channel_aux::var_info[] PROGMEM = {
{ AP_PARAM_INT16, "MIN", VAROFFSET(RC_Channel_aux, radio_min) }, AP_NESTEDGROUPINFO(RC_Channel),
{ AP_PARAM_INT16, "TRIM", VAROFFSET(RC_Channel_aux, radio_trim) }, AP_GROUPINFO("FUNCTION", RC_Channel_aux, function),
{ AP_PARAM_INT16, "MAX", VAROFFSET(RC_Channel_aux, radio_max) }, AP_GROUPINFO("ANGLE_MIN", RC_Channel_aux, angle_min),
{ AP_PARAM_INT8, "REV", VAROFFSET(RC_Channel_aux, _reverse) }, AP_GROUPINFO("ANGLE_MAX", RC_Channel_aux, angle_max),
{ AP_PARAM_INT16, "DZ", VAROFFSET(RC_Channel_aux, _dead_zone) }, AP_GROUPEND
{ AP_PARAM_INT8, "FUNCTION", VAROFFSET(RC_Channel_aux, function) },
{ AP_PARAM_INT8, "ANGLE_MIN", VAROFFSET(RC_Channel_aux, angle_min) },
{ AP_PARAM_INT8, "ANGLE_MAX", VAROFFSET(RC_Channel_aux, angle_max) },
{ AP_PARAM_NONE, "" }
}; };
RC_Channel_aux* g_rc_function[RC_Channel_aux::k_nr_aux_servo_functions]; // the aux. servo ch. assigned to each function RC_Channel_aux* g_rc_function[RC_Channel_aux::k_nr_aux_servo_functions]; // the aux. servo ch. assigned to each function