Rover: visual odometry moved to AP_Vehicle
This commit is contained in:
parent
ea14775793
commit
9a32e8208f
@ -28,11 +28,6 @@ bool GCS_Rover::supersimple_input_active() const
|
|||||||
void GCS_Rover::update_vehicle_sensor_status_flags(void)
|
void GCS_Rover::update_vehicle_sensor_status_flags(void)
|
||||||
{
|
{
|
||||||
// first what sensors/controllers we have
|
// 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();
|
const AP_Proximity *proximity = AP_Proximity::get_singleton();
|
||||||
if (proximity && proximity->get_status() > AP_Proximity::Status::NotConnected) {
|
if (proximity && proximity->get_status() > AP_Proximity::Status::NotConnected) {
|
||||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
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
|
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();
|
const RangeFinder *rangefinder = RangeFinder::get_singleton();
|
||||||
if (rangefinder && rangefinder->num_sensors() > 0) {
|
if (rangefinder && rangefinder->num_sensors() > 0) {
|
||||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
||||||
|
@ -416,9 +416,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||||||
// @Path: ../libraries/AP_Beacon/AP_Beacon.cpp
|
// @Path: ../libraries/AP_Beacon/AP_Beacon.cpp
|
||||||
AP_SUBGROUPINFO(beacon, "BCN", 6, ParametersG2, AP_Beacon),
|
AP_SUBGROUPINFO(beacon, "BCN", 6, ParametersG2, AP_Beacon),
|
||||||
|
|
||||||
// @Group: VISO
|
// 7 was used by AP_VisualOdometry
|
||||||
// @Path: ../libraries/AP_VisualOdom/AP_VisualOdom.cpp
|
|
||||||
AP_SUBGROUPINFO(visual_odom, "VISO", 7, ParametersG2, AP_VisualOdom),
|
|
||||||
|
|
||||||
// @Group: MOT_
|
// @Group: MOT_
|
||||||
// @Path: AP_MotorsUGV.cpp
|
// @Path: AP_MotorsUGV.cpp
|
||||||
|
@ -298,9 +298,6 @@ public:
|
|||||||
|
|
||||||
AP_Beacon beacon;
|
AP_Beacon beacon;
|
||||||
|
|
||||||
// Visual Odometry camera
|
|
||||||
AP_VisualOdom visual_odom;
|
|
||||||
|
|
||||||
// Motor library
|
// Motor library
|
||||||
AP_MotorsUGV motors;
|
AP_MotorsUGV motors;
|
||||||
|
|
||||||
|
@ -50,7 +50,6 @@
|
|||||||
#include <AP_Stats/AP_Stats.h> // statistics library
|
#include <AP_Stats/AP_Stats.h> // statistics library
|
||||||
#include <AP_Terrain/AP_Terrain.h>
|
#include <AP_Terrain/AP_Terrain.h>
|
||||||
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
|
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
|
||||||
#include <AP_VisualOdom/AP_VisualOdom.h>
|
|
||||||
#include <AP_WheelEncoder/AP_WheelEncoder.h>
|
#include <AP_WheelEncoder/AP_WheelEncoder.h>
|
||||||
#include <AP_WheelEncoder/AP_WheelRateControl.h>
|
#include <AP_WheelEncoder/AP_WheelRateControl.h>
|
||||||
#include <APM_Control/AR_AttitudeControl.h>
|
#include <APM_Control/AR_AttitudeControl.h>
|
||||||
|
@ -46,13 +46,6 @@
|
|||||||
#error XXX
|
#error XXX
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
|
||||||
// VISUAL ODOMETRY
|
|
||||||
#ifndef VISUAL_ODOMETRY_ENABLED
|
|
||||||
# define VISUAL_ODOMETRY_ENABLED ENABLED
|
|
||||||
#endif
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// STARTUP BEHAVIOUR
|
// STARTUP BEHAVIOUR
|
||||||
|
@ -1,7 +1,6 @@
|
|||||||
#include "Rover.h"
|
#include "Rover.h"
|
||||||
|
|
||||||
#include <AP_RangeFinder/AP_RangeFinder_Backend.h>
|
#include <AP_RangeFinder/AP_RangeFinder_Backend.h>
|
||||||
#include <AP_VisualOdom/AP_VisualOdom.h>
|
|
||||||
|
|
||||||
// check for new compass data - 10Hz
|
// check for new compass data - 10Hz
|
||||||
void Rover::update_compass(void)
|
void Rover::update_compass(void)
|
||||||
|
@ -73,9 +73,6 @@ void Rover::init_ardupilot()
|
|||||||
// init beacons used for non-gps position estimation
|
// init beacons used for non-gps position estimation
|
||||||
g2.beacon.init();
|
g2.beacon.init();
|
||||||
|
|
||||||
// init library used for visual position estimation
|
|
||||||
g2.visual_odom.init();
|
|
||||||
|
|
||||||
// and baro for EKF
|
// and baro for EKF
|
||||||
barometer.set_log_baro_bit(MASK_LOG_IMU);
|
barometer.set_log_baro_bit(MASK_LOG_IMU);
|
||||||
barometer.calibrate();
|
barometer.calibrate();
|
||||||
|
Loading…
Reference in New Issue
Block a user