Skip to content

Commit f35f3ea

Browse files
committed
refactor: Enhance code readability by improving formatting and consistency in Dynamixel hardware interface files
1 parent fa57a41 commit f35f3ea

File tree

5 files changed

+79
-43
lines changed

5 files changed

+79
-43
lines changed

include/dynamixel_hardware_interface/dynamixel/dynamixel.hpp

Lines changed: 13 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -295,13 +295,23 @@ class Dynamixel
295295
uint8_t item_size);
296296

297297
// Helper function for value conversion with unit info
298-
double ConvertValueWithUnitInfo(uint8_t id, std::string item_name, uint32_t raw_value, uint8_t size, bool is_signed);
298+
double ConvertValueWithUnitInfo(
299+
uint8_t id,
300+
std::string item_name,
301+
uint32_t raw_value,
302+
uint8_t size,
303+
bool is_signed);
299304

300305
// Helper function for converting unit values to raw values
301-
uint32_t ConvertUnitValueToRawValue(uint8_t id, std::string item_name, double unit_value, uint8_t size, bool is_signed);
306+
uint32_t ConvertUnitValueToRawValue(
307+
uint8_t id,
308+
std::string item_name,
309+
double unit_value,
310+
uint8_t size,
311+
bool is_signed);
302312

303313
// Helper function for writing values to buffer
304-
void WriteValueToBuffer(uint8_t* buffer, uint8_t offset, uint32_t value, uint8_t size);
314+
void WriteValueToBuffer(uint8_t * buffer, uint8_t offset, uint32_t value, uint8_t size);
305315
};
306316

307317
} // namespace dynamixel_hardware_interface

include/dynamixel_hardware_interface/dynamixel/dynamixel_info.hpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -106,7 +106,6 @@ double DynamixelInfo::ConvertValueToUnit(uint8_t id, std::string data_name, T va
106106
if (it != dxl_info_[id].unit_map.end()) {
107107
return static_cast<double>(value) * it->second;
108108
}
109-
// fprintf(stderr, "[WARN] No unit mapping found for '%s' in ID %d, returning raw value\n", data_name.c_str(), id);
110109
return static_cast<double>(value);
111110
}
112111

@@ -117,7 +116,6 @@ T DynamixelInfo::ConvertUnitToValue(uint8_t id, std::string data_name, double un
117116
if (it != dxl_info_[id].unit_map.end()) {
118117
return static_cast<T>(unit_value / it->second);
119118
}
120-
// fprintf(stderr, "[WARN] No unit mapping found for '%s' in ID %d, returning raw value\n", data_name.c_str(), id);
121119
return static_cast<T>(unit_value);
122120
}
123121

include/dynamixel_hardware_interface/dynamixel_hardware_interface.hpp

Lines changed: 31 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -51,43 +51,53 @@ namespace dynamixel_hardware_interface
5151
{
5252

5353
// Hardware Error Status bit definitions
54-
struct HardwareErrorStatusBitInfo {
54+
struct HardwareErrorStatusBitInfo
55+
{
5556
int bit;
56-
const char* label;
57-
const char* description;
57+
const char * label;
58+
const char * description;
5859
};
5960

6061
static constexpr HardwareErrorStatusBitInfo HardwareErrorStatusTable[] = {
6162
{0, "Input Voltage Error", "Detects that input voltage exceeds the configured operating voltage"},
6263
{1, "Motor Hall Sensor Error", "Detects that Motor hall sensor value exceeds normal range"},
63-
{2, "Overheating Error", "Detects that internal temperature exceeds the configured operating temperature"},
64+
{2, "Overheating Error",
65+
"Detects that internal temperature exceeds the configured operating temperature"},
6466
{3, "Motor Encoder Error", "Detects malfunction of the motor encoder"},
65-
{4, "Electrical Shock Error", "Detects electric shock on the circuit or insufficient power to operate the motor"},
67+
{4,
68+
"Electrical Shock Error",
69+
"Detects electric shock on the circuit or insufficient power to operate the motor"},
6670
{5, "Overload Error", "Detects that persistent load exceeds maximum output"},
6771
{6, "Not used", "Always 0"},
6872
{7, "Not used", "Always 0"}
6973
};
7074

71-
inline const HardwareErrorStatusBitInfo* get_hardware_error_status_bit_info(int bit) {
72-
for (const auto& entry : HardwareErrorStatusTable) {
73-
if (entry.bit == bit) return &entry;
75+
inline const HardwareErrorStatusBitInfo * get_hardware_error_status_bit_info(int bit)
76+
{
77+
for (const auto & entry : HardwareErrorStatusTable) {
78+
if (entry.bit == bit) {return &entry;}
7479
}
7580
return nullptr;
7681
}
7782

7883
// Error Code (153) definitions
79-
struct ErrorCodeInfo {
84+
struct ErrorCodeInfo
85+
{
8086
int value;
81-
const char* label;
82-
const char* description;
87+
const char * label;
88+
const char * description;
8389
};
8490

8591
static constexpr ErrorCodeInfo ErrorCodeTable[] = {
8692
{0x00, "No Error", "No error"},
8793
{0x01, "Over Voltage Error", "Device supply voltage exceeds the Max Voltage Limit(60)"},
8894
{0x02, "Low Voltage Error", "Device supply voltage exceeds the Min Voltage Limit(62)"},
89-
{0x03, "Inverter Overheating Error", "The inverter temperature has exceeded the Inverter Temperature Limit(56)"},
90-
{0x04, "Motor Overheating Error", "The motor temperature has exceeded the Motor Temperature Limit(57)"},
95+
{0x03,
96+
"Inverter Overheating Error",
97+
"The inverter temperature has exceeded the Inverter Temperature Limit(56)"},
98+
{0x04,
99+
"Motor Overheating Error",
100+
"The motor temperature has exceeded the Motor Temperature Limit(57)"},
91101
{0x05, "Overload Error", "Operating current exceeding rated current for an extended duration"},
92102
{0x07, "Inverter Error", "An issue has occurred with the inverter"},
93103
{0x09, "Battery Warning", "Low Multi-turn battery voltage. Replacement recommended"},
@@ -100,12 +110,16 @@ static constexpr ErrorCodeInfo ErrorCodeTable[] = {
100110
{0x11, "Following Error", "Position control error exceeds the Following Error Threshold(44)"},
101111
{0x12, "Bus Watchdog Error", "An issue has occurred with the Bus Watchdog"},
102112
{0x13, "Over Speed Error", "Rotates at a speed of 120% or more than the Velocity Limit(72)"},
103-
{0x14, "Position Limit Reached Error", "In position control mode, the current position has moved beyond the Max/Min Position Limit + Position Limit Threshold(38) range."}
113+
{0x14,
114+
"Position Limit Reached Error",
115+
"In position control mode, the current position has moved beyond the Max/Min Position Limit"
116+
" + Position Limit Threshold(38) range."}
104117
};
105118

106-
inline const ErrorCodeInfo* get_error_code_info(int value) {
107-
for (const auto& entry : ErrorCodeTable) {
108-
if (entry.value == value) return &entry;
119+
inline const ErrorCodeInfo * get_error_code_info(int value)
120+
{
121+
for (const auto & entry : ErrorCodeTable) {
122+
if (entry.value == value) {return &entry;}
109123
}
110124
return nullptr;
111125
}

src/dynamixel/dynamixel.cpp

Lines changed: 34 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -1645,9 +1645,11 @@ DxlError Dynamixel::ProcessReadData(
16451645
double unit_value;
16461646
bool is_signed;
16471647
if (dxl_info_.GetDxlUnitValue(ID, item_names[item_index], unit_value) &&
1648-
dxl_info_.GetDxlSignType(ID, item_names[item_index], is_signed)) {
1648+
dxl_info_.GetDxlSignType(ID, item_names[item_index], is_signed))
1649+
{
16491650
// Use unit info and sign type to properly convert the value
1650-
*data_ptrs[item_index] = ConvertValueWithUnitInfo(ID, item_names[item_index], dxl_getdata, size, is_signed);
1651+
*data_ptrs[item_index] = ConvertValueWithUnitInfo(ID, item_names[item_index], dxl_getdata,
1652+
size, is_signed);
16511653
} else {
16521654
// Fallback to existing logic for compatibility
16531655
if (item_names[item_index] == "Present Position") {
@@ -1681,9 +1683,11 @@ DxlError Dynamixel::ProcessDirectReadData(
16811683
double unit_value;
16821684
bool is_signed;
16831685
if (dxl_info_.GetDxlUnitValue(ID, item_names[item_index], unit_value) &&
1684-
dxl_info_.GetDxlSignType(ID, item_names[item_index], is_signed)) {
1686+
dxl_info_.GetDxlSignType(ID, item_names[item_index], is_signed))
1687+
{
16851688
// Use unit info and sign type to properly convert the value
1686-
*data_ptrs[item_index] = ConvertValueWithUnitInfo(ID, item_names[item_index], dxl_getdata, size, is_signed);
1689+
*data_ptrs[item_index] = ConvertValueWithUnitInfo(ID, item_names[item_index], dxl_getdata,
1690+
size, is_signed);
16871691
} else {
16881692
// Fallback to existing logic for compatibility
16891693
if (item_names[item_index] == "Present Position") {
@@ -1852,15 +1856,17 @@ DxlError Dynamixel::SetDxlValueToSyncWrite()
18521856
double unit_value;
18531857
bool is_signed;
18541858
if (dxl_info_.GetDxlUnitValue(ID, item_name, unit_value) &&
1855-
dxl_info_.GetDxlSignType(ID, item_name, is_signed)) {
1859+
dxl_info_.GetDxlSignType(ID, item_name, is_signed))
1860+
{
18561861
// Use unit info and sign type to properly convert the value
18571862
uint32_t raw_value = ConvertUnitValueToRawValue(ID, item_name, data, size, is_signed);
18581863
WriteValueToBuffer(param_write_value, added_byte, raw_value, size);
18591864
} else {
18601865
// Fallback to existing logic for compatibility
18611866
if (item_name == "Goal Position") {
18621867
int32_t goal_position = dxl_info_.ConvertRadianToValue(ID, data);
1863-
WriteValueToBuffer(param_write_value, added_byte, static_cast<uint32_t>(goal_position), 4);
1868+
WriteValueToBuffer(param_write_value, added_byte, static_cast<uint32_t>(goal_position),
1869+
4);
18641870
} else {
18651871
WriteValueToBuffer(param_write_value, added_byte, static_cast<uint32_t>(data), size);
18661872
}
@@ -1951,7 +1957,8 @@ DxlError Dynamixel::SetBulkWriteItemAndHandler()
19511957
// Store direct write info
19521958
direct_info_write_[it_write_data.comm_id].indirect_data_addr = min_addr;
19531959
direct_info_write_[it_write_data.comm_id].size = total_size;
1954-
direct_info_write_[it_write_data.comm_id].cnt = static_cast<uint16_t>(it_write_data.item_name.size());
1960+
direct_info_write_[it_write_data.comm_id].cnt =
1961+
static_cast<uint16_t>(it_write_data.item_name.size());
19551962
direct_info_write_[it_write_data.comm_id].item_name = it_write_data.item_name;
19561963
direct_info_write_[it_write_data.comm_id].item_size = it_write_data.item_size;
19571964

@@ -2042,15 +2049,17 @@ DxlError Dynamixel::SetDxlValueToBulkWrite()
20422049
double unit_value;
20432050
bool is_signed;
20442051
if (dxl_info_.GetDxlUnitValue(ID, item_name, unit_value) &&
2045-
dxl_info_.GetDxlSignType(ID, item_name, is_signed)) {
2052+
dxl_info_.GetDxlSignType(ID, item_name, is_signed))
2053+
{
20462054
// Use unit info and sign type to properly convert the value
20472055
uint32_t raw_value = ConvertUnitValueToRawValue(ID, item_name, data, size, is_signed);
20482056
WriteValueToBuffer(param_write_value, added_byte, raw_value, size);
20492057
} else {
20502058
// Fallback to existing logic for compatibility
20512059
if (item_name == "Goal Position") {
20522060
int32_t goal_position = dxl_info_.ConvertRadianToValue(ID, data);
2053-
WriteValueToBuffer(param_write_value, added_byte, static_cast<uint32_t>(goal_position), 4);
2061+
WriteValueToBuffer(param_write_value, added_byte, static_cast<uint32_t>(goal_position),
2062+
4);
20542063
} else {
20552064
WriteValueToBuffer(param_write_value, added_byte, static_cast<uint32_t>(data), size);
20562065
}
@@ -2081,15 +2090,17 @@ DxlError Dynamixel::SetDxlValueToBulkWrite()
20812090
double unit_value;
20822091
bool is_signed;
20832092
if (dxl_info_.GetDxlUnitValue(ID, item_name, unit_value) &&
2084-
dxl_info_.GetDxlSignType(ID, item_name, is_signed)) {
2093+
dxl_info_.GetDxlSignType(ID, item_name, is_signed))
2094+
{
20852095
// Use unit info and sign type to properly convert the value
20862096
uint32_t raw_value = ConvertUnitValueToRawValue(ID, item_name, data, size, is_signed);
20872097
WriteValueToBuffer(param_write_value, added_byte, raw_value, size);
20882098
} else {
20892099
// Fallback to existing logic for compatibility
20902100
if (item_name == "Goal Position") {
20912101
int32_t goal_position = dxl_info_.ConvertRadianToValue(ID, data);
2092-
WriteValueToBuffer(param_write_value, added_byte, static_cast<uint32_t>(goal_position), 4);
2102+
WriteValueToBuffer(param_write_value, added_byte, static_cast<uint32_t>(goal_position),
2103+
4);
20932104
} else {
20942105
WriteValueToBuffer(param_write_value, added_byte, static_cast<uint32_t>(data), size);
20952106
}
@@ -2147,7 +2158,9 @@ DxlError Dynamixel::AddIndirectWrite(
21472158
uint8_t using_size = indirect_info_write_[id].size;
21482159

21492160
for (uint16_t i = 0; i < item_size; i++) {
2150-
if (WriteItem(id, static_cast<uint16_t>(INDIRECT_ADDR + (using_size * 2)), 2, item_addr + i) != DxlError::OK) {
2161+
if (WriteItem(id, static_cast<uint16_t>(INDIRECT_ADDR + (using_size * 2)), 2,
2162+
item_addr + i) != DxlError::OK)
2163+
{
21512164
return DxlError::SET_BULK_WRITE_FAIL;
21522165
}
21532166
using_size++;
@@ -2173,7 +2186,9 @@ void Dynamixel::ResetDirectWrite(std::vector<uint8_t> id_arr)
21732186
}
21742187
}
21752188

2176-
double Dynamixel::ConvertValueWithUnitInfo(uint8_t id, std::string item_name, uint32_t raw_value, uint8_t size, bool is_signed)
2189+
double Dynamixel::ConvertValueWithUnitInfo(
2190+
uint8_t id, std::string item_name, uint32_t raw_value,
2191+
uint8_t size, bool is_signed)
21772192
{
21782193
if (size == 1) {
21792194
if (is_signed) {
@@ -2203,11 +2218,13 @@ double Dynamixel::ConvertValueWithUnitInfo(uint8_t id, std::string item_name, ui
22032218

22042219
// Throw error for unknown sizes
22052220
std::string error_msg = "Unknown data size " + std::to_string(size) +
2206-
" for item '" + item_name + "' in ID " + std::to_string(id);
2221+
" for item '" + item_name + "' in ID " + std::to_string(id);
22072222
throw std::runtime_error(error_msg);
22082223
}
22092224

2210-
uint32_t Dynamixel::ConvertUnitValueToRawValue(uint8_t id, std::string item_name, double unit_value, uint8_t size, bool is_signed)
2225+
uint32_t Dynamixel::ConvertUnitValueToRawValue(
2226+
uint8_t id, std::string item_name, double unit_value,
2227+
uint8_t size, bool is_signed)
22112228
{
22122229
if (size == 1) {
22132230
if (is_signed) {
@@ -2237,11 +2254,11 @@ uint32_t Dynamixel::ConvertUnitValueToRawValue(uint8_t id, std::string item_name
22372254

22382255
// Throw error for unknown sizes
22392256
std::string error_msg = "Unknown data size " + std::to_string(size) +
2240-
" for item '" + item_name + "' in ID " + std::to_string(id);
2257+
" for item '" + item_name + "' in ID " + std::to_string(id);
22412258
throw std::runtime_error(error_msg);
22422259
}
22432260

2244-
void Dynamixel::WriteValueToBuffer(uint8_t* buffer, uint8_t offset, uint32_t value, uint8_t size)
2261+
void Dynamixel::WriteValueToBuffer(uint8_t * buffer, uint8_t offset, uint32_t value, uint8_t size)
22452262
{
22462263
if (size == 1) {
22472264
buffer[offset] = static_cast<uint8_t>(value);

src/dynamixel/dynamixel_info.cpp

Lines changed: 1 addition & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -132,7 +132,7 @@ void DynamixelInfo::ReadDxlModelFile(uint8_t id, uint16_t model_num)
132132
}
133133

134134
if (unit_info_found) {
135-
getline(open_file, line); // Skip header line "Data Name value unit Sign Type"
135+
getline(open_file, line); // Skip header line "Data Name value unit Sign Type"
136136
while (!open_file.eof() ) {
137137
getline(open_file, line);
138138
if (strcmp(line.c_str(), "[control table]") == 0) {
@@ -271,7 +271,6 @@ bool DynamixelInfo::GetDxlUnitValue(uint8_t id, std::string data_name, double &
271271
unit_value = it->second;
272272
return true;
273273
}
274-
// fprintf(stderr, "[WARN] No unit mapping found for '%s' in ID %d\n", data_name.c_str(), id);
275274
return false;
276275
}
277276

@@ -282,7 +281,6 @@ bool DynamixelInfo::GetDxlSignType(uint8_t id, std::string data_name, bool & is_
282281
is_signed = it->second;
283282
return true;
284283
}
285-
// fprintf(stderr, "[WARN] No sign type mapping found for '%s' in ID %d\n", data_name.c_str(), id);
286284
return false;
287285
}
288286

@@ -292,7 +290,6 @@ double DynamixelInfo::GetUnitMultiplier(uint8_t id, std::string data_name)
292290
if (it != dxl_info_[id].unit_map.end()) {
293291
return it->second;
294292
}
295-
// fprintf(stderr, "[WARN] No unit mapping found for '%s' in ID %d, returning 1.0\n", data_name.c_str(), id);
296293
return 1.0;
297294
}
298295

0 commit comments

Comments
 (0)