ArduSub: move of CAN parameters into separate group

This commit is contained in:
Eugene Shamaev 2017-05-06 12:12:08 +03:00 committed by Francisco Ferreira
parent b95ebadf8b
commit 7314b515c0
4 changed files with 16 additions and 1 deletions

View File

@ -624,6 +624,12 @@ const AP_Param::Info Sub::var_info[] = {
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
#if HAL_WITH_UAVCAN
// @Group: CAN_
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig_CAN.cpp
GOBJECT(BoardConfig_CAN, "CAN_", AP_BoardConfig_CAN),
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
GOBJECT(sitl, "SIM_", SITL::SITL),
#endif

View File

@ -69,7 +69,7 @@ public:
k_param_serial_manager, // Serial ports, AP_SerialManager
k_param_notify, // Notify Library, AP_Notify
k_param_arming = 26, // Arming checks
k_param_BoardConfig_CAN,
// Sensor objects
k_param_ins = 30, // AP_InertialSensor

View File

@ -69,6 +69,7 @@
#include <AP_Notify/AP_Notify.h> // Notify library
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
#include <AP_BoardConfig/AP_BoardConfig.h> // board configuration library
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
#include <AP_Terrain/AP_Terrain.h>
#include <AP_JSButton/AP_JSButton.h> // Joystick/gamepad button function assignment
#include <AP_LeakDetector/AP_LeakDetector.h> // Leak detector
@ -251,6 +252,11 @@ private:
// board specific config
AP_BoardConfig BoardConfig;
#if HAL_WITH_UAVCAN
// board specific config for CAN bus
AP_BoardConfig_CAN BoardConfig_CAN;
#endif
// Failsafe
struct {
uint8_t pilot_input : 1; // true if pilot input failsafe is active, handles things like joystick being disconnected during operation

View File

@ -31,6 +31,9 @@ void Sub::init_ardupilot()
load_parameters();
BoardConfig.init();
#if HAL_WITH_UAVCAN
BoardConfig_CAN.init();
#endif
// identify ourselves correctly with the ground station
mavlink_system.sysid = g.sysid_this_mav;