Skip to content

Commit fcffc17

Browse files
committed
refactor: improve code readability and formatting
1 parent 2dfd57e commit fcffc17

File tree

2 files changed

+23
-12
lines changed

2 files changed

+23
-12
lines changed

src/dynamixel/dynamixel.cpp

Lines changed: 12 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -959,7 +959,8 @@ DxlError Dynamixel::SetBulkReadItemAndHandler()
959959
result);
960960
} else if(result == DxlError::CANNOT_FIND_CONTROL_ITEM) {
961961
fprintf(
962-
stderr, "[ID:%03d] 'Indirect Address Read' is not defined in control table, Cannot set Indirect Address Read for : [%s]\n",
962+
stderr, "[ID:%03d] 'Indirect Address Read' is not defined in control table, "
963+
"Cannot set Indirect Address Read for : [%s]\n",
963964
it_read_data.id,
964965
it_read_data.item_name.at(item_index).c_str());
965966
}
@@ -1015,12 +1016,15 @@ DxlError Dynamixel::SetBulkReadHandler(std::vector<uint8_t> id_arr)
10151016
return DxlError::OK;
10161017
}
10171018

1018-
DxlError Dynamixel::AddDirectRead(uint8_t id, std::string item_name, uint16_t item_addr, uint8_t item_size)
1019+
DxlError Dynamixel::AddDirectRead(
1020+
uint8_t id, std::string item_name, uint16_t item_addr, uint8_t item_size)
10191021
{
10201022
if (group_bulk_read_->addParam(id, item_addr, item_size) == true) {
1021-
fprintf(stderr, "[ID:%03d] Add BulkRead item : [%s][%d][%d]\n", id, item_name.c_str(), item_addr, item_size);
1023+
fprintf(stderr, "[ID:%03d] Add BulkRead item : [%s][%d][%d]\n",
1024+
id, item_name.c_str(), item_addr, item_size);
10221025
} else {
1023-
fprintf(stderr, "[ID:%03d] Failed to BulkRead item : [%s][%d][%d]\n", id, item_name.c_str(), item_addr, item_size);
1026+
fprintf(stderr, "[ID:%03d] Failed to BulkRead item : [%s][%d][%d]\n",
1027+
id, item_name.c_str(), item_addr, item_size);
10241028
return DxlError::SET_BULK_READ_FAIL;
10251029
}
10261030
return DxlError::OK;
@@ -1387,8 +1391,10 @@ DxlError Dynamixel::SetBulkWriteItemAndHandler()
13871391
// Check for gaps between items
13881392
std::vector<std::pair<uint16_t, uint16_t>> addr_ranges;
13891393
for (size_t item_index = 0; item_index < it_write_data.item_addr.size(); ++item_index) {
1390-
addr_ranges.push_back({it_write_data.item_addr[item_index],
1391-
it_write_data.item_addr[item_index] + it_write_data.item_size[item_index]});
1394+
addr_ranges.push_back({
1395+
it_write_data.item_addr[item_index],
1396+
it_write_data.item_addr[item_index] + it_write_data.item_size[item_index]
1397+
});
13921398
}
13931399
std::sort(addr_ranges.begin(), addr_ranges.end());
13941400

src/dynamixel_hardware_interface.cpp

Lines changed: 11 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -394,8 +394,8 @@ DynamixelHardware::export_command_interfaces()
394394
for (auto it : hdl_gpio_controller_commands_) {
395395
for (size_t i = 0; i < it.value_ptr_vec.size(); i++) {
396396
if (i >= it.interface_name_vec.size()) {
397-
RCLCPP_ERROR_STREAM(logger_, "Interface name vector size mismatch for gpio controller " << it.name <<
398-
". Expected size: " << it.value_ptr_vec.size() <<
397+
RCLCPP_ERROR_STREAM(logger_, "Interface name vector size mismatch for gpio controller " <<
398+
it.name << ". Expected size: " << it.value_ptr_vec.size() <<
399399
", Actual size: " << it.interface_name_vec.size());
400400
continue;
401401
}
@@ -436,7 +436,8 @@ hardware_interface::CallbackReturn DynamixelHardware::start()
436436
if (error_duration.seconds() * 1000 >= err_timeout_ms_) {
437437
RCLCPP_ERROR_STREAM(
438438
logger_,
439-
"Dynamixel Start Fail (Timeout: " << error_duration.seconds() * 1000 << "ms/" << err_timeout_ms_ << "ms): " << Dynamixel::DxlErrorToString(dxl_comm_err_));
439+
"Dynamixel Start Fail (Timeout: " << error_duration.seconds() * 1000 << "ms/" <<
440+
err_timeout_ms_ << "ms): " << Dynamixel::DxlErrorToString(dxl_comm_err_));
440441
return hardware_interface::CallbackReturn::ERROR;
441442
}
442443
}
@@ -987,7 +988,9 @@ void DynamixelHardware::MapInterfaces(
987988
auto map_it = iface_map.find(outer_iface);
988989
if (map_it == iface_map.end()) {
989990
std::ostringstream oss;
990-
oss << "No mapping found for '" << outer_handlers.at(i).name << "', interface '" << outer_iface << "'. Skipping. Available mapping keys: [";
991+
oss << "No mapping found for '" << outer_handlers.at(i).name
992+
<< "', interface '" << outer_iface
993+
<< "'. Skipping. Available mapping keys: [";
991994
size_t key_count = 0;
992995
for (const auto &pair : iface_map) {
993996
oss << pair.first;
@@ -1025,7 +1028,8 @@ void DynamixelHardware::MapInterfaces(
10251028
void DynamixelHardware::CalcTransmissionToJoint()
10261029
{
10271030
std::function<double(double)> conv = use_revolute_to_prismatic_
1028-
? std::function<double(double)>(std::bind(&DynamixelHardware::revoluteToPrismatic, this, std::placeholders::_1))
1031+
? std::function<double(double)>(
1032+
std::bind(&DynamixelHardware::revoluteToPrismatic, this, std::placeholders::_1))
10291033
: std::function<double(double)>();
10301034
this->MapInterfaces(
10311035
num_of_joints_,
@@ -1043,7 +1047,8 @@ void DynamixelHardware::CalcTransmissionToJoint()
10431047
void DynamixelHardware::CalcJointToTransmission()
10441048
{
10451049
std::function<double(double)> conv = use_revolute_to_prismatic_
1046-
? std::function<double(double)>(std::bind(&DynamixelHardware::prismaticToRevolute, this, std::placeholders::_1))
1050+
? std::function<double(double)>(
1051+
std::bind(&DynamixelHardware::prismaticToRevolute, this, std::placeholders::_1))
10471052
: std::function<double(double)>();
10481053
this->MapInterfaces(
10491054
num_of_transmissions_,

0 commit comments

Comments
 (0)