Skip to content
Snippets Groups Projects
Commit 89c99ce1 authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

Rover: enable AP_BoardConfig

parent b5822cd5
No related branches found
No related tags found
No related merge requests found
...@@ -92,6 +92,7 @@ ...@@ -92,6 +92,7 @@
#include <AP_Navigation.h> #include <AP_Navigation.h>
#include <APM_Control.h> #include <APM_Control.h>
#include <AP_L1_Control.h> #include <AP_L1_Control.h>
#include <AP_BoardConfig.h>
#include <AP_HAL_AVR.h> #include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.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 // mapping between input channels
static RCMapper rcmap; static RCMapper rcmap;
// board specific config
static AP_BoardConfig BoardConfig;
// primary control channels // primary control channels
static RC_Channel *channel_steer; static RC_Channel *channel_steer;
static RC_Channel *channel_throttle; static RC_Channel *channel_throttle;
......
...@@ -34,6 +34,7 @@ public: ...@@ -34,6 +34,7 @@ public:
k_param_initial_mode, k_param_initial_mode,
k_param_scheduler, k_param_scheduler,
k_param_relay, k_param_relay,
k_param_BoardConfig,
// IO pins // IO pins
k_param_rssi_pin = 20, k_param_rssi_pin = 20,
......
...@@ -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 // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
GOBJECT(battery, "BATT_", AP_BattMonitor), GOBJECT(battery, "BATT_", AP_BattMonitor),
// @Group: BRD_
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
AP_VAREND AP_VAREND
}; };
......
...@@ -104,6 +104,8 @@ static void init_ardupilot() ...@@ -104,6 +104,8 @@ static void init_ardupilot()
load_parameters(); load_parameters();
BoardConfig.init();
set_control_channels(); set_control_channels();
// after parameter load setup correct baud rate on uartA // after parameter load setup correct baud rate on uartA
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment