Rover: fixed cliSerial and clean out more gunk
This commit is contained in:
parent
5e7ca5b0f8
commit
54a722158a
@ -1,13 +1,8 @@
|
||||
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
// -*- 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 GCS_PROTOCOL GCS_PROTOCOL_NONE
|
||||
|
||||
//#define CONFIG_APM_HARDWARE APM_HARDWARE_APM2
|
||||
|
||||
#define LITE DISABLED // if LITE is ENABLED, you may use an APM1280 or APM2560 CPU only (IMU less) with a GPS MT3329
|
||||
@ -41,14 +36,3 @@
|
||||
// Ch3: to the motor ESC
|
||||
// Ch4: not used
|
||||
|
||||
// The following are the recommended settings for Xplane simulation. Remove the leading "/* and trailing "*/" to enable:
|
||||
|
||||
/*
|
||||
#define HIL_PROTOCOL HIL_PROTOCOL_MAVLINK
|
||||
#define HIL_MODE HIL_MODE_ATTITUDE
|
||||
#define HIL_PORT 0
|
||||
#define GCS_PROTOCOL GCS_PROTOCOL_MAVLINK
|
||||
#define GCS_PORT 3
|
||||
*/
|
||||
|
||||
|
||||
|
@ -134,7 +134,7 @@ FastSerialPort1(Serial1); // GPS port
|
||||
FastSerialPort3(Serial3); // Telemetry port for APM1
|
||||
#endif
|
||||
|
||||
static FastSerial *cliSerial = &Serial3;
|
||||
static FastSerial *cliSerial = &Serial;
|
||||
|
||||
// this sets up the parameter table, and sets the default values. This
|
||||
// must be the first AP_Param variable declared to ensure its
|
||||
@ -296,21 +296,7 @@ ModeFilterInt16_Size5 sonar_mode_filter(2);
|
||||
AP_RangeFinder_SharpGP2Y sonar(&sonar_analog_source, &sonar_mode_filter);
|
||||
#endif
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// PITOT selection
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
|
||||
#if CONFIG_PITOT_SOURCE == PITOT_SOURCE_ADC
|
||||
AP_AnalogSource_ADC pitot_analog_source( &adc,
|
||||
CONFIG_PITOT_SOURCE_ADC_CHANNEL, 1.0);
|
||||
#elif CONFIG_PITOT_SOURCE == PITOT_SOURCE_ANALOG_PIN
|
||||
AP_AnalogSource_Arduino pitot_analog_source(CONFIG_PITOT_SOURCE_ANALOG_PIN, 4.0);
|
||||
#endif
|
||||
|
||||
// Barometer filter
|
||||
AverageFilterInt32_Size5 baro_filter; // filtered pitch acceleration
|
||||
|
||||
// relay support
|
||||
AP_Relay relay;
|
||||
|
||||
// Camera/Antenna mount tracking and stabilisation stuff
|
||||
@ -1002,12 +988,8 @@ static void update_GPS(void)
|
||||
|
||||
static void update_current_flight_mode(void)
|
||||
{
|
||||
if(control_mode == AUTO){
|
||||
|
||||
switch(nav_command_ID){
|
||||
case MAV_CMD_NAV_TAKEOFF:
|
||||
break;
|
||||
default:
|
||||
if(control_mode == AUTO) {
|
||||
switch (nav_command_ID) {
|
||||
hold_course = -1;
|
||||
calc_nav_roll();
|
||||
calc_throttle();
|
||||
@ -1016,17 +998,11 @@ static void update_current_flight_mode(void)
|
||||
}else{
|
||||
switch(control_mode){
|
||||
case RTL:
|
||||
case LOITER:
|
||||
case GUIDED:
|
||||
hold_course = -1;
|
||||
calc_nav_roll();
|
||||
calc_throttle();
|
||||
break;
|
||||
|
||||
case FLY_BY_WIRE_A:
|
||||
case FLY_BY_WIRE_B:
|
||||
break;
|
||||
|
||||
case LEARNING:
|
||||
nav_roll = 0;
|
||||
nav_pitch = 0;
|
||||
@ -1040,18 +1016,6 @@ static void update_current_flight_mode(void)
|
||||
// throttle is passthrough
|
||||
break;
|
||||
|
||||
case CIRCLE:
|
||||
// we have no GPS installed and have lost radio contact
|
||||
// or we just want to fly around in a gentle circle w/o GPS
|
||||
// ----------------------------------------------------
|
||||
nav_roll = g.roll_limit / 3;
|
||||
nav_pitch = 0;
|
||||
|
||||
if (failsafe != FAILSAFE_NONE){
|
||||
g.channel_throttle.servo_out = g.throttle_cruise;
|
||||
}
|
||||
break;
|
||||
|
||||
case MANUAL:
|
||||
// servo_out is for Sim control only
|
||||
// ---------------------------------
|
||||
|
@ -96,20 +96,18 @@ static void set_servos(void)
|
||||
g.channel_throttle.radio_out = g.channel_throttle.radio_in;
|
||||
g.channel_rudder.radio_out = g.channel_roll.radio_in;
|
||||
} else {
|
||||
|
||||
g.channel_roll.calc_pwm();
|
||||
g.channel_roll.calc_pwm();
|
||||
g.channel_pitch.calc_pwm();
|
||||
g.channel_rudder.calc_pwm();
|
||||
|
||||
g.channel_throttle.radio_out = g.channel_throttle.radio_in;
|
||||
g.channel_throttle.servo_out = constrain(g.channel_throttle.servo_out, g.throttle_min.get(), g.throttle_max.get());
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
if (control_mode >= FLY_BY_WIRE_B) {
|
||||
// convert 0 to 100% into PWM
|
||||
g.channel_throttle.calc_pwm();
|
||||
}
|
||||
if (control_mode >= AUTO) {
|
||||
// convert 0 to 100% into PWM
|
||||
g.channel_throttle.calc_pwm();
|
||||
}
|
||||
|
||||
|
||||
#if HIL_MODE == HIL_MODE_DISABLED || HIL_SERVOS
|
||||
|
@ -42,9 +42,6 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
|
||||
base_mode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
|
||||
break;
|
||||
case LEARNING:
|
||||
case FLY_BY_WIRE_A:
|
||||
case FLY_BY_WIRE_B:
|
||||
case FLY_BY_WIRE_C:
|
||||
base_mode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
|
||||
break;
|
||||
case AUTO:
|
||||
@ -141,29 +138,12 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
|
||||
break;
|
||||
|
||||
case LEARNING:
|
||||
case FLY_BY_WIRE_A:
|
||||
control_sensors_enabled |= (1<<10); // 3D angular rate control
|
||||
control_sensors_enabled |= (1<<11); // attitude stabilisation
|
||||
break;
|
||||
|
||||
case FLY_BY_WIRE_B:
|
||||
control_sensors_enabled |= (1<<10); // 3D angular rate control
|
||||
control_sensors_enabled |= (1<<11); // attitude stabilisation
|
||||
control_sensors_enabled |= (1<<15); // motor control
|
||||
break;
|
||||
|
||||
case FLY_BY_WIRE_C:
|
||||
control_sensors_enabled |= (1<<10); // 3D angular rate control
|
||||
control_sensors_enabled |= (1<<11); // attitude stabilisation
|
||||
control_sensors_enabled |= (1<<13); // altitude control
|
||||
control_sensors_enabled |= (1<<15); // motor control
|
||||
break;
|
||||
|
||||
case AUTO:
|
||||
case RTL:
|
||||
case LOITER:
|
||||
case GUIDED:
|
||||
case CIRCLE:
|
||||
control_sensors_enabled |= (1<<10); // 3D angular rate control
|
||||
control_sensors_enabled |= (1<<11); // attitude stabilisation
|
||||
control_sensors_enabled |= (1<<12); // yaw position
|
||||
@ -1012,11 +992,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
|
||||
switch(packet.command) {
|
||||
|
||||
case MAV_CMD_NAV_LOITER_UNLIM:
|
||||
set_mode(LOITER);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
||||
set_mode(RTL);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
@ -1070,14 +1045,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
}
|
||||
switch (packet.custom_mode) {
|
||||
case MANUAL:
|
||||
case CIRCLE:
|
||||
case LEARNING:
|
||||
case FLY_BY_WIRE_A:
|
||||
case FLY_BY_WIRE_B:
|
||||
case FLY_BY_WIRE_C:
|
||||
case AUTO:
|
||||
case RTL:
|
||||
case LOITER:
|
||||
set_mode(packet.custom_mode);
|
||||
break;
|
||||
}
|
||||
|
@ -29,8 +29,6 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
GSCALAR(crosstrack_gain, "XTRK_GAIN_SC", XTRACK_GAIN_SCALED),
|
||||
GSCALAR(crosstrack_entry_angle, "XTRK_ANGLE_CD", XTRACK_ENTRY_ANGLE_CENTIDEGREE),
|
||||
|
||||
GSCALAR(altitude_mix, "ALT_MIX", ALTITUDE_MIX),
|
||||
|
||||
GSCALAR(command_total, "CMD_TOTAL", 0),
|
||||
GSCALAR(command_index, "CMD_INDEX", 0),
|
||||
GSCALAR(waypoint_radius, "WP_RADIUS", WP_RADIUS_DEFAULT),
|
||||
@ -61,10 +59,6 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
|
||||
GSCALAR(auto_trim, "TRIM_AUTO", AUTO_TRIM),
|
||||
GSCALAR(switch_enable, "SWITCH_ENABLE", REVERSE_SWITCH),
|
||||
GSCALAR(mix_mode, "ELEVON_MIXING", ELEVON_MIXING),
|
||||
GSCALAR(reverse_elevons, "ELEVON_REVERSE", ELEVON_REVERSE),
|
||||
GSCALAR(reverse_ch1_elevon, "ELEVON_CH1_REV", ELEVON_CH1_REVERSE),
|
||||
GSCALAR(reverse_ch2_elevon, "ELEVON_CH2_REV", ELEVON_CH2_REVERSE),
|
||||
GSCALAR(num_resets, "SYS_NUM_RESETS", 0),
|
||||
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
|
||||
GSCALAR(log_last_filenumber, "LOG_LASTFILE", 0),
|
||||
@ -74,11 +68,6 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
GSCALAR(ch7_option, "CH7_OPT", CH7_OPTION),
|
||||
|
||||
GSCALAR(compass_enabled, "MAG_ENABLE", MAGNETOMETER),
|
||||
GSCALAR(flap_1_percent, "FLAP_1_PERCNT", FLAP_1_PERCENT),
|
||||
GSCALAR(flap_1_speed, "FLAP_1_SPEED", FLAP_2_SPEED),
|
||||
GSCALAR(flap_2_percent, "FLAP_2_PERCNT", FLAP_2_PERCENT),
|
||||
GSCALAR(flap_2_speed, "FLAP_2_SPEED", FLAP_2_SPEED),
|
||||
|
||||
|
||||
GSCALAR(battery_monitoring, "BATT_MONITOR", DISABLED),
|
||||
GSCALAR(volt_div_ratio, "VOLT_DIVIDER", VOLT_DIV_RATIO),
|
||||
|
@ -50,23 +50,6 @@
|
||||
# define CONFIG_APM_HARDWARE APM_HARDWARE_APM1
|
||||
#endif
|
||||
|
||||
#ifndef X_PLANE
|
||||
# define X_PLANE DISABLED
|
||||
#endif
|
||||
|
||||
#if X_PLANE == ENABLED
|
||||
# define LITE ENABLED
|
||||
#else
|
||||
#ifndef LITE
|
||||
# define LITE DISABLED
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if defined( __AVR_ATmega1280__ )
|
||||
#define CLI_ENABLED DISABLED
|
||||
#define LOGGING_ENABLED DISABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// APM2 HARDWARE DEFAULTS
|
||||
//
|
||||
@ -77,13 +60,7 @@
|
||||
# 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
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
@ -181,14 +158,6 @@
|
||||
#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
|
||||
|
||||
#undef CONFIG_SONAR
|
||||
#define CONFIG_SONAR DISABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// GPS_PROTOCOL
|
||||
//
|
||||
@ -232,14 +201,10 @@
|
||||
#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
|
||||
@ -304,18 +269,6 @@
|
||||
#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
|
||||
@ -432,25 +385,6 @@
|
||||
# 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
|
||||
#ifndef FLAPERON
|
||||
# define FLAPERON DISABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// MOUNT (ANTENNA OR CAMERA)
|
||||
//
|
||||
@ -458,31 +392,6 @@
|
||||
# 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
|
||||
//
|
||||
@ -517,23 +426,6 @@
|
||||
#endif
|
||||
#define MIN_GNDSPEED_CM MIN_GNDSPEED*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
|
||||
//
|
||||
|
@ -96,19 +96,12 @@
|
||||
#define CIRCLE 1 // When flying sans GPS, and we loose the radio, just circle
|
||||
#define LEARNING 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
|
||||
#define HEADALT 17 // Lock the current heading and altitude
|
||||
#define LAND 21 // Landing mode
|
||||
|
||||
// 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
|
||||
|
@ -11,9 +11,6 @@ static void failsafe_short_on_event(int fstype)
|
||||
{
|
||||
case MANUAL:
|
||||
case LEARNING:
|
||||
case FLY_BY_WIRE_A: // middle position
|
||||
case FLY_BY_WIRE_B: // middle position
|
||||
set_mode(CIRCLE);
|
||||
break;
|
||||
|
||||
case AUTO:
|
||||
@ -42,8 +39,6 @@ static void failsafe_long_on_event(int fstype)
|
||||
{
|
||||
case MANUAL:
|
||||
case LEARNING:
|
||||
case FLY_BY_WIRE_A: // middle position
|
||||
case FLY_BY_WIRE_B: // middle position
|
||||
case CIRCLE:
|
||||
set_mode(RTL);
|
||||
break;
|
||||
|
@ -227,8 +227,6 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
|
||||
mode != MANUAL &&
|
||||
mode != CIRCLE &&
|
||||
mode != LEARNING &&
|
||||
mode != FLY_BY_WIRE_A &&
|
||||
mode != FLY_BY_WIRE_B &&
|
||||
mode != AUTO &&
|
||||
mode != RTL &&
|
||||
mode != LOITER)
|
||||
|
@ -368,35 +368,25 @@ static void set_mode(byte mode)
|
||||
|
||||
control_mode = mode;
|
||||
crash_timer = 0;
|
||||
throttle_last = 0;
|
||||
throttle = 500;
|
||||
throttle_last = 0;
|
||||
throttle = 500;
|
||||
|
||||
switch(control_mode)
|
||||
{
|
||||
case MANUAL:
|
||||
case LEARNING:
|
||||
case CIRCLE:
|
||||
case FLY_BY_WIRE_A:
|
||||
case FLY_BY_WIRE_B:
|
||||
break;
|
||||
|
||||
case AUTO:
|
||||
rtl_complete = false;
|
||||
restart_nav();
|
||||
rtl_complete = false;
|
||||
restart_nav();
|
||||
break;
|
||||
|
||||
case RTL:
|
||||
do_RTL();
|
||||
break;
|
||||
|
||||
case LOITER:
|
||||
do_loiter_at_location();
|
||||
break;
|
||||
|
||||
case GUIDED:
|
||||
set_guided_WP();
|
||||
break;
|
||||
|
||||
default:
|
||||
do_RTL();
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user