Skip to content

Commit

Permalink
fix parameter namespacing for gripper controller (#3023)
Browse files Browse the repository at this point in the history
* fix parameter name for parallel gripper mode

* update other params

* formatting

---------

Co-authored-by: Sebastian Jahr <[email protected]>
  • Loading branch information
mikeferguson and sjahr authored Oct 21, 2024
1 parent 7db58f8 commit 1b8044a
Showing 1 changed file with 6 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -156,7 +156,8 @@ class MoveItSimpleControllerManager : public moveit_controller_manager::MoveItCo

new_handle = std::make_shared<GripperControllerHandle>(node_, controller_name, action_ns, max_effort);
bool parallel_gripper = false;
if (node_->get_parameter(makeParameterName(PARAM_BASE_NAME, "parallel"), parallel_gripper) && parallel_gripper)
if (node_->get_parameter(makeParameterName(PARAM_BASE_NAME, controller_name, "parallel"), parallel_gripper) &&
parallel_gripper)
{
if (controller_joints.size() != 2)
{
Expand All @@ -170,14 +171,16 @@ class MoveItSimpleControllerManager : public moveit_controller_manager::MoveItCo
else
{
std::string command_joint;
if (!node_->get_parameter(makeParameterName(PARAM_BASE_NAME, "command_joint"), command_joint))
if (!node_->get_parameter(makeParameterName(PARAM_BASE_NAME, controller_name, "command_joint"),
command_joint))
command_joint = controller_joints[0];

static_cast<GripperControllerHandle*>(new_handle.get())->setCommandJoint(command_joint);
}

bool allow_failure;
node_->get_parameter_or(makeParameterName(PARAM_BASE_NAME, "allow_failure"), allow_failure, false);
node_->get_parameter_or(makeParameterName(PARAM_BASE_NAME, controller_name, "allow_failure"), allow_failure,
false);
static_cast<GripperControllerHandle*>(new_handle.get())->allowFailure(allow_failure);

RCLCPP_INFO_STREAM(getLogger(), "Added GripperCommand controller for " << controller_name);
Expand Down

0 comments on commit 1b8044a

Please sign in to comment.