mirror of https://github.com/ArduPilot/ardupilot
AP_DDS: create entities by binary
- Add topic name and type to topic table. - Use binary creation functions for participants and topics. - Add constant for domain ID. - Create publishers and datawriters by binary - Create subscribers, datareaders and services by binary - Add extra fields to the services table. - Remove dds_xrce_profile.xml - Document additional service table fields - Add QoS struct to topic and service tables - Replace profile labels with enums. Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
This commit is contained in:
parent
3ba16eb933
commit
c71ef23657
|
@ -819,8 +819,10 @@ bool AP_DDS_Client::create()
|
|||
.id = 0x01,
|
||||
.type = UXR_PARTICIPANT_ID
|
||||
};
|
||||
const char* participant_ref = "participant_profile";
|
||||
const auto participant_req_id = uxr_buffer_create_participant_ref(&session, reliable_out, participant_id,0,participant_ref,UXR_REPLACE);
|
||||
const char* participant_name = "ardupilot_dds";
|
||||
const uint16_t domain_id = 0;
|
||||
const auto participant_req_id = uxr_buffer_create_participant_bin(&session, reliable_out, participant_id,
|
||||
domain_id, participant_name, UXR_REPLACE);
|
||||
|
||||
//Participant requests
|
||||
constexpr uint8_t nRequestsParticipant = 1;
|
||||
|
@ -841,8 +843,8 @@ bool AP_DDS_Client::create()
|
|||
.id = topics[i].topic_id,
|
||||
.type = UXR_TOPIC_ID
|
||||
};
|
||||
const char* topic_ref = topics[i].topic_profile_label;
|
||||
const auto topic_req_id = uxr_buffer_create_topic_ref(&session,reliable_out,topic_id,participant_id,topic_ref,UXR_REPLACE);
|
||||
const auto topic_req_id = uxr_buffer_create_topic_bin(&session, reliable_out, topic_id,
|
||||
participant_id, topics[i].topic_name, topics[i].type_name, UXR_REPLACE);
|
||||
|
||||
// Status requests
|
||||
constexpr uint8_t nRequests = 3;
|
||||
|
@ -850,18 +852,18 @@ bool AP_DDS_Client::create()
|
|||
constexpr uint16_t requestTimeoutMs = nRequests * maxTimeMsPerRequestMs;
|
||||
uint8_t status[nRequests];
|
||||
|
||||
if (strlen(topics[i].dw_profile_label) > 0) {
|
||||
if (topics[i].topic_rw == Topic_rw::DataWriter) {
|
||||
// Publisher
|
||||
const uxrObjectId pub_id = {
|
||||
.id = topics[i].pub_id,
|
||||
.type = UXR_PUBLISHER_ID
|
||||
};
|
||||
const char* pub_xml = "";
|
||||
const auto pub_req_id = uxr_buffer_create_publisher_xml(&session,reliable_out,pub_id,participant_id,pub_xml,UXR_REPLACE);
|
||||
const auto pub_req_id = uxr_buffer_create_publisher_bin(&session, reliable_out, pub_id,
|
||||
participant_id, UXR_REPLACE);
|
||||
|
||||
// Data Writer
|
||||
const char* data_writer_ref = topics[i].dw_profile_label;
|
||||
const auto dwriter_req_id = uxr_buffer_create_datawriter_ref(&session,reliable_out,topics[i].dw_id,pub_id,data_writer_ref,UXR_REPLACE);
|
||||
const auto dwriter_req_id = uxr_buffer_create_datawriter_bin(&session, reliable_out, topics[i].dw_id,
|
||||
pub_id, topic_id, topics[i].qos, UXR_REPLACE);
|
||||
|
||||
// save the request statuses
|
||||
requests[0] = topic_req_id;
|
||||
|
@ -878,18 +880,18 @@ bool AP_DDS_Client::create()
|
|||
} else {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Topic/Pub/Writer session pass for index '%u'", msg_prefix, i);
|
||||
}
|
||||
} else if (strlen(topics[i].dr_profile_label) > 0) {
|
||||
} else if (topics[i].topic_rw == Topic_rw::DataReader) {
|
||||
// Subscriber
|
||||
const uxrObjectId sub_id = {
|
||||
.id = topics[i].sub_id,
|
||||
.type = UXR_SUBSCRIBER_ID
|
||||
};
|
||||
const char* sub_xml = "";
|
||||
const auto sub_req_id = uxr_buffer_create_subscriber_xml(&session,reliable_out,sub_id,participant_id,sub_xml,UXR_REPLACE);
|
||||
const auto sub_req_id = uxr_buffer_create_subscriber_bin(&session, reliable_out, sub_id,
|
||||
participant_id, UXR_REPLACE);
|
||||
|
||||
// Data Reader
|
||||
const char* data_reader_ref = topics[i].dr_profile_label;
|
||||
const auto dreader_req_id = uxr_buffer_create_datareader_ref(&session,reliable_out,topics[i].dr_id,sub_id,data_reader_ref,UXR_REPLACE);
|
||||
const auto dreader_req_id = uxr_buffer_create_datareader_bin(&session, reliable_out, topics[i].dr_id,
|
||||
sub_id, topic_id, topics[i].qos, UXR_REPLACE);
|
||||
|
||||
// save the request statuses
|
||||
requests[0] = topic_req_id;
|
||||
|
@ -916,13 +918,14 @@ bool AP_DDS_Client::create()
|
|||
|
||||
constexpr uint16_t requestTimeoutMs = maxTimeMsPerRequestMs;
|
||||
|
||||
if (strlen(services[i].rep_profile_label) > 0) {
|
||||
if (services[i].service_rr == Service_rr::Replier) {
|
||||
const uxrObjectId rep_id = {
|
||||
.id = services[i].rep_id,
|
||||
.type = UXR_REPLIER_ID
|
||||
};
|
||||
const char* replier_ref = services[i].rep_profile_label;
|
||||
const auto replier_req_id = uxr_buffer_create_replier_ref(&session, reliable_out, rep_id, participant_id, replier_ref, UXR_REPLACE);
|
||||
const auto replier_req_id = uxr_buffer_create_replier_bin(&session, reliable_out, rep_id,
|
||||
participant_id, services[i].service_name, services[i].request_type, services[i].reply_type,
|
||||
services[i].request_topic_name, services[i].reply_topic_name, services[i].qos, UXR_REPLACE);
|
||||
|
||||
uint16_t request = replier_req_id;
|
||||
uint8_t status;
|
||||
|
@ -937,7 +940,7 @@ bool AP_DDS_Client::create()
|
|||
uxr_buffer_request_data(&session, reliable_out, rep_id, reliable_in, &delivery_control);
|
||||
}
|
||||
|
||||
} else if (strlen(services[i].req_profile_label) > 0) {
|
||||
} else if (services[i].service_rr == Service_rr::Requester) {
|
||||
// TODO : Add Similar Code for Requester Profile
|
||||
}
|
||||
}
|
||||
|
|
|
@ -213,6 +213,12 @@ public:
|
|||
//! @brief Parameter storage
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
//! @brief Enum used to mark a topic as a data reader or writer
|
||||
enum class Topic_rw : uint8_t {
|
||||
DataReader = 0,
|
||||
DataWriter = 1,
|
||||
};
|
||||
|
||||
//! @brief Convenience grouping for a single "channel" of data
|
||||
struct Topic_table {
|
||||
const uint8_t topic_id;
|
||||
|
@ -220,12 +226,19 @@ public:
|
|||
const uint8_t sub_id; // added sub_id fields to avoid confusion
|
||||
const uxrObjectId dw_id;
|
||||
const uxrObjectId dr_id; // added dr_id fields to avoid confusion
|
||||
const char* topic_profile_label;
|
||||
const char* dw_profile_label;
|
||||
const char* dr_profile_label;
|
||||
const Topic_rw topic_rw;
|
||||
const char* topic_name;
|
||||
const char* type_name;
|
||||
const uxrQoS_t qos;
|
||||
};
|
||||
static const struct Topic_table topics[];
|
||||
|
||||
//! @brief Enum used to mark a service as a requester or replier
|
||||
enum class Service_rr : uint8_t {
|
||||
Requester = 0,
|
||||
Replier = 1,
|
||||
};
|
||||
|
||||
//! @brief Convenience grouping for a single "channel" of services
|
||||
struct Service_table {
|
||||
//! @brief Request ID for the service
|
||||
|
@ -234,11 +247,26 @@ public:
|
|||
//! @brief Reply ID for the service
|
||||
const uint8_t rep_id;
|
||||
|
||||
//! @brief Profile Label for the service requester
|
||||
const char* req_profile_label;
|
||||
//! @brief Service is requester or replier
|
||||
const Service_rr service_rr;
|
||||
|
||||
//! @brief Profile Label for the service replier
|
||||
const char* rep_profile_label;
|
||||
//! @brief Service name as it appears in ROS
|
||||
const char* service_name;
|
||||
|
||||
//! @brief Service requester message type
|
||||
const char* request_type;
|
||||
|
||||
//! @brief Service replier message type
|
||||
const char* reply_type;
|
||||
|
||||
//! @brief Service requester topic name
|
||||
const char* request_topic_name;
|
||||
|
||||
//! @brief Service replier topic name
|
||||
const char* reply_topic_name;
|
||||
|
||||
//! @brief QoS for the service
|
||||
const uxrQoS_t qos;
|
||||
};
|
||||
static const struct Service_table services[];
|
||||
};
|
||||
|
|
|
@ -15,13 +15,27 @@ constexpr struct AP_DDS_Client::Service_table AP_DDS_Client::services[] = {
|
|||
{
|
||||
.req_id = to_underlying(ServiceIndex::ARMING_MOTORS),
|
||||
.rep_id = to_underlying(ServiceIndex::ARMING_MOTORS),
|
||||
.req_profile_label = "",
|
||||
.rep_profile_label = "arm_motors__replier",
|
||||
.service_rr = Service_rr::Replier,
|
||||
.service_name = "rs/ap/arm_motorsService",
|
||||
.request_type = "ardupilot_msgs::srv::dds_::ArmMotors_Request_",
|
||||
.reply_type = "ardupilot_msgs::srv::dds_::ArmMotors_Response_",
|
||||
.request_topic_name = "rq/ap/arm_motorsRequest",
|
||||
.reply_topic_name = "rr/ap/arm_motorsReply",
|
||||
.qos = {
|
||||
.durability = UXR_DURABILITY_TRANSIENT_LOCAL,
|
||||
.reliability = UXR_RELIABILITY_RELIABLE,
|
||||
.history = UXR_HISTORY_KEEP_LAST,
|
||||
.depth = 5,
|
||||
},
|
||||
},
|
||||
{
|
||||
.req_id = to_underlying(ServiceIndex::MODE_SWITCH),
|
||||
.rep_id = to_underlying(ServiceIndex::MODE_SWITCH),
|
||||
.req_profile_label = "",
|
||||
.rep_profile_label = "mode_switch__replier",
|
||||
.service_rr = Service_rr::Replier,
|
||||
.service_name = "rs/ap/mode_switchService",
|
||||
.request_type = "ardupilot_msgs::srv::dds_::ModeSwitch_Request_",
|
||||
.reply_type = "ardupilot_msgs::srv::dds_::ModeSwitch_Response_",
|
||||
.request_topic_name = "rq/ap/mode_switchRequest",
|
||||
.reply_topic_name = "rr/ap/mode_switchReply",
|
||||
},
|
||||
};
|
||||
|
|
|
@ -42,9 +42,15 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
|
|||
.sub_id = to_underlying(TopicIndex::TIME_PUB),
|
||||
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::TIME_PUB), .type=UXR_DATAWRITER_ID},
|
||||
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::TIME_PUB), .type=UXR_DATAREADER_ID},
|
||||
.topic_profile_label = "time__t",
|
||||
.dw_profile_label = "time__dw",
|
||||
.dr_profile_label = "",
|
||||
.topic_rw = Topic_rw::DataWriter,
|
||||
.topic_name = "rt/ap/time",
|
||||
.type_name = "builtin_interfaces::msg::dds_::Time_",
|
||||
.qos = {
|
||||
.durability = UXR_DURABILITY_VOLATILE,
|
||||
.reliability = UXR_RELIABILITY_RELIABLE,
|
||||
.history = UXR_HISTORY_KEEP_LAST,
|
||||
.depth = 20,
|
||||
},
|
||||
},
|
||||
{
|
||||
.topic_id = to_underlying(TopicIndex::NAV_SAT_FIX_PUB),
|
||||
|
@ -52,9 +58,15 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
|
|||
.sub_id = to_underlying(TopicIndex::NAV_SAT_FIX_PUB),
|
||||
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::NAV_SAT_FIX_PUB), .type=UXR_DATAWRITER_ID},
|
||||
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::NAV_SAT_FIX_PUB), .type=UXR_DATAREADER_ID},
|
||||
.topic_profile_label = "navsatfix0__t",
|
||||
.dw_profile_label = "navsatfix0__dw",
|
||||
.dr_profile_label = "",
|
||||
.topic_rw = Topic_rw::DataWriter,
|
||||
.topic_name = "rt/ap/navsat/navsat0",
|
||||
.type_name = "tf2_msgs::msg::dds_::TFMessage_",
|
||||
.qos = {
|
||||
.durability = UXR_DURABILITY_VOLATILE,
|
||||
.reliability = UXR_RELIABILITY_BEST_EFFORT,
|
||||
.history = UXR_HISTORY_KEEP_LAST,
|
||||
.depth = 5,
|
||||
},
|
||||
},
|
||||
{
|
||||
.topic_id = to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB),
|
||||
|
@ -62,9 +74,15 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
|
|||
.sub_id = to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB),
|
||||
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB), .type=UXR_DATAWRITER_ID},
|
||||
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::STATIC_TRANSFORMS_PUB), .type=UXR_DATAREADER_ID},
|
||||
.topic_profile_label = "statictransforms__t",
|
||||
.dw_profile_label = "statictransforms__dw",
|
||||
.dr_profile_label = "",
|
||||
.topic_rw = Topic_rw::DataWriter,
|
||||
.topic_name = "rt/ap/tf_static",
|
||||
.type_name = "tf2_msgs::msg::dds_::TFMessage_",
|
||||
.qos = {
|
||||
.durability = UXR_DURABILITY_TRANSIENT_LOCAL,
|
||||
.reliability = UXR_RELIABILITY_RELIABLE,
|
||||
.history = UXR_HISTORY_KEEP_LAST,
|
||||
.depth = 1,
|
||||
},
|
||||
},
|
||||
{
|
||||
.topic_id = to_underlying(TopicIndex::BATTERY_STATE_PUB),
|
||||
|
@ -72,9 +90,15 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
|
|||
.sub_id = to_underlying(TopicIndex::BATTERY_STATE_PUB),
|
||||
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::BATTERY_STATE_PUB), .type=UXR_DATAWRITER_ID},
|
||||
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::BATTERY_STATE_PUB), .type=UXR_DATAREADER_ID},
|
||||
.topic_profile_label = "batterystate0__t",
|
||||
.dw_profile_label = "batterystate0__dw",
|
||||
.dr_profile_label = "",
|
||||
.topic_rw = Topic_rw::DataWriter,
|
||||
.topic_name = "rt/ap/battery/battery0",
|
||||
.type_name = "sensor_msgs::msg::dds_::BatteryState_",
|
||||
.qos = {
|
||||
.durability = UXR_DURABILITY_VOLATILE,
|
||||
.reliability = UXR_RELIABILITY_BEST_EFFORT,
|
||||
.history = UXR_HISTORY_KEEP_LAST,
|
||||
.depth = 5,
|
||||
},
|
||||
},
|
||||
{
|
||||
.topic_id = to_underlying(TopicIndex::IMU_PUB),
|
||||
|
@ -82,9 +106,15 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
|
|||
.sub_id = to_underlying(TopicIndex::IMU_PUB),
|
||||
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::IMU_PUB), .type=UXR_DATAWRITER_ID},
|
||||
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::IMU_PUB), .type=UXR_DATAREADER_ID},
|
||||
.topic_profile_label = "imu__t",
|
||||
.dw_profile_label = "imu__dw",
|
||||
.dr_profile_label = "",
|
||||
.topic_rw = Topic_rw::DataWriter,
|
||||
.topic_name = "rt/ap/imu/experimental/data",
|
||||
.type_name = "sensor_msgs::msg::dds_::Imu_",
|
||||
.qos = {
|
||||
.durability = UXR_DURABILITY_VOLATILE,
|
||||
.reliability = UXR_RELIABILITY_BEST_EFFORT,
|
||||
.history = UXR_HISTORY_KEEP_LAST,
|
||||
.depth = 5,
|
||||
},
|
||||
},
|
||||
{
|
||||
.topic_id = to_underlying(TopicIndex::LOCAL_POSE_PUB),
|
||||
|
@ -92,9 +122,15 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
|
|||
.sub_id = to_underlying(TopicIndex::LOCAL_POSE_PUB),
|
||||
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_POSE_PUB), .type=UXR_DATAWRITER_ID},
|
||||
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_POSE_PUB), .type=UXR_DATAREADER_ID},
|
||||
.topic_profile_label = "localpose__t",
|
||||
.dw_profile_label = "localpose__dw",
|
||||
.dr_profile_label = "",
|
||||
.topic_rw = Topic_rw::DataWriter,
|
||||
.topic_name = "rt/ap/pose/filtered",
|
||||
.type_name = "geometry_msgs::msg::dds_::PoseStamped_",
|
||||
.qos = {
|
||||
.durability = UXR_DURABILITY_VOLATILE,
|
||||
.reliability = UXR_RELIABILITY_BEST_EFFORT,
|
||||
.history = UXR_HISTORY_KEEP_LAST,
|
||||
.depth = 5,
|
||||
},
|
||||
},
|
||||
{
|
||||
.topic_id = to_underlying(TopicIndex::LOCAL_VELOCITY_PUB),
|
||||
|
@ -102,9 +138,15 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
|
|||
.sub_id = to_underlying(TopicIndex::LOCAL_VELOCITY_PUB),
|
||||
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_VELOCITY_PUB), .type=UXR_DATAWRITER_ID},
|
||||
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::LOCAL_VELOCITY_PUB), .type=UXR_DATAREADER_ID},
|
||||
.topic_profile_label = "localvelocity__t",
|
||||
.dw_profile_label = "localvelocity__dw",
|
||||
.dr_profile_label = "",
|
||||
.topic_rw = Topic_rw::DataWriter,
|
||||
.topic_name = "rt/ap/twist/filtered",
|
||||
.type_name = "geometry_msgs::msg::dds_::TwistStamped_",
|
||||
.qos = {
|
||||
.durability = UXR_DURABILITY_VOLATILE,
|
||||
.reliability = UXR_RELIABILITY_BEST_EFFORT,
|
||||
.history = UXR_HISTORY_KEEP_LAST,
|
||||
.depth = 5,
|
||||
},
|
||||
},
|
||||
{
|
||||
.topic_id = to_underlying(TopicIndex::GEOPOSE_PUB),
|
||||
|
@ -112,9 +154,15 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
|
|||
.sub_id = to_underlying(TopicIndex::GEOPOSE_PUB),
|
||||
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GEOPOSE_PUB), .type=UXR_DATAWRITER_ID},
|
||||
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GEOPOSE_PUB), .type=UXR_DATAREADER_ID},
|
||||
.topic_profile_label = "geopose__t",
|
||||
.dw_profile_label = "geopose__dw",
|
||||
.dr_profile_label = "",
|
||||
.topic_rw = Topic_rw::DataWriter,
|
||||
.topic_name = "rt/ap/geopose/filtered",
|
||||
.type_name = "geographic_msgs::msg::dds_::GeoPoseStamped_",
|
||||
.qos = {
|
||||
.durability = UXR_DURABILITY_VOLATILE,
|
||||
.reliability = UXR_RELIABILITY_BEST_EFFORT,
|
||||
.history = UXR_HISTORY_KEEP_LAST,
|
||||
.depth = 5,
|
||||
},
|
||||
},
|
||||
{
|
||||
.topic_id = to_underlying(TopicIndex::CLOCK_PUB),
|
||||
|
@ -122,9 +170,15 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
|
|||
.sub_id = to_underlying(TopicIndex::CLOCK_PUB),
|
||||
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::CLOCK_PUB), .type=UXR_DATAWRITER_ID},
|
||||
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::CLOCK_PUB), .type=UXR_DATAREADER_ID},
|
||||
.topic_profile_label = "clock__t",
|
||||
.dw_profile_label = "clock__dw",
|
||||
.dr_profile_label = "",
|
||||
.topic_rw = Topic_rw::DataWriter,
|
||||
.topic_name = "rt/ap/clock",
|
||||
.type_name = "rosgraph_msgs::msg::dds_::Clock_",
|
||||
.qos = {
|
||||
.durability = UXR_DURABILITY_VOLATILE,
|
||||
.reliability = UXR_RELIABILITY_RELIABLE,
|
||||
.history = UXR_HISTORY_KEEP_LAST,
|
||||
.depth = 20,
|
||||
},
|
||||
},
|
||||
{
|
||||
.topic_id = to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB),
|
||||
|
@ -132,9 +186,15 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
|
|||
.sub_id = to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB),
|
||||
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB), .type=UXR_DATAWRITER_ID},
|
||||
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GPS_GLOBAL_ORIGIN_PUB), .type=UXR_DATAREADER_ID},
|
||||
.topic_profile_label = "gps_global_origin__t",
|
||||
.dw_profile_label = "gps_global_origin__dw",
|
||||
.dr_profile_label = "",
|
||||
.topic_rw = Topic_rw::DataWriter,
|
||||
.topic_name = "rt/ap/gps_global_origin/filtered",
|
||||
.type_name = "geographic_msgs::msg::dds_::GeoPointStamped_",
|
||||
.qos = {
|
||||
.durability = UXR_DURABILITY_VOLATILE,
|
||||
.reliability = UXR_RELIABILITY_BEST_EFFORT,
|
||||
.history = UXR_HISTORY_KEEP_LAST,
|
||||
.depth = 5,
|
||||
},
|
||||
},
|
||||
{
|
||||
.topic_id = to_underlying(TopicIndex::JOY_SUB),
|
||||
|
@ -142,9 +202,15 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
|
|||
.sub_id = to_underlying(TopicIndex::JOY_SUB),
|
||||
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::JOY_SUB), .type=UXR_DATAWRITER_ID},
|
||||
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::JOY_SUB), .type=UXR_DATAREADER_ID},
|
||||
.topic_profile_label = "joy__t",
|
||||
.dw_profile_label = "",
|
||||
.dr_profile_label = "joy__dr",
|
||||
.topic_rw = Topic_rw::DataReader,
|
||||
.topic_name = "rt/ap/joy",
|
||||
.type_name = "sensor_msgs::msg::dds_::Joy_",
|
||||
.qos = {
|
||||
.durability = UXR_DURABILITY_VOLATILE,
|
||||
.reliability = UXR_RELIABILITY_RELIABLE,
|
||||
.history = UXR_HISTORY_KEEP_LAST,
|
||||
.depth = 5,
|
||||
},
|
||||
},
|
||||
{
|
||||
.topic_id = to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB),
|
||||
|
@ -152,9 +218,15 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
|
|||
.sub_id = to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB),
|
||||
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB), .type=UXR_DATAWRITER_ID},
|
||||
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::DYNAMIC_TRANSFORMS_SUB), .type=UXR_DATAREADER_ID},
|
||||
.topic_profile_label = "dynamictf__t",
|
||||
.dw_profile_label = "",
|
||||
.dr_profile_label = "dynamictf__dr",
|
||||
.topic_rw = Topic_rw::DataReader,
|
||||
.topic_name = "rt/ap/tf",
|
||||
.type_name = "tf2_msgs::msg::dds_::TFMessage_",
|
||||
.qos = {
|
||||
.durability = UXR_DURABILITY_VOLATILE,
|
||||
.reliability = UXR_RELIABILITY_RELIABLE,
|
||||
.history = UXR_HISTORY_KEEP_LAST,
|
||||
.depth = 5,
|
||||
},
|
||||
},
|
||||
{
|
||||
.topic_id = to_underlying(TopicIndex::VELOCITY_CONTROL_SUB),
|
||||
|
@ -162,9 +234,15 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
|
|||
.sub_id = to_underlying(TopicIndex::VELOCITY_CONTROL_SUB),
|
||||
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::VELOCITY_CONTROL_SUB), .type=UXR_DATAWRITER_ID},
|
||||
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::VELOCITY_CONTROL_SUB), .type=UXR_DATAREADER_ID},
|
||||
.topic_profile_label = "velocitycontrol__t",
|
||||
.dw_profile_label = "",
|
||||
.dr_profile_label = "velocitycontrol__dr",
|
||||
.topic_rw = Topic_rw::DataReader,
|
||||
.topic_name = "rt/ap/cmd_vel",
|
||||
.type_name = "geometry_msgs::msg::dds_::TwistStamped_",
|
||||
.qos = {
|
||||
.durability = UXR_DURABILITY_VOLATILE,
|
||||
.reliability = UXR_RELIABILITY_RELIABLE,
|
||||
.history = UXR_HISTORY_KEEP_LAST,
|
||||
.depth = 5,
|
||||
},
|
||||
},
|
||||
{
|
||||
.topic_id = to_underlying(TopicIndex::GLOBAL_POSITION_SUB),
|
||||
|
@ -172,8 +250,14 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
|
|||
.sub_id = to_underlying(TopicIndex::GLOBAL_POSITION_SUB),
|
||||
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GLOBAL_POSITION_SUB), .type=UXR_DATAWRITER_ID},
|
||||
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GLOBAL_POSITION_SUB), .type=UXR_DATAREADER_ID},
|
||||
.topic_profile_label = "globalposcontrol__t",
|
||||
.dw_profile_label = "",
|
||||
.dr_profile_label = "globalposcontrol__dr",
|
||||
.topic_rw = Topic_rw::DataReader,
|
||||
.topic_name = "rt/ap/cmd_gps_pose",
|
||||
.type_name = "ardupilot_msgs::msg::dds_::GlobalPosition_",
|
||||
.qos = {
|
||||
.durability = UXR_DURABILITY_VOLATILE,
|
||||
.reliability = UXR_RELIABILITY_RELIABLE,
|
||||
.history = UXR_HISTORY_KEEP_LAST,
|
||||
.depth = 5,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
|
|
@ -164,7 +164,7 @@ Next, follow the associated section for your chosen transport, and finally you c
|
|||
- Run the microROS agent
|
||||
```console
|
||||
cd ardupilot/libraries/AP_DDS
|
||||
ros2 run micro_ros_agent micro_ros_agent udp4 -p 2019 -r dds_xrce_profile.xml
|
||||
ros2 run micro_ros_agent micro_ros_agent udp4 -p 2019
|
||||
```
|
||||
- Run SITL (remember to kill any terminals running ardupilot SITL beforehand)
|
||||
```console
|
||||
|
@ -184,7 +184,7 @@ Next, follow the associated section for your chosen transport, and finally you c
|
|||
```console
|
||||
cd ardupilot/libraries/AP_DDS
|
||||
# assuming we are using tty/pts/2 for DDS Application
|
||||
ros2 run micro_ros_agent micro_ros_agent serial -b 115200 -r dds_xrce_profile.xml -D /dev/pts/2
|
||||
ros2 run micro_ros_agent micro_ros_agent serial -b 115200 -D /dev/pts/2
|
||||
```
|
||||
- Run SITL (remember to kill any terminals running ardupilot SITL beforehand)
|
||||
```console
|
||||
|
@ -318,11 +318,11 @@ If the message is custom for ardupilot, first create the ROS message in `Tools/r
|
|||
Then, build ardupilot_msgs with colcon.
|
||||
Finally, copy the IDL folder from the install directory into the source tree.
|
||||
|
||||
### Rules for adding topics and services to `dds_xrce_profile.xml`
|
||||
### Rules for adding topics and services
|
||||
|
||||
Topics and services available from `AP_DDS` are automatically mapped into ROS 2
|
||||
provided a few rules are followed when defining the entries in
|
||||
`dds_xrce_profile.xml`.
|
||||
provided a few rules are followed when defining the entries in the
|
||||
topic and service tables.
|
||||
|
||||
#### ROS 2 message and service interface types
|
||||
|
||||
|
@ -363,7 +363,9 @@ The table below provides example mappings for topics and services
|
|||
| ap/navsat/navsat0 | rt/ap/navsat/navsat0 |
|
||||
| ap/arm_motors | rq/ap/arm_motorsRequest, rr/ap/arm_motorsReply |
|
||||
|
||||
Refer to existing mappings in [`dds_xrce_profile.xml`](https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_DDS/dds_xrce_profile.xml) for additional details.
|
||||
Refer to existing mappings in [`AP_DDS_Topic_Table`](https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_DDS/AP_DDS_Topic_Table.h)
|
||||
and [`AP_DDS_Service_Table`](https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_DDS/AP_DDS_Service_Table.h)
|
||||
for additional details.
|
||||
|
||||
### Development Requirements
|
||||
|
||||
|
@ -412,7 +414,7 @@ Then run the Micro ROS agent
|
|||
cd /path/to/ros2_ws
|
||||
source install/setup.bash
|
||||
cd src/ardupilot/libraries/AP_DDS
|
||||
ros2 run micro_ros_agent micro_ros_agent serial -b 115200 -r dds_xrce_profile.xml -D /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02
|
||||
ros2 run micro_ros_agent micro_ros_agent serial -b 115200 -D /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02
|
||||
```
|
||||
|
||||
If connection fails, instead of running the Micro ROS agent, debug the stream
|
||||
|
|
|
@ -1,345 +0,0 @@
|
|||
<?xml version="1.0"?>
|
||||
<profiles>
|
||||
<participant profile_name="participant_profile">
|
||||
<rtps>
|
||||
<name>ardupilot_dds</name>
|
||||
</rtps>
|
||||
</participant>
|
||||
<topic profile_name="time__t">
|
||||
<name>rt/ap/time</name>
|
||||
<dataType>builtin_interfaces::msg::dds_::Time_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>20</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
<data_writer profile_name="time__dw">
|
||||
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
|
||||
<qos>
|
||||
<reliability>
|
||||
<kind>RELIABLE</kind>
|
||||
</reliability>
|
||||
</qos>
|
||||
<topic>
|
||||
<kind>NO_KEY</kind>
|
||||
<name>rt/ap/time</name>
|
||||
<dataType>builtin_interfaces::msg::dds_::Time_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>20</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
</data_writer>
|
||||
<topic profile_name="navsatfix0__t">
|
||||
<name>rt/ap/navsat/navsat0</name>
|
||||
<dataType>sensor_msgs::msg::dds_::NavSatFix_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>5</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
<data_writer profile_name="navsatfix0__dw">
|
||||
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
|
||||
<qos>
|
||||
<reliability>
|
||||
<kind>BEST_EFFORT</kind>
|
||||
</reliability>
|
||||
<durability>
|
||||
<kind>VOLATILE</kind>
|
||||
</durability>
|
||||
</qos>
|
||||
<topic>
|
||||
<kind>NO_KEY</kind>
|
||||
<name>rt/ap/navsat/navsat0</name>
|
||||
<dataType>sensor_msgs::msg::dds_::NavSatFix_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>5</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
</data_writer>
|
||||
<topic profile_name="statictransforms__t">
|
||||
<name>rt/ap/tf_static</name>
|
||||
<dataType>tf2_msgs::msg::dds_::TFMessage_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>1</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
<data_writer profile_name="statictransforms__dw">
|
||||
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
|
||||
<qos>
|
||||
<reliability>
|
||||
<kind>RELIABLE</kind>
|
||||
</reliability>
|
||||
<durability>
|
||||
<kind>TRANSIENT_LOCAL</kind>
|
||||
</durability>
|
||||
</qos>
|
||||
<topic>
|
||||
<kind>NO_KEY</kind>
|
||||
<name>rt/ap/tf_static</name>
|
||||
<dataType>tf2_msgs::msg::dds_::TFMessage_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>1</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
</data_writer>
|
||||
<topic profile_name="batterystate0__t">
|
||||
<name>rt/ap/battery/battery0</name>
|
||||
<dataType>sensor_msgs::msg::dds_::BatteryState_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>5</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
<data_writer profile_name="batterystate0__dw">
|
||||
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
|
||||
<qos>
|
||||
<reliability>
|
||||
<kind>BEST_EFFORT</kind>
|
||||
</reliability>
|
||||
<durability>
|
||||
<kind>VOLATILE</kind>
|
||||
</durability>
|
||||
</qos>
|
||||
<topic>
|
||||
<kind>NO_KEY</kind>
|
||||
<name>rt/ap/battery/battery0</name>
|
||||
<dataType>sensor_msgs::msg::dds_::BatteryState_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>5</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
</data_writer>
|
||||
<topic profile_name="imu__t">
|
||||
<name>rt/ap/imu/experimental/data</name>
|
||||
<dataType>sensor_msgs::msg::dds_::Imu_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>20</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
<data_writer profile_name="imu__dw">
|
||||
<topic>
|
||||
<kind>NO_KEY</kind>
|
||||
<name>rt/ap/imu/experimental/data</name>
|
||||
<dataType>sensor_msgs::msg::dds_::Imu_</dataType>
|
||||
</topic>
|
||||
<qos>
|
||||
<reliability>
|
||||
<kind>RELIABLE</kind>
|
||||
</reliability>
|
||||
<durability>
|
||||
<kind>TRANSIENT_LOCAL</kind>
|
||||
</durability>
|
||||
</qos>
|
||||
</data_writer>
|
||||
<topic profile_name="localpose__t">
|
||||
<name>rt/ap/pose/filtered</name>
|
||||
<dataType>geometry_msgs::msg::dds_::PoseStamped_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>5</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
<data_writer profile_name="localpose__dw">
|
||||
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
|
||||
<qos>
|
||||
<reliability>
|
||||
<kind>BEST_EFFORT</kind>
|
||||
</reliability>
|
||||
<durability>
|
||||
<kind>VOLATILE</kind>
|
||||
</durability>
|
||||
</qos>
|
||||
<topic>
|
||||
<kind>NO_KEY</kind>
|
||||
<name>rt/ap/pose/filtered</name>
|
||||
<dataType>geometry_msgs::msg::dds_::PoseStamped_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>5</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
</data_writer>
|
||||
<topic profile_name="localvelocity__t">
|
||||
<name>rt/ap/twist/filtered</name>
|
||||
<dataType>geometry_msgs::msg::dds_::TwistStamped_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>5</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
<data_writer profile_name="localvelocity__dw">
|
||||
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
|
||||
<qos>
|
||||
<reliability>
|
||||
<kind>BEST_EFFORT</kind>
|
||||
</reliability>
|
||||
<durability>
|
||||
<kind>VOLATILE</kind>
|
||||
</durability>
|
||||
</qos>
|
||||
<topic>
|
||||
<kind>NO_KEY</kind>
|
||||
<name>rt/ap/twist/filtered</name>
|
||||
<dataType>geometry_msgs::msg::dds_::TwistStamped_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>5</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
</data_writer>
|
||||
<topic profile_name="geopose__t">
|
||||
<name>rt/ap/geopose/filtered</name>
|
||||
<dataType>geographic_msgs::msg::dds_::GeoPoseStamped_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>5</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
<data_writer profile_name="geopose__dw">
|
||||
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
|
||||
<qos>
|
||||
<reliability>
|
||||
<kind>BEST_EFFORT</kind>
|
||||
</reliability>
|
||||
<durability>
|
||||
<kind>VOLATILE</kind>
|
||||
</durability>
|
||||
</qos>
|
||||
<topic>
|
||||
<kind>NO_KEY</kind>
|
||||
<name>rt/ap/geopose/filtered</name>
|
||||
<dataType>geographic_msgs::msg::dds_::GeoPoseStamped_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>5</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
</data_writer>
|
||||
<topic profile_name="clock__t">
|
||||
<name>rt/ap/clock</name>
|
||||
<dataType>rosgraph_msgs::msg::dds_::Clock_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>20</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
<data_writer profile_name="clock__dw">
|
||||
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
|
||||
<qos>
|
||||
<reliability>
|
||||
<kind>RELIABLE</kind>
|
||||
</reliability>
|
||||
</qos>
|
||||
<topic>
|
||||
<kind>NO_KEY</kind>
|
||||
<name>rt/ap/clock</name>
|
||||
<dataType>rosgraph_msgs::msg::dds_::Clock_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>20</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
</data_writer>
|
||||
<topic profile_name="gps_global_origin__t">
|
||||
<name>rt/ap/gps_global_origin/filtered</name>
|
||||
<dataType>geographic_msgs::msg::dds_::GeoPointStamped_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>5</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
<data_writer profile_name="gps_global_origin__dw">
|
||||
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
|
||||
<qos>
|
||||
<reliability>
|
||||
<kind>BEST_EFFORT</kind>
|
||||
</reliability>
|
||||
<durability>
|
||||
<kind>VOLATILE</kind>
|
||||
</durability>
|
||||
</qos>
|
||||
<topic>
|
||||
<kind>NO_KEY</kind>
|
||||
<name>rt/ap/gps_global_origin/filtered</name>
|
||||
<dataType>geographic_msgs::msg::dds_::GeoPointStamped_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>5</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
</data_writer>
|
||||
<topic profile_name="joy__t">
|
||||
<name>rt/ap/joy</name>
|
||||
<dataType>sensor_msgs::msg::dds_::Joy_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>5</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
<data_reader profile_name="joy__dr">
|
||||
<topic>
|
||||
<kind>NO_KEY</kind>
|
||||
<name>rt/ap/joy</name>
|
||||
<dataType>sensor_msgs::msg::dds_::Joy_</dataType>
|
||||
</topic>
|
||||
</data_reader>
|
||||
<topic profile_name="dynamictf__t">
|
||||
<name>rt/ap/tf</name>
|
||||
<dataType>tf2_msgs::msg::dds_::TFMessage_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>5</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
<data_reader profile_name="dynamictf__dr">
|
||||
<topic>
|
||||
<kind>NO_KEY</kind>
|
||||
<name>rt/ap/tf</name>
|
||||
<dataType>tf2_msgs::msg::dds_::TFMessage_</dataType>
|
||||
</topic>
|
||||
</data_reader>
|
||||
<topic profile_name="velocitycontrol__t">
|
||||
<name>rt/ap/cmd_vel</name>
|
||||
<dataType>geometry_msgs::msg::dds_::TwistStamped_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>5</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
<data_reader profile_name="velocitycontrol__dr">
|
||||
<topic>
|
||||
<kind>NO_KEY</kind>
|
||||
<name>rt/ap/cmd_vel</name>
|
||||
<dataType>geometry_msgs::msg::dds_::TwistStamped_</dataType>
|
||||
</topic>
|
||||
</data_reader>
|
||||
<replier profile_name="arm_motors__replier" service_name="rs/ap/arm_motorsService" request_type="ardupilot_msgs::srv::dds_::ArmMotors_Request_" reply_type="ardupilot_msgs::srv::dds_::ArmMotors_Response_">
|
||||
<request_topic_name>rq/ap/arm_motorsRequest</request_topic_name>
|
||||
<reply_topic_name>rr/ap/arm_motorsReply</reply_topic_name>
|
||||
</replier>
|
||||
<replier profile_name="mode_switch__replier" service_name="rs/ap/mode_switchService" request_type="ardupilot_msgs::srv::dds_::ModeSwitch_Request_" reply_type="ardupilot_msgs::srv::dds_::ModeSwitch_Response_">
|
||||
<request_topic_name>rq/ap/mode_switchRequest</request_topic_name>
|
||||
<reply_topic_name>rr/ap/mode_switchReply</reply_topic_name>
|
||||
</replier>
|
||||
<topic profile_name="globalposcontrol__t">
|
||||
<name>rt/ap/cmd_gps_pose</name>
|
||||
<dataType>ardupilot_msgs::msg::dds_::GlobalPosition_</dataType>
|
||||
<historyQos>
|
||||
<kind>KEEP_LAST</kind>
|
||||
<depth>5</depth>
|
||||
</historyQos>
|
||||
</topic>
|
||||
<data_reader profile_name="globalposcontrol__dr">
|
||||
<topic>
|
||||
<kind>NO_KEY</kind>
|
||||
<name>rt/ap/cmd_gps_pose</name>
|
||||
<dataType>ardupilot_msgs::msg::dds_::GlobalPosition_</dataType>
|
||||
</topic>
|
||||
</data_reader>
|
||||
</profiles>
|
Loading…
Reference in New Issue