PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
message_compatibility_check.hpp
1 /****************************************************************************
2  * Copyright (c) 2023 PX4 Development Team.
3  * SPDX-License-Identifier: BSD-3-Clause
4  ****************************************************************************/
5 
6 #pragma once
7 
8 #include <rclcpp/rclcpp.hpp>
9 using namespace std::chrono_literals; // NOLINT
10 
11 // Set of all messages used by the library (<topic_name>[, <topic_type>])
12 #define ALL_PX4_ROS2_MESSAGES \
13  {"fmu/in/actuator_motors"}, \
14  {"fmu/in/actuator_servos"}, \
15  {"fmu/in/arming_check_reply"}, \
16  {"fmu/in/aux_global_position", "VehicleGlobalPosition"}, \
17  {"fmu/in/config_control_setpoints", "VehicleControlMode"}, \
18  {"fmu/in/config_overrides_request", "ConfigOverrides"}, \
19  {"fmu/in/goto_setpoint"}, \
20  {"fmu/in/mode_completed"}, \
21  {"fmu/in/register_ext_component_request"}, \
22  {"fmu/in/trajectory_setpoint"}, \
23  {"fmu/in/unregister_ext_component"}, \
24  {"fmu/in/vehicle_attitude_setpoint"}, \
25  {"fmu/in/vehicle_command"}, \
26  {"fmu/in/vehicle_command_mode_executor", "VehicleCommand"}, \
27  {"fmu/in/vehicle_rates_setpoint"}, \
28  {"fmu/in/vehicle_visual_odometry", "VehicleOdometry"}, \
29  {"fmu/out/arming_check_request"}, \
30  {"fmu/out/manual_control_setpoint"}, \
31  {"fmu/out/mode_completed"}, \
32  {"fmu/out/register_ext_component_reply"}, \
33  {"fmu/out/vehicle_attitude"}, \
34  {"fmu/out/vehicle_angular_velocity"}, \
35  {"fmu/out/vehicle_command_ack"}, \
36  {"fmu/out/vehicle_global_position"}, \
37  {"fmu/out/vehicle_local_position"}, \
38  {"fmu/out/vehicle_status"}
39 
40 
41 namespace px4_ros2
42 {
48 {
49  std::string topic_name;
50  std::string topic_type{""};
51 };
52 
59  rclcpp::Node & node, const std::vector<MessageCompatibilityTopic> & messages_to_check,
60  const std::string & topic_namespace_prefix = "");
61 
63 } // namespace px4_ros2
bool messageCompatibilityCheck(rclcpp::Node &node, const std::vector< MessageCompatibilityTopic > &messages_to_check, const std::string &topic_namespace_prefix="")
Definition: message_compatibility_check.hpp:48
std::string topic_name
e.g. "fmu/out/vehicle_status"
Definition: message_compatibility_check.hpp:49