ArduPlane: move of CAN parameters into separate group

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

View File

@ -1088,6 +1088,12 @@ const AP_Param::Info Plane::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
// @Group: SIM_
// @Path: ../libraries/SITL/SITL.cpp

View File

@ -53,6 +53,7 @@ public:
k_param_avoidance_adsb,
k_param_landing,
k_param_NavEKF3,
k_param_BoardConfig_CAN,
// Misc
//

View File

@ -82,6 +82,7 @@
#include <AP_Arming/AP_Arming.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
@ -172,6 +173,11 @@ private:
// board specific config
AP_BoardConfig BoardConfig;
// board specific config for CAN bus
#if HAL_WITH_UAVCAN
AP_BoardConfig_CAN BoardConfig_CAN;
#endif
// primary input channels
RC_Channel *channel_roll;
RC_Channel *channel_pitch;

View File

@ -140,6 +140,9 @@ void Plane::init_ardupilot()
// setup any board specific drivers
BoardConfig.init();
#if HAL_WITH_UAVCAN
BoardConfig_CAN.init();
#endif
relay.init();