1234567891011121314151617181920212223242526272829303132333435363738 |
- #include <AP_HAL/AP_HAL.h>
- #include "AP_VisualOdom_MAV.h"
- #include <AP_SerialManager/AP_SerialManager.h>
- extern const AP_HAL::HAL& hal;
- AP_VisualOdom_MAV::AP_VisualOdom_MAV(AP_VisualOdom &frontend) :
- AP_VisualOdom_Backend(frontend)
- {
- }
- void AP_VisualOdom_MAV::handle_msg(const mavlink_message_t &msg)
- {
-
- mavlink_vision_position_delta_t packet;
- mavlink_msg_vision_position_delta_decode(&msg, &packet);
- const Vector3f angle_delta(packet.angle_delta[0], packet.angle_delta[1], packet.angle_delta[2]);
- const Vector3f position_delta(packet.position_delta[0], packet.position_delta[1], packet.position_delta[2]);
- set_deltas(angle_delta, position_delta, packet.time_delta_usec, packet.confidence);
- }
|