Skip to content

Commit

Permalink
Fix up parameter description
Browse files Browse the repository at this point in the history
  • Loading branch information
Abishalini committed Dec 7, 2023
1 parent 7b3f7c0 commit a9bdfcb
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -129,6 +129,7 @@ class MoveItSimpleControllerManager : public moveit_controller_manager::MoveItCo
{
RCLCPP_ERROR_STREAM(LOGGER, "Parallel Gripper requires exactly two joints, " << controller_joints.size()
<< " are specified");
continue;
}
static_cast<GripperControllerHandle*>(new_handle.get())
->setParallelJawGripper(controller_joints[0], controller_joints[1]);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,23 +11,23 @@ moveit_simple_controller_manager:
action_ns: {
type: string,
default_value: "",
description: "follow_joint_trajectory or gripper_cmd",
description: "Action namespace for the controller. The action topic names will start with `/controller_name/action_ns`",
validation: {
not_empty<>: []
}
}
type: {
type: string,
default_value: "",
description: "FollowJointTrajectory or GripperCommand",
description: "Controller type. FollowJointTrajectory or GripperCommand",
validation: {
not_empty<>: []
}
}
make_default: {
type: bool,
default_value: false,
description: "This param was originally named default. Can't use default with generate_param_lib as default is a C++ keyword. Marking a controller as
description: "This param was originally named default. Marking a controller as
default makes MoveIt prefer this controller when multiple options are available.",
validation: {
not_empty<>: []
Expand All @@ -45,17 +45,17 @@ moveit_simple_controller_manager:
max_effort: {
type: double,
default_value: 0.0,
description: "Parameter to be set if using GripperCommand"
description: "Max Effort. Parameter to be set if using GripperCommand"
}
parallel: {
type: bool,
default_value: false,
description: "Parameter to be set if using GripperCommand"
description: "Parallel gripper require exactly two joints. If true, specify only two joints. Parameter to be set if using GripperCommand"
}
command_joint: {
type: string,
default_value: "",
description: "Parameter to be set if using GripperCommand"
description: "If not parallel, set the joint to command. Parameter to be set if using GripperCommand"
}
allow_failure: {
type: bool,
Expand Down

0 comments on commit a9bdfcb

Please sign in to comment.