Skip to content

Commit ebce0be

Browse files
committed
Modified the error about unused id
Signed-off-by: Wonho Yun <[email protected]>
1 parent b1d8a28 commit ebce0be

File tree

2 files changed

+5
-7
lines changed

2 files changed

+5
-7
lines changed

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

src/dynamixel/dynamixel.cpp

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1027,9 +1027,7 @@ DxlError Dynamixel::ProcessReadData(
10271027
id,
10281028
static_cast<int32_t>(dxl_getdata));
10291029
} 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));
1030+
*data_ptrs[item_index] = dxl_info_.ConvertValueRPMToVelocityRPS(static_cast<int32_t>(dxl_getdata));
10331031
} else if (item_names[item_index] == "Present Current") {
10341032
*data_ptrs[item_index] = dxl_info_.ConvertCurrentToEffort(
10351033
id,
@@ -1173,7 +1171,7 @@ DxlError Dynamixel::SetDxlValueToSyncWrite()
11731171
param_write_value[added_byte + 0] = DXL_LOBYTE(goal_current);
11741172
param_write_value[added_byte + 1] = DXL_HIBYTE(goal_current);
11751173
} else if (indirect_info_write_[ID].item_name.at(item_index) == "Goal Velocity") {
1176-
int16_t goal_velocity = dxl_info_.ConvertVelocityRPSToValueRPM(ID, data);
1174+
int16_t goal_velocity = dxl_info_.ConvertVelocityRPSToValueRPM(data);
11771175
param_write_value[added_byte + 0] = DXL_LOBYTE(DXL_LOWORD(goal_velocity));
11781176
param_write_value[added_byte + 1] = DXL_HIBYTE(DXL_LOWORD(goal_velocity));
11791177
param_write_value[added_byte + 2] = DXL_LOBYTE(DXL_HIWORD(goal_velocity));
@@ -1288,7 +1286,7 @@ DxlError Dynamixel::SetDxlValueToBulkWrite()
12881286
param_write_value[added_byte + 0] = DXL_LOBYTE(goal_current);
12891287
param_write_value[added_byte + 1] = DXL_HIBYTE(goal_current);
12901288
} else if (indirect_info_write_[ID].item_name.at(item_index) == "Goal Velocity") {
1291-
int32_t goal_velocity = dxl_info_.ConvertVelocityRPSToValueRPM(ID, data);
1289+
int32_t goal_velocity = dxl_info_.ConvertVelocityRPSToValueRPM(data);
12921290
param_write_value[added_byte + 0] = DXL_LOBYTE(DXL_LOWORD(goal_velocity));
12931291
param_write_value[added_byte + 1] = DXL_HIBYTE(DXL_LOWORD(goal_velocity));
12941292
param_write_value[added_byte + 2] = DXL_LOBYTE(DXL_HIWORD(goal_velocity));

0 commit comments

Comments
 (0)