Skip to content

Commit f9b9cf2

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

File tree

3 files changed

+43
-42
lines changed

3 files changed

+43
-42
lines changed

include/dynamixel_hardware_interface/dynamixel_hardware_interface.hpp

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -359,15 +359,15 @@ class DynamixelHardware : public
359359
double prismaticToRevolute(double prismatic_value);
360360

361361
void MapInterfaces(
362-
size_t outer_size,
363-
size_t inner_size,
364-
std::vector<HandlerVarType> &outer_handlers,
365-
const std::vector<HandlerVarType> &inner_handlers,
366-
double **matrix,
367-
const std::unordered_map<std::string, std::vector<std::string>> &iface_map,
368-
const std::string &conversion_iface = "",
369-
const std::string &conversion_name = "",
370-
std::function<double(double)> conversion = nullptr);
362+
size_t outer_size,
363+
size_t inner_size,
364+
std::vector<HandlerVarType> & outer_handlers,
365+
const std::vector<HandlerVarType> & inner_handlers,
366+
double **matrix,
367+
const std::unordered_map<std::string, std::vector<std::string>> & iface_map,
368+
const std::string & conversion_iface = "",
369+
const std::string & conversion_name = "",
370+
std::function<double(double)> conversion = nullptr);
371371
};
372372

373373
// Conversion maps between ROS2 and Dynamixel interface names

src/dynamixel/dynamixel.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -907,15 +907,15 @@ DxlError Dynamixel::SetBulkReadItemAndHandler()
907907
for (size_t item_index = 1; item_index < it_read_data.item_addr.size(); ++item_index) {
908908
uint16_t addr = it_read_data.item_addr[item_index];
909909
uint16_t size = it_read_data.item_size[item_index];
910-
if (addr < min_addr) min_addr = addr;
911-
if (addr + size > max_end_addr) max_end_addr = addr + size;
910+
if (addr < min_addr) {min_addr = addr;}
911+
if (addr + size > max_end_addr) {max_end_addr = addr + size;}
912912
}
913913
uint8_t total_size = max_end_addr - min_addr;
914914
// Concatenate all item names with '+'
915915
std::string group_item_names;
916916
for (size_t i = 0; i < it_read_data.item_name.size(); ++i) {
917917
group_item_names += it_read_data.item_name[i];
918-
if (i + 1 < it_read_data.item_name.size()) group_item_names += " + ";
918+
if (i + 1 < it_read_data.item_name.size()) {group_item_names += " + ";}
919919
}
920920
// Call AddDirectRead once per id
921921
if (AddDirectRead(
@@ -1383,17 +1383,17 @@ DxlError Dynamixel::SetBulkWriteItemAndHandler()
13831383
for (size_t item_index = 1; item_index < it_write_data.item_addr.size(); ++item_index) {
13841384
uint16_t addr = it_write_data.item_addr[item_index];
13851385
uint16_t size = it_write_data.item_size[item_index];
1386-
if (addr < min_addr) min_addr = addr;
1387-
if (addr + size > max_end_addr) max_end_addr = addr + size;
1386+
if (addr < min_addr) {min_addr = addr;}
1387+
if (addr + size > max_end_addr) {max_end_addr = addr + size;}
13881388
}
13891389
uint8_t total_size = max_end_addr - min_addr;
13901390

13911391
// Check for gaps between items
13921392
std::vector<std::pair<uint16_t, uint16_t>> addr_ranges;
13931393
for (size_t item_index = 0; item_index < it_write_data.item_addr.size(); ++item_index) {
13941394
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]
1395+
it_write_data.item_addr[item_index],
1396+
it_write_data.item_addr[item_index] + it_write_data.item_size[item_index]
13971397
});
13981398
}
13991399
std::sort(addr_ranges.begin(), addr_ranges.end());

src/dynamixel_hardware_interface.cpp

Lines changed: 27 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -437,7 +437,7 @@ hardware_interface::CallbackReturn DynamixelHardware::start()
437437
RCLCPP_ERROR_STREAM(
438438
logger_,
439439
"Dynamixel Start Fail (Timeout: " << error_duration.seconds() * 1000 << "ms/" <<
440-
err_timeout_ms_ << "ms): " << Dynamixel::DxlErrorToString(dxl_comm_err_));
440+
err_timeout_ms_ << "ms): " << Dynamixel::DxlErrorToString(dxl_comm_err_));
441441
return hardware_interface::CallbackReturn::ERROR;
442442
}
443443
}
@@ -971,38 +971,38 @@ void DynamixelHardware::SetMatrix()
971971
}
972972

973973
void DynamixelHardware::MapInterfaces(
974-
size_t outer_size,
975-
size_t inner_size,
976-
std::vector<HandlerVarType> &outer_handlers,
977-
const std::vector<HandlerVarType> &inner_handlers,
978-
double **matrix,
979-
const std::unordered_map<std::string, std::vector<std::string>> &iface_map,
980-
const std::string &conversion_iface,
981-
const std::string &conversion_name,
982-
std::function<double(double)> conversion)
974+
size_t outer_size,
975+
size_t inner_size,
976+
std::vector<HandlerVarType> & outer_handlers,
977+
const std::vector<HandlerVarType> & inner_handlers,
978+
double **matrix,
979+
const std::unordered_map<std::string, std::vector<std::string>> & iface_map,
980+
const std::string & conversion_iface,
981+
const std::string & conversion_name,
982+
std::function<double(double)> conversion)
983983
{
984984
for (size_t i = 0; i < outer_size; ++i) {
985985
for (size_t k = 0; k < outer_handlers.at(i).interface_name_vec.size(); ++k) {
986986
double value = 0.0;
987-
const std::string &outer_iface = outer_handlers.at(i).interface_name_vec.at(k);
987+
const std::string & outer_iface = outer_handlers.at(i).interface_name_vec.at(k);
988988
auto map_it = iface_map.find(outer_iface);
989989
if (map_it == iface_map.end()) {
990990
std::ostringstream oss;
991991
oss << "No mapping found for '" << outer_handlers.at(i).name
992992
<< "', interface '" << outer_iface
993993
<< "'. Skipping. Available mapping keys: [";
994994
size_t key_count = 0;
995-
for (const auto &pair : iface_map) {
995+
for (const auto & pair : iface_map) {
996996
oss << pair.first;
997-
if (++key_count < iface_map.size()) oss << ", ";
997+
if (++key_count < iface_map.size()) {oss << ", ";}
998998
}
999999
oss << "]";
10001000
RCLCPP_WARN_STREAM(logger_, oss.str());
10011001
continue;
10021002
}
1003-
const std::vector<std::string> &mapped_ifaces = map_it->second;
1003+
const std::vector<std::string> & mapped_ifaces = map_it->second;
10041004
for (size_t j = 0; j < inner_size; ++j) {
1005-
for (const auto &mapped_iface : mapped_ifaces) {
1005+
for (const auto & mapped_iface : mapped_ifaces) {
10061006
auto it = std::find(
10071007
inner_handlers.at(j).interface_name_vec.begin(),
10081008
inner_handlers.at(j).interface_name_vec.end(),
@@ -1015,9 +1015,10 @@ void DynamixelHardware::MapInterfaces(
10151015
}
10161016
}
10171017
if (!conversion_iface.empty() && !conversion_name.empty() &&
1018-
outer_iface == conversion_iface &&
1019-
outer_handlers.at(i).name == conversion_name &&
1020-
conversion) {
1018+
outer_iface == conversion_iface &&
1019+
outer_handlers.at(i).name == conversion_name &&
1020+
conversion)
1021+
{
10211022
value = conversion(value);
10221023
}
10231024
*outer_handlers.at(i).value_ptr_vec.at(k) = value;
@@ -1027,10 +1028,10 @@ void DynamixelHardware::MapInterfaces(
10271028

10281029
void DynamixelHardware::CalcTransmissionToJoint()
10291030
{
1030-
std::function<double(double)> conv = use_revolute_to_prismatic_
1031-
? std::function<double(double)>(
1032-
std::bind(&DynamixelHardware::revoluteToPrismatic, this, std::placeholders::_1))
1033-
: std::function<double(double)>();
1031+
std::function<double(double)> conv = use_revolute_to_prismatic_ ?
1032+
std::function<double(double)>(
1033+
std::bind(&DynamixelHardware::revoluteToPrismatic, this, std::placeholders::_1)) :
1034+
std::function<double(double)>();
10341035
this->MapInterfaces(
10351036
num_of_joints_,
10361037
num_of_transmissions_,
@@ -1046,10 +1047,10 @@ void DynamixelHardware::CalcTransmissionToJoint()
10461047

10471048
void DynamixelHardware::CalcJointToTransmission()
10481049
{
1049-
std::function<double(double)> conv = use_revolute_to_prismatic_
1050-
? std::function<double(double)>(
1051-
std::bind(&DynamixelHardware::prismaticToRevolute, this, std::placeholders::_1))
1052-
: std::function<double(double)>();
1050+
std::function<double(double)> conv = use_revolute_to_prismatic_ ?
1051+
std::function<double(double)>(
1052+
std::bind(&DynamixelHardware::prismaticToRevolute, this, std::placeholders::_1)) :
1053+
std::function<double(double)>();
10531054
this->MapInterfaces(
10541055
num_of_transmissions_,
10551056
num_of_joints_,

0 commit comments

Comments
 (0)