Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_DDS: replace ref interface with binary interface in uxr create entity methods #27145

Merged
merged 5 commits into from
May 29, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 0 additions & 5 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -41,11 +41,6 @@ repos:
- id: check-xml
- id: check-yaml

- repo: https://github.com/lsst-ts/pre-commit-xmllint
rev: 6f36260b537bf9a42b6ea5262c915ae50786296e
hooks:
- id: format-xmllint
files: libraries/AP_DDS/dds_xrce_profile.xml
- repo: https://github.com/psf/black
rev: 23.7.0
hooks:
Expand Down
7 changes: 3 additions & 4 deletions Tools/ros2/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -191,7 +191,7 @@ socat -d -d pty,raw,echo=0,link=./dev/ttyROS0 pty,raw,echo=0,link=./dev/ttyROS1
```

```bash
ros2 run micro_ros_agent micro_ros_agent serial --baudrate 115200 --dev ./dev/ttyROS0 --refs $(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/dds_xrce_profile.xml
ros2 run micro_ros_agent micro_ros_agent serial --baudrate 115200 --dev ./dev/ttyROS0
```

```bash
Expand All @@ -209,7 +209,7 @@ ros2 launch ardupilot_sitl virtual_ports.launch.py tty0:=./dev/ttyROS0 tty1:=./d
```

```bash
ros2 launch ardupilot_sitl micro_ros_agent.launch.py transport:=serial refs:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/dds_xrce_profile.xml baudrate:=115200 device:=./dev/ttyROS0
ros2 launch ardupilot_sitl micro_ros_agent.launch.py transport:=serial baudrate:=115200 device:=./dev/ttyROS0
```

```bash
Expand All @@ -229,7 +229,6 @@ tty0:=./dev/ttyROS0 \
tty1:=./dev/ttyROS1 \
\
transport:=serial \
refs:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/dds_xrce_profile.xml \
baudrate:=115200 \
device:=./dev/ttyROS0 \
\
Expand All @@ -250,5 +249,5 @@ sitl:=127.0.0.1:5501
UDP version

```
ros2 launch ardupilot_sitl sitl_dds_udp.launch.py transport:=udp4 refs:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/dds_xrce_profile.xml synthetic_clock:=True wipe:=False model:=quad speedup:=1 slave:=0 instance:=0 defaults:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/copter.parm,$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/dds_udp.parm sim_address:=127.0.0.1 master:=tcp:127.0.0.1:5760 sitl:=127.0.0.1:5501
ros2 launch ardupilot_sitl sitl_dds_udp.launch.py transport:=udp4 synthetic_clock:=True wipe:=False model:=quad speedup:=1 slave:=0 instance:=0 defaults:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/copter.parm,$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/dds_udp.parm sim_address:=127.0.0.1 master:=tcp:127.0.0.1:5760 sitl:=127.0.0.1:5501
```
1 change: 0 additions & 1 deletion Tools/ros2/ardupilot_dds_tests/config/ardupilot_dds.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
middleware: dds
serial_baud: 115200
serial_device: ./dev/ttyROS0
refs_file: ./src/ardupilot/libraries/AP_DDS/dds_xrce_profile.xml

/ardupilot:
sim_vehicle_cmd: ./src/ardupilot/Tools/autotest/sim_vehicle.py
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,13 +74,6 @@ def micro_ros_agent_serial(device_dir):
LaunchDescriptionSource(mra_ld),
launch_arguments={
"transport": "serial",
"refs": PathJoinSubstitution(
[
FindPackageShare("ardupilot_sitl"),
"config",
"dds_xrce_profile.xml",
]
),
"baudrate": "115200",
"device": str(tty0),
}.items(),
Expand All @@ -97,13 +90,6 @@ def micro_ros_agent_udp():
LaunchDescriptionSource(mra_ld),
launch_arguments={
"transport": "udp4",
"refs": PathJoinSubstitution(
[
FindPackageShare("ardupilot_sitl"),
"config",
"dds_xrce_profile.xml",
]
),
}.items(),
)
yield ld, mra_actions
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@
# # default params
# self.mra_serial_device = f"./dev/ttyROS0"
# self.mra_serial_baud = 115200
# self.mra_refs_file = "dds_xrce_profile.xml"
#
# self.ap_sim_vehicle_cmd = "sim_vehicle.py"
# self.ap_serial_device = f"./dev/ttyROS1"
Expand Down
6 changes: 0 additions & 6 deletions Tools/ros2/ardupilot_sitl/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -81,12 +81,6 @@ install(DIRECTORY
DESTINATION share/${PROJECT_NAME}/
)

# Install DDS profile.
install(FILES
${ARDUPILOT_ROOT}/libraries/AP_DDS/dds_xrce_profile.xml
DESTINATION share/${PROJECT_NAME}/config
)

# Install additional default params.
install(DIRECTORY
config/default_params
Expand Down
39 changes: 21 additions & 18 deletions libraries/AP_DDS/AP_DDS_Client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -798,8 +798,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;
Expand All @@ -820,27 +822,27 @@ 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;
uint16_t requests[nRequests];
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;
Expand All @@ -857,18 +859,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;
Expand All @@ -895,13 +897,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;
Expand All @@ -916,7 +919,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
}
}
Expand Down
42 changes: 35 additions & 7 deletions libraries/AP_DDS/AP_DDS_Client.h
Original file line number Diff line number Diff line change
Expand Up @@ -213,19 +213,32 @@ class AP_DDS_Client
//! @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;
const uint8_t pub_id;
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
Expand All @@ -234,11 +247,26 @@ class AP_DDS_Client
//! @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 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 Profile Label for the service replier
const char* rep_profile_label;
//! @brief QoS for the service
const uxrQoS_t qos;
};
static const struct Service_table services[];
};
Expand Down
22 changes: 18 additions & 4 deletions libraries/AP_DDS/AP_DDS_Service_Table.h
Original file line number Diff line number Diff line change
Expand Up @@ -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",
},
};
Loading
Loading