Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_DDS/AP_DDS_Topic_Table.h
Views: 1798
#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_GEOPOSE_PUB_ENABLED42GEOPOSE_PUB,43#endif // AP_DDS_GEOPOSE_PUB_ENABLED44#if AP_DDS_GOAL_PUB_ENABLED45GOAL_PUB,46#endif // AP_DDS_GOAL_PUB_ENABLED47#if AP_DDS_CLOCK_PUB_ENABLED48CLOCK_PUB,49#endif // AP_DDS_CLOCK_PUB_ENABLED50#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED51GPS_GLOBAL_ORIGIN_PUB,52#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED53#if AP_DDS_STATUS_PUB_ENABLED54STATUS_PUB,55#endif // AP_DDS_STATUS_PUB_ENABLED56#if AP_DDS_JOY_SUB_ENABLED57JOY_SUB,58#endif // AP_DDS_JOY_SUB_ENABLED59#if AP_DDS_DYNAMIC_TF_SUB_ENABLED60DYNAMIC_TRANSFORMS_SUB,61#endif // AP_DDS_DYNAMIC_TF_SUB_ENABLED62#if AP_DDS_VEL_CTRL_ENABLED63VELOCITY_CONTROL_SUB,64#endif // AP_DDS_VEL_CTRL_ENABLED65#if AP_DDS_GLOBAL_POS_CTRL_ENABLED66GLOBAL_POSITION_SUB,67#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED68};6970static inline constexpr uint8_t to_underlying(const TopicIndex index)71{72static_assert(sizeof(index) == sizeof(uint8_t));73return static_cast<uint8_t>(index);74}757677constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {78#if AP_DDS_TIME_PUB_ENABLED79{80.topic_id = to_underlying(TopicIndex::TIME_PUB),81.pub_id = to_underlying(TopicIndex::TIME_PUB),82.sub_id = to_underlying(TopicIndex::TIME_PUB),83.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::TIME_PUB), .type=UXR_DATAWRITER_ID},84.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::TIME_PUB), .type=UXR_DATAREADER_ID},85.topic_rw = Topic_rw::DataWriter,86.topic_name = "rt/ap/time",87.type_name = "builtin_interfaces::msg::dds_::Time_",88.qos = {89.durability = UXR_DURABILITY_VOLATILE,90.reliability = UXR_RELIABILITY_RELIABLE,91.history = UXR_HISTORY_KEEP_LAST,92.depth = 20,93},94},95#endif // AP_DDS_TIME_PUB_ENABLED96#if AP_DDS_NAVSATFIX_PUB_ENABLED97{98.topic_id = to_underlying(TopicIndex::NAV_SAT_FIX_PUB),99.pub_id = to_underlying(TopicIndex::NAV_SAT_FIX_PUB),100.sub_id = to_underlying(TopicIndex::NAV_SAT_FIX_PUB),101.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::NAV_SAT_FIX_PUB), .type=UXR_DATAWRITER_ID},102.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::NAV_SAT_FIX_PUB), .type=UXR_DATAREADER_ID},103.topic_rw = Topic_rw::DataWriter,104.topic_name = "rt/ap/navsat",105.type_name = "sensor_msgs::msg::dds_::NavSatFix_",106.qos = {107.durability = UXR_DURABILITY_VOLATILE,108.reliability = UXR_RELIABILITY_BEST_EFFORT,109.history = UXR_HISTORY_KEEP_LAST,110.depth = 5,111},112},113#endif // AP_DDS_NAVSATFIX_PUB_ENABLED114#if AP_DDS_STATIC_TF_PUB_ENABLED115{116.topic_id = to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB),117.pub_id = to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB),118.sub_id = to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB),119.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB), .type=UXR_DATAWRITER_ID},120.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB), .type=UXR_DATAREADER_ID},121.topic_rw = Topic_rw::DataWriter,122.topic_name = "rt/ap/tf_static",123.type_name = "tf2_msgs::msg::dds_::TFMessage_",124.qos = {125.durability = UXR_DURABILITY_TRANSIENT_LOCAL,126.reliability = UXR_RELIABILITY_RELIABLE,127.history = UXR_HISTORY_KEEP_LAST,128.depth = 1,129},130},131#endif // AP_DDS_STATIC_TF_PUB_ENABLED132#if AP_DDS_BATTERY_STATE_PUB_ENABLED133{134.topic_id = to_underlying(TopicIndex::BATTERY_STATE_PUB),135.pub_id = to_underlying(TopicIndex::BATTERY_STATE_PUB),136.sub_id = to_underlying(TopicIndex::BATTERY_STATE_PUB),137.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::BATTERY_STATE_PUB), .type=UXR_DATAWRITER_ID},138.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::BATTERY_STATE_PUB), .type=UXR_DATAREADER_ID},139.topic_rw = Topic_rw::DataWriter,140.topic_name = "rt/ap/battery",141.type_name = "sensor_msgs::msg::dds_::BatteryState_",142.qos = {143.durability = UXR_DURABILITY_VOLATILE,144.reliability = UXR_RELIABILITY_BEST_EFFORT,145.history = UXR_HISTORY_KEEP_LAST,146.depth = 5,147},148},149#endif // AP_DDS_BATTERY_STATE_PUB_ENABLED150#if AP_DDS_IMU_PUB_ENABLED151{152.topic_id = to_underlying(TopicIndex::IMU_PUB),153.pub_id = to_underlying(TopicIndex::IMU_PUB),154.sub_id = to_underlying(TopicIndex::IMU_PUB),155.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::IMU_PUB), .type=UXR_DATAWRITER_ID},156.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::IMU_PUB), .type=UXR_DATAREADER_ID},157.topic_rw = Topic_rw::DataWriter,158.topic_name = "rt/ap/imu/experimental/data",159.type_name = "sensor_msgs::msg::dds_::Imu_",160.qos = {161.durability = UXR_DURABILITY_VOLATILE,162.reliability = UXR_RELIABILITY_BEST_EFFORT,163.history = UXR_HISTORY_KEEP_LAST,164.depth = 5,165},166},167#endif //AP_DDS_IMU_PUB_ENABLED168#if AP_DDS_LOCAL_POSE_PUB_ENABLED169{170.topic_id = to_underlying(TopicIndex::LOCAL_POSE_PUB),171.pub_id = to_underlying(TopicIndex::LOCAL_POSE_PUB),172.sub_id = to_underlying(TopicIndex::LOCAL_POSE_PUB),173.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_POSE_PUB), .type=UXR_DATAWRITER_ID},174.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_POSE_PUB), .type=UXR_DATAREADER_ID},175.topic_rw = Topic_rw::DataWriter,176.topic_name = "rt/ap/pose/filtered",177.type_name = "geometry_msgs::msg::dds_::PoseStamped_",178.qos = {179.durability = UXR_DURABILITY_VOLATILE,180.reliability = UXR_RELIABILITY_BEST_EFFORT,181.history = UXR_HISTORY_KEEP_LAST,182.depth = 5,183},184},185#endif // AP_DDS_LOCAL_POSE_PUB_ENABLED186#if AP_DDS_LOCAL_VEL_PUB_ENABLED187{188.topic_id = to_underlying(TopicIndex::LOCAL_VELOCITY_PUB),189.pub_id = to_underlying(TopicIndex::LOCAL_VELOCITY_PUB),190.sub_id = to_underlying(TopicIndex::LOCAL_VELOCITY_PUB),191.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_VELOCITY_PUB), .type=UXR_DATAWRITER_ID},192.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_VELOCITY_PUB), .type=UXR_DATAREADER_ID},193.topic_rw = Topic_rw::DataWriter,194.topic_name = "rt/ap/twist/filtered",195.type_name = "geometry_msgs::msg::dds_::TwistStamped_",196.qos = {197.durability = UXR_DURABILITY_VOLATILE,198.reliability = UXR_RELIABILITY_BEST_EFFORT,199.history = UXR_HISTORY_KEEP_LAST,200.depth = 5,201},202},203#endif // AP_DDS_LOCAL_VEL_PUB_ENABLED204#if AP_DDS_AIRSPEED_PUB_ENABLED205{206.topic_id = to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB),207.pub_id = to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB),208.sub_id = to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB),209.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB), .type=UXR_DATAWRITER_ID},210.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_AIRSPEED_PUB), .type=UXR_DATAREADER_ID},211.topic_rw = Topic_rw::DataWriter,212.topic_name = "rt/ap/airspeed",213.type_name = "geometry_msgs::msg::dds_::Vector3Stamped_",214.qos = {215.durability = UXR_DURABILITY_VOLATILE,216.reliability = UXR_RELIABILITY_BEST_EFFORT,217.history = UXR_HISTORY_KEEP_LAST,218.depth = 5,219},220},221#endif // AP_DDS_AIRSPEED_PUB_ENABLED222#if AP_DDS_GEOPOSE_PUB_ENABLED223{224.topic_id = to_underlying(TopicIndex::GEOPOSE_PUB),225.pub_id = to_underlying(TopicIndex::GEOPOSE_PUB),226.sub_id = to_underlying(TopicIndex::GEOPOSE_PUB),227.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GEOPOSE_PUB), .type=UXR_DATAWRITER_ID},228.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GEOPOSE_PUB), .type=UXR_DATAREADER_ID},229.topic_rw = Topic_rw::DataWriter,230.topic_name = "rt/ap/geopose/filtered",231.type_name = "geographic_msgs::msg::dds_::GeoPoseStamped_",232.qos = {233.durability = UXR_DURABILITY_VOLATILE,234.reliability = UXR_RELIABILITY_BEST_EFFORT,235.history = UXR_HISTORY_KEEP_LAST,236.depth = 5,237},238},239#endif // AP_DDS_GEOPOSE_PUB_ENABLED240#if AP_DDS_GOAL_PUB_ENABLED241{242.topic_id = to_underlying(TopicIndex::GOAL_PUB),243.pub_id = to_underlying(TopicIndex::GOAL_PUB),244.sub_id = to_underlying(TopicIndex::GOAL_PUB),245.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GOAL_PUB), .type=UXR_DATAWRITER_ID},246.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GOAL_PUB), .type=UXR_DATAREADER_ID},247.topic_rw = Topic_rw::DataWriter,248.topic_name = "rt/ap/goal_lla",249.type_name = "geographic_msgs::msg::dds_::GeoPointStamped_",250.qos = {251.durability = UXR_DURABILITY_TRANSIENT_LOCAL,252.reliability = UXR_RELIABILITY_RELIABLE,253.history = UXR_HISTORY_KEEP_LAST,254.depth = 1,255},256},257#endif // AP_DDS_GOAL_PUB_ENABLED258#if AP_DDS_CLOCK_PUB_ENABLED259{260.topic_id = to_underlying(TopicIndex::CLOCK_PUB),261.pub_id = to_underlying(TopicIndex::CLOCK_PUB),262.sub_id = to_underlying(TopicIndex::CLOCK_PUB),263.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::CLOCK_PUB), .type=UXR_DATAWRITER_ID},264.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::CLOCK_PUB), .type=UXR_DATAREADER_ID},265.topic_rw = Topic_rw::DataWriter,266.topic_name = "rt/ap/clock",267.type_name = "rosgraph_msgs::msg::dds_::Clock_",268.qos = {269.durability = UXR_DURABILITY_VOLATILE,270.reliability = UXR_RELIABILITY_RELIABLE,271.history = UXR_HISTORY_KEEP_LAST,272.depth = 20,273},274},275#endif // AP_DDS_CLOCK_PUB_ENABLED276#if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED277{278.topic_id = to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB),279.pub_id = to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB),280.sub_id = to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB),281.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB), .type=UXR_DATAWRITER_ID},282.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB), .type=UXR_DATAREADER_ID},283.topic_rw = Topic_rw::DataWriter,284.topic_name = "rt/ap/gps_global_origin/filtered",285.type_name = "geographic_msgs::msg::dds_::GeoPointStamped_",286.qos = {287.durability = UXR_DURABILITY_VOLATILE,288.reliability = UXR_RELIABILITY_BEST_EFFORT,289.history = UXR_HISTORY_KEEP_LAST,290.depth = 5,291},292},293#endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED294#if AP_DDS_STATUS_PUB_ENABLED295{296.topic_id = to_underlying(TopicIndex::STATUS_PUB),297.pub_id = to_underlying(TopicIndex::STATUS_PUB),298.sub_id = to_underlying(TopicIndex::STATUS_PUB),299.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::STATUS_PUB), .type=UXR_DATAWRITER_ID},300.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::STATUS_PUB), .type=UXR_DATAREADER_ID},301.topic_rw = Topic_rw::DataWriter,302.topic_name = "rt/ap/status",303.type_name = "ardupilot_msgs::msg::dds_::Status_",304.qos = {305.durability = UXR_DURABILITY_TRANSIENT_LOCAL,306.reliability = UXR_RELIABILITY_RELIABLE,307.history = UXR_HISTORY_KEEP_LAST,308.depth = 1,309},310},311#endif // AP_DDS_STATUS_PUB_ENABLED312#if AP_DDS_JOY_SUB_ENABLED313{314.topic_id = to_underlying(TopicIndex::JOY_SUB),315.pub_id = to_underlying(TopicIndex::JOY_SUB),316.sub_id = to_underlying(TopicIndex::JOY_SUB),317.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::JOY_SUB), .type=UXR_DATAWRITER_ID},318.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::JOY_SUB), .type=UXR_DATAREADER_ID},319.topic_rw = Topic_rw::DataReader,320.topic_name = "rt/ap/joy",321.type_name = "sensor_msgs::msg::dds_::Joy_",322.qos = {323.durability = UXR_DURABILITY_VOLATILE,324.reliability = UXR_RELIABILITY_BEST_EFFORT,325.history = UXR_HISTORY_KEEP_LAST,326.depth = 5,327},328},329#endif // AP_DDS_JOY_SUB_ENABLED330#if AP_DDS_DYNAMIC_TF_SUB_ENABLED331{332.topic_id = to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB),333.pub_id = to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB),334.sub_id = to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB),335.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB), .type=UXR_DATAWRITER_ID},336.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB), .type=UXR_DATAREADER_ID},337.topic_rw = Topic_rw::DataReader,338.topic_name = "rt/ap/tf",339.type_name = "tf2_msgs::msg::dds_::TFMessage_",340.qos = {341.durability = UXR_DURABILITY_VOLATILE,342.reliability = UXR_RELIABILITY_BEST_EFFORT,343.history = UXR_HISTORY_KEEP_LAST,344.depth = 5,345},346},347#endif // AP_DDS_DYNAMIC_TF_SUB_ENABLED348#if AP_DDS_VEL_CTRL_ENABLED349{350.topic_id = to_underlying(TopicIndex::VELOCITY_CONTROL_SUB),351.pub_id = to_underlying(TopicIndex::VELOCITY_CONTROL_SUB),352.sub_id = to_underlying(TopicIndex::VELOCITY_CONTROL_SUB),353.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::VELOCITY_CONTROL_SUB), .type=UXR_DATAWRITER_ID},354.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::VELOCITY_CONTROL_SUB), .type=UXR_DATAREADER_ID},355.topic_rw = Topic_rw::DataReader,356.topic_name = "rt/ap/cmd_vel",357.type_name = "geometry_msgs::msg::dds_::TwistStamped_",358.qos = {359.durability = UXR_DURABILITY_VOLATILE,360.reliability = UXR_RELIABILITY_BEST_EFFORT,361.history = UXR_HISTORY_KEEP_LAST,362.depth = 5,363},364},365#endif // AP_DDS_VEL_CTRL_ENABLED366#if AP_DDS_GLOBAL_POS_CTRL_ENABLED367{368.topic_id = to_underlying(TopicIndex::GLOBAL_POSITION_SUB),369.pub_id = to_underlying(TopicIndex::GLOBAL_POSITION_SUB),370.sub_id = to_underlying(TopicIndex::GLOBAL_POSITION_SUB),371.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GLOBAL_POSITION_SUB), .type=UXR_DATAWRITER_ID},372.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GLOBAL_POSITION_SUB), .type=UXR_DATAREADER_ID},373.topic_rw = Topic_rw::DataReader,374.topic_name = "rt/ap/cmd_gps_pose",375.type_name = "ardupilot_msgs::msg::dds_::GlobalPosition_",376.qos = {377.durability = UXR_DURABILITY_VOLATILE,378.reliability = UXR_RELIABILITY_BEST_EFFORT,379.history = UXR_HISTORY_KEEP_LAST,380.depth = 5,381},382},383#endif // AP_DDS_GLOBAL_POS_CTRL_ENABLED384};385386387