mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
Copter: visual odometry moved to AP_Vehicle
This commit is contained in:
parent
05a37db07c
commit
04c3f040a8
@ -18,7 +18,6 @@
|
||||
//#define PARACHUTE DISABLED // disable parachute release to save 1k of flash
|
||||
//#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 VISUAL_ODOMETRY_ENABLED DISABLED // disable visual odometry to save 2K 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
|
||||
|
@ -129,9 +129,6 @@
|
||||
#if OPTFLOW == ENABLED
|
||||
# include <AP_OpticalFlow/AP_OpticalFlow.h>
|
||||
#endif
|
||||
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
||||
# include <AP_VisualOdom/AP_VisualOdom.h>
|
||||
#endif
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
# include <AP_RangeFinder/AP_RangeFinder.h>
|
||||
#endif
|
||||
@ -847,7 +844,6 @@ private:
|
||||
void accel_cal_update(void);
|
||||
void init_proximity();
|
||||
void update_proximity();
|
||||
void init_visual_odom();
|
||||
void winch_init();
|
||||
void winch_update();
|
||||
|
||||
|
@ -51,13 +51,6 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
||||
}
|
||||
#endif
|
||||
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
||||
const AP_VisualOdom *visual_odom = AP::visualodom();
|
||||
if (visual_odom && visual_odom->enabled()) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
||||
}
|
||||
#endif
|
||||
const Copter::ap_t &ap = copter.ap;
|
||||
|
||||
@ -126,11 +119,6 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
|
||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
||||
}
|
||||
#endif
|
||||
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
||||
if (visual_odom && visual_odom->enabled() && visual_odom->healthy()) {
|
||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
if (!copter.g2.proximity.sensor_failed()) {
|
||||
|
@ -844,11 +844,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
|
||||
AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels_Copter),
|
||||
|
||||
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
||||
// @Group: VISO
|
||||
// @Path: ../libraries/AP_VisualOdom/AP_VisualOdom.cpp
|
||||
AP_SUBGROUPINFO(visual_odom, "VISO", 18, ParametersG2, AP_VisualOdom),
|
||||
#endif
|
||||
// 18 was used by AP_VisualOdom
|
||||
|
||||
// @Group: TCAL
|
||||
// @Path: ../libraries/AP_TempCalibration/AP_TempCalibration.cpp
|
||||
|
@ -9,9 +9,6 @@
|
||||
#if MODE_FOLLOW_ENABLED == ENABLED
|
||||
# include <AP_Follow/AP_Follow.h>
|
||||
#endif
|
||||
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
||||
# include <AP_VisualOdom/AP_VisualOdom.h>
|
||||
#endif
|
||||
|
||||
// Global parameter class.
|
||||
//
|
||||
@ -514,11 +511,6 @@ public:
|
||||
AP_Beacon beacon;
|
||||
#endif
|
||||
|
||||
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
||||
// Visual Odometry camera
|
||||
AP_VisualOdom visual_odom;
|
||||
#endif
|
||||
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
// proximity (aka object avoidance) library
|
||||
AP_Proximity proximity;
|
||||
|
@ -207,13 +207,10 @@
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// OPTICAL_FLOW & VISUAL ODOMETRY
|
||||
// OPTICAL_FLOW
|
||||
#ifndef OPTFLOW
|
||||
# define OPTFLOW ENABLED
|
||||
#endif
|
||||
#ifndef VISUAL_ODOMETRY_ENABLED
|
||||
# define VISUAL_ODOMETRY_ENABLED !HAL_MINIMIZE_FEATURES
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Auto Tuning
|
||||
|
@ -223,14 +223,6 @@ void Copter::init_proximity(void)
|
||||
#endif
|
||||
}
|
||||
|
||||
// init visual odometry sensor
|
||||
void Copter::init_visual_odom()
|
||||
{
|
||||
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
||||
g2.visual_odom.init();
|
||||
#endif
|
||||
}
|
||||
|
||||
// winch and wheel encoder initialisation
|
||||
void Copter::winch_init()
|
||||
{
|
||||
|
@ -171,9 +171,6 @@ void Copter::init_ardupilot()
|
||||
g2.beacon.init();
|
||||
#endif
|
||||
|
||||
// init visual odometry
|
||||
init_visual_odom();
|
||||
|
||||
#if RPM_ENABLED == ENABLED
|
||||
// initialise AP_RPM library
|
||||
rpm_sensor.init();
|
||||
@ -327,9 +324,6 @@ bool Copter::ekf_position_ok() const
|
||||
// optflow_position_ok - returns true if optical flow based position estimate is ok
|
||||
bool Copter::optflow_position_ok() const
|
||||
{
|
||||
#if OPTFLOW != ENABLED && VISUAL_ODOMETRY_ENABLED != ENABLED
|
||||
return false;
|
||||
#else
|
||||
// return immediately if EKF not used
|
||||
if (!ahrs.have_inertial_nav()) {
|
||||
return false;
|
||||
@ -342,8 +336,8 @@ bool Copter::optflow_position_ok() const
|
||||
enabled = true;
|
||||
}
|
||||
#endif
|
||||
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
||||
if (g2.visual_odom.enabled()) {
|
||||
#if HAL_VISUALODOM_ENABLED
|
||||
if (visual_odom.enabled()) {
|
||||
enabled = true;
|
||||
}
|
||||
#endif
|
||||
@ -360,7 +354,6 @@ bool Copter::optflow_position_ok() const
|
||||
} else {
|
||||
return (filt_status.flags.horiz_pos_rel && !filt_status.flags.const_pos_mode);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// update_auto_armed - update status of auto_armed flag
|
||||
|
Loading…
Reference in New Issue
Block a user