mirror of https://github.com/ArduPilot/ardupilot
Copter: HAL_PROXIMITY_ENABLED replaces PROXIMITY_ENABLED
This commit is contained in:
parent
d4f1eacbed
commit
91fa40aea6
|
@ -10,7 +10,6 @@
|
||||||
//#define AC_FENCE DISABLED // disable fence to save 2k of flash
|
//#define AC_FENCE DISABLED // disable fence to save 2k of flash
|
||||||
//#define CAMERA DISABLED // disable camera trigger to save 1k 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 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_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_AVOID_ENABLED DISABLED // disable stop-at-fence library
|
||||||
//#define AC_OAPATHPLANNER_ENABLED DISABLED // disable path planning around obstacles
|
//#define AC_OAPATHPLANNER_ENABLED DISABLED // disable path planning around obstacles
|
||||||
|
|
|
@ -477,7 +477,7 @@ bool AP_Arming_Copter::pre_arm_ekf_attitude_check()
|
||||||
// check nothing is too close to vehicle
|
// check nothing is too close to vehicle
|
||||||
bool AP_Arming_Copter::proximity_checks(bool display_failure) const
|
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)) {
|
if (!AP_Arming::proximity_checks(display_failure)) {
|
||||||
return false;
|
return false;
|
||||||
|
|
|
@ -107,7 +107,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
||||||
#if RANGEFINDER_ENABLED == ENABLED
|
#if RANGEFINDER_ENABLED == ENABLED
|
||||||
SCHED_TASK(read_rangefinder, 20, 100),
|
SCHED_TASK(read_rangefinder, 20, 100),
|
||||||
#endif
|
#endif
|
||||||
#if PROXIMITY_ENABLED == ENABLED
|
#if HAL_PROXIMITY_ENABLED
|
||||||
SCHED_TASK_CLASS(AP_Proximity, &copter.g2.proximity, update, 200, 50),
|
SCHED_TASK_CLASS(AP_Proximity, &copter.g2.proximity, update, 200, 50),
|
||||||
#endif
|
#endif
|
||||||
#if BEACON_ENABLED == ENABLED
|
#if BEACON_ENABLED == ENABLED
|
||||||
|
@ -427,7 +427,7 @@ void Copter::ten_hz_logging_loop()
|
||||||
}
|
}
|
||||||
if (should_log(MASK_LOG_CTUN)) {
|
if (should_log(MASK_LOG_CTUN)) {
|
||||||
attitude_control->control_monitor_log();
|
attitude_control->control_monitor_log();
|
||||||
#if PROXIMITY_ENABLED == ENABLED
|
#if HAL_PROXIMITY_ENABLED
|
||||||
logger.Write_Proximity(g2.proximity); // Write proximity sensor distances
|
logger.Write_Proximity(g2.proximity); // Write proximity sensor distances
|
||||||
#endif
|
#endif
|
||||||
#if BEACON_ENABLED == ENABLED
|
#if BEACON_ENABLED == ENABLED
|
||||||
|
|
|
@ -67,6 +67,7 @@
|
||||||
#include <AP_Parachute/AP_Parachute.h>
|
#include <AP_Parachute/AP_Parachute.h>
|
||||||
#include <AC_Sprayer/AC_Sprayer.h>
|
#include <AC_Sprayer/AC_Sprayer.h>
|
||||||
#include <AP_ADSB/AP_ADSB.h>
|
#include <AP_ADSB/AP_ADSB.h>
|
||||||
|
#include <AP_Proximity/AP_Proximity.h>
|
||||||
|
|
||||||
// Configuration
|
// Configuration
|
||||||
#include "defines.h"
|
#include "defines.h"
|
||||||
|
@ -129,9 +130,6 @@
|
||||||
#if RANGEFINDER_ENABLED == ENABLED
|
#if RANGEFINDER_ENABLED == ENABLED
|
||||||
# include <AP_RangeFinder/AP_RangeFinder.h>
|
# include <AP_RangeFinder/AP_RangeFinder.h>
|
||||||
#endif
|
#endif
|
||||||
#if PROXIMITY_ENABLED == ENABLED
|
|
||||||
# include <AP_Proximity/AP_Proximity.h>
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#include <AP_Mount/AP_Mount.h>
|
#include <AP_Mount/AP_Mount.h>
|
||||||
|
|
||||||
|
|
|
@ -61,7 +61,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
|
||||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
||||||
control_sensors_enabled |= 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()) {
|
if (copter.g2.proximity.sensor_present()) {
|
||||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_PROXIMITY;
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_PROXIMITY;
|
||||||
}
|
}
|
||||||
|
@ -106,7 +106,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if PROXIMITY_ENABLED == ENABLED
|
#if HAL_PROXIMITY_ENABLED
|
||||||
if (copter.g2.proximity.sensor_enabled()) {
|
if (copter.g2.proximity.sensor_enabled()) {
|
||||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_PROXIMITY;
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_PROXIMITY;
|
||||||
}
|
}
|
||||||
|
@ -126,7 +126,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if PROXIMITY_ENABLED == ENABLED
|
#if HAL_PROXIMITY_ENABLED
|
||||||
if (!copter.g2.proximity.sensor_failed()) {
|
if (!copter.g2.proximity.sensor_failed()) {
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_PROXIMITY;
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_PROXIMITY;
|
||||||
}
|
}
|
||||||
|
|
|
@ -821,7 +821,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||||
AP_SUBGROUPINFO(beacon, "BCN", 14, ParametersG2, AP_Beacon),
|
AP_SUBGROUPINFO(beacon, "BCN", 14, ParametersG2, AP_Beacon),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if PROXIMITY_ENABLED == ENABLED
|
#if HAL_PROXIMITY_ENABLED
|
||||||
// @Group: PRX
|
// @Group: PRX
|
||||||
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
|
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
|
||||||
AP_SUBGROUPINFO(proximity, "PRX", 8, ParametersG2, AP_Proximity),
|
AP_SUBGROUPINFO(proximity, "PRX", 8, ParametersG2, AP_Proximity),
|
||||||
|
@ -1065,7 +1065,7 @@ ParametersG2::ParametersG2(void)
|
||||||
#if BEACON_ENABLED == ENABLED
|
#if BEACON_ENABLED == ENABLED
|
||||||
, beacon(copter.serial_manager)
|
, beacon(copter.serial_manager)
|
||||||
#endif
|
#endif
|
||||||
#if PROXIMITY_ENABLED == ENABLED
|
#if HAL_PROXIMITY_ENABLED
|
||||||
, proximity()
|
, proximity()
|
||||||
#endif
|
#endif
|
||||||
#if ADVANCED_FAILSAFE == ENABLED
|
#if ADVANCED_FAILSAFE == ENABLED
|
||||||
|
|
|
@ -2,6 +2,7 @@
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include "RC_Channel.h"
|
#include "RC_Channel.h"
|
||||||
|
#include <AP_Proximity/AP_Proximity.h>
|
||||||
|
|
||||||
#if GRIPPER_ENABLED == ENABLED
|
#if GRIPPER_ENABLED == ENABLED
|
||||||
# include <AP_Gripper/AP_Gripper.h>
|
# include <AP_Gripper/AP_Gripper.h>
|
||||||
|
@ -520,7 +521,7 @@ public:
|
||||||
AP_Beacon beacon;
|
AP_Beacon beacon;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if PROXIMITY_ENABLED == ENABLED
|
#if HAL_PROXIMITY_ENABLED
|
||||||
// proximity (aka object avoidance) library
|
// proximity (aka object avoidance) library
|
||||||
AP_Proximity proximity;
|
AP_Proximity proximity;
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -116,13 +116,6 @@
|
||||||
# define RANGEFINDER_GLITCH_NUM_SAMPLES 3 // number of rangefinder glitches in a row to take new reading
|
# define RANGEFINDER_GLITCH_NUM_SAMPLES 3 // number of rangefinder glitches in a row to take new reading
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
|
||||||
// Proximity sensor
|
|
||||||
//
|
|
||||||
#ifndef PROXIMITY_ENABLED
|
|
||||||
# define PROXIMITY_ENABLED ENABLED
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef MAV_SYSTEM_ID
|
#ifndef MAV_SYSTEM_ID
|
||||||
# define MAV_SYSTEM_ID 1
|
# define MAV_SYSTEM_ID 1
|
||||||
#endif
|
#endif
|
||||||
|
@ -685,9 +678,6 @@
|
||||||
#define AC_OAPATHPLANNER_ENABLED !HAL_MINIMIZE_FEATURES
|
#define AC_OAPATHPLANNER_ENABLED !HAL_MINIMIZE_FEATURES
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AC_AVOID_ENABLED && !PROXIMITY_ENABLED
|
|
||||||
#error AC_Avoidance relies on PROXIMITY_ENABLED which is disabled
|
|
||||||
#endif
|
|
||||||
#if AC_AVOID_ENABLED && !AC_FENCE
|
#if AC_AVOID_ENABLED && !AC_FENCE
|
||||||
#error AC_Avoidance relies on AC_FENCE which is disabled
|
#error AC_Avoidance relies on AC_FENCE which is disabled
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -97,7 +97,7 @@ void Copter::read_rangefinder(void)
|
||||||
#if MODE_CIRCLE_ENABLED
|
#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());
|
circle_nav->set_rangefinder_alt(rangefinder_state.enabled && wp_nav->rangefinder_used(), rangefinder_state.alt_healthy, rangefinder_state.alt_cm_filt.get());
|
||||||
#endif
|
#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());
|
g2.proximity.set_rangefinder_alt(rangefinder_state.enabled, rangefinder_state.alt_healthy, rangefinder_state.alt_cm_filt.get());
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -224,7 +224,7 @@ void Copter::accel_cal_update()
|
||||||
// initialise proximity sensor
|
// initialise proximity sensor
|
||||||
void Copter::init_proximity(void)
|
void Copter::init_proximity(void)
|
||||||
{
|
{
|
||||||
#if PROXIMITY_ENABLED == ENABLED
|
#if HAL_PROXIMITY_ENABLED
|
||||||
g2.proximity.init();
|
g2.proximity.init();
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue