You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
// Clear joint control method bits corresponding to stop interfaces
if (interface_name == (this->dataPtr->joints_[j].name + "/" +
hardware_interface::HW_IF_POSITION))
{
this->dataPtr->joints_[j].joint_control_method &= static_cast<ControlMethod_>(VELOCITY & EFFORT);
}
then according to the given comment
// Clear joint control method bits corresponding to stop interfaces
only the POSITION bit should get unset.
But because of the & in VELOCITY & EFFORT every bit in the ControlMethod is set to zero.
Expected behavior
When the & would be replaced by | then only the desired flag would be unset, e.g. stopping POSITION in the following code fragment would only stop position (unset position bit) and not set all bits to zero:
Describe the bug
When inspecting the gz_ros2_control code - in particular the GazeboSimSystem::perform_command_mode_switch method in gz_systems.cpp
I found a potential bug:
The ControlMethod enum
holds information on active command modes of an joint.
When performing a GazeboSimSystem::perform_command_mode_switch
then according to the given comment
only the POSITION bit should get unset.
But because of the & in
VELOCITY & EFFORT
every bit in the ControlMethod is set to zero.Expected behavior
When the & would be replaced by | then only the desired flag would be unset, e.g. stopping POSITION in the following code fragment would only stop position (unset position bit) and not set all bits to zero:
Is this a bug or desired behavior?
Environment:
The text was updated successfully, but these errors were encountered: