Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Copter/Sub/Rover/Plane: HAL_PROXIMITY_ENABLED to disable AP_Proximity #17006

Merged
merged 10 commits into from
Mar 26, 2021
2 changes: 0 additions & 2 deletions ArduCopter/APM_Config.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@
//#define AC_FENCE DISABLED // disable fence to save 2k of flash
//#define CAMERA DISABLED // disable camera trigger to save 1k of flash
//#define RANGEFINDER_ENABLED DISABLED // disable rangefinder to save 1k of flash
//#define PROXIMITY_ENABLED DISABLED // disable proximity sensors
//#define AC_RALLY DISABLED // disable rally points library (must also disable terrain which relies on rally)
//#define AC_AVOID_ENABLED DISABLED // disable stop-at-fence library
//#define AC_OAPATHPLANNER_ENABLED DISABLED // disable path planning around obstacles
Expand All @@ -19,7 +18,6 @@
//#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
//#define OPTFLOW DISABLED // disable optical flow sensor to save 5K of flash space
//#define FRSKY_TELEM_ENABLED DISABLED // disable FRSky telemetry
//#define ADSB_ENABLED DISABLED // disable ADSB support
//#define PRECISION_LANDING DISABLED // disable precision landing using companion computer or IRLock sensor
//#define BEACON_ENABLED DISABLED // disable beacon support
//#define SPRAYER_ENABLED DISABLED // disable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -477,7 +477,7 @@ bool AP_Arming_Copter::pre_arm_ekf_attitude_check()
// check nothing is too close to vehicle
bool AP_Arming_Copter::proximity_checks(bool display_failure) const
{
#if PROXIMITY_ENABLED == ENABLED
#if HAL_PROXIMITY_ENABLED

if (!AP_Arming::proximity_checks(display_failure)) {
return false;
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#if RANGEFINDER_ENABLED == ENABLED
SCHED_TASK(read_rangefinder, 20, 100),
#endif
#if PROXIMITY_ENABLED == ENABLED
#if HAL_PROXIMITY_ENABLED
SCHED_TASK_CLASS(AP_Proximity, &copter.g2.proximity, update, 200, 50),
#endif
#if BEACON_ENABLED == ENABLED
Expand Down Expand Up @@ -427,7 +427,7 @@ void Copter::ten_hz_logging_loop()
}
if (should_log(MASK_LOG_CTUN)) {
attitude_control->control_monitor_log();
#if PROXIMITY_ENABLED == ENABLED
#if HAL_PROXIMITY_ENABLED
logger.Write_Proximity(g2.proximity); // Write proximity sensor distances
#endif
#if BEACON_ENABLED == ENABLED
Expand Down
4 changes: 1 addition & 3 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@
#include <AP_Parachute/AP_Parachute.h>
#include <AC_Sprayer/AC_Sprayer.h>
#include <AP_ADSB/AP_ADSB.h>
#include <AP_Proximity/AP_Proximity.h>

// Configuration
#include "defines.h"
Expand Down Expand Up @@ -129,9 +130,6 @@
#if RANGEFINDER_ENABLED == ENABLED
# include <AP_RangeFinder/AP_RangeFinder.h>
#endif
#if PROXIMITY_ENABLED == ENABLED
# include <AP_Proximity/AP_Proximity.h>
#endif

#include <AP_Mount/AP_Mount.h>

Expand Down
6 changes: 3 additions & 3 deletions ArduCopter/GCS_Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
}
#if PROXIMITY_ENABLED == ENABLED
#if HAL_PROXIMITY_ENABLED
if (copter.g2.proximity.sensor_present()) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_PROXIMITY;
}
Expand Down Expand Up @@ -106,7 +106,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
break;
}

#if PROXIMITY_ENABLED == ENABLED
#if HAL_PROXIMITY_ENABLED
if (copter.g2.proximity.sensor_enabled()) {
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_PROXIMITY;
}
Expand All @@ -126,7 +126,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
}
#endif

#if PROXIMITY_ENABLED == ENABLED
#if HAL_PROXIMITY_ENABLED
if (!copter.g2.proximity.sensor_failed()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_PROXIMITY;
}
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -821,7 +821,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
AP_SUBGROUPINFO(beacon, "BCN", 14, ParametersG2, AP_Beacon),
#endif

#if PROXIMITY_ENABLED == ENABLED
#if HAL_PROXIMITY_ENABLED
// @Group: PRX
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
AP_SUBGROUPINFO(proximity, "PRX", 8, ParametersG2, AP_Proximity),
Expand Down Expand Up @@ -1065,7 +1065,7 @@ ParametersG2::ParametersG2(void)
#if BEACON_ENABLED == ENABLED
, beacon(copter.serial_manager)
#endif
#if PROXIMITY_ENABLED == ENABLED
#if HAL_PROXIMITY_ENABLED
, proximity()
#endif
#if ADVANCED_FAILSAFE == ENABLED
Expand Down
3 changes: 2 additions & 1 deletion ArduCopter/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

#include <AP_Common/AP_Common.h>
#include "RC_Channel.h"
#include <AP_Proximity/AP_Proximity.h>

#if GRIPPER_ENABLED == ENABLED
# include <AP_Gripper/AP_Gripper.h>
Expand Down Expand Up @@ -520,7 +521,7 @@ class ParametersG2 {
AP_Beacon beacon;
#endif

#if PROXIMITY_ENABLED == ENABLED
#if HAL_PROXIMITY_ENABLED
// proximity (aka object avoidance) library
AP_Proximity proximity;
#endif
Expand Down
10 changes: 0 additions & 10 deletions ArduCopter/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -116,13 +116,6 @@
# define RANGEFINDER_GLITCH_NUM_SAMPLES 3 // number of rangefinder glitches in a row to take new reading
#endif

//////////////////////////////////////////////////////////////////////////////
// Proximity sensor
//
#ifndef PROXIMITY_ENABLED
# define PROXIMITY_ENABLED ENABLED
#endif

#ifndef MAV_SYSTEM_ID
# define MAV_SYSTEM_ID 1
#endif
Expand Down Expand Up @@ -685,9 +678,6 @@
#define AC_OAPATHPLANNER_ENABLED !HAL_MINIMIZE_FEATURES
#endif

#if AC_AVOID_ENABLED && !PROXIMITY_ENABLED
#error AC_Avoidance relies on PROXIMITY_ENABLED which is disabled
#endif
#if AC_AVOID_ENABLED && !AC_FENCE
#error AC_Avoidance relies on AC_FENCE which is disabled
#endif
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/sensors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ void Copter::read_rangefinder(void)
#if MODE_CIRCLE_ENABLED
circle_nav->set_rangefinder_alt(rangefinder_state.enabled && wp_nav->rangefinder_used(), rangefinder_state.alt_healthy, rangefinder_state.alt_cm_filt.get());
#endif
#if PROXIMITY_ENABLED == ENABLED
#if HAL_PROXIMITY_ENABLED
g2.proximity.set_rangefinder_alt(rangefinder_state.enabled, rangefinder_state.alt_healthy, rangefinder_state.alt_cm_filt.get());
#endif
}
Expand Down Expand Up @@ -224,7 +224,7 @@ void Copter::accel_cal_update()
// initialise proximity sensor
void Copter::init_proximity(void)
{
#if PROXIMITY_ENABLED == ENABLED
#if HAL_PROXIMITY_ENABLED
g2.proximity.init();
#endif
}
2 changes: 1 addition & 1 deletion ArduSub/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -630,7 +630,7 @@ const AP_Param::Info Sub::var_info[] = {
*/
const AP_Param::GroupInfo ParametersG2::var_info[] = {

#if PROXIMITY_ENABLED == ENABLED
#if HAL_PROXIMITY_ENABLED
// @Group: PRX
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
AP_SUBGROUPINFO(proximity, "PRX", 2, ParametersG2, AP_Proximity),
Expand Down
2 changes: 1 addition & 1 deletion ArduSub/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -324,7 +324,7 @@ class ParametersG2 {
AP_Gripper gripper;
#endif

#if PROXIMITY_ENABLED == ENABLED
#if HAL_PROXIMITY_ENABLED
// proximity (aka object avoidance) library
AP_Proximity proximity;
#endif
Expand Down
5 changes: 1 addition & 4 deletions ArduSub/Sub.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,7 @@
#include <AP_JSButton/AP_JSButton.h> // Joystick/gamepad button function assignment
#include <AP_LeakDetector/AP_LeakDetector.h> // Leak detector
#include <AP_TemperatureSensor/TSYS01.h>
#include <AP_Proximity/AP_Proximity.h>

// Local modules
#include "defines.h"
Expand Down Expand Up @@ -93,10 +94,6 @@
#include <AP_Gripper/AP_Gripper.h> // gripper stuff
#endif

#if PROXIMITY_ENABLED == ENABLED
#include <AP_Proximity/AP_Proximity.h>
#endif

#if AVOIDANCE_ENABLED == ENABLED
#include <AC_Avoidance/AC_Avoid.h> // Stop at fence library
#endif
Expand Down
9 changes: 1 addition & 8 deletions ArduSub/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -88,17 +88,10 @@
# define AVOIDANCE_ENABLED DISABLED
#endif

#if AVOIDANCE_ENABLED == ENABLED // Avoidance Library relies on Proximity and Fence
# define PROXIMITY_ENABLED ENABLED
#if AVOIDANCE_ENABLED == ENABLED // Avoidance Library relies on Fence
# define FENCE_ENABLED ENABLED
#endif

// Proximity sensor
//
#ifndef PROXIMITY_ENABLED
# define PROXIMITY_ENABLED DISABLED
#endif

#ifndef MAV_SYSTEM_ID
# define MAV_SYSTEM_ID 1
#endif
Expand Down
5 changes: 5 additions & 0 deletions Rover/GCS_Rover.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 |
Expand Down Expand Up @@ -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
}
4 changes: 4 additions & 0 deletions Rover/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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(),
Expand Down
2 changes: 2 additions & 0 deletions Rover/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -329,8 +329,10 @@ class ParametersG2 {
// fence library
AC_Fence fence;

#if HAL_PROXIMITY_ENABLED
// proximity library
AP_Proximity proximity;
#endif

// avoidance library
AC_Avoid avoid;
Expand Down
4 changes: 4 additions & 0 deletions Rover/Rover.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down Expand Up @@ -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
}

/*
Expand Down
2 changes: 2 additions & 0 deletions Rover/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
6 changes: 6 additions & 0 deletions libraries/AC_Avoidance/AC_Avoid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -361,6 +361,7 @@ void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_c
}
}

#if HAL_PROXIMITY_ENABLED
// get distance from proximity sensor
float proximity_alt_diff;
AP_Proximity *proximity = AP::proximity();
Expand All @@ -371,6 +372,7 @@ void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_c
limit_alt = true;
}
}
#endif

// limit climb rate
if (limit_alt) {
Expand Down Expand Up @@ -1084,6 +1086,7 @@ void AC_Avoid::adjust_velocity_beacon_fence(float kP, float accel_cmss, Vector2f
*/
void AC_Avoid::adjust_velocity_proximity(float kP, float accel_cmss, Vector3f &desired_vel_cms, Vector3f &backup_vel, float kP_z, float accel_cmss_z, float dt)
{
#if HAL_PROXIMITY_ENABLED
// exit immediately if proximity sensor is not present
AP_Proximity *proximity = AP::proximity();
if (!proximity) {
Expand Down Expand Up @@ -1211,6 +1214,7 @@ void AC_Avoid::adjust_velocity_proximity(float kP, float accel_cmss, Vector3f &d
desired_vel_cms = Vector3f{safe_vel_2d.x, safe_vel_2d.y, safe_vel.z};
const Vector2f backup_vel_xy = _ahrs.body_to_earth2D(desired_back_vel_cms_xy);
backup_vel = Vector3f{backup_vel_xy.x, backup_vel_xy.y, desired_back_vel_cms_z};
#endif // HAL_PROXIMITY_ENABLED
}

/*
Expand Down Expand Up @@ -1371,6 +1375,7 @@ float AC_Avoid::distance_to_lean_pct(float dist_m)
// returns the maximum positive and negative roll and pitch percentages (in -1 ~ +1 range) based on the proximity sensor
void AC_Avoid::get_proximity_roll_pitch_pct(float &roll_positive, float &roll_negative, float &pitch_positive, float &pitch_negative)
{
#if HAL_PROXIMITY_ENABLED
AP_Proximity *proximity = AP::proximity();
if (proximity == nullptr) {
return;
Expand Down Expand Up @@ -1414,6 +1419,7 @@ void AC_Avoid::get_proximity_roll_pitch_pct(float &roll_positive, float &roll_ne
}
}
}
#endif // HAL_PROXIMITY_ENABLED
}

// singleton instance
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_Arming/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -843,6 +843,7 @@ bool AP_Arming::system_checks(bool report)
// check nothing is too close to vehicle
bool AP_Arming::proximity_checks(bool report) const
{
#if HAL_PROXIMITY_ENABLED
const AP_Proximity *proximity = AP::proximity();
// return true immediately if no sensor present
if (proximity == nullptr) {
Expand All @@ -857,6 +858,7 @@ bool AP_Arming::proximity_checks(bool report) const
check_failed(report, "check proximity sensor");
return false;
}
#endif

return true;
}
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_Logger/AP_Logger.h
Original file line number Diff line number Diff line change
Expand Up @@ -330,7 +330,9 @@ class AP_Logger
uint8_t sequence,
const RallyLocation &rally_point);
void Write_Beacon(AP_Beacon &beacon);
#if HAL_PROXIMITY_ENABLED
void Write_Proximity(AP_Proximity &proximity);
#endif
void Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f& point);
void Write_OABendyRuler(uint8_t type, bool active, float target_yaw, float target_pitch, bool ignore_chg, float margin, const Location &final_dest, const Location &oa_dest);
void Write_OADijkstra(uint8_t state, uint8_t error_id, uint8_t curr_point, uint8_t tot_points, const Location &final_dest, const Location &oa_dest);
Expand Down
Loading