Browse Source

Rover: enable AP_BoardConfig

master
Andrew Tridgell 11 years ago
parent
commit
89c99ce145
  1. 4
      APMrover2/APMrover2.pde
  2. 1
      APMrover2/Parameters.h
  3. 4
      APMrover2/Parameters.pde
  4. 2
      APMrover2/system.pde

4
APMrover2/APMrover2.pde

@ -92,6 +92,7 @@ @@ -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; @@ -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;

1
APMrover2/Parameters.h

@ -34,6 +34,7 @@ public: @@ -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,

4
APMrover2/Parameters.pde

@ -482,6 +482,10 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -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
};

2
APMrover2/system.pde

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

Loading…
Cancel
Save