Skip to content

Commit

Permalink
APMrover2: remove checks for HAL_BOARD_APM2 and HAL_BOARD_APM1
Browse files Browse the repository at this point in the history
  • Loading branch information
lucasdemarchi authored and tridge committed Nov 4, 2015
1 parent 3b0a1ef commit 45ba943
Show file tree
Hide file tree
Showing 4 changed files with 8 additions and 80 deletions.
4 changes: 0 additions & 4 deletions APMrover2/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -197,19 +197,15 @@ const AP_Param::Info Rover::var_info[] = {
// @Group: RC9_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
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_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_10, "RC10_", RC_Channel_aux),

// @Group: RC11_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_11, "RC11_", RC_Channel_aux),
#endif

#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
// @Group: RC12_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_12, "RC12_", RC_Channel_aux),
Expand Down
20 changes: 6 additions & 14 deletions APMrover2/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -245,12 +245,8 @@ class Parameters {
RC_Channel_aux rc_8;
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
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_11;
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
RC_Channel_aux rc_12;
RC_Channel_aux rc_13;
RC_Channel_aux rc_14;
Expand Down Expand Up @@ -309,16 +305,12 @@ class Parameters {
rc_7(CH_7),
rc_8(CH_8),
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
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_11 (CH_11),
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
rc_12 (CH_12),
rc_13 (CH_13),
rc_14 (CH_14),
rc_9(CH_9),
rc_10(CH_10),
rc_11(CH_11),
rc_12(CH_12),
rc_13(CH_13),
rc_14(CH_14),
#endif

// PID controller initial P initial I initial D initial imax
Expand Down
44 changes: 2 additions & 42 deletions APMrover2/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,18 +32,6 @@
/// 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...
#define ENABLED 1
#define DISABLED 0
Expand All @@ -58,13 +46,7 @@
#define HIL_MODE HIL_MODE_DISABLED
#endif

#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
# 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
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
# define BATTERY_PIN_1 1
# define CURRENT_PIN_1 2
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
Expand Down Expand Up @@ -98,11 +80,7 @@
//

#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
#endif
#define FRSKY_TELEM_ENABLED ENABLED
#endif


Expand Down Expand Up @@ -286,25 +264,7 @@
# define LOGGING_ENABLED ENABLED
#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
#endif



//////////////////////////////////////////////////////////////////////////////
Expand Down
20 changes: 0 additions & 20 deletions APMrover2/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,10 +74,6 @@ static void failsafe_check_static()
rover.failsafe_check();
}

#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
AP_ADC_ADS7844 apm1_adc;
#endif

void Rover::init_ardupilot()
{
// initialise console serial port
Expand Down Expand Up @@ -147,10 +143,6 @@ void Rover::init_ardupilot()
// more than 5ms remaining in your call to hal.scheduler->delay
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 (!compass.init()|| !compass.read()) {
cliSerial->println("Compass initialisation failed!");
Expand Down Expand Up @@ -431,18 +423,6 @@ void Rover::check_usb_mux(void)

// the user has switched to/from the telemetry port
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
}


Expand Down

0 comments on commit 45ba943

Please sign in to comment.