Skip to content

Commit aeb04a5

Browse files
committed
Fix clang tidy in multiple pkgs.
1 parent 4e214c8 commit aeb04a5

File tree

2 files changed

+11
-11
lines changed

2 files changed

+11
-11
lines changed

ur_controllers/src/force_torque_sensor_controller.cpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -57,8 +57,8 @@ controller_interface::InterfaceConfiguration ForceTorqueStateController::state_i
5757

5858
controller_interface::return_type ur_controllers::ForceTorqueStateController::update()
5959
{
60-
geometry_msgs::msg::Vector3 fVec;
61-
geometry_msgs::msg::Vector3 tVec;
60+
geometry_msgs::msg::Vector3 f_vec;
61+
geometry_msgs::msg::Vector3 t_vec;
6262

6363
if (state_interfaces_.size() != fts_params_.state_interfaces_names_.size())
6464
return controller_interface::return_type::ERROR;
@@ -68,22 +68,22 @@ controller_interface::return_type ur_controllers::ForceTorqueStateController::up
6868
switch (index)
6969
{
7070
case 0:
71-
fVec.set__x(state_interfaces_[index].get_value());
71+
f_vec.set__x(state_interfaces_[index].get_value());
7272
break;
7373
case 1:
74-
fVec.set__y(state_interfaces_[index].get_value());
74+
f_vec.set__y(state_interfaces_[index].get_value());
7575
break;
7676
case 2:
77-
fVec.set__z(state_interfaces_[index].get_value());
77+
f_vec.set__z(state_interfaces_[index].get_value());
7878
break;
7979
case 3:
80-
tVec.set__x(state_interfaces_[index].get_value());
80+
t_vec.set__x(state_interfaces_[index].get_value());
8181
break;
8282
case 4:
83-
tVec.set__y(state_interfaces_[index].get_value());
83+
t_vec.set__y(state_interfaces_[index].get_value());
8484
break;
8585
case 5:
86-
tVec.set__z(state_interfaces_[index].get_value());
86+
t_vec.set__z(state_interfaces_[index].get_value());
8787
break;
8888
default:
8989
break;
@@ -94,8 +94,8 @@ controller_interface::return_type ur_controllers::ForceTorqueStateController::up
9494
wrench_state_msg_.header.frame_id = fts_params_.frame_id;
9595

9696
// update wrench state message
97-
wrench_state_msg_.wrench.set__force(fVec);
98-
wrench_state_msg_.wrench.set__torque(tVec);
97+
wrench_state_msg_.wrench.set__force(f_vec);
98+
wrench_state_msg_.wrench.set__torque(t_vec);
9999

100100
// publish
101101
wrench_state_publisher_->publish(wrench_state_msg_);

ur_robot_driver/src/dashboard_client_ros.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -135,7 +135,7 @@ DashboardClientROS::DashboardClientROS(const rclcpp::Node::SharedPtr& node, cons
135135

136136
// Service to query the current program state
137137
program_state_service_ = node_->create_service<ur_dashboard_msgs::srv::GetProgramState>(
138-
"program_state", [&](const ur_dashboard_msgs::srv::GetProgramState::Request::SharedPtr,
138+
"program_state", [&](const ur_dashboard_msgs::srv::GetProgramState::Request::SharedPtr /*unused*/,
139139
ur_dashboard_msgs::srv::GetProgramState::Response::SharedPtr resp) {
140140
resp->answer = this->client_.sendAndReceive("programState\n");
141141
std::smatch match;

0 commit comments

Comments
 (0)