1 // Class for handling external localization data.
2 // For historical reasons, it's called odometry to match AP_VisualOdom.
6 #include "AP_DDS_config.h"
7 #if AP_DDS_VISUALODOM_ENABLED
9 #include "geometry_msgs/msg/TransformStamped.h"
10 #include "tf2_msgs/msg/TFMessage.h"
11 #include "AP_Math/vector3.h"
12 #include "AP_Math/quaternion.h"
14 class AP_DDS_External_Odom
18 // Handler for external position localization
19 static void handle_external_odom(const tf2_msgs_msg_TFMessage
& msg
);
21 // Checks the child and parent frames match a set needed for external odom.
22 // Since multiple different transforms can be sent, this validates the specific transform is
24 static bool is_odometry_frame(const geometry_msgs_msg_TransformStamped
& msg
);
26 // Helper to convert from ROS transform to AP datatypes
27 // ros_transform is in ENU
28 // translation is in NED
29 static void convert_transform(const geometry_msgs_msg_Transform
& ros_transform
, Vector3f
& translation
, Quaternion
& rotation
);
33 #endif // AP_DDS_VISUALODOM_ENABLED