@@ -57,8 +57,8 @@ controller_interface::InterfaceConfiguration ForceTorqueStateController::state_i
5757
5858controller_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_);
0 commit comments