From 9a32e8208fc8fe644c13a98f56b3ccfc0a22c003 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 6 Apr 2020 13:13:35 +0900 Subject: [PATCH] Rover: visual odometry moved to AP_Vehicle --- APMrover2/GCS_Rover.cpp | 8 -------- APMrover2/Parameters.cpp | 4 +--- APMrover2/Parameters.h | 3 --- APMrover2/Rover.h | 1 - APMrover2/config.h | 7 ------- APMrover2/sensors.cpp | 1 - APMrover2/system.cpp | 3 --- 7 files changed, 1 insertion(+), 26 deletions(-) diff --git a/APMrover2/GCS_Rover.cpp b/APMrover2/GCS_Rover.cpp index 7b7a92bfa9..e045de3baf 100644 --- a/APMrover2/GCS_Rover.cpp +++ b/APMrover2/GCS_Rover.cpp @@ -28,11 +28,6 @@ bool GCS_Rover::supersimple_input_active() const void GCS_Rover::update_vehicle_sensor_status_flags(void) { // first what sensors/controllers we have - 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; - } 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; @@ -58,9 +53,6 @@ void GCS_Rover::update_vehicle_sensor_status_flags(void) control_sensors_health |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; // X/Y position control } - if (visual_odom && visual_odom->enabled() && visual_odom->healthy()) { - control_sensors_health |= MAV_SYS_STATUS_SENSOR_VISION_POSITION; - } const RangeFinder *rangefinder = RangeFinder::get_singleton(); if (rangefinder && rangefinder->num_sensors() > 0) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION; diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index df1f06a266..6ce9409d9d 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -416,9 +416,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Path: ../libraries/AP_Beacon/AP_Beacon.cpp AP_SUBGROUPINFO(beacon, "BCN", 6, ParametersG2, AP_Beacon), - // @Group: VISO - // @Path: ../libraries/AP_VisualOdom/AP_VisualOdom.cpp - AP_SUBGROUPINFO(visual_odom, "VISO", 7, ParametersG2, AP_VisualOdom), + // 7 was used by AP_VisualOdometry // @Group: MOT_ // @Path: AP_MotorsUGV.cpp diff --git a/APMrover2/Parameters.h b/APMrover2/Parameters.h index 173ba19589..0d7e838c77 100644 --- a/APMrover2/Parameters.h +++ b/APMrover2/Parameters.h @@ -298,9 +298,6 @@ public: AP_Beacon beacon; - // Visual Odometry camera - AP_VisualOdom visual_odom; - // Motor library AP_MotorsUGV motors; diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 23adc5350b..4f204ac880 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -50,7 +50,6 @@ #include // statistics library #include #include // needed for AHRS build -#include #include #include #include diff --git a/APMrover2/config.h b/APMrover2/config.h index 894ced5585..d9e5a1c37d 100644 --- a/APMrover2/config.h +++ b/APMrover2/config.h @@ -46,13 +46,6 @@ #error XXX #endif - -////////////////////////////////////////////////////////////////////////////// -// VISUAL ODOMETRY -#ifndef VISUAL_ODOMETRY_ENABLED -# define VISUAL_ODOMETRY_ENABLED ENABLED -#endif - ////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////// // STARTUP BEHAVIOUR diff --git a/APMrover2/sensors.cpp b/APMrover2/sensors.cpp index f62c3c3b04..69bac92917 100644 --- a/APMrover2/sensors.cpp +++ b/APMrover2/sensors.cpp @@ -1,7 +1,6 @@ #include "Rover.h" #include -#include // check for new compass data - 10Hz void Rover::update_compass(void) diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index fa7f848164..e7acb30249 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -73,9 +73,6 @@ void Rover::init_ardupilot() // init beacons used for non-gps position estimation g2.beacon.init(); - // init library used for visual position estimation - g2.visual_odom.init(); - // and baro for EKF barometer.set_log_baro_bit(MASK_LOG_IMU); barometer.calibrate();