Skip to content

Commit 541632c

Browse files
authored
Merge pull request #32 from ROBOTIS-GIT/feature-modified-build-error
Modified Build Error
2 parents b981138 + cdb4d70 commit 541632c

File tree

5 files changed

+23
-17
lines changed

5 files changed

+23
-17
lines changed

CHANGELOG.rst

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,11 @@
22
Changelog for package dynamixel_hardware_interface
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
1.4.3 (2025-04-10)
6+
------------------
7+
* Fixed build errors
8+
* Contributors: Wonho Yun
9+
510
1.4.2 (2025-04-05)
611
------------------
712
* Added OM-Y dynamixel model files

include/dynamixel_hardware_interface/dynamixel/dynamixel_info.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -86,9 +86,9 @@ class DynamixelInfo
8686
{return static_cast<int16_t>(effort / dxl_info_[id].torque_constant);}
8787
inline double ConvertCurrentToEffort(uint8_t id, int16_t current)
8888
{return static_cast<double>(current * dxl_info_[id].torque_constant);}
89-
inline double ConvertValueRPMToVelocityRPS(uint8_t id, int32_t value_rpm)
89+
inline double ConvertValueRPMToVelocityRPS(int32_t value_rpm)
9090
{return static_cast<double>(value_rpm * 0.01 / 60.0 * 2.0 * M_PI);}
91-
inline int32_t ConvertVelocityRPSToValueRPM(uint8_t id, double vel_rps)
91+
inline int32_t ConvertVelocityRPSToValueRPM(double vel_rps)
9292
{return static_cast<int32_t>(vel_rps * 100.0 * 60.0 / 2.0 / M_PI);}
9393
};
9494

package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>dynamixel_hardware_interface</name>
5-
<version>1.4.2</version>
5+
<version>1.4.3</version>
66
<description>
77
ROS 2 package providing a hardware interface for controlling Dynamixel motors via the ROS 2 control framework.
88
</description>

src/dynamixel/dynamixel.cpp

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -635,6 +635,8 @@ std::string Dynamixel::DxlErrorToString(DxlError error_num)
635635
return "DLX_HARDWARE_ERROR";
636636
case DXL_REBOOT_FAIL:
637637
return "DXL_REBOOT_FAIL";
638+
default:
639+
return "UNKNOWN_ERROR";
638640
}
639641
}
640642

@@ -965,15 +967,15 @@ DxlError Dynamixel::ProcessReadCommunication(
965967
dxl_comm_result = group_sync_read->txPacket();
966968
if (dxl_comm_result != COMM_SUCCESS) {
967969
fprintf(
968-
stderr, "SyncRead Tx Fail [Dxl Size : %d] [Error code : %d]\n",
970+
stderr, "SyncRead Tx Fail [Dxl Size : %ld] [Error code : %d]\n",
969971
read_data_list_.size(), dxl_comm_result);
970972
return DxlError::SYNC_READ_FAIL;
971973
}
972974
} else {
973975
dxl_comm_result = group_bulk_read->txPacket();
974976
if (dxl_comm_result != COMM_SUCCESS) {
975977
fprintf(
976-
stderr, "BulkRead Tx Fail [Dxl Size : %d] [Error code : %d]\n",
978+
stderr, "BulkRead Tx Fail [Dxl Size : %ld] [Error code : %d]\n",
977979
read_data_list_.size(), dxl_comm_result);
978980
return DxlError::BULK_READ_FAIL;
979981
}
@@ -989,15 +991,15 @@ DxlError Dynamixel::ProcessReadCommunication(
989991
dxl_comm_result = group_sync_read->rxPacket();
990992
if (dxl_comm_result != COMM_SUCCESS) {
991993
fprintf(
992-
stderr, "SyncRead Rx Fail [Dxl Size : %d] [Error code : %d]\n",
994+
stderr, "SyncRead Rx Fail [Dxl Size : %ld] [Error code : %d]\n",
993995
read_data_list_.size(), dxl_comm_result);
994996
return DxlError::SYNC_READ_FAIL;
995997
}
996998
} else {
997999
dxl_comm_result = group_bulk_read->rxPacket();
9981000
if (dxl_comm_result != COMM_SUCCESS) {
9991001
fprintf(
1000-
stderr, "BulkRead Rx Fail [Dxl Size : %d] [Error code : %d]\n",
1002+
stderr, "BulkRead Rx Fail [Dxl Size : %ld] [Error code : %d]\n",
10011003
read_data_list_.size(), dxl_comm_result);
10021004
return DxlError::BULK_READ_FAIL;
10031005
}
@@ -1027,9 +1029,8 @@ DxlError Dynamixel::ProcessReadData(
10271029
id,
10281030
static_cast<int32_t>(dxl_getdata));
10291031
} else if (item_names[item_index] == "Present Velocity") {
1030-
*data_ptrs[item_index] = dxl_info_.ConvertValueRPMToVelocityRPS(
1031-
id,
1032-
static_cast<int32_t>(dxl_getdata));
1032+
*data_ptrs[item_index] =
1033+
dxl_info_.ConvertValueRPMToVelocityRPS(static_cast<int32_t>(dxl_getdata));
10331034
} else if (item_names[item_index] == "Present Current") {
10341035
*data_ptrs[item_index] = dxl_info_.ConvertCurrentToEffort(
10351036
id,
@@ -1173,7 +1174,7 @@ DxlError Dynamixel::SetDxlValueToSyncWrite()
11731174
param_write_value[added_byte + 0] = DXL_LOBYTE(goal_current);
11741175
param_write_value[added_byte + 1] = DXL_HIBYTE(goal_current);
11751176
} else if (indirect_info_write_[ID].item_name.at(item_index) == "Goal Velocity") {
1176-
int16_t goal_velocity = dxl_info_.ConvertVelocityRPSToValueRPM(ID, data);
1177+
int16_t goal_velocity = dxl_info_.ConvertVelocityRPSToValueRPM(data);
11771178
param_write_value[added_byte + 0] = DXL_LOBYTE(DXL_LOWORD(goal_velocity));
11781179
param_write_value[added_byte + 1] = DXL_HIBYTE(DXL_LOWORD(goal_velocity));
11791180
param_write_value[added_byte + 2] = DXL_LOBYTE(DXL_HIWORD(goal_velocity));
@@ -1288,7 +1289,7 @@ DxlError Dynamixel::SetDxlValueToBulkWrite()
12881289
param_write_value[added_byte + 0] = DXL_LOBYTE(goal_current);
12891290
param_write_value[added_byte + 1] = DXL_HIBYTE(goal_current);
12901291
} else if (indirect_info_write_[ID].item_name.at(item_index) == "Goal Velocity") {
1291-
int32_t goal_velocity = dxl_info_.ConvertVelocityRPSToValueRPM(ID, data);
1292+
int32_t goal_velocity = dxl_info_.ConvertVelocityRPSToValueRPM(data);
12921293
param_write_value[added_byte + 0] = DXL_LOBYTE(DXL_LOWORD(goal_velocity));
12931294
param_write_value[added_byte + 1] = DXL_HIBYTE(DXL_LOWORD(goal_velocity));
12941295
param_write_value[added_byte + 2] = DXL_LOBYTE(DXL_HIWORD(goal_velocity));

src/dynamixel_hardware_interface.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -376,13 +376,13 @@ DynamixelHardware::export_command_interfaces()
376376
}
377377

378378
hardware_interface::CallbackReturn DynamixelHardware::on_activate(
379-
const rclcpp_lifecycle::State & previous_state)
379+
[[maybe_unused]] const rclcpp_lifecycle::State & previous_state)
380380
{
381381
return start();
382382
}
383383

384384
hardware_interface::CallbackReturn DynamixelHardware::on_deactivate(
385-
const rclcpp_lifecycle::State & previous_state)
385+
[[maybe_unused]] const rclcpp_lifecycle::State & previous_state)
386386
{
387387
return stop();
388388
}
@@ -440,7 +440,7 @@ hardware_interface::CallbackReturn DynamixelHardware::stop()
440440
}
441441

442442
hardware_interface::return_type DynamixelHardware::read(
443-
const rclcpp::Time & time, const rclcpp::Duration & period)
443+
[[maybe_unused]] const rclcpp::Time & time, const rclcpp::Duration & period)
444444
{
445445
double period_ms = period.seconds() * 1000;
446446
if (dxl_status_ == REBOOTING) {
@@ -503,7 +503,7 @@ hardware_interface::return_type DynamixelHardware::read(
503503
return hardware_interface::return_type::OK;
504504
}
505505
hardware_interface::return_type DynamixelHardware::write(
506-
const rclcpp::Time & time, const rclcpp::Duration & period)
506+
[[maybe_unused]] const rclcpp::Time & time, const rclcpp::Duration & period)
507507
{
508508
if (dxl_status_ == DXL_OK || dxl_status_ == HW_ERROR) {
509509
dxl_comm_->WriteItemBuf();
@@ -1051,7 +1051,7 @@ void DynamixelHardware::set_dxl_data_srv_callback(
10511051
}
10521052

10531053
void DynamixelHardware::reboot_dxl_srv_callback(
1054-
const std::shared_ptr<dynamixel_interfaces::srv::RebootDxl::Request> request,
1054+
[[maybe_unused]] const std::shared_ptr<dynamixel_interfaces::srv::RebootDxl::Request> request,
10551055
std::shared_ptr<dynamixel_interfaces::srv::RebootDxl::Response> response)
10561056
{
10571057
if (CommReset()) {

0 commit comments

Comments
 (0)