From 1b69cf68ec3b7ef36ee090a8e6d564106e64ff27 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 25 Mar 2021 17:47:29 +0900 Subject: [PATCH] Rover: integrate HAL_PROXIMITY_ENABLED --- Rover/GCS_Rover.cpp | 5 +++++ Rover/Parameters.cpp | 4 ++++ Rover/Parameters.h | 2 ++ Rover/Rover.cpp | 4 ++++ Rover/system.cpp | 2 ++ 5 files changed, 17 insertions(+) diff --git a/Rover/GCS_Rover.cpp b/Rover/GCS_Rover.cpp index e045de3baf..60c9215a25 100644 --- a/Rover/GCS_Rover.cpp +++ b/Rover/GCS_Rover.cpp @@ -28,11 +28,13 @@ bool GCS_Rover::supersimple_input_active() const void GCS_Rover::update_vehicle_sensor_status_flags(void) { // first what sensors/controllers we have +#if HAL_PROXIMITY_ENABLED const AP_Proximity *proximity = AP_Proximity::get_singleton(); if (proximity && proximity->get_status() > AP_Proximity::Status::NotConnected) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; } +#endif control_sensors_present |= MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL | @@ -62,7 +64,10 @@ void GCS_Rover::update_vehicle_sensor_status_flags(void) control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; } } + +#if HAL_PROXIMITY_ENABLED if (proximity && proximity->get_status() != AP_Proximity::Status::NoData) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; } +#endif } diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 75b6b743f1..470f522a4a 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -496,9 +496,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Path: ../libraries/AC_Fence/AC_Fence.cpp AP_SUBGROUPINFO(fence, "FENCE_", 17, ParametersG2, AC_Fence), +#if HAL_PROXIMITY_ENABLED // @Group: PRX // @Path: ../libraries/AP_Proximity/AP_Proximity.cpp AP_SUBGROUPINFO(proximity, "PRX", 18, ParametersG2, AP_Proximity), +#endif // @Group: AVOID_ // @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp @@ -701,7 +703,9 @@ ParametersG2::ParametersG2(void) wheel_rate_control(wheel_encoder), attitude_control(rover.ahrs), smart_rtl(), +#if HAL_PROXIMITY_ENABLED proximity(), +#endif avoid(), follow(), windvane(), diff --git a/Rover/Parameters.h b/Rover/Parameters.h index 6940d54389..604c16f92a 100644 --- a/Rover/Parameters.h +++ b/Rover/Parameters.h @@ -329,8 +329,10 @@ public: // fence library AC_Fence fence; +#if HAL_PROXIMITY_ENABLED // proximity library AP_Proximity proximity; +#endif // avoidance library AC_Avoid avoid; diff --git a/Rover/Rover.cpp b/Rover/Rover.cpp index e6091757b7..60fba7f230 100644 --- a/Rover/Rover.cpp +++ b/Rover/Rover.cpp @@ -56,7 +56,9 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_GPS, &rover.gps, update, 50, 300), SCHED_TASK_CLASS(AP_Baro, &rover.barometer, update, 10, 200), SCHED_TASK_CLASS(AP_Beacon, &rover.g2.beacon, update, 50, 200), +#if HAL_PROXIMITY_ENABLED SCHED_TASK_CLASS(AP_Proximity, &rover.g2.proximity, update, 50, 200), +#endif SCHED_TASK_CLASS(AP_WindVane, &rover.g2.windvane, update, 20, 100), SCHED_TASK_CLASS(AC_Fence, &rover.g2.fence, update, 10, 100), SCHED_TASK(update_wheel_encoder, 50, 200), @@ -300,9 +302,11 @@ void Rover::update_logging1(void) Log_Write_Nav_Tuning(); } +#if HAL_PROXIMITY_ENABLED if (should_log(MASK_LOG_RANGEFINDER)) { logger.Write_Proximity(g2.proximity); } +#endif } /* diff --git a/Rover/system.cpp b/Rover/system.cpp index bc8471705d..b03b7fb59f 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -67,8 +67,10 @@ void Rover::init_ardupilot() // initialise rangefinder rangefinder.init(ROTATION_NONE); +#if HAL_PROXIMITY_ENABLED // init proximity sensor g2.proximity.init(); +#endif // init beacons used for non-gps position estimation g2.beacon.init();