gz_ros2_control icon indicating copy to clipboard operation
gz_ros2_control copied to clipboard

[Bug] gz_ros2_control command_mode_switch: When unsetting ControlMode bits for stop_interfaces all bits get unset

Open baconbrot opened this issue 9 months ago • 0 comments

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

enum ControlMethod_
 {
   NONE      = 0,
   POSITION  = (1 << 0),
   VELOCITY  = (1 << 1),
   EFFORT    = (1 << 2),
 };

typedef SafeEnum<enum ControlMethod_> ControlMethod;

holds information on active command modes of an joint.

When performing a GazeboSimSystem::perform_command_mode_switch

// 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:

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);
}

Is this a bug or desired behavior?

Environment:

  • Branch: Master

baconbrot avatar May 15 '24 14:05 baconbrot