Browse Source

AP_VisualOdom: front-end implements handle_vision_position_estimate with eulers

zr-v5.1
Randy Mackay 5 years ago
parent
commit
a41b169635
  1. 5
      libraries/AP_VisualOdom/AP_VisualOdom.cpp
  2. 9
      libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp
  3. 1
      libraries/AP_VisualOdom/AP_VisualOdom_Backend.h

5
libraries/AP_VisualOdom/AP_VisualOdom.cpp

@ -131,7 +131,10 @@ void AP_VisualOdom::handle_vision_position_estimate(uint64_t remote_time_us, uin
// call backend // call backend
if (_driver != nullptr) { if (_driver != nullptr) {
_driver->handle_vision_position_estimate(remote_time_us, time_ms, x, y, z, roll, pitch, yaw); // convert attitude to quaternion and call backend
Quaternion attitude;
attitude.from_euler(roll, pitch, yaw);
_driver->handle_vision_position_estimate(remote_time_us, time_ms, x, y, z, attitude);
} }
} }

9
libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp

@ -35,15 +35,6 @@ bool AP_VisualOdom_Backend::healthy() const
return ((AP_HAL::millis() - _last_update_ms) < AP_VISUALODOM_TIMEOUT_MS); return ((AP_HAL::millis() - _last_update_ms) < AP_VISUALODOM_TIMEOUT_MS);
} }
// general purpose method to send position estimate data to EKF
// distances in meters, roll, pitch and yaw are in radians
void AP_VisualOdom_Backend::handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, float roll, float pitch, float yaw)
{
Quaternion attitude;
attitude.from_euler(roll, pitch, yaw);
handle_vision_position_estimate(remote_time_us, time_ms, x, y, z, attitude);
}
// general purpose method to send position estimate data to EKF // general purpose method to send position estimate data to EKF
void AP_VisualOdom_Backend::handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude) void AP_VisualOdom_Backend::handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude)
{ {

1
libraries/AP_VisualOdom/AP_VisualOdom_Backend.h

@ -33,7 +33,6 @@ public:
// general purpose methods to consume position estimate data and send to EKF // general purpose methods to consume position estimate data and send to EKF
// distances in meters, roll, pitch and yaw are in radians // distances in meters, roll, pitch and yaw are in radians
void handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, float roll, float pitch, float yaw);
void handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude); void handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude);
// calibrate camera attitude to align with vehicle's AHRS/EKF attitude // calibrate camera attitude to align with vehicle's AHRS/EKF attitude

Loading…
Cancel
Save