PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
Loading...
Searching...
No Matches
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>
9using 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/battery_status"}, \
31 {"fmu/out/home_position"}, \
32 {"fmu/out/manual_control_setpoint"}, \
33 {"fmu/out/mode_completed"}, \
34 {"fmu/out/register_ext_component_reply"}, \
35 {"fmu/out/vehicle_attitude"}, \
36 {"fmu/out/vehicle_angular_velocity"}, \
37 {"fmu/out/vehicle_command_ack"}, \
38 {"fmu/out/vehicle_global_position"}, \
39 {"fmu/out/vehicle_land_detected"}, \
40 {"fmu/out/vehicle_local_position"}, \
41 {"fmu/out/vehicle_status"}, \
42 {"fmu/out/vtol_vehicle_status"}
43
44
45namespace px4_ros2
46{
52{
53 std::string topic_name;
54 std::string topic_type{""};
55};
56
63 rclcpp::Node & node, const std::vector<MessageCompatibilityTopic> & messages_to_check,
64 const std::string & topic_namespace_prefix = "");
65
67} // 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:52
std::string topic_type
e.g. VehicleStatus. If empty, it's inferred from the topic_name // NOLINT
Definition message_compatibility_check.hpp:54
std::string topic_name
e.g. "fmu/out/vehicle_status"
Definition message_compatibility_check.hpp:53