diff --git a/fd_description/config/fd.config.xacro b/fd_description/config/fd.config.xacro
index 56da320..757c819 100644
--- a/fd_description/config/fd.config.xacro
+++ b/fd_description/config/fd.config.xacro
@@ -18,6 +18,7 @@
+ params="robot_id plugin_name:='FDHapticInterface' interface_id:='-1' interface_sn:='-1' effector_mass:='-1.0' use_fake_hardware:='false' use_orientation:='false' orientation_is_actuated:='false' use_clutch:='false' emulate_button:='false' ignore_orientation_readings:='false'">
@@ -11,6 +11,7 @@
fd_hardware/FDEffortHardwareInterface
${interface_id}
+ ${interface_sn}
${emulate_button}
${robot_id}_inertia
${effector_mass}
diff --git a/fd_hardware/include/fd_hardware/fd_effort_hi.hpp b/fd_hardware/include/fd_hardware/fd_effort_hi.hpp
index f545075..40264b3 100644
--- a/fd_hardware/include/fd_hardware/fd_effort_hi.hpp
+++ b/fd_hardware/include/fd_hardware/fd_effort_hi.hpp
@@ -62,6 +62,9 @@ class FDEffortHardwareInterface : public hardware_interface::SystemInterface
/// ID of the interface (Rq: "-1" = invalid/any that is connected)
char interface_ID_ = -1;
+ /// Serial number of the interface (Rq: "-1" = invalid / unspecified)
+ int interface_SN_ = -1;
+
/// Turned to true after the connection
bool isConnected_ = false;
diff --git a/fd_hardware/src/fd_effort_hi.cpp b/fd_hardware/src/fd_effort_hi.cpp
index cc12e00..a444b1e 100644
--- a/fd_hardware/src/fd_effort_hi.cpp
+++ b/fd_hardware/src/fd_effort_hi.cpp
@@ -161,6 +161,15 @@ CallbackReturn FDEffortHardwareInterface::on_init(
interface_ID_ = -1;
}
+
+ auto it_interface_serial_number = info_.hardware_parameters.find("interface_serial_number");
+ if (it_interface_serial_number != info_.hardware_parameters.end()) {
+ interface_SN_ = stoi(it_interface_serial_number->second);
+ RCLCPP_INFO(LOGGER, "Using interface serial number: %d", interface_SN_);
+ } else {
+ interface_SN_ = -1;
+ }
+
auto it_emulate_button = info_.hardware_parameters.find("emulate_button");
if (it_emulate_button != info_.hardware_parameters.end()) {
emulate_button_ = hardware_interface::parse_bool(it_emulate_button->second);
@@ -462,16 +471,23 @@ bool FDEffortHardwareInterface::connectToDevice()
// Open connection
bool dhd_open_success = false;
- if (interface_ID_ < 0) {
- // Open default device
- RCLCPP_INFO(LOGGER, "dhd : Connecting to default device...");
- interface_ID_ = dhdOpen();
+ if (interface_SN_ >= 0) {
+ // Open specified device from serial number
+ RCLCPP_INFO(
+ LOGGER, "dhd : Connecting to device with serial number %d, please wait...", interface_SN_);
+ uint16_t serialNumber = static_cast(interface_SN_);
+ interface_ID_ = dhdOpenSerial(serialNumber);
dhd_open_success = (interface_ID_ >= 0);
- } else {
- // Open specified device
- RCLCPP_INFO(LOGGER, "dhd : Connecting to device with ID= %d...", interface_ID_);
+ } else if (interface_ID_ >= 0) {
+ // Open specified device from device ID
+ RCLCPP_INFO(LOGGER, "dhd : Connecting to device with ID= %d, please wait...", interface_ID_);
interface_ID_ = dhdOpenID(interface_ID_);
dhd_open_success = (interface_ID_ >= 0);
+ } else {
+ // Open default device
+ RCLCPP_INFO(LOGGER, "dhd : Connecting to default device., please wait..");
+ interface_ID_ = dhdOpen();
+ dhd_open_success = (interface_ID_ >= 0);
}
// Check connection and setup dhd device