mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_VisualOdom: add HAL_VISUALODOM_ENABLED
This commit is contained in:
parent
8f94a0cfb0
commit
3d75dc7815
@ -14,6 +14,9 @@
|
||||
*/
|
||||
|
||||
#include "AP_VisualOdom.h"
|
||||
|
||||
#if HAL_VISUALODOM_ENABLED
|
||||
|
||||
#include "AP_VisualOdom_Backend.h"
|
||||
#include "AP_VisualOdom_MAV.h"
|
||||
#include "AP_VisualOdom_IntelT265.h"
|
||||
@ -210,3 +213,5 @@ AP_VisualOdom *visualodom()
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -14,6 +14,15 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||
|
||||
#ifndef HAL_VISUALODOM_ENABLED
|
||||
#define HAL_VISUALODOM_ENABLED !HAL_MINIMIZE_FEATURES
|
||||
#endif
|
||||
|
||||
#if HAL_VISUALODOM_ENABLED
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
@ -88,3 +97,5 @@ private:
|
||||
namespace AP {
|
||||
AP_VisualOdom *visualodom();
|
||||
};
|
||||
|
||||
#endif // HAL_VISUALODOM_ENABLED
|
||||
|
@ -14,6 +14,9 @@
|
||||
*/
|
||||
|
||||
#include "AP_VisualOdom_Backend.h"
|
||||
|
||||
#if HAL_VISUALODOM_ENABLED
|
||||
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
@ -34,3 +37,5 @@ bool AP_VisualOdom_Backend::healthy() const
|
||||
// healthy if we have received sensor messages within the past 300ms
|
||||
return ((AP_HAL::millis() - _last_update_ms) < AP_VISUALODOM_TIMEOUT_MS);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -14,11 +14,10 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include "AP_VisualOdom.h"
|
||||
|
||||
#if HAL_VISUALODOM_ENABLED
|
||||
|
||||
class AP_VisualOdom_Backend
|
||||
{
|
||||
public:
|
||||
@ -54,3 +53,6 @@ protected:
|
||||
AP_VisualOdom &_frontend; // reference to frontend
|
||||
uint32_t _last_update_ms; // system time of last update from sensor (used by health checks)
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
|
@ -14,6 +14,9 @@
|
||||
*/
|
||||
|
||||
#include "AP_VisualOdom_IntelT265.h"
|
||||
|
||||
#if HAL_VISUALODOM_ENABLED
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
@ -191,3 +194,5 @@ bool AP_VisualOdom_IntelT265::pre_arm_check(char *failure_msg, uint8_t failure_m
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -2,6 +2,8 @@
|
||||
|
||||
#include "AP_VisualOdom_Backend.h"
|
||||
|
||||
#if HAL_VISUALODOM_ENABLED
|
||||
|
||||
class AP_VisualOdom_IntelT265 : public AP_VisualOdom_Backend
|
||||
{
|
||||
|
||||
@ -43,3 +45,5 @@ protected:
|
||||
bool _error_orientation; // true if the orientation is not supported
|
||||
Quaternion _attitude_last; // last attitude received from camera (used for arming checks)
|
||||
};
|
||||
|
||||
#endif
|
||||
|
@ -14,6 +14,9 @@
|
||||
*/
|
||||
|
||||
#include "AP_VisualOdom_MAV.h"
|
||||
|
||||
#if HAL_VISUALODOM_ENABLED
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
@ -81,3 +84,5 @@ void AP_VisualOdom_MAV::handle_vision_position_estimate(uint64_t remote_time_us,
|
||||
// record time for health monitoring
|
||||
_last_update_ms = AP_HAL::millis();
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -2,6 +2,8 @@
|
||||
|
||||
#include "AP_VisualOdom_Backend.h"
|
||||
|
||||
#if HAL_VISUALODOM_ENABLED
|
||||
|
||||
class AP_VisualOdom_MAV : public AP_VisualOdom_Backend
|
||||
{
|
||||
|
||||
@ -15,3 +17,5 @@ public:
|
||||
// consume vision position estimate data and send to EKF. distances in meters
|
||||
void handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude) override;
|
||||
};
|
||||
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user