mirror of https://github.com/ArduPilot/ardupilot
AntennaTracker: move of CAN parameters into separate group
This commit is contained in:
parent
c75f30eb9b
commit
b365a4ddf5
|
@ -293,6 +293,12 @@ const AP_Param::Info Tracker::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
|
||||
|
||||
// GPS driver
|
||||
// @Group: GPS_
|
||||
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
|
||||
|
|
|
@ -92,6 +92,7 @@ public:
|
|||
k_param_gcs3, // stream rates for fourth MAVLink port
|
||||
k_param_log_bitmask, // 140
|
||||
k_param_notify,
|
||||
k_param_BoardConfig_CAN,
|
||||
|
||||
//
|
||||
// 150: Telemetry control
|
||||
|
|
|
@ -58,6 +58,7 @@
|
|||
#include <AP_Airspeed/AP_Airspeed.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
|
||||
#include <AP_OpticalFlow/AP_OpticalFlow.h>
|
||||
#include <AP_RangeFinder/AP_RangeFinder.h>
|
||||
#include <AP_Beacon/AP_Beacon.h>
|
||||
|
@ -142,6 +143,11 @@ private:
|
|||
|
||||
AP_BoardConfig BoardConfig;
|
||||
|
||||
#if HAL_WITH_UAVCAN
|
||||
// board specific config for CAN bus
|
||||
AP_BoardConfig_CAN BoardConfig_CAN;
|
||||
#endif
|
||||
|
||||
struct Location current_loc;
|
||||
|
||||
enum ControlMode control_mode = INITIALISING;
|
||||
|
|
|
@ -41,6 +41,9 @@ void Tracker::init_tracker()
|
|||
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
|
||||
|
||||
BoardConfig.init();
|
||||
#if HAL_WITH_UAVCAN
|
||||
BoardConfig_CAN.init();
|
||||
#endif
|
||||
|
||||
// initialise notify
|
||||
notify.init(false);
|
||||
|
|
Loading…
Reference in New Issue