You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
302 lines
12 KiB
302 lines
12 KiB
11 years ago
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||
|
|
||
|
/*
|
||
|
* AntennaTracker parameter definitions
|
||
|
*
|
||
|
*/
|
||
|
|
||
|
#define GSCALAR(v, name, def) { g.v.vtype, name, Parameters::k_param_ ## v, &g.v, {def_value : def} }
|
||
|
#define ASCALAR(v, name, def) { aparm.v.vtype, name, Parameters::k_param_ ## v, &aparm.v, {def_value : def} }
|
||
|
#define GGROUP(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &g.v, {group_info : class::var_info} }
|
||
|
#define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &v, {group_info : class::var_info} }
|
||
11 years ago
|
#define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, &v, {group_info : class::var_info} }
|
||
11 years ago
|
|
||
|
const AP_Param::Info var_info[] PROGMEM = {
|
||
|
GSCALAR(format_version, "FORMAT_VERSION", 0),
|
||
|
GSCALAR(software_type, "SYSID_SW_TYPE", Parameters::k_software_type),
|
||
|
|
||
|
// @Param: SYSID_THISMAV
|
||
10 years ago
|
// @DisplayName: MAVLink system ID of this vehicle
|
||
|
// @Description: Allows setting an individual system id for this vehicle to distinguish it from others on the same network
|
||
11 years ago
|
// @Range: 1 255
|
||
|
// @User: Advanced
|
||
|
GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID),
|
||
|
|
||
|
// @Param: SYSID_MYGCS
|
||
|
// @DisplayName: Ground station MAVLink system ID
|
||
|
// @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match.
|
||
|
// @Range: 1 255
|
||
|
// @User: Advanced
|
||
|
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),
|
||
|
|
||
10 years ago
|
// @Param: SYSID_TARGET
|
||
|
// @DisplayName: Target vehicle's MAVLink system ID
|
||
|
// @Description: The identifier of the vehicle being tracked. This should be zero (to auto detect) or be the same as the SYSID_THISMAV parameter of the vehicle being tracked.
|
||
|
// @Range: 1 255
|
||
|
// @User: Advanced
|
||
|
GSCALAR(sysid_target, "SYSID_TARGET", 0),
|
||
|
|
||
11 years ago
|
// @Param: MAG_ENABLE
|
||
|
// @DisplayName: Enable Compass
|
||
|
// @Description: Setting this to Enabled(1) will enable the compass. Setting this to Disabled(0) will disable the compass. Note that this is separate from COMPASS_USE. This will enable the low level senor, and will enable logging of magnetometer data. To use the compass for navigation you must also set COMPASS_USE to 1.
|
||
|
// @Values: 0:Disabled,1:Enabled
|
||
|
// @User: Standard
|
||
|
GSCALAR(compass_enabled, "MAG_ENABLE", 1),
|
||
|
|
||
11 years ago
|
// @Param: YAW_SLEW_TIME
|
||
|
// @DisplayName: Time for yaw to slew through its full range
|
||
|
// @Description: This controls how rapidly the tracker will change the servo output for yaw. It is set as the number of seconds to do a full rotation. You can use this parameter to slow the trackers movements, which may help with some types of trackers. A value of zero will allow for unlimited servo movement per update.
|
||
|
// @Units: seconds
|
||
|
// @Increment: 0.1
|
||
|
// @Range: 0 20
|
||
11 years ago
|
// @User: Standard
|
||
11 years ago
|
GSCALAR(yaw_slew_time, "YAW_SLEW_TIME", 2),
|
||
|
|
||
|
// @Param: PITCH_SLEW_TIME
|
||
|
// @DisplayName: Time for pitch to slew through its full range
|
||
|
// @Description: This controls how rapidly the tracker will change the servo output for pitch. It is set as the number of seconds to do a full range of pitch movement. You can use this parameter to slow the trackers movements, which may help with some types of trackers. A value of zero will allow for unlimited servo movement per update.
|
||
|
// @Units: seconds
|
||
|
// @Increment: 0.1
|
||
|
// @Range: 0 20
|
||
11 years ago
|
// @User: Standard
|
||
11 years ago
|
GSCALAR(pitch_slew_time, "PITCH_SLEW_TIME", 2),
|
||
|
|
||
11 years ago
|
// @Param: SCAN_SPEED
|
||
|
// @DisplayName: Speed at which to rotate in scan mode
|
||
|
// @Description: This controls how rapidly the tracker will move the servos in SCAN mode
|
||
|
// @Units: degrees/second
|
||
|
// @Increment: 1
|
||
|
// @Range: 0 100
|
||
11 years ago
|
// @User: Standard
|
||
11 years ago
|
GSCALAR(scan_speed, "SCAN_SPEED", 5),
|
||
|
|
||
11 years ago
|
// @Param: MIN_REVERSE_TIME
|
||
|
// @DisplayName: Minimum time to apply a yaw reversal
|
||
|
// @Description: When the tracker detects it has reached the limit of servo movement in yaw it will reverse and try moving to the other extreme of yaw. This parameter controls the minimum time it should reverse for. It is used to cope with trackers that have a significant lag in movement to ensure they do move all the way around.
|
||
|
// @Units: seconds
|
||
|
// @Increment: 1
|
||
|
// @Range: 0 20
|
||
11 years ago
|
// @User: Standard
|
||
11 years ago
|
GSCALAR(min_reverse_time, "MIN_REVERSE_TIME", 1),
|
||
|
|
||
|
// @Param: START_LATITUDE
|
||
|
// @DisplayName: Initial Latitude before GPS lock
|
||
|
// @Description: Combined with START_LONGITUDE this parameter allows for an initial position of the tracker to be set. This position will be used until the GPS gets lock. It can also be used to run a stationary tracker with no GPS attached.
|
||
|
// @Units: degrees
|
||
|
// @Increment: 0.000001
|
||
|
// @Range: -90 90
|
||
11 years ago
|
// @User: Standard
|
||
11 years ago
|
GSCALAR(start_latitude, "START_LATITUDE", 0),
|
||
|
|
||
|
// @Param: START_LONGITUDE
|
||
|
// @DisplayName: Initial Longitude before GPS lock
|
||
|
// @Description: Combined with START_LATITUDE this parameter allows for an initial position of the tracker to be set. This position will be used until the GPS gets lock. It can also be used to run a stationary tracker with no GPS attached.
|
||
|
// @Units: degrees
|
||
|
// @Increment: 0.000001
|
||
|
// @Range: -180 180
|
||
11 years ago
|
// @User: Standard
|
||
11 years ago
|
GSCALAR(start_longitude, "START_LONGITUDE", 0),
|
||
|
|
||
|
// @Param: STARTUP_DELAY
|
||
|
// @DisplayName: Delay before first servo movement from trim
|
||
|
// @Description: This parameter can be used to force the servos to their trim value for a time on startup. This can help with some servo types
|
||
|
// @Units: seconds
|
||
|
// @Increment: 0.1
|
||
|
// @Range: 0 10
|
||
11 years ago
|
// @User: Standard
|
||
11 years ago
|
GSCALAR(startup_delay, "STARTUP_DELAY", 0),
|
||
|
|
||
11 years ago
|
// @Param: SERVO_TYPE
|
||
|
// @DisplayName: Type of servo system being used
|
||
|
// @Description: This allows selection of position servos or on/off servos
|
||
10 years ago
|
// @Values: 0:Position,1:OnOff
|
||
11 years ago
|
// @User: Standard
|
||
11 years ago
|
GSCALAR(servo_type, "SERVO_TYPE", SERVO_TYPE_POSITION),
|
||
|
|
||
|
// @Param: ONOFF_YAW_RATE
|
||
|
// @DisplayName: Yaw rate for on/off servos
|
||
|
// @Description: Rate of change of yaw in degrees/second for on/off servos
|
||
|
// @Units: degrees/second
|
||
|
// @Increment: 0.1
|
||
|
// @Range: 0 50
|
||
11 years ago
|
// @User: Standard
|
||
11 years ago
|
GSCALAR(onoff_yaw_rate, "ONOFF_YAW_RATE", 9.0f),
|
||
|
|
||
|
// @Param: ONOFF_PITCH_RATE
|
||
|
// @DisplayName: Pitch rate for on/off servos
|
||
|
// @Description: Rate of change of pitch in degrees/second for on/off servos
|
||
|
// @Units: degrees/second
|
||
|
// @Increment: 0.1
|
||
|
// @Range: 0 50
|
||
11 years ago
|
// @User: Standard
|
||
11 years ago
|
GSCALAR(onoff_pitch_rate, "ONOFF_PITCH_RATE", 1.0f),
|
||
|
|
||
|
// @Param: ONOFF_YAW_MINT
|
||
|
// @DisplayName: Yaw minimum movement time
|
||
|
// @Description: Minimum amount of time in seconds to move in yaw
|
||
|
// @Units: seconds
|
||
|
// @Increment: 0.01
|
||
|
// @Range: 0 2
|
||
11 years ago
|
// @User: Standard
|
||
11 years ago
|
GSCALAR(onoff_yaw_mintime, "ONOFF_YAW_MINT", 0.1f),
|
||
|
|
||
|
// @Param: ONOFF_PITCH_MINT
|
||
|
// @DisplayName: Pitch minimum movement time
|
||
|
// @Description: Minimim amount of time in seconds to move in pitch
|
||
|
// @Units: seconds
|
||
|
// @Increment: 0.01
|
||
|
// @Range: 0 2
|
||
11 years ago
|
// @User: Standard
|
||
11 years ago
|
GSCALAR(onoff_pitch_mintime, "ONOFF_PITCH_MINT", 0.1f),
|
||
|
|
||
11 years ago
|
// @Param: YAW_TRIM
|
||
|
// @DisplayName: Yaw trim
|
||
|
// @Description: Amount of extra yaw to add when tracking. This allows for small adjustments for an out of trim compass.
|
||
|
// @Units: degrees
|
||
|
// @Increment: 0.1
|
||
|
// @Range: -10 10
|
||
11 years ago
|
// @User: Standard
|
||
11 years ago
|
GSCALAR(yaw_trim, "YAW_TRIM", 0),
|
||
|
|
||
|
// @Param: PITCH_TRIM
|
||
|
// @DisplayName: Pitch trim
|
||
|
// @Description: Amount of extra pitch to add when tracking. This allows for small adjustments for a badly calibrated barometer.
|
||
|
// @Units: degrees
|
||
|
// @Increment: 0.1
|
||
|
// @Range: -10 10
|
||
11 years ago
|
// @User: Standard
|
||
11 years ago
|
GSCALAR(pitch_trim, "PITCH_TRIM", 0),
|
||
|
|
||
10 years ago
|
// @Param: YAW_RANGE
|
||
|
// @DisplayName: Yaw Angle Range
|
||
|
// @Description: Yaw axis total range of motion in degrees
|
||
|
// @Units: degrees
|
||
|
// @Increment: 0.1
|
||
|
// @Range: 0 360
|
||
|
// @User: Standard
|
||
|
GSCALAR(yaw_range, "YAW_RANGE", YAW_RANGE_DEFAULT),
|
||
|
|
||
|
// @Param: PITCH_RANGE
|
||
|
// @DisplayName: Pitch Range
|
||
|
// @Description: Pitch axis total range of motion in degrees
|
||
|
// @Units: degrees
|
||
|
// @Increment: 0.1
|
||
|
// @Range: 0 180
|
||
|
// @User: Standard
|
||
|
GSCALAR(pitch_range, "PITCH_RANGE", PITCH_RANGE_DEFAULT),
|
||
|
|
||
10 years ago
|
// @Param: DISTANCE_MIN
|
||
|
// @DisplayName: Distance minimum to target
|
||
|
// @Description: Tracker will track targets at least this distance away
|
||
|
// @Units: meters
|
||
|
// @Increment: 1
|
||
|
// @Range: 0 100
|
||
|
// @User: Standard
|
||
|
GSCALAR(distance_min, "DISTANCE_MIN", DISTANCE_MIN_DEFAULT),
|
||
|
|
||
11 years ago
|
// barometer ground calibration. The GND_ prefix is chosen for
|
||
|
// compatibility with previous releases of ArduPlane
|
||
|
// @Group: GND_
|
||
|
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
|
||
|
GOBJECT(barometer, "GND_", AP_Baro),
|
||
|
|
||
|
// @Group: COMPASS_
|
||
|
// @Path: ../libraries/AP_Compass/Compass.cpp
|
||
|
GOBJECT(compass, "COMPASS_", Compass),
|
||
|
|
||
|
// @Group: SCHED_
|
||
|
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
|
||
|
GOBJECT(scheduler, "SCHED_", AP_Scheduler),
|
||
|
|
||
|
// @Group: SR0_
|
||
|
// @Path: GCS_Mavlink.pde
|
||
11 years ago
|
GOBJECTN(gcs[0], gcs0, "SR0_", GCS_MAVLINK),
|
||
|
|
||
|
// @Group: SR1_
|
||
|
// @Path: GCS_Mavlink.pde
|
||
|
GOBJECTN(gcs[1], gcs1, "SR1_", GCS_MAVLINK),
|
||
11 years ago
|
|
||
11 years ago
|
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
||
|
// @Group: SR2_
|
||
11 years ago
|
// @Path: GCS_Mavlink.pde
|
||
11 years ago
|
GOBJECTN(gcs[2], gcs2, "SR2_", GCS_MAVLINK),
|
||
|
#endif
|
||
11 years ago
|
|
||
10 years ago
|
#if MAVLINK_COMM_NUM_BUFFERS > 3
|
||
|
// @Group: SR3_
|
||
|
// @Path: GCS_Mavlink.pde
|
||
|
GOBJECTN(gcs[3], gcs3, "SR3_", GCS_MAVLINK),
|
||
|
#endif
|
||
|
|
||
11 years ago
|
// @Group: INS_
|
||
|
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
|
||
|
GOBJECT(ins, "INS_", AP_InertialSensor),
|
||
|
|
||
|
// @Group: AHRS_
|
||
|
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
|
||
|
GOBJECT(ahrs, "AHRS_", AP_AHRS),
|
||
|
|
||
10 years ago
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||
11 years ago
|
// @Group: SIM_
|
||
|
// @Path: ../libraries/SITL/SITL.cpp
|
||
|
GOBJECT(sitl, "SIM_", SITL),
|
||
|
#endif
|
||
|
|
||
11 years ago
|
// @Group: BRD_
|
||
|
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
|
||
|
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
|
||
|
|
||
11 years ago
|
// GPS driver
|
||
|
// @Group: GPS_
|
||
|
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
|
||
|
GOBJECT(gps, "GPS_", AP_GPS),
|
||
|
|
||
11 years ago
|
// RC channel
|
||
|
//-----------
|
||
|
// @Group: RC1_
|
||
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
||
|
GOBJECT(channel_yaw, "RC1_", RC_Channel),
|
||
|
|
||
|
// @Group: RC2_
|
||
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
||
|
GOBJECT(channel_pitch, "RC2_", RC_Channel),
|
||
|
|
||
10 years ago
|
// @Group: SERIAL
|
||
|
// @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp
|
||
|
GOBJECT(serial_manager, "SERIAL", AP_SerialManager),
|
||
|
|
||
11 years ago
|
GGROUP(pidPitch2Srv, "PITCH2SRV_", PID),
|
||
|
GGROUP(pidYaw2Srv, "YAW2SRV_", PID),
|
||
|
|
||
11 years ago
|
// @Param: CMD_TOTAL
|
||
|
// @DisplayName: Number of loaded mission items
|
||
|
// @Description: Set to 1 if HOME location has been loaded by the ground station. Do not change this manually.
|
||
|
// @Range: 1 255
|
||
|
// @User: Advanced
|
||
|
GSCALAR(command_total, "CMD_TOTAL", 0),
|
||
|
|
||
|
|
||
11 years ago
|
AP_VAREND
|
||
|
};
|
||
|
|
||
|
|
||
|
static void load_parameters(void)
|
||
|
{
|
||
|
if (!g.format_version.load() ||
|
||
|
g.format_version != Parameters::k_format_version) {
|
||
|
|
||
|
// erase all parameters
|
||
|
cliSerial->printf_P(PSTR("Firmware change: erasing EEPROM...\n"));
|
||
|
AP_Param::erase_all();
|
||
|
|
||
|
// save the current format version
|
||
|
g.format_version.set_and_save(Parameters::k_format_version);
|
||
|
cliSerial->println_P(PSTR("done."));
|
||
|
} else {
|
||
|
uint32_t before = hal.scheduler->micros();
|
||
|
// Load all auto-loaded EEPROM variables
|
||
|
AP_Param::load_all();
|
||
|
cliSerial->printf_P(PSTR("load_all took %luus\n"), hal.scheduler->micros() - before);
|
||
|
}
|
||
|
}
|