Skip to content

Commit 73e4387

Browse files
[pre-commit.ci] auto fixes from pre-commit.com hooks
for more information, see https://pre-commit.ci
1 parent a5ff9ea commit 73e4387

File tree

1 file changed

+10
-10
lines changed

1 file changed

+10
-10
lines changed

src/system_odri.cpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@ SystemOdriHardware::read_default_cmd_state_value(
5858
std::string str_des_start_pos = info_.hardware_parameters[default_joint_cs];
5959

6060
typedef std::map<std::string, PosVelEffortGains> map_pveg;
61-
map_pveg* hw_cs;
61+
map_pveg *hw_cs;
6262
if (default_joint_cs == "default_joint_cmd") {
6363
hw_cs = &hw_commands_;
6464
} else if (default_joint_cs == "default_joint_state") {
@@ -73,9 +73,10 @@ SystemOdriHardware::read_default_cmd_state_value(
7373
while (!iss_def_cmd_val.eof()) {
7474
// Find joint name.
7575
std::string joint_name;
76-
RCLCPP_INFO_STREAM(
77-
rclcpp::get_logger("SystemOdriHardware"),
78-
" Current value of iss_def_cmd_val for " << default_joint_cs << ":" << iss_def_cmd_val.str().c_str());
76+
RCLCPP_INFO_STREAM(rclcpp::get_logger("SystemOdriHardware"),
77+
" Current value of iss_def_cmd_val for "
78+
<< default_joint_cs << ":"
79+
<< iss_def_cmd_val.str().c_str());
7980
iss_def_cmd_val >> joint_name;
8081
if (joint_name == "" && iss_def_cmd_val.eof()) {
8182
break;
@@ -483,20 +484,19 @@ hardware_interface::CallbackReturn SystemOdriHardware::on_activate(
483484
// First set the key
484485
joint_name_to_array_index_[joint.name] = 0;
485486
}
486-
487+
487488
/// Then build the index.
488489
// Warning: depends on order of joint tags within ros2_control tag
489-
// and on order in robot.joint_modules.motor_numbers in config_solo12.yaml
490+
// and on order in robot.joint_modules.motor_numbers in
491+
// config_solo12.yaml
490492
uint idx = 0;
491493
for (auto it = joint_name_to_array_index_.begin();
492494
it != joint_name_to_array_index_.end(); ++it) {
493-
RCLCPP_INFO_STREAM(
494-
rclcpp::get_logger("SystemOdriHardware"),
495-
"joint_name=" << it->first << " -> index=" << idx);
495+
RCLCPP_INFO_STREAM(rclcpp::get_logger("SystemOdriHardware"),
496+
"joint_name=" << it->first << " -> index=" << idx);
496497
joint_name_to_array_index_[it->first] = idx++;
497498
}
498499

499-
500500
return hardware_interface::CallbackReturn::SUCCESS;
501501
}
502502

0 commit comments

Comments
 (0)