@@ -55,12 +55,12 @@ CallbackReturn JointStateTopicSystem::on_init(const hardware_interface::Hardware
5555 }
5656
5757 // Initialize storage for all joints' standard interfaces, regardless of their existence and set all values to nan
58- joint_commands_ .resize (standard_interfaces_.size ());
59- joint_states_ .resize (standard_interfaces_.size ());
58+ joint_command_values_ .resize (standard_interfaces_.size ());
59+ joint_state_values_ .resize (standard_interfaces_.size ());
6060 for (auto i = 0u ; i < standard_interfaces_.size (); i++)
6161 {
62- joint_commands_ [i].resize (get_hardware_info ().joints .size (), 0.0 );
63- joint_states_ [i].resize (get_hardware_info ().joints .size (), 0.0 );
62+ joint_command_values_ [i].resize (get_hardware_info ().joints .size (), 0.0 );
63+ joint_state_values_ [i].resize (get_hardware_info ().joints .size (), 0.0 );
6464 }
6565
6666 // Initial command values
@@ -77,8 +77,8 @@ CallbackReturn JointStateTopicSystem::on_init(const hardware_interface::Hardware
7777 // Check the initial_value param is used
7878 if (!interface.initial_value .empty ())
7979 {
80- joint_states_ [index][i] = std::stod (interface.initial_value );
81- joint_commands_ [index][i] = std::stod (interface.initial_value );
80+ joint_state_values_ [index][i] = std::stod (interface.initial_value );
81+ joint_command_values_ [index][i] = std::stod (interface.initial_value );
8282 }
8383 }
8484 }
@@ -134,7 +134,7 @@ CallbackReturn JointStateTopicSystem::on_init(const hardware_interface::Hardware
134134 [this ](const sensor_msgs::msg::JointState::SharedPtr joint_state) { latest_joint_state_ = *joint_state; });
135135
136136 // if the values on the `joint_states_topic` are wrapped between -2*pi and 2*pi (like they are in Isaac Sim)
137- // sum the total joint rotation returned on the `joint_states_ ` interface
137+ // sum the total joint rotation returned on the `joint_state_values_ ` interface
138138 if (get_hardware_parameter (" sum_wrapped_joint_states" , " false" ) == " true" )
139139 {
140140 sum_wrapped_joint_states_ = true ;
@@ -154,7 +154,7 @@ std::vector<hardware_interface::StateInterface> JointStateTopicSystem::export_st
154154 for (const auto & interface : joint.state_interfaces )
155155 {
156156 // Add interface: if not in the standard list then use "other" interface list
157- if (!getInterface (joint.name , interface.name , i, joint_states_ , state_interfaces))
157+ if (!getInterface (joint.name , interface.name , i, joint_state_values_ , state_interfaces))
158158 {
159159 throw std::runtime_error (" Interface is not found in the standard list." );
160160 }
@@ -174,7 +174,7 @@ std::vector<hardware_interface::CommandInterface> JointStateTopicSystem::export_
174174 const auto & joint = get_hardware_info ().joints [i];
175175 for (const auto & interface : joint.command_interfaces )
176176 {
177- if (!getInterface (joint.name , interface.name , i, joint_commands_ , command_interfaces))
177+ if (!getInterface (joint.name , interface.name , i, joint_command_values_ , command_interfaces))
178178 {
179179 throw std::runtime_error (" Interface is not found in the standard list." );
180180 }
@@ -198,26 +198,26 @@ hardware_interface::return_type JointStateTopicSystem::read(const rclcpp::Time&
198198 auto j = static_cast <std::size_t >(std::distance (joints.begin (), it));
199199 if (sum_wrapped_joint_states_)
200200 {
201- sumRotationFromMinus2PiTo2Pi (latest_joint_state_.position [i], joint_states_ [POSITION_INTERFACE_INDEX][j]);
201+ sumRotationFromMinus2PiTo2Pi (latest_joint_state_.position [i], joint_state_values_ [POSITION_INTERFACE_INDEX][j]);
202202 }
203203 else
204204 {
205- joint_states_ [POSITION_INTERFACE_INDEX][j] = latest_joint_state_.position [i];
205+ joint_state_values_ [POSITION_INTERFACE_INDEX][j] = latest_joint_state_.position [i];
206206 }
207207 if (!latest_joint_state_.velocity .empty ())
208208 {
209- joint_states_ [VELOCITY_INTERFACE_INDEX][j] = latest_joint_state_.velocity [i];
209+ joint_state_values_ [VELOCITY_INTERFACE_INDEX][j] = latest_joint_state_.velocity [i];
210210 }
211211 if (!latest_joint_state_.effort .empty ())
212212 {
213- joint_states_ [EFFORT_INTERFACE_INDEX][j] = latest_joint_state_.effort [i];
213+ joint_state_values_ [EFFORT_INTERFACE_INDEX][j] = latest_joint_state_.effort [i];
214214 }
215215 }
216216 }
217217
218218 for (const auto & mimic_joint : mimic_joints_)
219219 {
220- for (auto & joint_state : joint_states_ )
220+ for (auto & joint_state : joint_state_values_ )
221221 {
222222 joint_state[mimic_joint.joint_index ] = mimic_joint.multiplier * joint_state[mimic_joint.mimicked_joint_index ];
223223 }
@@ -247,8 +247,8 @@ hardware_interface::return_type JointStateTopicSystem::write(const rclcpp::Time&
247247 // To avoid spamming TopicBased's joint command topic we check the difference between the joint states and
248248 // the current joint commands, if it's smaller than a threshold we don't publish it.
249249 const auto diff = std::transform_reduce (
250- joint_states_ [POSITION_INTERFACE_INDEX].cbegin (), joint_states_ [POSITION_INTERFACE_INDEX].cend (),
251- joint_commands_ [POSITION_INTERFACE_INDEX].cbegin (), 0.0 ,
250+ joint_state_values_ [POSITION_INTERFACE_INDEX].cbegin (), joint_state_values_ [POSITION_INTERFACE_INDEX].cend (),
251+ joint_command_values_ [POSITION_INTERFACE_INDEX].cbegin (), 0.0 ,
252252 [](const auto d1, const auto d2) { return std::abs (d1) + std::abs (d2); }, std::minus<double >{});
253253 if (diff <= trigger_joint_command_threshold_)
254254 {
@@ -265,15 +265,15 @@ hardware_interface::return_type JointStateTopicSystem::write(const rclcpp::Time&
265265 {
266266 if (interface.name == hardware_interface::HW_IF_POSITION)
267267 {
268- joint_state.position .push_back (joint_commands_ [POSITION_INTERFACE_INDEX][i]);
268+ joint_state.position .push_back (joint_command_values_ [POSITION_INTERFACE_INDEX][i]);
269269 }
270270 else if (interface.name == hardware_interface::HW_IF_VELOCITY)
271271 {
272- joint_state.velocity .push_back (joint_commands_ [VELOCITY_INTERFACE_INDEX][i]);
272+ joint_state.velocity .push_back (joint_command_values_ [VELOCITY_INTERFACE_INDEX][i]);
273273 }
274274 else if (interface.name == hardware_interface::HW_IF_EFFORT)
275275 {
276- joint_state.effort .push_back (joint_commands_ [EFFORT_INTERFACE_INDEX][i]);
276+ joint_state.effort .push_back (joint_command_values_ [EFFORT_INTERFACE_INDEX][i]);
277277 }
278278 else
279279 {
0 commit comments