APMrover2: move of CAN parameters into separate group

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

View File

@ -470,6 +470,12 @@ const AP_Param::Info Rover::var_info[] = {
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp // @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig), 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
// GPS driver // GPS driver
// @Group: GPS_ // @Group: GPS_
// @Path: ../libraries/AP_GPS/AP_GPS.cpp // @Path: ../libraries/AP_GPS/AP_GPS.cpp

View File

@ -22,6 +22,7 @@ public:
// //
k_param_format_version = 0, k_param_format_version = 0,
k_param_software_type, k_param_software_type,
k_param_BoardConfig_CAN,
// Misc // Misc
// //

View File

@ -61,6 +61,7 @@
#include <APM_Control/APM_Control.h> #include <APM_Control/APM_Control.h>
#include <AP_L1_Control/AP_L1_Control.h> #include <AP_L1_Control/AP_L1_Control.h>
#include <AP_BoardConfig/AP_BoardConfig.h> #include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
#include <AP_Frsky_Telem/AP_Frsky_Telem.h> #include <AP_Frsky_Telem/AP_Frsky_Telem.h>
#include "AP_Arming.h" #include "AP_Arming.h"
@ -129,6 +130,11 @@ private:
// board specific config // board specific config
AP_BoardConfig BoardConfig; AP_BoardConfig BoardConfig;
#if HAL_WITH_UAVCAN
// board specific config for CAN bus
AP_BoardConfig_CAN BoardConfig_CAN;
#endif
// primary control channels // primary control channels
RC_Channel *channel_steer; RC_Channel *channel_steer;
RC_Channel *channel_throttle; RC_Channel *channel_throttle;

View File

@ -107,6 +107,9 @@ void Rover::init_ardupilot()
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5); hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
BoardConfig.init(); BoardConfig.init();
#if HAL_WITH_UAVCAN
BoardConfig_CAN.init();
#endif
// initialise notify system // initialise notify system
notify.init(false); notify.init(false);