32 mavlink_vision_position_delta_t packet;
33 mavlink_msg_vision_position_delta_decode(msg, &packet);
35 const Vector3f angle_delta(packet.angle_delta[0], packet.angle_delta[1], packet.angle_delta[2]);
36 const Vector3f position_delta(packet.position_delta[0], packet.position_delta[1], packet.position_delta[2]);
37 set_deltas(angle_delta, position_delta, packet.time_delta_usec, packet.confidence);
void set_deltas(const Vector3f &angle_delta, const Vector3f &position_delta, uint64_t time_delta_usec, float confidence)
AP_VisualOdom_MAV(AP_VisualOdom &frontend)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void handle_msg(mavlink_message_t *msg) override