Browse Source

Copter: visual odometry moved to AP_Vehicle

zr-v5.1
Randy Mackay 5 years ago
parent
commit
04c3f040a8
  1. 1
      ArduCopter/APM_Config.h
  2. 4
      ArduCopter/Copter.h
  3. 12
      ArduCopter/GCS_Copter.cpp
  4. 6
      ArduCopter/Parameters.cpp
  5. 8
      ArduCopter/Parameters.h
  6. 5
      ArduCopter/config.h
  7. 8
      ArduCopter/sensors.cpp
  8. 11
      ArduCopter/system.cpp

1
ArduCopter/APM_Config.h

@ -18,7 +18,6 @@
//#define PARACHUTE DISABLED // disable parachute release to save 1k of flash //#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 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 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 FRSKY_TELEM_ENABLED DISABLED // disable FRSky telemetry
//#define ADSB_ENABLED DISABLED // disable ADSB support //#define ADSB_ENABLED DISABLED // disable ADSB support
//#define PRECISION_LANDING DISABLED // disable precision landing using companion computer or IRLock sensor //#define PRECISION_LANDING DISABLED // disable precision landing using companion computer or IRLock sensor

4
ArduCopter/Copter.h

@ -129,9 +129,6 @@
#if OPTFLOW == ENABLED #if OPTFLOW == ENABLED
# include <AP_OpticalFlow/AP_OpticalFlow.h> # include <AP_OpticalFlow/AP_OpticalFlow.h>
#endif #endif
#if VISUAL_ODOMETRY_ENABLED == ENABLED
# include <AP_VisualOdom/AP_VisualOdom.h>
#endif
#if RANGEFINDER_ENABLED == ENABLED #if RANGEFINDER_ENABLED == ENABLED
# include <AP_RangeFinder/AP_RangeFinder.h> # include <AP_RangeFinder/AP_RangeFinder.h>
#endif #endif
@ -847,7 +844,6 @@ private:
void accel_cal_update(void); void accel_cal_update(void);
void init_proximity(); void init_proximity();
void update_proximity(); void update_proximity();
void init_visual_odom();
void winch_init(); void winch_init();
void winch_update(); void winch_update();

12
ArduCopter/GCS_Copter.cpp

@ -51,13 +51,6 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION; control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
control_sensors_enabled |= 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 #endif
const Copter::ap_t &ap = copter.ap; 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; control_sensors_health |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
} }
#endif #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 PROXIMITY_ENABLED == ENABLED
if (!copter.g2.proximity.sensor_failed()) { if (!copter.g2.proximity.sensor_failed()) {

6
ArduCopter/Parameters.cpp

@ -844,11 +844,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h // @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels_Copter), AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels_Copter),
#if VISUAL_ODOMETRY_ENABLED == ENABLED // 18 was used by AP_VisualOdom
// @Group: VISO
// @Path: ../libraries/AP_VisualOdom/AP_VisualOdom.cpp
AP_SUBGROUPINFO(visual_odom, "VISO", 18, ParametersG2, AP_VisualOdom),
#endif
// @Group: TCAL // @Group: TCAL
// @Path: ../libraries/AP_TempCalibration/AP_TempCalibration.cpp // @Path: ../libraries/AP_TempCalibration/AP_TempCalibration.cpp

8
ArduCopter/Parameters.h

@ -9,9 +9,6 @@
#if MODE_FOLLOW_ENABLED == ENABLED #if MODE_FOLLOW_ENABLED == ENABLED
# include <AP_Follow/AP_Follow.h> # include <AP_Follow/AP_Follow.h>
#endif #endif
#if VISUAL_ODOMETRY_ENABLED == ENABLED
# include <AP_VisualOdom/AP_VisualOdom.h>
#endif
// Global parameter class. // Global parameter class.
// //
@ -514,11 +511,6 @@ public:
AP_Beacon beacon; AP_Beacon beacon;
#endif #endif
#if VISUAL_ODOMETRY_ENABLED == ENABLED
// Visual Odometry camera
AP_VisualOdom visual_odom;
#endif
#if PROXIMITY_ENABLED == ENABLED #if PROXIMITY_ENABLED == ENABLED
// proximity (aka object avoidance) library // proximity (aka object avoidance) library
AP_Proximity proximity; AP_Proximity proximity;

5
ArduCopter/config.h

@ -207,13 +207,10 @@
#endif #endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// OPTICAL_FLOW & VISUAL ODOMETRY // OPTICAL_FLOW
#ifndef OPTFLOW #ifndef OPTFLOW
# define OPTFLOW ENABLED # define OPTFLOW ENABLED
#endif #endif
#ifndef VISUAL_ODOMETRY_ENABLED
# define VISUAL_ODOMETRY_ENABLED !HAL_MINIMIZE_FEATURES
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Auto Tuning // Auto Tuning

8
ArduCopter/sensors.cpp

@ -223,14 +223,6 @@ void Copter::init_proximity(void)
#endif #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 // winch and wheel encoder initialisation
void Copter::winch_init() void Copter::winch_init()
{ {

11
ArduCopter/system.cpp

@ -171,9 +171,6 @@ void Copter::init_ardupilot()
g2.beacon.init(); g2.beacon.init();
#endif #endif
// init visual odometry
init_visual_odom();
#if RPM_ENABLED == ENABLED #if RPM_ENABLED == ENABLED
// initialise AP_RPM library // initialise AP_RPM library
rpm_sensor.init(); 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 // optflow_position_ok - returns true if optical flow based position estimate is ok
bool Copter::optflow_position_ok() const bool Copter::optflow_position_ok() const
{ {
#if OPTFLOW != ENABLED && VISUAL_ODOMETRY_ENABLED != ENABLED
return false;
#else
// return immediately if EKF not used // return immediately if EKF not used
if (!ahrs.have_inertial_nav()) { if (!ahrs.have_inertial_nav()) {
return false; return false;
@ -342,8 +336,8 @@ bool Copter::optflow_position_ok() const
enabled = true; enabled = true;
} }
#endif #endif
#if VISUAL_ODOMETRY_ENABLED == ENABLED #if HAL_VISUALODOM_ENABLED
if (g2.visual_odom.enabled()) { if (visual_odom.enabled()) {
enabled = true; enabled = true;
} }
#endif #endif
@ -360,7 +354,6 @@ bool Copter::optflow_position_ok() const
} else { } else {
return (filt_status.flags.horiz_pos_rel && !filt_status.flags.const_pos_mode); return (filt_status.flags.horiz_pos_rel && !filt_status.flags.const_pos_mode);
} }
#endif
} }
// update_auto_armed - update status of auto_armed flag // update_auto_armed - update status of auto_armed flag

Loading…
Cancel
Save