Rover: use AP_BEACON_ENABLED instead of BEACON_ENABLED

This commit is contained in:
Peter Barker 2023-04-09 18:54:09 +10:00 committed by Peter Barker
parent f2cc1c501b
commit ff21f86a9c
4 changed files with 12 additions and 0 deletions

View File

@ -425,9 +425,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
AP_SUBGROUPINFO(afs, "AFS_", 5, ParametersG2, AP_AdvancedFailsafe), AP_SUBGROUPINFO(afs, "AFS_", 5, ParametersG2, AP_AdvancedFailsafe),
#endif #endif
#if AP_BEACON_ENABLED
// @Group: BCN // @Group: BCN
// @Path: ../libraries/AP_Beacon/AP_Beacon.cpp // @Path: ../libraries/AP_Beacon/AP_Beacon.cpp
AP_SUBGROUPINFO(beacon, "BCN", 6, ParametersG2, AP_Beacon), AP_SUBGROUPINFO(beacon, "BCN", 6, ParametersG2, AP_Beacon),
#endif
// 7 was used by AP_VisualOdometry // 7 was used by AP_VisualOdometry
@ -730,7 +732,9 @@ ParametersG2::ParametersG2(void)
#if ADVANCED_FAILSAFE == ENABLED #if ADVANCED_FAILSAFE == ENABLED
afs(), afs(),
#endif #endif
#if AP_BEACON_ENABLED
beacon(), beacon(),
#endif
motors(rover.ServoRelayEvents, wheel_rate_control), motors(rover.ServoRelayEvents, wheel_rate_control),
wheel_rate_control(wheel_encoder), wheel_rate_control(wheel_encoder),
attitude_control(), attitude_control(),

View File

@ -312,7 +312,9 @@ public:
AP_AdvancedFailsafe_Rover afs; AP_AdvancedFailsafe_Rover afs;
#endif #endif
#if AP_BEACON_ENABLED
AP_Beacon beacon; AP_Beacon beacon;
#endif
// Motor library // Motor library
AP_MotorsUGV motors; AP_MotorsUGV motors;

View File

@ -80,7 +80,9 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
SCHED_TASK(set_servos, 400, 200, 15), SCHED_TASK(set_servos, 400, 200, 15),
SCHED_TASK_CLASS(AP_GPS, &rover.gps, update, 50, 300, 18), SCHED_TASK_CLASS(AP_GPS, &rover.gps, update, 50, 300, 18),
SCHED_TASK_CLASS(AP_Baro, &rover.barometer, update, 10, 200, 21), SCHED_TASK_CLASS(AP_Baro, &rover.barometer, update, 10, 200, 21),
#if AP_BEACON_ENABLED
SCHED_TASK_CLASS(AP_Beacon, &rover.g2.beacon, update, 50, 200, 24), SCHED_TASK_CLASS(AP_Beacon, &rover.g2.beacon, update, 50, 200, 24),
#endif
#if HAL_PROXIMITY_ENABLED #if HAL_PROXIMITY_ENABLED
SCHED_TASK_CLASS(AP_Proximity, &rover.g2.proximity, update, 50, 200, 27), SCHED_TASK_CLASS(AP_Proximity, &rover.g2.proximity, update, 50, 200, 27),
#endif #endif
@ -377,7 +379,9 @@ void Rover::update_logging1(void)
if (should_log(MASK_LOG_THR)) { if (should_log(MASK_LOG_THR)) {
Log_Write_Throttle(); Log_Write_Throttle();
#if AP_BEACON_ENABLED
g2.beacon.log(); g2.beacon.log();
#endif
} }
if (should_log(MASK_LOG_NTUN)) { if (should_log(MASK_LOG_NTUN)) {

View File

@ -75,8 +75,10 @@ void Rover::init_ardupilot()
g2.proximity.init(); g2.proximity.init();
#endif #endif
#if AP_BEACON_ENABLED
// init beacons used for non-gps position estimation // init beacons used for non-gps position estimation
g2.beacon.init(); g2.beacon.init();
#endif
// and baro for EKF // and baro for EKF
barometer.set_log_baro_bit(MASK_LOG_IMU); barometer.set_log_baro_bit(MASK_LOG_IMU);