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

Plane: enable AP_BoardConfig

parent 50a90a10
No related branches found
No related tags found
No related merge requests found
......@@ -74,6 +74,7 @@
#include <AP_BattMonitor.h> // Battery monitor library
#include <AP_Arming.h>
#include <AP_BoardConfig.h>
// Pre-AP_HAL compatibility
#include "compat.h"
......@@ -127,6 +128,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_roll;
static RC_Channel *channel_pitch;
......
......@@ -100,6 +100,7 @@ public:
k_param_hil_err_limit,
k_param_sonar,
k_param_log_bitmask,
k_param_BoardConfig,
// 100: Arming parameters
k_param_arming = 100,
......
......@@ -938,6 +938,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),
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
// @Group: SIM_
// @Path: ../libraries/SITL/SITL.cpp
......
......@@ -92,6 +92,8 @@ static void init_ardupilot()
//
load_parameters();
BoardConfig.init();
set_control_channels();
// reset the uartA baud rate after parameter load
......
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