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/tests/test_ap_dds_external_odom.cpp
Views: 1799
1
#include <AP_gtest.h>
2
3
#include <AP_DDS/AP_DDS_config.h>
4
5
#include <AP_DDS/AP_DDS_External_Odom.h>
6
#include "geometry_msgs/msg/TransformStamped.h"
7
#include <AP_HAL/AP_HAL.h>
8
9
#if AP_DDS_VISUALODOM_ENABLED
10
11
const AP_HAL::HAL &hal = AP_HAL::get_HAL();
12
13
TEST(AP_DDS_EXTERNAL_ODOM, test_is_odometry_success)
14
{
15
geometry_msgs_msg_TransformStamped msg {};
16
17
strncpy(msg.header.frame_id, "odom", strlen("odom") + 1);
18
strncpy(msg.child_frame_id, "base_link", strlen("base_link") + 1);
19
ASSERT_TRUE(AP_DDS_External_Odom::is_odometry_frame(msg));
20
21
strncpy(msg.header.frame_id, "invalid", strlen("invalid") + 1);
22
strncpy(msg.child_frame_id, "base_link", strlen("base_link") + 1);
23
ASSERT_FALSE(AP_DDS_External_Odom::is_odometry_frame(msg));
24
25
strncpy(msg.header.frame_id, "odom", strlen("odom") + 1);
26
strncpy(msg.child_frame_id, "invalid", strlen("invalid") + 1);
27
ASSERT_FALSE(AP_DDS_External_Odom::is_odometry_frame(msg));
28
29
strncpy(msg.header.frame_id, "odom_with_invalid_extra", strlen("odom_with_invalid_extra") + 1);
30
strncpy(msg.child_frame_id, "base_link", strlen("base_link") + 1);
31
ASSERT_FALSE(AP_DDS_External_Odom::is_odometry_frame(msg));
32
33
strncpy(msg.header.frame_id, "odom", strlen("odom") + 1);
34
strncpy(msg.child_frame_id, "base_link_with_invalid_extra", strlen("base_link_with_invalid_extra") + 1);
35
ASSERT_FALSE(AP_DDS_External_Odom::is_odometry_frame(msg));
36
37
strncpy(msg.header.frame_id, "x", strlen("x") + 1);
38
strncpy(msg.child_frame_id, "base_link", strlen("base_link") + 1);
39
ASSERT_FALSE(AP_DDS_External_Odom::is_odometry_frame(msg));
40
}
41
42
#endif // AP_DDS_VISUALODOM_ENABLED
43
44
AP_GTEST_MAIN()
45
46