Path: blob/master/libraries/AP_DDS/AP_DDS_Topic_Table.h
9584 views
#include "builtin_interfaces/msg/Time.h"1#include "sensor_msgs/msg/NavSatFix.h"2#include "tf2_msgs/msg/TFMessage.h"3#include "sensor_msgs/msg/BatteryState.h"4#include "geographic_msgs/msg/GeoPoseStamped.h"5#include "geometry_msgs/msg/Vector3Stamped.h"6#if AP_DDS_IMU_PUB_ENABLED7#include "sensor_msgs/msg/Imu.h"8#endif //AP_DDS_IMU_PUB_ENABLED910#include "uxr/client/client.h"1112// Code generated table based on the enabled topics.13// Mavgen is using python, loops are not readable.14// Can use jinja to template (like Flask)1516enum class TopicIndex: uint8_t {17#if AP_DDS_TIME_PUB_ENABLED18TIME_PUB,19#endif // AP_DDS_TIME_PUB_ENABLED20#if AP_DDS_NAVSATFIX_PUB_ENABLED21NAV_SAT_FIX_PUB,22#endif // AP_DDS_NAVSATFIX_PUB_ENABLED23#if AP_DDS_STATIC_TF_PUB_ENABLED24STATIC_TRANSFORMS_PUB,25#endif // AP_DDS_STATIC_TF_PUB_ENABLED26#if AP_DDS_BATTERY_STATE_PUB_ENABLED27BATTERY_STATE_PUB,28#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED29#if AP_DDS_IMU_PUB_ENABLED30IMU_PUB,31#endif //AP_DDS_IMU_PUB_ENABLED32#if AP_DDS_LOCAL_POSE_PUB_ENABLED33LOCAL_POSE_PUB,34#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED35#if AP_DDS_LOCAL_VEL_PUB_ENABLED36LOCAL_VELOCITY_PUB,37#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED38#if AP_DDS_AIRSPEED_PUB_ENABLED39LOCAL_AIRSPEED_PUB,40#endif // AP_DDS_AIRSPEED_PUB_ENABLED41#if AP_DDS_RC_PUB_ENABLED42LOCAL_RC_PUB,43#endif // AP_DDS_RC_PUB_ENABLED44#if AP_DDS_GEOPOSE_PUB_ENABLED45GEOPOSE_PUB,46#endif // AP_DDS_GEOPOSE_PUB_ENABLED47#if AP_DDS_GOAL_PUB_ENABLED48GOAL_PUB,49#endif // AP_DDS_GOAL_PUB_ENABLED50#if AP_DDS_CLOCK_PUB_ENABLED51CLOCK_PUB,52#endif // AP_DDS_CLOCK_PUB_ENABLED53#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED54GPS_GLOBAL_ORIGIN_PUB,55#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED56#if AP_DDS_STATUS_PUB_ENABLED57STATUS_PUB,58#endif // AP_DDS_STATUS_PUB_ENABLED59#if AP_DDS_JOY_SUB_ENABLED60JOY_SUB,61#endif // AP_DDS_JOY_SUB_ENABLED62#if AP_DDS_DYNAMIC_TF_SUB_ENABLED63DYNAMIC_TRANSFORMS_SUB,64#endif // AP_DDS_DYNAMIC_TF_SUB_ENABLED65#if AP_DDS_VEL_CTRL_ENABLED66VELOCITY_CONTROL_SUB,67#endif // AP_DDS_VEL_CTRL_ENABLED68#if AP_DDS_GLOBAL_POS_CTRL_ENABLED69GLOBAL_POSITION_SUB,70#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED71};7273static inline constexpr uint8_t to_underlying(const TopicIndex index)74{75static_assert(sizeof(index) == sizeof(uint8_t));76return static_cast<uint8_t>(index);77}787980constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {81#if AP_DDS_TIME_PUB_ENABLED82{83.topic_id = to_underlying(TopicIndex::TIME_PUB),84.pub_id = to_underlying(TopicIndex::TIME_PUB),85.sub_id = to_underlying(TopicIndex::TIME_PUB),86.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::TIME_PUB), .type=UXR_DATAWRITER_ID},87.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::TIME_PUB), .type=UXR_DATAREADER_ID},88.topic_rw = Topic_rw::DataWriter,89.topic_name = "rt/ap/time",90.type_name = "builtin_interfaces::msg::dds_::Time_",91.qos = {92.durability = UXR_DURABILITY_VOLATILE,93.reliability = UXR_RELIABILITY_RELIABLE,94.history = UXR_HISTORY_KEEP_LAST,95.depth = 20,96},97},98#endif // AP_DDS_TIME_PUB_ENABLED99#if AP_DDS_NAVSATFIX_PUB_ENABLED100{101.topic_id = to_underlying(TopicIndex::NAV_SAT_FIX_PUB),102.pub_id = to_underlying(TopicIndex::NAV_SAT_FIX_PUB),103.sub_id = to_underlying(TopicIndex::NAV_SAT_FIX_PUB),104.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::NAV_SAT_FIX_PUB), .type=UXR_DATAWRITER_ID},105.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::NAV_SAT_FIX_PUB), .type=UXR_DATAREADER_ID},106.topic_rw = Topic_rw::DataWriter,107.topic_name = "rt/ap/navsat",108.type_name = "sensor_msgs::msg::dds_::NavSatFix_",109.qos = {110.durability = UXR_DURABILITY_VOLATILE,111.reliability = UXR_RELIABILITY_BEST_EFFORT,112.history = UXR_HISTORY_KEEP_LAST,113.depth = 5,114},115},116#endif // AP_DDS_NAVSATFIX_PUB_ENABLED117#if AP_DDS_STATIC_TF_PUB_ENABLED118{119.topic_id = to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB),120.pub_id = to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB),121.sub_id = to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB),122.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB), .type=UXR_DATAWRITER_ID},123.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB), .type=UXR_DATAREADER_ID},124.topic_rw = Topic_rw::DataWriter,125.topic_name = "rt/ap/tf_static",126.type_name = "tf2_msgs::msg::dds_::TFMessage_",127.qos = {128.durability = UXR_DURABILITY_TRANSIENT_LOCAL,129.reliability = UXR_RELIABILITY_RELIABLE,130.history = UXR_HISTORY_KEEP_LAST,131.depth = 1,132},133},134#endif // AP_DDS_STATIC_TF_PUB_ENABLED135#if AP_DDS_BATTERY_STATE_PUB_ENABLED136{137.topic_id = to_underlying(TopicIndex::BATTERY_STATE_PUB),138.pub_id = to_underlying(TopicIndex::BATTERY_STATE_PUB),139.sub_id = to_underlying(TopicIndex::BATTERY_STATE_PUB),140.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::BATTERY_STATE_PUB), .type=UXR_DATAWRITER_ID},141.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::BATTERY_STATE_PUB), .type=UXR_DATAREADER_ID},142.topic_rw = Topic_rw::DataWriter,143.topic_name = "rt/ap/battery",144.type_name = "sensor_msgs::msg::dds_::BatteryState_",145.qos = {146.durability = UXR_DURABILITY_VOLATILE,147.reliability = UXR_RELIABILITY_BEST_EFFORT,148.history = UXR_HISTORY_KEEP_LAST,149.depth = 5,150},151},152#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED153#if AP_DDS_IMU_PUB_ENABLED154{155.topic_id = to_underlying(TopicIndex::IMU_PUB),156.pub_id = to_underlying(TopicIndex::IMU_PUB),157.sub_id = to_underlying(TopicIndex::IMU_PUB),158.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::IMU_PUB), .type=UXR_DATAWRITER_ID},159.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::IMU_PUB), .type=UXR_DATAREADER_ID},160.topic_rw = Topic_rw::DataWriter,161.topic_name = "rt/ap/imu/experimental/data",162.type_name = "sensor_msgs::msg::dds_::Imu_",163.qos = {164.durability = UXR_DURABILITY_VOLATILE,165.reliability = UXR_RELIABILITY_BEST_EFFORT,166.history = UXR_HISTORY_KEEP_LAST,167.depth = 5,168},169},170#endif //AP_DDS_IMU_PUB_ENABLED171#if AP_DDS_LOCAL_POSE_PUB_ENABLED172{173.topic_id = to_underlying(TopicIndex::LOCAL_POSE_PUB),174.pub_id = to_underlying(TopicIndex::LOCAL_POSE_PUB),175.sub_id = to_underlying(TopicIndex::LOCAL_POSE_PUB),176.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_POSE_PUB), .type=UXR_DATAWRITER_ID},177.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_POSE_PUB), .type=UXR_DATAREADER_ID},178.topic_rw = Topic_rw::DataWriter,179.topic_name = "rt/ap/pose/filtered",180.type_name = "geometry_msgs::msg::dds_::PoseStamped_",181.qos = {182.durability = UXR_DURABILITY_VOLATILE,183.reliability = UXR_RELIABILITY_BEST_EFFORT,184.history = UXR_HISTORY_KEEP_LAST,185.depth = 5,186},187},188#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED189#if AP_DDS_LOCAL_VEL_PUB_ENABLED190{191.topic_id = to_underlying(TopicIndex::LOCAL_VELOCITY_PUB),192.pub_id = to_underlying(TopicIndex::LOCAL_VELOCITY_PUB),193.sub_id = to_underlying(TopicIndex::LOCAL_VELOCITY_PUB),194.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_VELOCITY_PUB), .type=UXR_DATAWRITER_ID},195.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_VELOCITY_PUB), .type=UXR_DATAREADER_ID},196.topic_rw = Topic_rw::DataWriter,197.topic_name = "rt/ap/twist/filtered",198.type_name = "geometry_msgs::msg::dds_::TwistStamped_",199.qos = {200.durability = UXR_DURABILITY_VOLATILE,201.reliability = UXR_RELIABILITY_BEST_EFFORT,202.history = UXR_HISTORY_KEEP_LAST,203.depth = 5,204},205},206#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED207#if AP_DDS_AIRSPEED_PUB_ENABLED208{209.topic_id = to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB),210.pub_id = to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB),211.sub_id = to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB),212.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB), .type=UXR_DATAWRITER_ID},213.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB), .type=UXR_DATAREADER_ID},214.topic_rw = Topic_rw::DataWriter,215.topic_name = "rt/ap/airspeed",216.type_name = "ardupilot_msgs::msg::dds_::Airspeed_",217.qos = {218.durability = UXR_DURABILITY_VOLATILE,219.reliability = UXR_RELIABILITY_BEST_EFFORT,220.history = UXR_HISTORY_KEEP_LAST,221.depth = 5,222},223},224#endif // AP_DDS_AIRSPEED_PUB_ENABLED225#if AP_DDS_RC_PUB_ENABLED226{227.topic_id = to_underlying(TopicIndex::LOCAL_RC_PUB),228.pub_id = to_underlying(TopicIndex::LOCAL_RC_PUB),229.sub_id = to_underlying(TopicIndex::LOCAL_RC_PUB),230.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_RC_PUB), .type=UXR_DATAWRITER_ID},231.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_RC_PUB), .type=UXR_DATAREADER_ID},232.topic_rw = Topic_rw::DataWriter,233.topic_name = "rt/ap/rc",234.type_name = "ardupilot_msgs::msg::dds_::Rc_",235.qos = {236.durability = UXR_DURABILITY_VOLATILE,237.reliability = UXR_RELIABILITY_BEST_EFFORT,238.history = UXR_HISTORY_KEEP_LAST,239.depth = 1,240},241},242#endif // AP_DDS_RC_PUB_ENABLED243#if AP_DDS_GEOPOSE_PUB_ENABLED244{245.topic_id = to_underlying(TopicIndex::GEOPOSE_PUB),246.pub_id = to_underlying(TopicIndex::GEOPOSE_PUB),247.sub_id = to_underlying(TopicIndex::GEOPOSE_PUB),248.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GEOPOSE_PUB), .type=UXR_DATAWRITER_ID},249.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GEOPOSE_PUB), .type=UXR_DATAREADER_ID},250.topic_rw = Topic_rw::DataWriter,251.topic_name = "rt/ap/geopose/filtered",252.type_name = "geographic_msgs::msg::dds_::GeoPoseStamped_",253.qos = {254.durability = UXR_DURABILITY_VOLATILE,255.reliability = UXR_RELIABILITY_BEST_EFFORT,256.history = UXR_HISTORY_KEEP_LAST,257.depth = 5,258},259},260#endif // AP_DDS_GEOPOSE_PUB_ENABLED261#if AP_DDS_GOAL_PUB_ENABLED262{263.topic_id = to_underlying(TopicIndex::GOAL_PUB),264.pub_id = to_underlying(TopicIndex::GOAL_PUB),265.sub_id = to_underlying(TopicIndex::GOAL_PUB),266.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GOAL_PUB), .type=UXR_DATAWRITER_ID},267.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GOAL_PUB), .type=UXR_DATAREADER_ID},268.topic_rw = Topic_rw::DataWriter,269.topic_name = "rt/ap/goal_lla",270.type_name = "geographic_msgs::msg::dds_::GeoPointStamped_",271.qos = {272.durability = UXR_DURABILITY_TRANSIENT_LOCAL,273.reliability = UXR_RELIABILITY_RELIABLE,274.history = UXR_HISTORY_KEEP_LAST,275.depth = 1,276},277},278#endif // AP_DDS_GOAL_PUB_ENABLED279#if AP_DDS_CLOCK_PUB_ENABLED280{281.topic_id = to_underlying(TopicIndex::CLOCK_PUB),282.pub_id = to_underlying(TopicIndex::CLOCK_PUB),283.sub_id = to_underlying(TopicIndex::CLOCK_PUB),284.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::CLOCK_PUB), .type=UXR_DATAWRITER_ID},285.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::CLOCK_PUB), .type=UXR_DATAREADER_ID},286.topic_rw = Topic_rw::DataWriter,287.topic_name = "rt/ap/clock",288.type_name = "rosgraph_msgs::msg::dds_::Clock_",289.qos = {290.durability = UXR_DURABILITY_VOLATILE,291.reliability = UXR_RELIABILITY_RELIABLE,292.history = UXR_HISTORY_KEEP_LAST,293.depth = 20,294},295},296#endif // AP_DDS_CLOCK_PUB_ENABLED297#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED298{299.topic_id = to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB),300.pub_id = to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB),301.sub_id = to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB),302.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB), .type=UXR_DATAWRITER_ID},303.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB), .type=UXR_DATAREADER_ID},304.topic_rw = Topic_rw::DataWriter,305.topic_name = "rt/ap/gps_global_origin/filtered",306.type_name = "geographic_msgs::msg::dds_::GeoPointStamped_",307.qos = {308.durability = UXR_DURABILITY_VOLATILE,309.reliability = UXR_RELIABILITY_BEST_EFFORT,310.history = UXR_HISTORY_KEEP_LAST,311.depth = 5,312},313},314#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED315#if AP_DDS_STATUS_PUB_ENABLED316{317.topic_id = to_underlying(TopicIndex::STATUS_PUB),318.pub_id = to_underlying(TopicIndex::STATUS_PUB),319.sub_id = to_underlying(TopicIndex::STATUS_PUB),320.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::STATUS_PUB), .type=UXR_DATAWRITER_ID},321.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::STATUS_PUB), .type=UXR_DATAREADER_ID},322.topic_rw = Topic_rw::DataWriter,323.topic_name = "rt/ap/status",324.type_name = "ardupilot_msgs::msg::dds_::Status_",325.qos = {326.durability = UXR_DURABILITY_TRANSIENT_LOCAL,327.reliability = UXR_RELIABILITY_RELIABLE,328.history = UXR_HISTORY_KEEP_LAST,329.depth = 1,330},331},332#endif // AP_DDS_STATUS_PUB_ENABLED333#if AP_DDS_JOY_SUB_ENABLED334{335.topic_id = to_underlying(TopicIndex::JOY_SUB),336.pub_id = to_underlying(TopicIndex::JOY_SUB),337.sub_id = to_underlying(TopicIndex::JOY_SUB),338.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::JOY_SUB), .type=UXR_DATAWRITER_ID},339.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::JOY_SUB), .type=UXR_DATAREADER_ID},340.topic_rw = Topic_rw::DataReader,341.topic_name = "rt/ap/joy",342.type_name = "sensor_msgs::msg::dds_::Joy_",343.qos = {344.durability = UXR_DURABILITY_VOLATILE,345.reliability = UXR_RELIABILITY_BEST_EFFORT,346.history = UXR_HISTORY_KEEP_LAST,347.depth = 5,348},349},350#endif // AP_DDS_JOY_SUB_ENABLED351#if AP_DDS_DYNAMIC_TF_SUB_ENABLED352{353.topic_id = to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB),354.pub_id = to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB),355.sub_id = to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB),356.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB), .type=UXR_DATAWRITER_ID},357.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB), .type=UXR_DATAREADER_ID},358.topic_rw = Topic_rw::DataReader,359.topic_name = "rt/ap/tf",360.type_name = "tf2_msgs::msg::dds_::TFMessage_",361.qos = {362.durability = UXR_DURABILITY_VOLATILE,363.reliability = UXR_RELIABILITY_BEST_EFFORT,364.history = UXR_HISTORY_KEEP_LAST,365.depth = 5,366},367},368#endif // AP_DDS_DYNAMIC_TF_SUB_ENABLED369#if AP_DDS_VEL_CTRL_ENABLED370{371.topic_id = to_underlying(TopicIndex::VELOCITY_CONTROL_SUB),372.pub_id = to_underlying(TopicIndex::VELOCITY_CONTROL_SUB),373.sub_id = to_underlying(TopicIndex::VELOCITY_CONTROL_SUB),374.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::VELOCITY_CONTROL_SUB), .type=UXR_DATAWRITER_ID},375.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::VELOCITY_CONTROL_SUB), .type=UXR_DATAREADER_ID},376.topic_rw = Topic_rw::DataReader,377.topic_name = "rt/ap/cmd_vel",378.type_name = "geometry_msgs::msg::dds_::TwistStamped_",379.qos = {380.durability = UXR_DURABILITY_VOLATILE,381.reliability = UXR_RELIABILITY_BEST_EFFORT,382.history = UXR_HISTORY_KEEP_LAST,383.depth = 5,384},385},386#endif // AP_DDS_VEL_CTRL_ENABLED387#if AP_DDS_GLOBAL_POS_CTRL_ENABLED388{389.topic_id = to_underlying(TopicIndex::GLOBAL_POSITION_SUB),390.pub_id = to_underlying(TopicIndex::GLOBAL_POSITION_SUB),391.sub_id = to_underlying(TopicIndex::GLOBAL_POSITION_SUB),392.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GLOBAL_POSITION_SUB), .type=UXR_DATAWRITER_ID},393.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GLOBAL_POSITION_SUB), .type=UXR_DATAREADER_ID},394.topic_rw = Topic_rw::DataReader,395.topic_name = "rt/ap/cmd_gps_pose",396.type_name = "ardupilot_msgs::msg::dds_::GlobalPosition_",397.qos = {398.durability = UXR_DURABILITY_VOLATILE,399.reliability = UXR_RELIABILITY_BEST_EFFORT,400.history = UXR_HISTORY_KEEP_LAST,401.depth = 5,402},403},404#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED405};406407408