Path: blob/master/libraries/AP_DDS/AP_DDS_External_Odom.h
9316 views
// Class for handling external localization data.1// For historical reasons, it's called odometry to match AP_VisualOdom.23#pragma once45#include "AP_DDS_config.h"6#if AP_DDS_VISUALODOM_ENABLED78#include "geometry_msgs/msg/TransformStamped.h"9#include "tf2_msgs/msg/TFMessage.h"10#include "AP_Math/vector3.h"11#include "AP_Math/quaternion.h"1213class AP_DDS_External_Odom14{15public:1617// Handler for external position localization18static void handle_external_odom(const tf2_msgs_msg_TFMessage& msg);1920// Checks the child and parent frames match a set needed for external odom.21// Since multiple different transforms can be sent, this validates the specific transform is22// for odometry.23static bool is_odometry_frame(const geometry_msgs_msg_TransformStamped& msg);2425// Helper to convert from ROS transform to AP datatypes26// ros_transform is in ENU27// translation is in NED28static void convert_transform(const geometry_msgs_msg_Transform& ros_transform, Vector3f& translation, Quaternion& rotation);2930};3132#endif // AP_DDS_VISUALODOM_ENABLED333435