AntennaTracker: added boardconfig object

this allows the safety switch to be disabled
This commit is contained in:
Andrew Tridgell 2014-03-27 08:06:50 +11:00
parent 55c60b8f07
commit 72c12fb2b3
4 changed files with 11 additions and 1 deletions

View File

@ -58,6 +58,7 @@
#include <AP_BattMonitor.h> // Battery monitor library
#include <AP_Airspeed.h>
#include <RC_Channel.h>
#include <AP_BoardConfig.h>
// Configuration
#include "config.h"
@ -191,6 +192,9 @@ static RC_Channel channel_pitch(CH_2);
static const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;
static GCS_MAVLINK gcs[MAVLINK_COMM_NUM_BUFFERS];
// board specific config
static AP_BoardConfig BoardConfig;
////////////////////////////////////////////////////////////////////////////////
// 3D Location vectors
// Location structure defined in AP_Common

View File

@ -76,8 +76,8 @@ public:
k_param_start_latitude,
k_param_start_longitude,
k_param_startup_delay,
k_param_BoardConfig,
k_param_channel_yaw = 200,
k_param_channel_pitch,

View File

@ -149,6 +149,10 @@ const AP_Param::Info var_info[] PROGMEM = {
GOBJECT(sitl, "SIM_", SITL),
#endif
// @Group: BRD_
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
// RC channel
//-----------
// @Group: RC1_

View File

@ -14,6 +14,8 @@ static void init_tracker()
// Check the EEPROM format version before loading any parameters from EEPROM
load_parameters();
BoardConfig.init();
// reset the uartA baud rate after parameter load
hal.uartA->begin(map_baudrate(g.serial0_baud, SERIAL0_BAUD));