Rover: enable AP_BoardConfig

This commit is contained in:
Andrew Tridgell 2014-01-20 12:57:59 +11:00
parent b5822cd549
commit 89c99ce145
4 changed files with 11 additions and 0 deletions

View File

@ -92,6 +92,7 @@
#include <AP_Navigation.h>
#include <APM_Control.h>
#include <AP_L1_Control.h>
#include <AP_BoardConfig.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
@ -143,6 +144,9 @@ static AP_Scheduler scheduler;
// mapping between input channels
static RCMapper rcmap;
// board specific config
static AP_BoardConfig BoardConfig;
// primary control channels
static RC_Channel *channel_steer;
static RC_Channel *channel_throttle;

View File

@ -34,6 +34,7 @@ public:
k_param_initial_mode,
k_param_scheduler,
k_param_relay,
k_param_BoardConfig,
// IO pins
k_param_rssi_pin = 20,

View File

@ -482,6 +482,10 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
GOBJECT(battery, "BATT_", AP_BattMonitor),
// @Group: BRD_
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
AP_VAREND
};

View File

@ -104,6 +104,8 @@ static void init_ardupilot()
load_parameters();
BoardConfig.init();
set_control_channels();
// after parameter load setup correct baud rate on uartA