mirror of https://github.com/ArduPilot/ardupilot
Copter: move proximity to g2
This commit is contained in:
parent
fa36b563bc
commit
0aab175051
|
@ -76,7 +76,7 @@ Copter::Copter(void) :
|
|||
pos_control(ahrs, inertial_nav, motors, attitude_control,
|
||||
g.p_alt_hold, g.p_vel_z, g.pid_accel_z,
|
||||
g.p_pos_xy, g.pi_vel_xy),
|
||||
avoid(ahrs, inertial_nav, fence, proximity),
|
||||
avoid(ahrs, inertial_nav, fence, g2.proximity),
|
||||
wp_nav(inertial_nav, ahrs, pos_control, attitude_control),
|
||||
circle_nav(inertial_nav, ahrs, pos_control),
|
||||
pmTest1(0),
|
||||
|
|
|
@ -197,10 +197,6 @@ private:
|
|||
LowPassFilterFloat alt_cm_filt; // altitude filter
|
||||
} rangefinder_state = { false, false, 0, 0 };
|
||||
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
AP_Proximity proximity {serial_manager};
|
||||
#endif
|
||||
|
||||
AP_RPM rpm_sensor;
|
||||
|
||||
// Inertial Navigation EKF
|
||||
|
|
|
@ -144,7 +144,7 @@ NOINLINE void Copter::send_extended_status1(mavlink_channel_t chan)
|
|||
control_sensors_present |= MAV_SYS_STATUS_LOGGING;
|
||||
}
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
if (copter.proximity.get_status() > AP_Proximity::Proximity_NotConnected) {
|
||||
if (copter.g2.proximity.get_status() > AP_Proximity::Proximity_NotConnected) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
||||
}
|
||||
#endif
|
||||
|
@ -232,7 +232,7 @@ NOINLINE void Copter::send_extended_status1(mavlink_channel_t chan)
|
|||
}
|
||||
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
if (copter.proximity.get_status() < AP_Proximity::Proximity_Good) {
|
||||
if (copter.g2.proximity.get_status() < AP_Proximity::Proximity_Good) {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -770,19 +770,19 @@ void Copter::Log_Write_Proximity()
|
|||
{
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
float sector_distance[8] = {0,0,0,0,0,0,0,0};
|
||||
proximity.get_horizontal_distance(0, sector_distance[0]);
|
||||
proximity.get_horizontal_distance(45, sector_distance[1]);
|
||||
proximity.get_horizontal_distance(90, sector_distance[2]);
|
||||
proximity.get_horizontal_distance(135, sector_distance[3]);
|
||||
proximity.get_horizontal_distance(180, sector_distance[4]);
|
||||
proximity.get_horizontal_distance(225, sector_distance[5]);
|
||||
proximity.get_horizontal_distance(270, sector_distance[6]);
|
||||
proximity.get_horizontal_distance(315, sector_distance[7]);
|
||||
g2.proximity.get_horizontal_distance(0, sector_distance[0]);
|
||||
g2.proximity.get_horizontal_distance(45, sector_distance[1]);
|
||||
g2.proximity.get_horizontal_distance(90, sector_distance[2]);
|
||||
g2.proximity.get_horizontal_distance(135, sector_distance[3]);
|
||||
g2.proximity.get_horizontal_distance(180, sector_distance[4]);
|
||||
g2.proximity.get_horizontal_distance(225, sector_distance[5]);
|
||||
g2.proximity.get_horizontal_distance(270, sector_distance[6]);
|
||||
g2.proximity.get_horizontal_distance(315, sector_distance[7]);
|
||||
|
||||
struct log_Proximity pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_PROXIMITY_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
health : (uint8_t)proximity.get_status(),
|
||||
health : (uint8_t)g2.proximity.get_status(),
|
||||
dist0 : sector_distance[0],
|
||||
dist45 : sector_distance[1],
|
||||
dist90 : sector_distance[2],
|
||||
|
|
|
@ -911,12 +911,6 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
// @Path: ../libraries/AP_Avoidance/AP_Avoidance.cpp
|
||||
GOBJECT(avoidance_adsb, "AVD_", AP_Avoidance_Copter),
|
||||
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
// @Group: PRX_
|
||||
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
|
||||
GOBJECT(proximity, "PRX_", AP_Proximity),
|
||||
#endif
|
||||
|
||||
// @Param: AUTOTUNE_AXES
|
||||
// @DisplayName: Autotune axis bitmask
|
||||
// @Description: 1-byte bitmap of axes to autotune
|
||||
|
@ -1014,6 +1008,12 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
// @User: Advanced
|
||||
AP_GROUPINFO("DEV_OPTIONS", 7, ParametersG2, dev_options, 0),
|
||||
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
// @Group: PRX_
|
||||
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
|
||||
AP_SUBGROUPINFO(proximity, "PRX_", 8, ParametersG2, AP_Proximity),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -1022,8 +1022,9 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
constructor for g2 object
|
||||
*/
|
||||
ParametersG2::ParametersG2(void)
|
||||
: proximity(copter.serial_manager)
|
||||
#if ADVANCED_FAILSAFE == ENABLED
|
||||
: afs(copter.mission, copter.barometer, copter.gps, copter.rcmap)
|
||||
,afs(copter.mission, copter.barometer, copter.gps, copter.rcmap)
|
||||
#endif
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
|
|
@ -362,7 +362,6 @@ public:
|
|||
k_param_rtl_climb_min,
|
||||
k_param_rpm_sensor,
|
||||
k_param_autotune_min_d, // 251
|
||||
k_param_proximity,
|
||||
k_param_DataFlash = 253, // 253 - Logging Group
|
||||
|
||||
// 254,255: reserved
|
||||
|
@ -559,6 +558,11 @@ public:
|
|||
// ground effect compensation enable/disable
|
||||
AP_Int8 gndeffect_comp_enabled;
|
||||
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
// proximity (aka object avoidance) library
|
||||
AP_Proximity proximity;
|
||||
#endif
|
||||
|
||||
#if ADVANCED_FAILSAFE == ENABLED
|
||||
// advanced failsafe library
|
||||
AP_AdvancedFailsafe_Copter afs;
|
||||
|
|
|
@ -380,7 +380,7 @@ bool Copter::parameter_checks(bool display_failure)
|
|||
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
// check proximity sensor if enabled
|
||||
if (copter.proximity.get_status() == AP_Proximity::Proximity_NoData) {
|
||||
if (copter.g2.proximity.get_status() == AP_Proximity::Proximity_NoData) {
|
||||
if (display_failure) {
|
||||
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: check proximity sensor");
|
||||
}
|
||||
|
|
|
@ -258,7 +258,7 @@ void Copter::button_update(void)
|
|||
void Copter::init_proximity(void)
|
||||
{
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
proximity.init();
|
||||
g2.proximity.init();
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -266,7 +266,7 @@ void Copter::init_proximity(void)
|
|||
void Copter::update_proximity(void)
|
||||
{
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
proximity.update();
|
||||
g2.proximity.update();
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue