APMrover2: remove checks for HAL_BOARD_APM2 and HAL_BOARD_APM1
This commit is contained in:
parent
3b0a1ef563
commit
45ba94343d
@ -197,9 +197,7 @@ const AP_Param::Info Rover::var_info[] = {
|
|||||||
// @Group: RC9_
|
// @Group: RC9_
|
||||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||||
GGROUP(rc_9, "RC9_", RC_Channel_aux),
|
GGROUP(rc_9, "RC9_", RC_Channel_aux),
|
||||||
#endif
|
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
|
||||||
// @Group: RC10_
|
// @Group: RC10_
|
||||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||||
GGROUP(rc_10, "RC10_", RC_Channel_aux),
|
GGROUP(rc_10, "RC10_", RC_Channel_aux),
|
||||||
@ -207,9 +205,7 @@ const AP_Param::Info Rover::var_info[] = {
|
|||||||
// @Group: RC11_
|
// @Group: RC11_
|
||||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||||
GGROUP(rc_11, "RC11_", RC_Channel_aux),
|
GGROUP(rc_11, "RC11_", RC_Channel_aux),
|
||||||
#endif
|
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
|
||||||
// @Group: RC12_
|
// @Group: RC12_
|
||||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||||
GGROUP(rc_12, "RC12_", RC_Channel_aux),
|
GGROUP(rc_12, "RC12_", RC_Channel_aux),
|
||||||
|
@ -245,12 +245,8 @@ public:
|
|||||||
RC_Channel_aux rc_8;
|
RC_Channel_aux rc_8;
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||||
RC_Channel_aux rc_9;
|
RC_Channel_aux rc_9;
|
||||||
#endif
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
|
||||||
RC_Channel_aux rc_10;
|
RC_Channel_aux rc_10;
|
||||||
RC_Channel_aux rc_11;
|
RC_Channel_aux rc_11;
|
||||||
#endif
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
|
||||||
RC_Channel_aux rc_12;
|
RC_Channel_aux rc_12;
|
||||||
RC_Channel_aux rc_13;
|
RC_Channel_aux rc_13;
|
||||||
RC_Channel_aux rc_14;
|
RC_Channel_aux rc_14;
|
||||||
@ -310,12 +306,8 @@ public:
|
|||||||
rc_8(CH_8),
|
rc_8(CH_8),
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||||
rc_9(CH_9),
|
rc_9(CH_9),
|
||||||
#endif
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
|
||||||
rc_10(CH_10),
|
rc_10(CH_10),
|
||||||
rc_11(CH_11),
|
rc_11(CH_11),
|
||||||
#endif
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
|
||||||
rc_12(CH_12),
|
rc_12(CH_12),
|
||||||
rc_13(CH_13),
|
rc_13(CH_13),
|
||||||
rc_14(CH_14),
|
rc_14(CH_14),
|
||||||
|
@ -32,18 +32,6 @@
|
|||||||
/// change in your local copy of APM_Config.h.
|
/// change in your local copy of APM_Config.h.
|
||||||
///
|
///
|
||||||
|
|
||||||
#if defined( __AVR_ATmega1280__ )
|
|
||||||
// default choices for a 1280. We can't fit everything in, so we
|
|
||||||
// make some popular choices by default
|
|
||||||
#define LOGGING_ENABLED DISABLED
|
|
||||||
#ifndef MOUNT
|
|
||||||
# define MOUNT DISABLED
|
|
||||||
#endif
|
|
||||||
#ifndef CAMERA
|
|
||||||
# define CAMERA DISABLED
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Just so that it's completely clear...
|
// Just so that it's completely clear...
|
||||||
#define ENABLED 1
|
#define ENABLED 1
|
||||||
#define DISABLED 0
|
#define DISABLED 0
|
||||||
@ -58,13 +46,7 @@
|
|||||||
#define HIL_MODE HIL_MODE_DISABLED
|
#define HIL_MODE HIL_MODE_DISABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
# define BATTERY_PIN_1 0
|
|
||||||
# define CURRENT_PIN_1 1
|
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
|
||||||
# define BATTERY_PIN_1 1
|
|
||||||
# define CURRENT_PIN_1 2
|
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
||||||
# define BATTERY_PIN_1 1
|
# define BATTERY_PIN_1 1
|
||||||
# define CURRENT_PIN_1 2
|
# define CURRENT_PIN_1 2
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
@ -98,12 +80,8 @@
|
|||||||
//
|
//
|
||||||
|
|
||||||
#ifndef FRSKY_TELEM_ENABLED
|
#ifndef FRSKY_TELEM_ENABLED
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
|
||||||
# define FRSKY_TELEM_ENABLED DISABLED
|
|
||||||
#else
|
|
||||||
#define FRSKY_TELEM_ENABLED ENABLED
|
#define FRSKY_TELEM_ENABLED ENABLED
|
||||||
#endif
|
#endif
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
#ifndef CH7_OPTION
|
#ifndef CH7_OPTION
|
||||||
@ -286,25 +264,7 @@
|
|||||||
# define LOGGING_ENABLED ENABLED
|
# define LOGGING_ENABLED ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
|
||||||
#define DEFAULT_LOG_BITMASK \
|
|
||||||
MASK_LOG_ATTITUDE_MED | \
|
|
||||||
MASK_LOG_GPS | \
|
|
||||||
MASK_LOG_PM | \
|
|
||||||
MASK_LOG_CTUN | \
|
|
||||||
MASK_LOG_NTUN | \
|
|
||||||
MASK_LOG_MODE | \
|
|
||||||
MASK_LOG_CMD | \
|
|
||||||
MASK_LOG_SONAR | \
|
|
||||||
MASK_LOG_COMPASS | \
|
|
||||||
MASK_LOG_CURRENT | \
|
|
||||||
MASK_LOG_STEERING | \
|
|
||||||
MASK_LOG_CAMERA
|
|
||||||
#else
|
|
||||||
// other systems have plenty of space for full logs
|
|
||||||
#define DEFAULT_LOG_BITMASK 0xffff
|
#define DEFAULT_LOG_BITMASK 0xffff
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
@ -74,10 +74,6 @@ static void failsafe_check_static()
|
|||||||
rover.failsafe_check();
|
rover.failsafe_check();
|
||||||
}
|
}
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
|
||||||
AP_ADC_ADS7844 apm1_adc;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
void Rover::init_ardupilot()
|
void Rover::init_ardupilot()
|
||||||
{
|
{
|
||||||
// initialise console serial port
|
// initialise console serial port
|
||||||
@ -147,10 +143,6 @@ void Rover::init_ardupilot()
|
|||||||
// more than 5ms remaining in your call to hal.scheduler->delay
|
// more than 5ms remaining in your call to hal.scheduler->delay
|
||||||
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
|
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
|
||||||
apm1_adc.Init(); // APM ADC library initialization
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (g.compass_enabled==true) {
|
if (g.compass_enabled==true) {
|
||||||
if (!compass.init()|| !compass.read()) {
|
if (!compass.init()|| !compass.read()) {
|
||||||
cliSerial->println("Compass initialisation failed!");
|
cliSerial->println("Compass initialisation failed!");
|
||||||
@ -431,18 +423,6 @@ void Rover::check_usb_mux(void)
|
|||||||
|
|
||||||
// the user has switched to/from the telemetry port
|
// the user has switched to/from the telemetry port
|
||||||
usb_connected = usb_check;
|
usb_connected = usb_check;
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
|
||||||
// the APM2 has a MUX setup where the first serial port switches
|
|
||||||
// between USB and a TTL serial connection. When on USB we use
|
|
||||||
// SERIAL0_BAUD, but when connected as a TTL serial port we run it
|
|
||||||
// at SERIAL1_BAUD.
|
|
||||||
if (usb_connected) {
|
|
||||||
serial_manager.set_console_baud(AP_SerialManager::SerialProtocol_Console, 0);
|
|
||||||
} else {
|
|
||||||
serial_manager.set_console_baud(AP_SerialManager::SerialProtocol_MAVLink, 0);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user