mirror of https://github.com/ArduPilot/ardupilot
demo of AP_Param with ArduPlane parameters
This commit is contained in:
parent
12dac42174
commit
2792abfce2
|
@ -0,0 +1,41 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
// This file is just a placeholder for your configuration file. If you wish to change any of the setup parameters from
|
||||
// their default values, place the appropriate #define statements here.
|
||||
|
||||
// For example if you wanted the Port 3 baud rate to be 38400 you would add a statement like the one below (uncommented)
|
||||
//#define SERIAL3_BAUD 38400
|
||||
|
||||
// # define CONFIG_APM_HARDWARE APM_HARDWARE_APM2
|
||||
// # define APM2_BETA_HARDWARE
|
||||
|
||||
|
||||
// You may also put an include statement here to point at another configuration file. This is convenient if you maintain
|
||||
// different configuration files for different aircraft or HIL simulation. See the examples below
|
||||
//#include "APM_Config_mavlink_hil.h"
|
||||
//#include "Skywalker.h"
|
||||
|
||||
// The following are the recommended settings for Xplane simulation. Remove the leading "/* and trailing "*/" to enable:
|
||||
|
||||
/*
|
||||
#define HIL_MODE HIL_MODE_ATTITUDE
|
||||
*/
|
||||
|
||||
/*
|
||||
// HIL_MODE SELECTION
|
||||
//
|
||||
// Mavlink supports
|
||||
// 1. HIL_MODE_ATTITUDE : simulated position, airspeed, and attitude
|
||||
// 2. HIL_MODE_SENSORS: full sensor simulation
|
||||
#define HIL_MODE HIL_MODE_ATTITUDE
|
||||
|
||||
// Sensors
|
||||
// All sensors are supported in all modes.
|
||||
// The magnetometer is not used in
|
||||
// HIL_MODE_ATTITUDE but you may leave it
|
||||
// enabled if you wish.
|
||||
#define AIRSPEED_SENSOR ENABLED
|
||||
#define MAGNETOMETER ENABLED
|
||||
#define AIRSPEED_CRUISE 25
|
||||
#define THROTTLE_FAILSAFE ENABLED
|
||||
*/
|
|
@ -0,0 +1,4 @@
|
|||
#
|
||||
# Trivial makefile for building APM
|
||||
#
|
||||
include ../../libraries/AP_Common/Arduino.mk
|
|
@ -0,0 +1,449 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#ifndef PARAMETERS_H
|
||||
#define PARAMETERS_H
|
||||
|
||||
#include <AP_Common.h>
|
||||
|
||||
// Global parameter class.
|
||||
//
|
||||
class Parameters {
|
||||
public:
|
||||
// The version of the layout as described by the parameter enum.
|
||||
//
|
||||
// When changing the parameter enum in an incompatible fashion, this
|
||||
// value should be incremented by one.
|
||||
//
|
||||
// The increment will prevent old parameters from being used incorrectly
|
||||
// by newer code.
|
||||
//
|
||||
static const uint16_t k_format_version = 12;
|
||||
|
||||
// The parameter software_type is set up solely for ground station use
|
||||
// and identifies the software type (eg ArduPilotMega versus ArduCopterMega)
|
||||
// GCS will interpret values 0-9 as ArduPilotMega. Developers may use
|
||||
// values within that range to identify different branches.
|
||||
//
|
||||
static const uint16_t k_software_type = 0; // 0 for APM trunk
|
||||
|
||||
enum {
|
||||
// Layout version number, always key zero.
|
||||
//
|
||||
k_param_format_version = 0,
|
||||
k_param_software_type,
|
||||
|
||||
// Misc
|
||||
//
|
||||
k_param_auto_trim,
|
||||
k_param_switch_enable,
|
||||
k_param_log_bitmask,
|
||||
k_param_pitch_trim,
|
||||
k_param_mix_mode,
|
||||
k_param_reverse_elevons,
|
||||
k_param_reverse_ch1_elevon,
|
||||
k_param_reverse_ch2_elevon,
|
||||
k_param_flap_1_percent,
|
||||
k_param_flap_1_speed,
|
||||
k_param_flap_2_percent,
|
||||
k_param_flap_2_speed,
|
||||
k_param_num_resets,
|
||||
k_param_log_last_filenumber, // *** Deprecated - remove with next eeprom number change
|
||||
k_param_reset_switch_chan,
|
||||
|
||||
|
||||
// 110: Telemetry control
|
||||
//
|
||||
k_param_streamrates_port0 = 110,
|
||||
k_param_streamrates_port3,
|
||||
k_param_sysid_this_mav,
|
||||
k_param_sysid_my_gcs,
|
||||
k_param_serial3_baud,
|
||||
|
||||
// 120: Fly-by-wire control
|
||||
//
|
||||
k_param_flybywire_airspeed_min = 120,
|
||||
k_param_flybywire_airspeed_max,
|
||||
k_param_FBWB_min_altitude, // 0=disabled, minimum value for altitude in cm (for first time try 30 meters = 3000 cm)
|
||||
|
||||
//
|
||||
// 130: Sensor parameters
|
||||
//
|
||||
k_param_IMU_calibration = 130,
|
||||
k_param_altitude_mix,
|
||||
k_param_airspeed_ratio,
|
||||
k_param_ground_temperature,
|
||||
k_param_ground_pressure,
|
||||
k_param_compass_enabled,
|
||||
k_param_compass,
|
||||
k_param_battery_monitoring,
|
||||
k_param_volt_div_ratio,
|
||||
k_param_curr_amp_per_volt,
|
||||
k_param_input_voltage,
|
||||
k_param_pack_capacity,
|
||||
k_param_airspeed_offset,
|
||||
k_param_sonar_enabled,
|
||||
k_param_airspeed_enabled,
|
||||
|
||||
//
|
||||
// 150: Navigation parameters
|
||||
//
|
||||
k_param_crosstrack_gain = 150,
|
||||
k_param_crosstrack_entry_angle,
|
||||
k_param_roll_limit,
|
||||
k_param_pitch_limit_max,
|
||||
k_param_pitch_limit_min,
|
||||
k_param_airspeed_cruise,
|
||||
k_param_RTL_altitude,
|
||||
k_param_inverted_flight_ch,
|
||||
k_param_min_gndspeed,
|
||||
|
||||
//
|
||||
// 170: Radio settings
|
||||
//
|
||||
k_param_channel_roll = 170,
|
||||
k_param_channel_pitch,
|
||||
k_param_channel_throttle,
|
||||
k_param_channel_rudder,
|
||||
k_param_rc_5,
|
||||
k_param_rc_6,
|
||||
k_param_rc_7,
|
||||
k_param_rc_8,
|
||||
|
||||
k_param_throttle_min,
|
||||
k_param_throttle_max,
|
||||
k_param_throttle_fs_enabled,
|
||||
k_param_throttle_fs_value,
|
||||
k_param_throttle_cruise,
|
||||
|
||||
k_param_short_fs_action,
|
||||
k_param_long_fs_action,
|
||||
k_param_gcs_heartbeat_fs_enabled,
|
||||
k_param_throttle_slewrate,
|
||||
|
||||
//
|
||||
// 200: Feed-forward gains
|
||||
//
|
||||
k_param_kff_pitch_compensation = 200,
|
||||
k_param_kff_rudder_mix,
|
||||
k_param_kff_pitch_to_throttle,
|
||||
k_param_kff_throttle_to_pitch,
|
||||
|
||||
//
|
||||
// 210: flight modes
|
||||
//
|
||||
k_param_flight_mode_channel = 210,
|
||||
k_param_flight_mode1,
|
||||
k_param_flight_mode2,
|
||||
k_param_flight_mode3,
|
||||
k_param_flight_mode4,
|
||||
k_param_flight_mode5,
|
||||
k_param_flight_mode6,
|
||||
|
||||
//
|
||||
// 220: Waypoint data
|
||||
//
|
||||
k_param_waypoint_mode = 220,
|
||||
k_param_command_total,
|
||||
k_param_command_index,
|
||||
k_param_waypoint_radius,
|
||||
k_param_loiter_radius,
|
||||
k_param_fence_action,
|
||||
k_param_fence_total,
|
||||
k_param_fence_channel,
|
||||
k_param_fence_minalt,
|
||||
k_param_fence_maxalt,
|
||||
|
||||
//
|
||||
// 240: PID Controllers
|
||||
//
|
||||
// Heading-to-roll PID:
|
||||
// heading error from command to roll command deviation from trim
|
||||
// (bank to turn strategy)
|
||||
//
|
||||
k_param_pidNavRoll = 240,
|
||||
|
||||
// Roll-to-servo PID:
|
||||
// roll error from command to roll servo deviation from trim
|
||||
// (tracks commanded bank angle)
|
||||
//
|
||||
k_param_pidServoRoll,
|
||||
|
||||
//
|
||||
// Pitch control
|
||||
//
|
||||
// Pitch-to-servo PID:
|
||||
// pitch error from command to pitch servo deviation from trim
|
||||
// (front-side strategy)
|
||||
//
|
||||
k_param_pidServoPitch,
|
||||
|
||||
// Airspeed-to-pitch PID:
|
||||
// airspeed error from command to pitch servo deviation from trim
|
||||
// (back-side strategy)
|
||||
//
|
||||
k_param_pidNavPitchAirspeed,
|
||||
|
||||
//
|
||||
// Yaw control
|
||||
//
|
||||
// Yaw-to-servo PID:
|
||||
// yaw rate error from command to yaw servo deviation from trim
|
||||
// (stabilizes dutch roll)
|
||||
//
|
||||
k_param_pidServoRudder,
|
||||
|
||||
//
|
||||
// Throttle control
|
||||
//
|
||||
// Energy-to-throttle PID:
|
||||
// total energy error from command to throttle servo deviation from trim
|
||||
// (throttle back-side strategy alternative)
|
||||
//
|
||||
k_param_pidTeThrottle,
|
||||
|
||||
// Altitude-to-pitch PID:
|
||||
// altitude error from command to pitch servo deviation from trim
|
||||
// (throttle front-side strategy alternative)
|
||||
//
|
||||
k_param_pidNavPitchAltitude,
|
||||
|
||||
// 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;
|
||||
|
||||
// Feed-forward gains
|
||||
//
|
||||
AP_Float kff_pitch_compensation;
|
||||
AP_Float kff_rudder_mix;
|
||||
AP_Float kff_pitch_to_throttle;
|
||||
AP_Float kff_throttle_to_pitch;
|
||||
|
||||
// Crosstrack navigation
|
||||
//
|
||||
AP_Float crosstrack_gain;
|
||||
AP_Int16 crosstrack_entry_angle;
|
||||
|
||||
// Estimation
|
||||
//
|
||||
AP_Float altitude_mix;
|
||||
AP_Float airspeed_ratio;
|
||||
AP_Int16 airspeed_offset;
|
||||
|
||||
// Waypoints
|
||||
//
|
||||
AP_Int8 waypoint_mode;
|
||||
AP_Int8 command_total;
|
||||
AP_Int8 command_index;
|
||||
AP_Int8 waypoint_radius;
|
||||
AP_Int8 loiter_radius;
|
||||
#if GEOFENCE_ENABLED == ENABLED
|
||||
AP_Int8 fence_action;
|
||||
AP_Int8 fence_total;
|
||||
AP_Int8 fence_channel;
|
||||
AP_Int16 fence_minalt; // meters
|
||||
AP_Int16 fence_maxalt; // meters
|
||||
#endif
|
||||
|
||||
// Fly-by-wire
|
||||
//
|
||||
AP_Int8 flybywire_airspeed_min;
|
||||
AP_Int8 flybywire_airspeed_max;
|
||||
AP_Int16 FBWB_min_altitude;
|
||||
|
||||
// Throttle
|
||||
//
|
||||
AP_Int8 throttle_min;
|
||||
AP_Int8 throttle_max;
|
||||
AP_Int8 throttle_slewrate;
|
||||
AP_Int8 throttle_fs_enabled;
|
||||
AP_Int16 throttle_fs_value;
|
||||
AP_Int8 throttle_cruise;
|
||||
|
||||
// Failsafe
|
||||
AP_Int8 short_fs_action;
|
||||
AP_Int8 long_fs_action;
|
||||
AP_Int8 gcs_heartbeat_fs_enabled;
|
||||
|
||||
// Flight modes
|
||||
//
|
||||
AP_Int8 flight_mode_channel;
|
||||
AP_Int8 flight_mode1;
|
||||
AP_Int8 flight_mode2;
|
||||
AP_Int8 flight_mode3;
|
||||
AP_Int8 flight_mode4;
|
||||
AP_Int8 flight_mode5;
|
||||
AP_Int8 flight_mode6;
|
||||
|
||||
// Navigational maneuvering limits
|
||||
//
|
||||
AP_Int16 roll_limit;
|
||||
AP_Int16 pitch_limit_max;
|
||||
AP_Int16 pitch_limit_min;
|
||||
|
||||
// Misc
|
||||
//
|
||||
AP_Int8 auto_trim;
|
||||
AP_Int8 switch_enable;
|
||||
AP_Int8 mix_mode;
|
||||
AP_Int8 reverse_elevons;
|
||||
AP_Int8 reverse_ch1_elevon;
|
||||
AP_Int8 reverse_ch2_elevon;
|
||||
AP_Int16 num_resets;
|
||||
AP_Int16 log_bitmask;
|
||||
AP_Int16 log_last_filenumber; // *** Deprecated - remove with next eeprom number change
|
||||
AP_Int8 reset_switch_chan;
|
||||
AP_Int16 airspeed_cruise;
|
||||
AP_Int16 min_gndspeed;
|
||||
AP_Int16 pitch_trim;
|
||||
AP_Int16 RTL_altitude;
|
||||
AP_Int16 ground_temperature;
|
||||
AP_Int32 ground_pressure;
|
||||
AP_Int8 compass_enabled;
|
||||
AP_Int16 angle_of_attack;
|
||||
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_Float input_voltage;
|
||||
AP_Int16 pack_capacity; // Battery pack capacity less reserve
|
||||
AP_Int8 inverted_flight_ch; // 0=disabled, 1-8 is channel for inverted flight trigger
|
||||
AP_Int8 sonar_enabled;
|
||||
AP_Int8 airspeed_enabled;
|
||||
AP_Int8 flap_1_percent;
|
||||
AP_Int8 flap_1_speed;
|
||||
AP_Int8 flap_2_percent;
|
||||
AP_Int8 flap_2_speed;
|
||||
|
||||
// RC channels
|
||||
RC_Channel channel_roll;
|
||||
RC_Channel channel_pitch;
|
||||
RC_Channel channel_throttle;
|
||||
RC_Channel channel_rudder;
|
||||
RC_Channel_aux rc_5;
|
||||
RC_Channel_aux rc_6;
|
||||
RC_Channel_aux rc_7;
|
||||
RC_Channel_aux rc_8;
|
||||
|
||||
// PID controllers
|
||||
//
|
||||
PID pidNavRoll;
|
||||
PID pidServoRoll;
|
||||
PID pidServoPitch;
|
||||
PID pidNavPitchAirspeed;
|
||||
PID pidServoRudder;
|
||||
PID pidTeThrottle;
|
||||
PID pidNavPitchAltitude;
|
||||
|
||||
Parameters() :
|
||||
format_version (k_format_version),
|
||||
software_type (k_software_type),
|
||||
|
||||
sysid_this_mav (MAV_SYSTEM_ID),
|
||||
sysid_my_gcs (255),
|
||||
serial3_baud (SERIAL3_BAUD/1000),
|
||||
|
||||
kff_pitch_compensation (PITCH_COMP),
|
||||
kff_rudder_mix (RUDDER_MIX),
|
||||
kff_pitch_to_throttle (P_TO_T),
|
||||
kff_throttle_to_pitch (T_TO_P),
|
||||
|
||||
crosstrack_gain (XTRACK_GAIN_SCALED),
|
||||
crosstrack_entry_angle (XTRACK_ENTRY_ANGLE_CENTIDEGREE),
|
||||
|
||||
altitude_mix (ALTITUDE_MIX),
|
||||
airspeed_ratio (AIRSPEED_RATIO),
|
||||
airspeed_offset (0),
|
||||
|
||||
/* XXX waypoint_mode missing here */
|
||||
command_total (0),
|
||||
command_index (0),
|
||||
waypoint_radius (WP_RADIUS_DEFAULT),
|
||||
loiter_radius (LOITER_RADIUS_DEFAULT),
|
||||
|
||||
#if GEOFENCE_ENABLED == ENABLED
|
||||
fence_action (0),
|
||||
fence_total (0),
|
||||
fence_channel (0),
|
||||
fence_minalt (0),
|
||||
fence_maxalt (0),
|
||||
#endif
|
||||
|
||||
flybywire_airspeed_min (AIRSPEED_FBW_MIN),
|
||||
flybywire_airspeed_max (AIRSPEED_FBW_MAX),
|
||||
|
||||
throttle_min (THROTTLE_MIN),
|
||||
throttle_max (THROTTLE_MAX),
|
||||
throttle_slewrate (THROTTLE_SLEW_LIMIT),
|
||||
throttle_fs_enabled (THROTTLE_FAILSAFE),
|
||||
throttle_fs_value (THROTTLE_FS_VALUE),
|
||||
throttle_cruise (THROTTLE_CRUISE),
|
||||
|
||||
short_fs_action (SHORT_FAILSAFE_ACTION),
|
||||
long_fs_action (LONG_FAILSAFE_ACTION),
|
||||
gcs_heartbeat_fs_enabled(GCS_HEARTBEAT_FAILSAFE),
|
||||
|
||||
flight_mode_channel (FLIGHT_MODE_CHANNEL),
|
||||
flight_mode1 (FLIGHT_MODE_1),
|
||||
flight_mode2 (FLIGHT_MODE_2),
|
||||
flight_mode3 (FLIGHT_MODE_3),
|
||||
flight_mode4 (FLIGHT_MODE_4),
|
||||
flight_mode5 (FLIGHT_MODE_5),
|
||||
flight_mode6 (FLIGHT_MODE_6),
|
||||
|
||||
roll_limit (HEAD_MAX_CENTIDEGREE),
|
||||
pitch_limit_max (PITCH_MAX_CENTIDEGREE),
|
||||
pitch_limit_min (PITCH_MIN_CENTIDEGREE),
|
||||
|
||||
auto_trim (AUTO_TRIM),
|
||||
switch_enable (REVERSE_SWITCH),
|
||||
mix_mode (ELEVON_MIXING),
|
||||
reverse_elevons (ELEVON_REVERSE),
|
||||
reverse_ch1_elevon (ELEVON_CH1_REVERSE),
|
||||
reverse_ch2_elevon (ELEVON_CH2_REVERSE),
|
||||
num_resets (0),
|
||||
log_bitmask (DEFAULT_LOG_BITMASK),
|
||||
log_last_filenumber (0),
|
||||
reset_switch_chan (0),
|
||||
airspeed_cruise (AIRSPEED_CRUISE_CM),
|
||||
min_gndspeed (MIN_GNDSPEED_CM),
|
||||
pitch_trim (0),
|
||||
RTL_altitude (ALT_HOLD_HOME_CM),
|
||||
FBWB_min_altitude (ALT_HOLD_FBW_CM),
|
||||
ground_temperature (0),
|
||||
ground_pressure (0),
|
||||
compass_enabled (MAGNETOMETER),
|
||||
flap_1_percent (FLAP_1_PERCENT),
|
||||
flap_1_speed (FLAP_1_SPEED),
|
||||
flap_2_percent (FLAP_2_PERCENT),
|
||||
flap_2_speed (FLAP_2_SPEED),
|
||||
|
||||
|
||||
battery_monitoring (DISABLED),
|
||||
volt_div_ratio (VOLT_DIV_RATIO),
|
||||
curr_amp_per_volt (CURR_AMP_PER_VOLT),
|
||||
input_voltage (INPUT_VOLTAGE),
|
||||
pack_capacity (HIGH_DISCHARGE),
|
||||
inverted_flight_ch (0),
|
||||
sonar_enabled (SONAR_ENABLED),
|
||||
airspeed_enabled (AIRSPEED_SENSOR),
|
||||
|
||||
// PID controller initial P initial I initial D initial imax
|
||||
//---------------------------------------------------------------------------------------------------------------------------------------
|
||||
pidNavRoll (NAV_ROLL_P, NAV_ROLL_I, NAV_ROLL_D, NAV_ROLL_INT_MAX_CENTIDEGREE),
|
||||
pidServoRoll (SERVO_ROLL_P, SERVO_ROLL_I, SERVO_ROLL_D, SERVO_ROLL_INT_MAX_CENTIDEGREE),
|
||||
pidServoPitch (SERVO_PITCH_P, SERVO_PITCH_I, SERVO_PITCH_D, SERVO_PITCH_INT_MAX_CENTIDEGREE),
|
||||
pidNavPitchAirspeed (NAV_PITCH_ASP_P, NAV_PITCH_ASP_I, NAV_PITCH_ASP_D, NAV_PITCH_ASP_INT_MAX_CMSEC),
|
||||
pidServoRudder (SERVO_YAW_P, SERVO_YAW_I, SERVO_YAW_D, SERVO_YAW_INT_MAX),
|
||||
pidTeThrottle (THROTTLE_TE_P, THROTTLE_TE_I, THROTTLE_TE_D, THROTTLE_TE_INT_MAX),
|
||||
pidNavPitchAltitude (NAV_PITCH_ALT_P, NAV_PITCH_ALT_I, NAV_PITCH_ALT_D, NAV_PITCH_ALT_INT_MAX_CM)
|
||||
{}
|
||||
};
|
||||
|
||||
#endif // PARAMETERS_H
|
|
@ -0,0 +1,147 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
/*
|
||||
Parameters.pde example for new variable scheme
|
||||
Andrew Tridgell February 2012
|
||||
*/
|
||||
|
||||
#define GSCALAR(v, name) { g.v.vtype, name, Parameters::k_param_ ## v, &g.v }
|
||||
#define GGROUP(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &g.v, class::var_info }
|
||||
#define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &v, class::var_info }
|
||||
|
||||
static const AP_Param::Info var_info[] PROGMEM = {
|
||||
GSCALAR(format_version, "FORMAT_VERSION"),
|
||||
GSCALAR(software_type, "SOFTWARE_TYPE"),
|
||||
GSCALAR(sysid_this_mav, "SYSID_THIS_MAV"),
|
||||
GSCALAR(sysid_my_gcs, "SYSID_MYGCS"),
|
||||
GSCALAR(serial3_baud, "SERIAL3_BAUD"),
|
||||
GSCALAR(kff_pitch_compensation, "KFF_PTCHCOMP"),
|
||||
GSCALAR(kff_rudder_mix, "KFF_RDDRMIX"),
|
||||
GSCALAR(kff_pitch_to_throttle, "KFF_PTCH2THR"),
|
||||
GSCALAR(kff_throttle_to_pitch, "KFF_THR2PTCH"),
|
||||
|
||||
GSCALAR(crosstrack_gain, "XTRK_GAIN_SC"),
|
||||
GSCALAR(crosstrack_entry_angle, "XTRK_ANGLE_CD"),
|
||||
|
||||
GSCALAR(altitude_mix, "ALT_MIX"),
|
||||
GSCALAR(airspeed_ratio, "ARSPD_RATIO"),
|
||||
GSCALAR(airspeed_offset, "ARSPD_OFFSET"),
|
||||
|
||||
GSCALAR(command_total, "CMD_TOTAL"),
|
||||
GSCALAR(command_index, "CMD_INDEX"),
|
||||
GSCALAR(waypoint_radius, "WP_RADIUS"),
|
||||
GSCALAR(loiter_radius, "WP_LOITER_RAD"),
|
||||
|
||||
#if GEOFENCE_ENABLED == ENABLED
|
||||
GSCALAR(fence_action, "FENCE_ACTION"),
|
||||
GSCALAR(fence_total, "FENCE_TOTAL"),
|
||||
GSCALAR(fence_channel, "FENCE_CHANNEL"),
|
||||
GSCALAR(fence_minalt, "FENCE_MINALT"),
|
||||
GSCALAR(fence_maxalt, "FENCE_MAXALT"),
|
||||
#endif
|
||||
|
||||
GSCALAR(flybywire_airspeed_min, "ARSPD_FBW_MIN"),
|
||||
GSCALAR(flybywire_airspeed_max, "ARSPD_FBW_MAX"),
|
||||
|
||||
GSCALAR(throttle_min, "THR_MIN"),
|
||||
GSCALAR(throttle_max, "THR_MAX"),
|
||||
GSCALAR(throttle_slewrate, "THR_SLEWRATE"),
|
||||
GSCALAR(throttle_fs_enabled, "THR_FAILSAFE"),
|
||||
GSCALAR(throttle_fs_value, "THR_FS_VALUE"),
|
||||
GSCALAR(throttle_cruise, "TRIM_THROTTLE"),
|
||||
|
||||
GSCALAR(short_fs_action, "FS_SHORT_ACTN"),
|
||||
GSCALAR(long_fs_action, "FS_LONG_ACTN"),
|
||||
GSCALAR(gcs_heartbeat_fs_enabled, "FS_GCS_ENABL"),
|
||||
|
||||
GSCALAR(flight_mode_channel, "FLTMODE_CH"),
|
||||
GSCALAR(flight_mode1, "FLTMODE1"),
|
||||
GSCALAR(flight_mode2, "FLTMODE2"),
|
||||
GSCALAR(flight_mode3, "FLTMODE3"),
|
||||
GSCALAR(flight_mode4, "FLTMODE4"),
|
||||
GSCALAR(flight_mode5, "FLTMODE5"),
|
||||
GSCALAR(flight_mode6, "FLTMODE6"),
|
||||
|
||||
GSCALAR(roll_limit, "LIM_ROLL_CD"),
|
||||
GSCALAR(pitch_limit_max, "LIM_PITCH_MAX"),
|
||||
GSCALAR(pitch_limit_min, "LIM_PITCH_MIN"),
|
||||
|
||||
GSCALAR(auto_trim, "TRIM_AUTO"),
|
||||
GSCALAR(switch_enable, "SWITCH_ENABLE"),
|
||||
GSCALAR(mix_mode, "ELEVON_MIXING"),
|
||||
GSCALAR(reverse_elevons, "ELEVON_REVERSE"),
|
||||
GSCALAR(reverse_ch1_elevon, "ELEVON_CH1_REV"),
|
||||
GSCALAR(reverse_ch2_elevon, "ELEVON_CH2_REV"),
|
||||
GSCALAR(num_resets, "SYS_NUM_RESETS"),
|
||||
GSCALAR(log_bitmask, "LOG_BITMASK"),
|
||||
GSCALAR(log_last_filenumber, "LOG_LASTFILE"),
|
||||
GSCALAR(reset_switch_chan, "RST_SWITCH_CH"),
|
||||
GSCALAR(airspeed_cruise, "TRIM_ARSPD_CM"),
|
||||
GSCALAR(min_gndspeed, "MIN_GNDSPD_CM"),
|
||||
GSCALAR(pitch_trim, "TRIM_PITCH_CD"),
|
||||
GSCALAR(RTL_altitude, "ALT_HOLD_RTL"),
|
||||
GSCALAR(FBWB_min_altitude, "ALT_HOLD_FBWCM"),
|
||||
GSCALAR(ground_temperature, "GND_TEMP"),
|
||||
GSCALAR(ground_pressure, "GND_ABS_PRESS"),
|
||||
GSCALAR(compass_enabled, "MAG_ENABLE"),
|
||||
GSCALAR(flap_1_percent, "FLAP_1_PERCNT"),
|
||||
GSCALAR(flap_1_speed, "FLAP_1_SPEED"),
|
||||
GSCALAR(flap_2_percent, "FLAP_2_PERCNT"),
|
||||
GSCALAR(flap_2_speed, "FLAP_2_SPEED"),
|
||||
|
||||
|
||||
GSCALAR(battery_monitoring, "BATT_MONITOR"),
|
||||
GSCALAR(volt_div_ratio, "VOLT_DIVIDER"),
|
||||
GSCALAR(curr_amp_per_volt, "AMP_PER_VOLT"),
|
||||
GSCALAR(input_voltage, "INPUT_VOLTS"),
|
||||
GSCALAR(pack_capacity, "BATT_CAPACITY"),
|
||||
GSCALAR(inverted_flight_ch, "INVERTEDFLT_CH"),
|
||||
GSCALAR(sonar_enabled, "SONAR_ENABLE"),
|
||||
GSCALAR(airspeed_enabled, "ARSPD_ENABLE"),
|
||||
|
||||
GGROUP(channel_roll, "RC1_", RC_Channel),
|
||||
GGROUP(channel_pitch, "RC2_", RC_Channel),
|
||||
GGROUP(channel_throttle, "RC3_", RC_Channel),
|
||||
GGROUP(channel_rudder, "RC4_", RC_Channel),
|
||||
GGROUP(rc_5, "RC5_", RC_Channel_aux),
|
||||
GGROUP(rc_6, "RC6_", RC_Channel_aux),
|
||||
GGROUP(rc_7, "RC7_", RC_Channel_aux),
|
||||
GGROUP(rc_8, "RC8_", RC_Channel_aux),
|
||||
|
||||
GGROUP(pidNavRoll, "HDNG2RLL_", PID),
|
||||
GGROUP(pidServoRoll, "RLL2SRV_", PID),
|
||||
GGROUP(pidServoPitch, "PTCH2SRV_", PID),
|
||||
GGROUP(pidNavPitchAirspeed, "ARSP2PTCH_", PID),
|
||||
GGROUP(pidServoRudder, "YW2SRV_", PID),
|
||||
GGROUP(pidTeThrottle, "ENRGY2THR_", PID),
|
||||
GGROUP(pidNavPitchAltitude, "ALT2PTCH_", PID),
|
||||
|
||||
// variables not in the g class which contain EEPROM saved variables
|
||||
GOBJECT(compass, "COMPASS_", Compass)
|
||||
};
|
||||
|
||||
|
||||
static void load_parameters(void)
|
||||
{
|
||||
// setup the AP_Var subsystem for storage to EEPROM
|
||||
AP_Param::setup(var_info, sizeof(var_info)/sizeof(var_info[0]));
|
||||
|
||||
if (!g.format_version.load() ||
|
||||
g.format_version != Parameters::k_format_version) {
|
||||
|
||||
// erase all parameters
|
||||
Serial.printf_P(PSTR("Firmware change: erasing EEPROM...\n"));
|
||||
delay(100); // wait for serial send
|
||||
AP_Param::erase_all();
|
||||
|
||||
// save the current format version
|
||||
g.format_version.set_and_save(Parameters::k_format_version);
|
||||
Serial.println_P(PSTR("done."));
|
||||
} else {
|
||||
unsigned long before = micros();
|
||||
// Load all auto-loaded EEPROM variables
|
||||
AP_Param::load_all();
|
||||
|
||||
Serial.printf_P(PSTR("load_all took %luus\n"), micros() - before);
|
||||
}
|
||||
}
|
|
@ -0,0 +1,65 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
/*
|
||||
new variable scheme
|
||||
Andrew Tridgell February 2012
|
||||
*/
|
||||
|
||||
#include <FastSerial.h>
|
||||
#include <AP_Common.h>
|
||||
#include <PID.h> // PID library
|
||||
#include <APM_RC.h> // ArduPilot Mega RC Library
|
||||
#include <RC_Channel.h> // RC Channel Library
|
||||
#include <AP_Compass.h> // ArduPilot Mega Magnetometer Library
|
||||
#include <I2C.h>
|
||||
#include <AP_Math.h>
|
||||
#include <config.h>
|
||||
#include <Parameters.h>
|
||||
|
||||
static Parameters g;
|
||||
static AP_Compass_HMC5843 compass;
|
||||
|
||||
FastSerialPort0(Serial);
|
||||
|
||||
#define SERIAL0_BAUD 115200
|
||||
|
||||
void setup() {
|
||||
Serial.begin(SERIAL0_BAUD, 128, 128);
|
||||
|
||||
load_parameters();
|
||||
|
||||
Serial.printf_P(PSTR("sizeof(RC_Channel)=%u\n"), (unsigned)sizeof(RC_Channel));
|
||||
Serial.printf_P(PSTR("sizeof(g)=%u\n"), (unsigned)sizeof(g));
|
||||
Serial.printf_P(PSTR("sizeof(g.throttle_min)=%u\n"), (unsigned)sizeof(g.throttle_min));
|
||||
Serial.printf_P(PSTR("sizeof(g.channel_roll)=%u\n"), (unsigned)sizeof(g.channel_roll));
|
||||
Serial.printf_P(PSTR("throttle_max now: %u\n"), (unsigned)g.throttle_max);
|
||||
|
||||
// try set interfaces
|
||||
g.throttle_min.set(g.throttle_min+1);
|
||||
g.throttle_min.save();
|
||||
g.throttle_min.set_and_save(g.throttle_min+1);
|
||||
|
||||
Serial.printf_P(PSTR("throttle_min now: %u\n"), (unsigned)g.throttle_min);
|
||||
|
||||
// find a variable by name
|
||||
AP_Param *vp;
|
||||
vp = AP_Param::find("RLL2SRV_P");
|
||||
((AP_Float *)vp)->set(23);
|
||||
|
||||
Serial.printf_P(PSTR("RLL2SRV_P=%f\n"),
|
||||
g.pidServoRoll.kP());
|
||||
|
||||
char s[AP_MAX_NAME_SIZE+1];
|
||||
|
||||
g.throttle_min.copy_name(s, sizeof(s));
|
||||
s[AP_MAX_NAME_SIZE] = 0;
|
||||
Serial.printf_P(PSTR("THROTTLE_MIN.copy_name()->%s\n"), s);
|
||||
|
||||
g.channel_roll.radio_min.copy_name(s, sizeof(s));
|
||||
s[AP_MAX_NAME_SIZE] = 0;
|
||||
Serial.printf_P(PSTR("RC1_MIN.copy_name()->%s %p\n"), s, &g.channel_roll.radio_min);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
}
|
|
@ -0,0 +1,836 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
//
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
// WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING
|
||||
//
|
||||
// DO NOT EDIT this file to adjust your configuration. Create your own
|
||||
// APM_Config.h and use APM_Config.h.example as a reference.
|
||||
//
|
||||
// WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING
|
||||
///
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
// Default and automatic configuration details.
|
||||
//
|
||||
// Notes for maintainers:
|
||||
//
|
||||
// - Try to keep this file organised in the same order as APM_Config.h.example
|
||||
//
|
||||
|
||||
#include "defines.h"
|
||||
|
||||
///
|
||||
/// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that
|
||||
/// change in your local copy of APM_Config.h.
|
||||
///
|
||||
#include "APM_Config.h" // <== THIS INCLUDE, DO NOT EDIT IT. EVER.
|
||||
///
|
||||
/// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that
|
||||
/// change in your local copy of APM_Config.h.
|
||||
///
|
||||
|
||||
// Just so that it's completely clear...
|
||||
#define ENABLED 1
|
||||
#define DISABLED 0
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// HARDWARE CONFIGURATION AND CONNECTIONS
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// APM HARDWARE
|
||||
//
|
||||
|
||||
#ifndef CONFIG_APM_HARDWARE
|
||||
# define CONFIG_APM_HARDWARE APM_HARDWARE_APM1
|
||||
#endif
|
||||
|
||||
#if defined( __AVR_ATmega1280__ )
|
||||
#define CLI_ENABLED DISABLED
|
||||
#define LOGGING_ENABLED DISABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// APM2 HARDWARE DEFAULTS
|
||||
//
|
||||
|
||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
||||
# define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000
|
||||
# define CONFIG_PUSHBUTTON DISABLED
|
||||
# define CONFIG_RELAY DISABLED
|
||||
# define MAG_ORIENTATION AP_COMPASS_APM2_SHIELD
|
||||
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
|
||||
# define CONFIG_PITOT_SOURCE PITOT_SOURCE_ANALOG_PIN
|
||||
# define MAGNETOMETER ENABLED
|
||||
# ifdef APM2_BETA_HARDWARE
|
||||
# define CONFIG_BARO AP_BARO_BMP085
|
||||
# else // APM2 Production Hardware (default)
|
||||
# define CONFIG_BARO AP_BARO_MS5611
|
||||
# endif
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// LED and IO Pins
|
||||
//
|
||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
|
||||
# define A_LED_PIN 37
|
||||
# define B_LED_PIN 36
|
||||
# define C_LED_PIN 35
|
||||
# define LED_ON HIGH
|
||||
# define LED_OFF LOW
|
||||
# define SLIDE_SWITCH_PIN 40
|
||||
# define PUSHBUTTON_PIN 41
|
||||
# define USB_MUX_PIN -1
|
||||
# define CONFIG_RELAY ENABLED
|
||||
# define BATTERY_PIN_1 0
|
||||
# define CURRENT_PIN_1 1
|
||||
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
||||
# define A_LED_PIN 27
|
||||
# define B_LED_PIN 26
|
||||
# define C_LED_PIN 25
|
||||
# define LED_ON LOW
|
||||
# define LED_OFF HIGH
|
||||
# define SLIDE_SWITCH_PIN (-1)
|
||||
# define PUSHBUTTON_PIN (-1)
|
||||
# define CLI_SLIDER_ENABLED DISABLED
|
||||
# define USB_MUX_PIN 23
|
||||
# define BATTERY_PIN_1 1
|
||||
# define CURRENT_PIN_1 2
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// AIRSPEED_SENSOR
|
||||
// AIRSPEED_RATIO
|
||||
//
|
||||
#ifndef AIRSPEED_SENSOR
|
||||
# define AIRSPEED_SENSOR DISABLED
|
||||
#endif
|
||||
|
||||
#ifndef AIRSPEED_RATIO
|
||||
# define AIRSPEED_RATIO 1.9936 // Note - this varies from the value in ArduPilot due to the difference in ADC resolution
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// IMU Selection
|
||||
//
|
||||
#ifndef CONFIG_IMU_TYPE
|
||||
# define CONFIG_IMU_TYPE CONFIG_IMU_OILPAN
|
||||
#endif
|
||||
|
||||
#if CONFIG_IMU_TYPE == CONFIG_IMU_MPU6000
|
||||
# ifndef CONFIG_MPU6000_CHIP_SELECT_PIN
|
||||
# define CONFIG_MPU6000_CHIP_SELECT_PIN 53
|
||||
# endif
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// ADC Enable - used to eliminate for systems which don't have ADC.
|
||||
//
|
||||
#ifndef CONFIG_ADC
|
||||
# if CONFIG_IMU_TYPE == CONFIG_IMU_OILPAN
|
||||
# define CONFIG_ADC ENABLED
|
||||
# else
|
||||
# define CONFIG_ADC DISABLED
|
||||
# endif
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Barometer
|
||||
//
|
||||
|
||||
#ifndef CONFIG_BARO
|
||||
# define CONFIG_BARO AP_BARO_BMP085
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Pitot
|
||||
//
|
||||
|
||||
#ifndef PITOT_ENABLED
|
||||
# define PITOT_ENABLED DISABLED
|
||||
#endif
|
||||
|
||||
#ifndef CONFIG_PITOT_SOURCE
|
||||
# define CONFIG_PITOT_SOURCE PITOT_SOURCE_ADC
|
||||
#endif
|
||||
|
||||
#if CONFIG_PITOT_SOURCE == PITOT_SOURCE_ADC
|
||||
# ifndef CONFIG_PITOT_SOURCE_ADC_CHANNEL
|
||||
# define CONFIG_PITOT_SOURCE_ADC_CHANNEL 7
|
||||
# endif
|
||||
#elif CONFIG_PITOT_SOURCE == PITOT_SOURCE_ANALOG_PIN
|
||||
# ifndef CONFIG_PITOT_SOURCE_ANALOG_PIN
|
||||
# define CONFIG_PITOT_SOURCE_ANALOG_PIN 0
|
||||
# endif
|
||||
#else
|
||||
# warning Invalid value for CONFIG_PITOT_SOURCE, disabling airspeed
|
||||
# undef PITOT_ENABLED
|
||||
# define PITOT_ENABLED DISABLED
|
||||
#endif
|
||||
|
||||
#ifndef SONAR_TYPE
|
||||
# define SONAR_TYPE MAX_SONAR_LV // MAX_SONAR_XL,
|
||||
#endif
|
||||
|
||||
#ifndef SONAR_ENABLED
|
||||
#define SONAR_ENABLED DISABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// HIL_MODE OPTIONAL
|
||||
|
||||
#ifndef HIL_MODE
|
||||
#define HIL_MODE HIL_MODE_DISABLED
|
||||
#endif
|
||||
|
||||
#if HIL_MODE != HIL_MODE_DISABLED // we are in HIL mode
|
||||
# undef GPS_PROTOCOL
|
||||
# define GPS_PROTOCOL GPS_PROTOCOL_NONE
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// GPS_PROTOCOL
|
||||
//
|
||||
// Note that this test must follow the HIL_PROTOCOL block as the HIL
|
||||
// setup may override the GPS configuration.
|
||||
//
|
||||
#ifndef GPS_PROTOCOL
|
||||
# define GPS_PROTOCOL GPS_PROTOCOL_AUTO
|
||||
#endif
|
||||
|
||||
#ifndef MAV_SYSTEM_ID
|
||||
# define MAV_SYSTEM_ID 1
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Serial port speeds.
|
||||
//
|
||||
#ifndef SERIAL0_BAUD
|
||||
# define SERIAL0_BAUD 115200
|
||||
#endif
|
||||
#ifndef SERIAL3_BAUD
|
||||
# define SERIAL3_BAUD 57600
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Battery monitoring
|
||||
//
|
||||
#ifndef BATTERY_EVENT
|
||||
# define BATTERY_EVENT DISABLED
|
||||
#endif
|
||||
#ifndef LOW_VOLTAGE
|
||||
# define LOW_VOLTAGE 9.6
|
||||
#endif
|
||||
#ifndef VOLT_DIV_RATIO
|
||||
# define VOLT_DIV_RATIO 3.56 // This is the proper value for an on-board APM1 voltage divider with a 3.9kOhm resistor
|
||||
//# define VOLT_DIV_RATIO 15.70 // This is the proper value for the AttoPilot 50V/90A sensor
|
||||
//# define VOLT_DIV_RATIO 4.127 // This is the proper value for the AttoPilot 13.6V/45A sensor
|
||||
|
||||
#endif
|
||||
|
||||
#ifndef CURR_AMP_PER_VOLT
|
||||
# define CURR_AMP_PER_VOLT 27.32 // This is the proper value for the AttoPilot 50V/90A sensor
|
||||
//# define CURR_AMP_PER_VOLT 13.66 // This is the proper value for the AttoPilot 13.6V/45A sensor
|
||||
#endif
|
||||
|
||||
#ifndef CURR_AMPS_OFFSET
|
||||
# define CURR_AMPS_OFFSET 0.0
|
||||
#endif
|
||||
#ifndef HIGH_DISCHARGE
|
||||
# define HIGH_DISCHARGE 1760
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// INPUT_VOLTAGE
|
||||
//
|
||||
#ifndef INPUT_VOLTAGE
|
||||
# define INPUT_VOLTAGE 4.68 // 4.68 is the average value for a sample set. This is the value at the processor with 5.02 applied at the servo rail
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// MAGNETOMETER
|
||||
#ifndef MAGNETOMETER
|
||||
# define MAGNETOMETER DISABLED
|
||||
#endif
|
||||
#ifndef MAG_ORIENTATION
|
||||
# define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// RADIO CONFIGURATION
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Radio channel limits
|
||||
//
|
||||
// Note that these are not called out in APM_Config.h.reference.
|
||||
//
|
||||
#ifndef CH5_MIN
|
||||
# define CH5_MIN 1000
|
||||
#endif
|
||||
#ifndef CH5_MAX
|
||||
# define CH5_MAX 2000
|
||||
#endif
|
||||
#ifndef CH6_MIN
|
||||
# define CH6_MIN 1000
|
||||
#endif
|
||||
#ifndef CH6_MAX
|
||||
# define CH6_MAX 2000
|
||||
#endif
|
||||
#ifndef CH7_MIN
|
||||
# define CH7_MIN 1000
|
||||
#endif
|
||||
#ifndef CH7_MAX
|
||||
# define CH7_MAX 2000
|
||||
#endif
|
||||
#ifndef CH8_MIN
|
||||
# define CH8_MIN 1000
|
||||
#endif
|
||||
#ifndef CH8_MAX
|
||||
# define CH8_MAX 2000
|
||||
#endif
|
||||
|
||||
|
||||
#ifndef FLAP_1_PERCENT
|
||||
# define FLAP_1_PERCENT 0
|
||||
#endif
|
||||
#ifndef FLAP_1_SPEED
|
||||
# define FLAP_1_SPEED 255
|
||||
#endif
|
||||
#ifndef FLAP_2_PERCENT
|
||||
# define FLAP_2_PERCENT 0
|
||||
#endif
|
||||
#ifndef FLAP_2_SPEED
|
||||
# define FLAP_2_SPEED 255
|
||||
#endif
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// FLIGHT_MODE
|
||||
// FLIGHT_MODE_CHANNEL
|
||||
//
|
||||
#ifndef FLIGHT_MODE_CHANNEL
|
||||
# define FLIGHT_MODE_CHANNEL 8
|
||||
#endif
|
||||
#if (FLIGHT_MODE_CHANNEL != 5) && (FLIGHT_MODE_CHANNEL != 6) && (FLIGHT_MODE_CHANNEL != 7) && (FLIGHT_MODE_CHANNEL != 8)
|
||||
# error XXX
|
||||
# error XXX You must set FLIGHT_MODE_CHANNEL to 5, 6, 7 or 8
|
||||
# error XXX
|
||||
#endif
|
||||
|
||||
#if !defined(FLIGHT_MODE_1)
|
||||
# define FLIGHT_MODE_1 RTL
|
||||
#endif
|
||||
#if !defined(FLIGHT_MODE_2)
|
||||
# define FLIGHT_MODE_2 RTL
|
||||
#endif
|
||||
#if !defined(FLIGHT_MODE_3)
|
||||
# define FLIGHT_MODE_3 STABILIZE
|
||||
#endif
|
||||
#if !defined(FLIGHT_MODE_4)
|
||||
# define FLIGHT_MODE_4 STABILIZE
|
||||
#endif
|
||||
#if !defined(FLIGHT_MODE_5)
|
||||
# define FLIGHT_MODE_5 MANUAL
|
||||
#endif
|
||||
#if !defined(FLIGHT_MODE_6)
|
||||
# define FLIGHT_MODE_6 MANUAL
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// THROTTLE_FAILSAFE
|
||||
// THROTTLE_FS_VALUE
|
||||
// SHORT_FAILSAFE_ACTION
|
||||
// LONG_FAILSAFE_ACTION
|
||||
// GCS_HEARTBEAT_FAILSAFE
|
||||
//
|
||||
#ifndef THROTTLE_FAILSAFE
|
||||
# define THROTTLE_FAILSAFE ENABLED
|
||||
#endif
|
||||
#ifndef THROTTLE_FS_VALUE
|
||||
# define THROTTLE_FS_VALUE 950
|
||||
#endif
|
||||
#ifndef SHORT_FAILSAFE_ACTION
|
||||
# define SHORT_FAILSAFE_ACTION 0
|
||||
#endif
|
||||
#ifndef LONG_FAILSAFE_ACTION
|
||||
# define LONG_FAILSAFE_ACTION 0
|
||||
#endif
|
||||
#ifndef GCS_HEARTBEAT_FAILSAFE
|
||||
# define GCS_HEARTBEAT_FAILSAFE DISABLED
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// AUTO_TRIM
|
||||
//
|
||||
#ifndef AUTO_TRIM
|
||||
# define AUTO_TRIM DISABLED
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// THROTTLE_REVERSE
|
||||
//
|
||||
#ifndef THROTTLE_REVERSE
|
||||
# define THROTTLE_REVERSE DISABLED
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// ENABLE_STICK_MIXING
|
||||
//
|
||||
#ifndef ENABLE_STICK_MIXING
|
||||
# define ENABLE_STICK_MIXING ENABLED
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// THROTTLE_OUT
|
||||
//
|
||||
#ifndef THROTTE_OUT
|
||||
# define THROTTLE_OUT ENABLED
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// STARTUP BEHAVIOUR
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// GROUND_START_DELAY
|
||||
//
|
||||
#ifndef GROUND_START_DELAY
|
||||
# define GROUND_START_DELAY 0
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// ENABLE_AIR_START
|
||||
//
|
||||
#ifndef ENABLE_AIR_START
|
||||
# define ENABLE_AIR_START DISABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// ENABLE REVERSE_SWITCH
|
||||
//
|
||||
#ifndef REVERSE_SWITCH
|
||||
# define REVERSE_SWITCH ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// ENABLE ELEVON_MIXING
|
||||
//
|
||||
#ifndef ELEVON_MIXING
|
||||
# define ELEVON_MIXING DISABLED
|
||||
#endif
|
||||
#ifndef ELEVON_REVERSE
|
||||
# define ELEVON_REVERSE DISABLED
|
||||
#endif
|
||||
#ifndef ELEVON_CH1_REVERSE
|
||||
# define ELEVON_CH1_REVERSE DISABLED
|
||||
#endif
|
||||
#ifndef ELEVON_CH2_REVERSE
|
||||
# define ELEVON_CH2_REVERSE DISABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// MOUNT (ANTENNA OR CAMERA)
|
||||
//
|
||||
#ifndef MOUNT
|
||||
# define MOUNT DISABLED
|
||||
#endif
|
||||
|
||||
#if defined( __AVR_ATmega1280__ ) && CAMERA == ENABLED
|
||||
// The small ATmega1280 chip does not have enough memory for camera support
|
||||
// so disable CLI, this will allow camera support and other improvements to fit.
|
||||
// This should almost have no side effects, because the APM planner can now do a complete board setup.
|
||||
#define CLI_ENABLED DISABLED
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// FLIGHT AND NAVIGATION CONTROL
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Altitude measurement and control.
|
||||
//
|
||||
#ifndef ALT_EST_GAIN
|
||||
# define ALT_EST_GAIN 0.01
|
||||
#endif
|
||||
#ifndef ALTITUDE_MIX
|
||||
# define ALTITUDE_MIX 1
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// AIRSPEED_CRUISE
|
||||
//
|
||||
#ifndef AIRSPEED_CRUISE
|
||||
# define AIRSPEED_CRUISE 12 // 12 m/s
|
||||
#endif
|
||||
#define AIRSPEED_CRUISE_CM AIRSPEED_CRUISE*100
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// MIN_GNDSPEED
|
||||
//
|
||||
#ifndef MIN_GNDSPEED
|
||||
# define MIN_GNDSPEED 0 // m/s (0 disables)
|
||||
#endif
|
||||
#define MIN_GNDSPEED_CM MIN_GNDSPEED*100
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// FLY_BY_WIRE_B airspeed control
|
||||
//
|
||||
#ifndef AIRSPEED_FBW_MIN
|
||||
# define AIRSPEED_FBW_MIN 6
|
||||
#endif
|
||||
#ifndef AIRSPEED_FBW_MAX
|
||||
# define AIRSPEED_FBW_MAX 22
|
||||
#endif
|
||||
|
||||
#ifndef ALT_HOLD_FBW
|
||||
# define ALT_HOLD_FBW 0
|
||||
#endif
|
||||
#define ALT_HOLD_FBW_CM ALT_HOLD_FBW*100
|
||||
|
||||
|
||||
|
||||
/* The following parmaeters have no corresponding control implementation
|
||||
#ifndef THROTTLE_ALT_P
|
||||
# define THROTTLE_ALT_P 0.32
|
||||
#endif
|
||||
#ifndef THROTTLE_ALT_I
|
||||
# define THROTTLE_ALT_I 0.0
|
||||
#endif
|
||||
#ifndef THROTTLE_ALT_D
|
||||
# define THROTTLE_ALT_D 0.0
|
||||
#endif
|
||||
#ifndef THROTTLE_ALT_INT_MAX
|
||||
# define THROTTLE_ALT_INT_MAX 20
|
||||
#endif
|
||||
#define THROTTLE_ALT_INT_MAX_CM THROTTLE_ALT_INT_MAX*100
|
||||
*/
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Servo Mapping
|
||||
//
|
||||
#ifndef THROTTLE_MIN
|
||||
# define THROTTLE_MIN 0 // percent
|
||||
#endif
|
||||
#ifndef THROTTLE_CRUISE
|
||||
# define THROTTLE_CRUISE 45
|
||||
#endif
|
||||
#ifndef THROTTLE_MAX
|
||||
# define THROTTLE_MAX 75
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Autopilot control limits
|
||||
//
|
||||
#ifndef HEAD_MAX
|
||||
# define HEAD_MAX 45
|
||||
#endif
|
||||
#ifndef PITCH_MAX
|
||||
# define PITCH_MAX 15
|
||||
#endif
|
||||
#ifndef PITCH_MIN
|
||||
# define PITCH_MIN -25
|
||||
#endif
|
||||
#define HEAD_MAX_CENTIDEGREE HEAD_MAX * 100
|
||||
#define PITCH_MAX_CENTIDEGREE PITCH_MAX * 100
|
||||
#define PITCH_MIN_CENTIDEGREE PITCH_MIN * 100
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Attitude control gains
|
||||
//
|
||||
#ifndef SERVO_ROLL_P
|
||||
# define SERVO_ROLL_P 0.4
|
||||
#endif
|
||||
#ifndef SERVO_ROLL_I
|
||||
# define SERVO_ROLL_I 0.0
|
||||
#endif
|
||||
#ifndef SERVO_ROLL_D
|
||||
# define SERVO_ROLL_D 0.0
|
||||
#endif
|
||||
#ifndef SERVO_ROLL_INT_MAX
|
||||
# define SERVO_ROLL_INT_MAX 5
|
||||
#endif
|
||||
#define SERVO_ROLL_INT_MAX_CENTIDEGREE SERVO_ROLL_INT_MAX*100
|
||||
#ifndef ROLL_SLEW_LIMIT
|
||||
# define ROLL_SLEW_LIMIT 0
|
||||
#endif
|
||||
#ifndef SERVO_PITCH_P
|
||||
# define SERVO_PITCH_P 0.6
|
||||
#endif
|
||||
#ifndef SERVO_PITCH_I
|
||||
# define SERVO_PITCH_I 0.0
|
||||
#endif
|
||||
#ifndef SERVO_PITCH_D
|
||||
# define SERVO_PITCH_D 0.0
|
||||
#endif
|
||||
#ifndef SERVO_PITCH_INT_MAX
|
||||
# define SERVO_PITCH_INT_MAX 5
|
||||
#endif
|
||||
#define SERVO_PITCH_INT_MAX_CENTIDEGREE SERVO_PITCH_INT_MAX*100
|
||||
#ifndef PITCH_COMP
|
||||
# define PITCH_COMP 0.2
|
||||
#endif
|
||||
#ifndef SERVO_YAW_P
|
||||
# define SERVO_YAW_P 0.0
|
||||
#endif
|
||||
#ifndef SERVO_YAW_I
|
||||
# define SERVO_YAW_I 0.0
|
||||
#endif
|
||||
#ifndef SERVO_YAW_D
|
||||
# define SERVO_YAW_D 0.0
|
||||
#endif
|
||||
#ifndef SERVO_YAW_INT_MAX
|
||||
# define SERVO_YAW_INT_MAX 0
|
||||
#endif
|
||||
#ifndef RUDDER_MIX
|
||||
# define RUDDER_MIX 0.5
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Navigation control gains
|
||||
//
|
||||
#ifndef NAV_ROLL_P
|
||||
# define NAV_ROLL_P 0.7
|
||||
#endif
|
||||
#ifndef NAV_ROLL_I
|
||||
# define NAV_ROLL_I 0.0
|
||||
#endif
|
||||
#ifndef NAV_ROLL_D
|
||||
# define NAV_ROLL_D 0.02
|
||||
#endif
|
||||
#ifndef NAV_ROLL_INT_MAX
|
||||
# define NAV_ROLL_INT_MAX 5
|
||||
#endif
|
||||
#define NAV_ROLL_INT_MAX_CENTIDEGREE NAV_ROLL_INT_MAX*100
|
||||
#ifndef NAV_PITCH_ASP_P
|
||||
# define NAV_PITCH_ASP_P 0.65
|
||||
#endif
|
||||
#ifndef NAV_PITCH_ASP_I
|
||||
# define NAV_PITCH_ASP_I 0.0
|
||||
#endif
|
||||
#ifndef NAV_PITCH_ASP_D
|
||||
# define NAV_PITCH_ASP_D 0.0
|
||||
#endif
|
||||
#ifndef NAV_PITCH_ASP_INT_MAX
|
||||
# define NAV_PITCH_ASP_INT_MAX 5
|
||||
#endif
|
||||
#define NAV_PITCH_ASP_INT_MAX_CMSEC NAV_PITCH_ASP_INT_MAX*100
|
||||
#ifndef NAV_PITCH_ALT_P
|
||||
# define NAV_PITCH_ALT_P 0.65
|
||||
#endif
|
||||
#ifndef NAV_PITCH_ALT_I
|
||||
# define NAV_PITCH_ALT_I 0.0
|
||||
#endif
|
||||
#ifndef NAV_PITCH_ALT_D
|
||||
# define NAV_PITCH_ALT_D 0.0
|
||||
#endif
|
||||
#ifndef NAV_PITCH_ALT_INT_MAX
|
||||
# define NAV_PITCH_ALT_INT_MAX 5
|
||||
#endif
|
||||
#define NAV_PITCH_ALT_INT_MAX_CM NAV_PITCH_ALT_INT_MAX*100
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Energy/Altitude control gains
|
||||
//
|
||||
#ifndef THROTTLE_TE_P
|
||||
# define THROTTLE_TE_P 0.50
|
||||
#endif
|
||||
#ifndef THROTTLE_TE_I
|
||||
# define THROTTLE_TE_I 0.0
|
||||
#endif
|
||||
#ifndef THROTTLE_TE_D
|
||||
# define THROTTLE_TE_D 0.0
|
||||
#endif
|
||||
#ifndef THROTTLE_TE_INT_MAX
|
||||
# define THROTTLE_TE_INT_MAX 20
|
||||
#endif
|
||||
#ifndef THROTTLE_SLEW_LIMIT
|
||||
# define THROTTLE_SLEW_LIMIT 0
|
||||
#endif
|
||||
#ifndef P_TO_T
|
||||
# define P_TO_T 0
|
||||
#endif
|
||||
#ifndef T_TO_P
|
||||
# define T_TO_P 0
|
||||
#endif
|
||||
#ifndef PITCH_TARGET
|
||||
# define PITCH_TARGET 0
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Crosstrack compensation
|
||||
//
|
||||
#ifndef XTRACK_GAIN
|
||||
# define XTRACK_GAIN 1 // deg/m
|
||||
#endif
|
||||
#ifndef XTRACK_ENTRY_ANGLE
|
||||
# define XTRACK_ENTRY_ANGLE 30 // deg
|
||||
#endif
|
||||
# define XTRACK_GAIN_SCALED XTRACK_GAIN*100
|
||||
# define XTRACK_ENTRY_ANGLE_CENTIDEGREE XTRACK_ENTRY_ANGLE*100
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// DEBUGGING
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Dataflash logging control
|
||||
//
|
||||
|
||||
#ifndef LOGGING_ENABLED
|
||||
# define LOGGING_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
|
||||
#ifndef LOG_ATTITUDE_FAST
|
||||
# define LOG_ATTITUDE_FAST DISABLED
|
||||
#endif
|
||||
#ifndef LOG_ATTITUDE_MED
|
||||
# define LOG_ATTITUDE_MED ENABLED
|
||||
#endif
|
||||
#ifndef LOG_GPS
|
||||
# define LOG_GPS ENABLED
|
||||
#endif
|
||||
#ifndef LOG_PM
|
||||
# define LOG_PM ENABLED
|
||||
#endif
|
||||
#ifndef LOG_CTUN
|
||||
# define LOG_CTUN DISABLED
|
||||
#endif
|
||||
#ifndef LOG_NTUN
|
||||
# define LOG_NTUN DISABLED
|
||||
#endif
|
||||
#ifndef LOG_MODE
|
||||
# define LOG_MODE ENABLED
|
||||
#endif
|
||||
#ifndef LOG_RAW
|
||||
# define LOG_RAW DISABLED
|
||||
#endif
|
||||
#ifndef LOG_CMD
|
||||
# define LOG_CMD ENABLED
|
||||
#endif
|
||||
#ifndef LOG_CUR
|
||||
# define LOG_CUR DISABLED
|
||||
#endif
|
||||
|
||||
// calculate the default log_bitmask
|
||||
#define LOGBIT(_s) (LOG_##_s ? MASK_LOG_##_s : 0)
|
||||
|
||||
#define DEFAULT_LOG_BITMASK \
|
||||
LOGBIT(ATTITUDE_FAST) | \
|
||||
LOGBIT(ATTITUDE_MED) | \
|
||||
LOGBIT(GPS) | \
|
||||
LOGBIT(PM) | \
|
||||
LOGBIT(CTUN) | \
|
||||
LOGBIT(NTUN) | \
|
||||
LOGBIT(MODE) | \
|
||||
LOGBIT(RAW) | \
|
||||
LOGBIT(CMD) | \
|
||||
LOGBIT(CUR)
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Navigation defaults
|
||||
//
|
||||
#ifndef WP_RADIUS_DEFAULT
|
||||
# define WP_RADIUS_DEFAULT 30
|
||||
#endif
|
||||
|
||||
#ifndef LOITER_RADIUS_DEFAULT
|
||||
# define LOITER_RADIUS_DEFAULT 60
|
||||
#endif
|
||||
|
||||
#ifndef ALT_HOLD_HOME
|
||||
# define ALT_HOLD_HOME 100
|
||||
#endif
|
||||
#define ALT_HOLD_HOME_CM ALT_HOLD_HOME*100
|
||||
|
||||
#ifndef USE_CURRENT_ALT
|
||||
# define USE_CURRENT_ALT FALSE
|
||||
#endif
|
||||
|
||||
#ifndef INVERTED_FLIGHT_PWM
|
||||
# define INVERTED_FLIGHT_PWM 1750
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Developer Items
|
||||
//
|
||||
|
||||
#ifndef STANDARD_SPEED
|
||||
# define STANDARD_SPEED 15.0
|
||||
#define STANDARD_SPEED_SQUARED (STANDARD_SPEED * STANDARD_SPEED)
|
||||
#endif
|
||||
#define STANDARD_THROTTLE_SQUARED (THROTTLE_CRUISE * THROTTLE_CRUISE)
|
||||
|
||||
// use this to enable servos in HIL mode
|
||||
#ifndef HIL_SERVOS
|
||||
# define HIL_SERVOS DISABLED
|
||||
#endif
|
||||
|
||||
// use this to completely disable the CLI
|
||||
#ifndef CLI_ENABLED
|
||||
# define CLI_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
// use this to disable the CLI slider switch
|
||||
#ifndef CLI_SLIDER_ENABLED
|
||||
# define CLI_SLIDER_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
// delay to prevent Xbee bricking, in milliseconds
|
||||
#ifndef MAVLINK_TELEMETRY_PORT_DELAY
|
||||
# define MAVLINK_TELEMETRY_PORT_DELAY 2000
|
||||
#endif
|
||||
|
||||
// use this to disable gen-fencing
|
||||
#ifndef GEOFENCE_ENABLED
|
||||
# define GEOFENCE_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
// pwm value on FENCE_CHANNEL to use to enable fenced mode
|
||||
#ifndef FENCE_ENABLE_PWM
|
||||
# define FENCE_ENABLE_PWM 1750
|
||||
#endif
|
||||
|
||||
// a digital pin to set high when the geo-fence triggers. Defaults
|
||||
// to -1, which means don't activate a pin
|
||||
#ifndef FENCE_TRIGGERED_PIN
|
||||
# define FENCE_TRIGGERED_PIN -1
|
||||
#endif
|
||||
|
||||
// if RESET_SWITCH_CH is not zero, then this is the PWM value on
|
||||
// that channel where we reset the control mode to the current switch
|
||||
// position (to for example return to switched mode after failsafe or
|
||||
// fence breach)
|
||||
#ifndef RESET_SWITCH_CHAN_PWM
|
||||
# define RESET_SWITCH_CHAN_PWM 1750
|
||||
#endif
|
|
@ -0,0 +1,231 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#ifndef _DEFINES_H
|
||||
#define _DEFINES_H
|
||||
|
||||
// Internal defines, don't edit and expect things to work
|
||||
// -------------------------------------------------------
|
||||
|
||||
#define TRUE 1
|
||||
#define FALSE 0
|
||||
#define ToRad(x) (x*0.01745329252) // *pi/180
|
||||
#define ToDeg(x) (x*57.2957795131) // *180/pi
|
||||
|
||||
#define DEBUG 0
|
||||
#define LOITER_RANGE 60 // for calculating power outside of loiter radius
|
||||
#define SERVO_MAX 4500 // This value represents 45 degrees and is just an arbitrary representation of servo max travel.
|
||||
|
||||
// failsafe
|
||||
// ----------------------
|
||||
#define FAILSAFE_NONE 0
|
||||
#define FAILSAFE_SHORT 1
|
||||
#define FAILSAFE_LONG 2
|
||||
#define FAILSAFE_GCS 3
|
||||
#define FAILSAFE_SHORT_TIME 1500 // Miliiseconds
|
||||
#define FAILSAFE_LONG_TIME 20000 // Miliiseconds
|
||||
|
||||
|
||||
// active altitude sensor
|
||||
// ----------------------
|
||||
#define SONAR 0
|
||||
#define BARO 1
|
||||
|
||||
#define PITOT_SOURCE_ADC 1
|
||||
#define PITOT_SOURCE_ANALOG_PIN 2
|
||||
|
||||
#define T6 1000000
|
||||
#define T7 10000000
|
||||
|
||||
// GPS type codes - use the names, not the numbers
|
||||
#define GPS_PROTOCOL_NONE -1
|
||||
#define GPS_PROTOCOL_NMEA 0
|
||||
#define GPS_PROTOCOL_SIRF 1
|
||||
#define GPS_PROTOCOL_UBLOX 2
|
||||
#define GPS_PROTOCOL_IMU 3
|
||||
#define GPS_PROTOCOL_MTK 4
|
||||
#define GPS_PROTOCOL_HIL 5
|
||||
#define GPS_PROTOCOL_MTK16 6
|
||||
#define GPS_PROTOCOL_AUTO 7
|
||||
|
||||
#define CH_ROLL CH_1
|
||||
#define CH_PITCH CH_2
|
||||
#define CH_THROTTLE CH_3
|
||||
#define CH_RUDDER CH_4
|
||||
#define CH_YAW CH_4
|
||||
|
||||
// HIL enumerations
|
||||
#define HIL_MODE_DISABLED 0
|
||||
#define HIL_MODE_ATTITUDE 1
|
||||
#define HIL_MODE_SENSORS 2
|
||||
|
||||
// Auto Pilot modes
|
||||
// ----------------
|
||||
#define MANUAL 0
|
||||
#define CIRCLE 1 // When flying sans GPS, and we loose the radio, just circle
|
||||
#define STABILIZE 2
|
||||
|
||||
#define FLY_BY_WIRE_A 5 // Fly By Wire A has left stick horizontal => desired roll angle, left stick vertical => desired pitch angle, right stick vertical = manual throttle
|
||||
#define FLY_BY_WIRE_B 6 // Fly By Wire B has left stick horizontal => desired roll angle, left stick vertical => desired pitch angle, right stick vertical => desired airspeed
|
||||
#define FLY_BY_WIRE_C 7 // Fly By Wire C has left stick horizontal => desired roll angle, left stick vertical => desired climb rate, right stick vertical => desired airspeed
|
||||
// Fly By Wire B and Fly By Wire C require airspeed sensor
|
||||
#define AUTO 10
|
||||
#define RTL 11
|
||||
#define LOITER 12
|
||||
//#define TAKEOFF 13 // This is not used by APM. It appears here for consistency with ACM
|
||||
//#define LAND 14 // This is not used by APM. It appears here for consistency with ACM
|
||||
#define GUIDED 15
|
||||
#define INITIALISING 16 // in startup routines
|
||||
|
||||
|
||||
// Commands - Note that APM now uses a subset of the MAVLink protocol commands. See enum MAV_CMD in the GCS_Mavlink library
|
||||
#define CMD_BLANK 0 // there is no command stored in the mem location requested
|
||||
#define NO_COMMAND 0
|
||||
#define WAIT_COMMAND 255
|
||||
|
||||
// Command/Waypoint/Location Options Bitmask
|
||||
//--------------------
|
||||
#define MASK_OPTIONS_RELATIVE_ALT (1<<0) // 1 = Relative altitude
|
||||
|
||||
//repeating events
|
||||
#define NO_REPEAT 0
|
||||
#define CH_5_TOGGLE 1
|
||||
#define CH_6_TOGGLE 2
|
||||
#define CH_7_TOGGLE 3
|
||||
#define CH_8_TOGGLE 4
|
||||
#define RELAY_TOGGLE 5
|
||||
#define STOP_REPEAT 10
|
||||
|
||||
#define MAV_CMD_CONDITION_YAW 23
|
||||
|
||||
// GCS Message ID's
|
||||
/// NOTE: to ensure we never block on sending MAVLink messages
|
||||
/// please keep each MSG_ to a single MAVLink message. If need be
|
||||
/// create new MSG_ IDs for additional messages on the same
|
||||
/// stream
|
||||
enum ap_message {
|
||||
MSG_HEARTBEAT,
|
||||
MSG_ATTITUDE,
|
||||
MSG_LOCATION,
|
||||
MSG_EXTENDED_STATUS1,
|
||||
MSG_EXTENDED_STATUS2,
|
||||
MSG_NAV_CONTROLLER_OUTPUT,
|
||||
MSG_CURRENT_WAYPOINT,
|
||||
MSG_VFR_HUD,
|
||||
MSG_RADIO_OUT,
|
||||
MSG_RADIO_IN,
|
||||
MSG_RAW_IMU1,
|
||||
MSG_RAW_IMU2,
|
||||
MSG_RAW_IMU3,
|
||||
MSG_GPS_STATUS,
|
||||
MSG_GPS_RAW,
|
||||
MSG_SERVO_OUT,
|
||||
MSG_NEXT_WAYPOINT,
|
||||
MSG_NEXT_PARAM,
|
||||
MSG_STATUSTEXT,
|
||||
MSG_FENCE_STATUS,
|
||||
MSG_RETRY_DEFERRED // this must be last
|
||||
};
|
||||
|
||||
enum gcs_severity {
|
||||
SEVERITY_LOW=1,
|
||||
SEVERITY_MEDIUM,
|
||||
SEVERITY_HIGH,
|
||||
SEVERITY_CRITICAL
|
||||
};
|
||||
|
||||
// Logging parameters
|
||||
#define LOG_INDEX_MSG 0xF0
|
||||
#define LOG_ATTITUDE_MSG 0x01
|
||||
#define LOG_GPS_MSG 0x02
|
||||
#define LOG_MODE_MSG 0X03
|
||||
#define LOG_CONTROL_TUNING_MSG 0X04
|
||||
#define LOG_NAV_TUNING_MSG 0X05
|
||||
#define LOG_PERFORMANCE_MSG 0X06
|
||||
#define LOG_RAW_MSG 0x07
|
||||
#define LOG_CMD_MSG 0x08
|
||||
#define LOG_CURRENT_MSG 0x09
|
||||
#define LOG_STARTUP_MSG 0x0A
|
||||
#define TYPE_AIRSTART_MSG 0x00
|
||||
#define TYPE_GROUNDSTART_MSG 0x01
|
||||
#define MAX_NUM_LOGS 100
|
||||
|
||||
#define MASK_LOG_ATTITUDE_FAST (1<<0)
|
||||
#define MASK_LOG_ATTITUDE_MED (1<<1)
|
||||
#define MASK_LOG_GPS (1<<2)
|
||||
#define MASK_LOG_PM (1<<3)
|
||||
#define MASK_LOG_CTUN (1<<4)
|
||||
#define MASK_LOG_NTUN (1<<5)
|
||||
#define MASK_LOG_MODE (1<<6)
|
||||
#define MASK_LOG_RAW (1<<7)
|
||||
#define MASK_LOG_CMD (1<<8)
|
||||
#define MASK_LOG_CUR (1<<9)
|
||||
|
||||
// Waypoint Modes
|
||||
// ----------------
|
||||
#define ABS_WP 0
|
||||
#define REL_WP 1
|
||||
|
||||
// Command Queues
|
||||
// ---------------
|
||||
#define COMMAND_MUST 0
|
||||
#define COMMAND_MAY 1
|
||||
#define COMMAND_NOW 2
|
||||
|
||||
// Events
|
||||
// ------
|
||||
#define EVENT_WILL_REACH_WAYPOINT 1
|
||||
#define EVENT_SET_NEW_COMMAND_INDEX 2
|
||||
#define EVENT_LOADED_WAYPOINT 3
|
||||
#define EVENT_LOOP 4
|
||||
|
||||
// Climb rate calculations
|
||||
#define ALTITUDE_HISTORY_LENGTH 8 //Number of (time,altitude) points to regress a climb rate from
|
||||
|
||||
|
||||
#define BATTERY_VOLTAGE(x) (x*(g.input_voltage/1024.0))*g.volt_div_ratio
|
||||
#define CURRENT_AMPS(x) ((x*(g.input_voltage/1024.0))-CURR_AMPS_OFFSET)*g.curr_amp_per_volt
|
||||
|
||||
#define RELAY_PIN 47
|
||||
|
||||
|
||||
// sonar
|
||||
#define MAX_SONAR_XL 0
|
||||
#define MAX_SONAR_LV 1
|
||||
#define SonarToCm(x) (x*1.26) // Sonar raw value to centimeters
|
||||
#define AN4 4
|
||||
#define AN5 5
|
||||
|
||||
#define SPEEDFILT 400 // centimeters/second; the speed below which a groundstart will be triggered
|
||||
|
||||
|
||||
// EEPROM addresses
|
||||
#define EEPROM_MAX_ADDR 4096
|
||||
// parameters get the first 1KiB of EEPROM, remainder is for waypoints
|
||||
#define WP_START_BYTE 0x400 // where in memory home WP is stored + all other WP
|
||||
#define WP_SIZE 15
|
||||
|
||||
// fence points are stored at the end of the EEPROM
|
||||
#define MAX_FENCEPOINTS 20
|
||||
#define FENCE_WP_SIZE sizeof(Vector2l)
|
||||
#define FENCE_START_BYTE (EEPROM_MAX_ADDR-(MAX_FENCEPOINTS*FENCE_WP_SIZE))
|
||||
|
||||
#define MAX_WAYPOINTS ((FENCE_START_BYTE - WP_START_BYTE) / WP_SIZE) - 1 // - 1 to be safe
|
||||
|
||||
#define ONBOARD_PARAM_NAME_LENGTH 15
|
||||
|
||||
// convert a boolean (0 or 1) to a sign for multiplying (0 maps to 1, 1 maps to -1)
|
||||
#define BOOL_TO_SIGN(bvalue) ((bvalue)?-1:1)
|
||||
|
||||
// mark a function as not to be inlined
|
||||
#define NOINLINE __attribute__((noinline))
|
||||
|
||||
#define CONFIG_IMU_OILPAN 1
|
||||
#define CONFIG_IMU_MPU6000 2
|
||||
|
||||
#define APM_HARDWARE_APM1 1
|
||||
#define APM_HARDWARE_APM2 2
|
||||
|
||||
#define AP_BARO_BMP085 1
|
||||
#define AP_BARO_MS5611 2
|
||||
|
||||
#endif // _DEFINES_H
|
Loading…
Reference in New Issue