CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_DDS/AP_DDS_External_Odom.h
Views: 1798
1
// Class for handling external localization data.
2
// For historical reasons, it's called odometry to match AP_VisualOdom.
3
4
#pragma once
5
6
#include "AP_DDS_config.h"
7
#if AP_DDS_VISUALODOM_ENABLED
8
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"
13
14
class AP_DDS_External_Odom
15
{
16
public:
17
18
// Handler for external position localization
19
static void handle_external_odom(const tf2_msgs_msg_TFMessage& msg);
20
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
23
// for odometry.
24
static bool is_odometry_frame(const geometry_msgs_msg_TransformStamped& msg);
25
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);
30
31
};
32
33
#endif // AP_DDS_VISUALODOM_ENABLED
34
35