Skip to content

Commit 4ea4204

Browse files
committed
refactor: enhance code formatting and readability across multiple files
1 parent 81c2aee commit 4ea4204

File tree

3 files changed

+30
-23
lines changed

3 files changed

+30
-23
lines changed

include/dynamixel_hardware_interface/dynamixel_hardware_interface.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -364,7 +364,7 @@ class DynamixelHardware : public
364364
size_t inner_size,
365365
std::vector<HandlerVarType> & outer_handlers,
366366
const std::vector<HandlerVarType> & inner_handlers,
367-
double **matrix,
367+
double ** matrix,
368368
const std::unordered_map<std::string, std::vector<std::string>> & iface_map,
369369
const std::string & conversion_iface = "",
370370
const std::string & conversion_name = "",

src/dynamixel/dynamixel.cpp

Lines changed: 16 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -919,10 +919,10 @@ DxlError Dynamixel::SetBulkReadItemAndHandler()
919919
}
920920
// Call AddDirectRead once per id
921921
if (AddDirectRead(
922-
it_read_data.id,
923-
group_item_names,
924-
min_addr,
925-
total_size) != DxlError::OK)
922+
it_read_data.id,
923+
group_item_names,
924+
min_addr,
925+
total_size) != DxlError::OK)
926926
{
927927
fprintf(stderr, "Cannot set the BulkRead handler.\n");
928928
return DxlError::BULK_READ_FAIL;
@@ -951,13 +951,13 @@ DxlError Dynamixel::SetBulkReadItemAndHandler()
951951
stderr, "[ID:%03d] Add Indirect Address Read Item : [%s]\n",
952952
it_read_data.id,
953953
it_read_data.item_name.at(item_index).c_str());
954-
} else if(result == DxlError::SET_BULK_READ_FAIL) {
954+
} else if (result == DxlError::SET_BULK_READ_FAIL) {
955955
fprintf(
956956
stderr, "[ID:%03d] Failed to Indirect Address Read Item : [%s], %d\n",
957957
it_read_data.id,
958958
it_read_data.item_name.at(item_index).c_str(),
959959
result);
960-
} else if(result == DxlError::CANNOT_FIND_CONTROL_ITEM) {
960+
} else if (result == DxlError::CANNOT_FIND_CONTROL_ITEM) {
961961
fprintf(
962962
stderr, "[ID:%03d] 'Indirect Address Read' is not defined in control table, "
963963
"Cannot set Indirect Address Read for : [%s]\n",
@@ -1020,10 +1020,12 @@ DxlError Dynamixel::AddDirectRead(
10201020
uint8_t id, std::string item_name, uint16_t item_addr, uint8_t item_size)
10211021
{
10221022
if (group_bulk_read_->addParam(id, item_addr, item_size) == true) {
1023-
fprintf(stderr, "[ID:%03d] Add BulkRead item : [%s][%d][%d]\n",
1023+
fprintf(
1024+
stderr, "[ID:%03d] Add BulkRead item : [%s][%d][%d]\n",
10241025
id, item_name.c_str(), item_addr, item_size);
10251026
} else {
1026-
fprintf(stderr, "[ID:%03d] Failed to BulkRead item : [%s][%d][%d]\n",
1027+
fprintf(
1028+
stderr, "[ID:%03d] Failed to BulkRead item : [%s][%d][%d]\n",
10271029
id, item_name.c_str(), item_addr, item_size);
10281030
return DxlError::SET_BULK_READ_FAIL;
10291031
}
@@ -1391,17 +1393,19 @@ DxlError Dynamixel::SetBulkWriteItemAndHandler()
13911393
// Check for gaps between items
13921394
std::vector<std::pair<uint16_t, uint16_t>> addr_ranges;
13931395
for (size_t item_index = 0; item_index < it_write_data.item_addr.size(); ++item_index) {
1394-
addr_ranges.push_back({
1396+
addr_ranges.push_back(
1397+
{
13951398
it_write_data.item_addr[item_index],
13961399
it_write_data.item_addr[item_index] + it_write_data.item_size[item_index]
1397-
});
1400+
});
13981401
}
13991402
std::sort(addr_ranges.begin(), addr_ranges.end());
14001403

14011404
for (size_t i = 0; i < addr_ranges.size() - 1; ++i) {
14021405
if (addr_ranges[i].second != addr_ranges[i + 1].first) {
1403-
fprintf(stderr, "[ID:%03d] Error: Gap detected between items at addresses %d and %d\n",
1404-
it_write_data.id, addr_ranges[i].second, addr_ranges[i + 1].first);
1406+
fprintf(
1407+
stderr, "[ID:%03d] Error: Gap detected between items at addresses %d and %d\n",
1408+
it_write_data.id, addr_ranges[i].second, addr_ranges[i + 1].first);
14051409
return DxlError::BULK_WRITE_FAIL;
14061410
}
14071411
}

src/dynamixel_hardware_interface.cpp

Lines changed: 13 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -394,9 +394,10 @@ 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 " <<
398-
it.name << ". Expected size: " << it.value_ptr_vec.size() <<
399-
", Actual size: " << it.interface_name_vec.size());
397+
RCLCPP_ERROR_STREAM(
398+
logger_, "Interface name vector size mismatch for gpio controller " <<
399+
it.name << ". Expected size: " << it.value_ptr_vec.size() <<
400+
", Actual size: " << it.interface_name_vec.size());
400401
continue;
401402
}
402403
command_interfaces.emplace_back(
@@ -975,7 +976,7 @@ void DynamixelHardware::MapInterfaces(
975976
size_t inner_size,
976977
std::vector<HandlerVarType> & outer_handlers,
977978
const std::vector<HandlerVarType> & inner_handlers,
978-
double **matrix,
979+
double ** matrix,
979980
const std::unordered_map<std::string, std::vector<std::string>> & iface_map,
980981
const std::string & conversion_iface,
981982
const std::string & conversion_name,
@@ -1030,7 +1031,7 @@ void DynamixelHardware::CalcTransmissionToJoint()
10301031
{
10311032
std::function<double(double)> conv = use_revolute_to_prismatic_ ?
10321033
std::function<double(double)>(
1033-
std::bind(&DynamixelHardware::revoluteToPrismatic, this, std::placeholders::_1)) :
1034+
std::bind(&DynamixelHardware::revoluteToPrismatic, this, std::placeholders::_1)) :
10341035
std::function<double(double)>();
10351036
this->MapInterfaces(
10361037
num_of_joints_,
@@ -1049,7 +1050,7 @@ void DynamixelHardware::CalcJointToTransmission()
10491050
{
10501051
std::function<double(double)> conv = use_revolute_to_prismatic_ ?
10511052
std::function<double(double)>(
1052-
std::bind(&DynamixelHardware::prismaticToRevolute, this, std::placeholders::_1)) :
1053+
std::bind(&DynamixelHardware::prismaticToRevolute, this, std::placeholders::_1)) :
10531054
std::function<double(double)>();
10541055
this->MapInterfaces(
10551056
num_of_transmissions_,
@@ -1076,8 +1077,9 @@ void DynamixelHardware::SyncJointCommandWithStates()
10761077
it_commands.interface_name_vec.end(),
10771078
pos_cmd_name);
10781079
if (cmd_it == it_commands.interface_name_vec.end()) {
1079-
RCLCPP_WARN_STREAM(logger_,
1080-
"No position interface found in command interfaces for joint '" <<
1080+
RCLCPP_WARN_STREAM(
1081+
logger_,
1082+
"No position interface found in command interfaces for joint '" <<
10811083
it_commands.name << "'. Skipping sync!");
10821084
continue;
10831085
}
@@ -1088,8 +1090,9 @@ void DynamixelHardware::SyncJointCommandWithStates()
10881090
it_states.interface_name_vec.end(),
10891091
pos_cmd_name);
10901092
if (state_it == it_states.interface_name_vec.end()) {
1091-
RCLCPP_WARN_STREAM(logger_,
1092-
"No position interface found in state interfaces for joint '" <<
1093+
RCLCPP_WARN_STREAM(
1094+
logger_,
1095+
"No position interface found in state interfaces for joint '" <<
10931096
it_states.name << "'. Skipping sync!");
10941097
continue;
10951098
}

0 commit comments

Comments
 (0)