mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 22:18:28 -04:00
Rover: use AP_BEACON_ENABLED instead of BEACON_ENABLED
This commit is contained in:
parent
f2cc1c501b
commit
ff21f86a9c
@ -425,9 +425,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
AP_SUBGROUPINFO(afs, "AFS_", 5, ParametersG2, AP_AdvancedFailsafe),
|
||||
#endif
|
||||
|
||||
#if AP_BEACON_ENABLED
|
||||
// @Group: BCN
|
||||
// @Path: ../libraries/AP_Beacon/AP_Beacon.cpp
|
||||
AP_SUBGROUPINFO(beacon, "BCN", 6, ParametersG2, AP_Beacon),
|
||||
#endif
|
||||
|
||||
// 7 was used by AP_VisualOdometry
|
||||
|
||||
@ -730,7 +732,9 @@ ParametersG2::ParametersG2(void)
|
||||
#if ADVANCED_FAILSAFE == ENABLED
|
||||
afs(),
|
||||
#endif
|
||||
#if AP_BEACON_ENABLED
|
||||
beacon(),
|
||||
#endif
|
||||
motors(rover.ServoRelayEvents, wheel_rate_control),
|
||||
wheel_rate_control(wheel_encoder),
|
||||
attitude_control(),
|
||||
|
@ -312,7 +312,9 @@ public:
|
||||
AP_AdvancedFailsafe_Rover afs;
|
||||
#endif
|
||||
|
||||
#if AP_BEACON_ENABLED
|
||||
AP_Beacon beacon;
|
||||
#endif
|
||||
|
||||
// Motor library
|
||||
AP_MotorsUGV motors;
|
||||
|
@ -80,7 +80,9 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
||||
SCHED_TASK(set_servos, 400, 200, 15),
|
||||
SCHED_TASK_CLASS(AP_GPS, &rover.gps, update, 50, 300, 18),
|
||||
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),
|
||||
#endif
|
||||
#if HAL_PROXIMITY_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Proximity, &rover.g2.proximity, update, 50, 200, 27),
|
||||
#endif
|
||||
@ -377,7 +379,9 @@ void Rover::update_logging1(void)
|
||||
|
||||
if (should_log(MASK_LOG_THR)) {
|
||||
Log_Write_Throttle();
|
||||
#if AP_BEACON_ENABLED
|
||||
g2.beacon.log();
|
||||
#endif
|
||||
}
|
||||
|
||||
if (should_log(MASK_LOG_NTUN)) {
|
||||
|
@ -75,8 +75,10 @@ void Rover::init_ardupilot()
|
||||
g2.proximity.init();
|
||||
#endif
|
||||
|
||||
#if AP_BEACON_ENABLED
|
||||
// init beacons used for non-gps position estimation
|
||||
g2.beacon.init();
|
||||
#endif
|
||||
|
||||
// and baro for EKF
|
||||
barometer.set_log_baro_bit(MASK_LOG_IMU);
|
||||
|
Loading…
Reference in New Issue
Block a user