From 035f83ace9f72ef4ec8cedf307c9cb7cf2cb39cb Mon Sep 17 00:00:00 2001 From: Abishalini Date: Wed, 6 Dec 2023 10:41:16 -0700 Subject: [PATCH 1/5] Add generate_param_lib to CMakeLists.txt and package.xml --- .../CMakeLists.txt | 17 +++++++++ .../package.xml | 1 + .../src/moveit_simple_controller_manager.cpp | 37 ++++++++++++------- ..._simple_controller_manager_parameters.yaml | 9 +++++ 4 files changed, 51 insertions(+), 13 deletions(-) create mode 100644 moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager_parameters.yaml diff --git a/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt b/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt index c51930686f..3a62c703d5 100644 --- a/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt +++ b/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt @@ -11,6 +11,7 @@ find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) find_package(control_msgs REQUIRED) find_package(rclcpp_action REQUIRED) +find_package(generate_parameter_library REQUIRED) # Finds Boost Components include(ConfigExtras.cmake) @@ -21,6 +22,12 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS rclcpp_action moveit_core pluginlib + generate_parameter_library +) + +generate_parameter_library( + moveit_simple_controller_manager_parameters # cmake target name for the parameter library + src/moveit_simple_controller_manager_parameters.yaml # path to input yaml file ) include_directories( @@ -39,6 +46,16 @@ ament_target_dependencies(moveit_simple_controller_manager Boost ) +target_link_libraries(moveit_simple_controller_manager moveit_simple_controller_manager_parameters) + +install( + TARGETS moveit_simple_controller_manager_parameters + EXPORT ${PROJECT_NAME}Targets + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + install( TARGETS moveit_simple_controller_manager EXPORT moveit_simple_controller_managerTargets diff --git a/moveit_plugins/moveit_simple_controller_manager/package.xml b/moveit_plugins/moveit_simple_controller_manager/package.xml index efa6058759..566900bf1b 100644 --- a/moveit_plugins/moveit_simple_controller_manager/package.xml +++ b/moveit_plugins/moveit_simple_controller_manager/package.xml @@ -25,6 +25,7 @@ pluginlib control_msgs rclcpp_action + generate_parameter_library ament_lint_auto ament_lint_common diff --git a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp index c2989141f8..e3469f7f32 100644 --- a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp +++ b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp @@ -48,6 +48,8 @@ #include #include +#include + namespace { /** @@ -94,19 +96,25 @@ class MoveItSimpleControllerManager : public moveit_controller_manager::MoveItCo void initialize(const rclcpp::Node::SharedPtr& node) override { node_ = node; - if (!node_->has_parameter(makeParameterName(PARAM_BASE_NAME, "controller_names"))) - { - RCLCPP_ERROR_STREAM(LOGGER, "No controller_names specified."); - return; - } - rclcpp::Parameter controller_names_param; - node_->get_parameter(makeParameterName(PARAM_BASE_NAME, "controller_names"), controller_names_param); - if (controller_names_param.get_type() != rclcpp::ParameterType::PARAMETER_STRING_ARRAY) - { - RCLCPP_ERROR(LOGGER, "Parameter controller_names should be specified as a string array"); - return; - } - std::vector controller_names = controller_names_param.as_string_array(); + const auto param_prefix = "moveit_simple_controller_manager"; + param_listener_ = std::make_shared(node_, param_prefix); + params_ = param_listener_->get_params(); + + // ************** generate param library has checks already in place. Add catch block so that the code does not + // segfault ************ if (!node_->has_parameter(makeParameterName(PARAM_BASE_NAME, "controller_names"))) + // { + // RCLCPP_ERROR_STREAM(LOGGER, "No controller_names specified."); + // return; + // } + // rclcpp::Parameter controller_names_param; + // node_->get_parameter(makeParameterName(PARAM_BASE_NAME, "controller_names"), controller_names_param); + // if (controller_names_param.get_type() != rclcpp::ParameterType::PARAMETER_STRING_ARRAY) + // { + // RCLCPP_ERROR(LOGGER, "Parameter controller_names should be specified as a string array"); + // return; + // } + std::vector controller_names = params_.controller_names; + /* actually create each controller */ for (const std::string& controller_name : controller_names) { @@ -291,6 +299,9 @@ class MoveItSimpleControllerManager : public moveit_controller_manager::MoveItCo rclcpp::Node::SharedPtr node_; std::map controllers_; std::map controller_states_; + + std::shared_ptr param_listener_; + moveit_simple_controller_manager::Params params_; }; } // end namespace moveit_simple_controller_manager diff --git a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager_parameters.yaml b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager_parameters.yaml new file mode 100644 index 0000000000..dd4cb0ff10 --- /dev/null +++ b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager_parameters.yaml @@ -0,0 +1,9 @@ +moveit_simple_controller_manager: + controller_names: { + type: string_array, + default_value: [], + description: "List of controllers for MoveIt's controller manager", + validation: { + not_empty<>: [] + } + } From 1d70d9b9ea627ae5ac2552e6f3c1cef8bc759a7b Mon Sep 17 00:00:00 2001 From: Abishalini Date: Wed, 6 Dec 2023 14:00:18 -0700 Subject: [PATCH 2/5] Refactor param reading in moveit simple controller manager --- .../src/moveit_simple_controller_manager.cpp | 99 ++++++------------- ..._simple_controller_manager_parameters.yaml | 56 +++++++++++ 2 files changed, 88 insertions(+), 67 deletions(-) diff --git a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp index e3469f7f32..d62fc7d8b0 100644 --- a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp +++ b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp @@ -96,95 +96,60 @@ class MoveItSimpleControllerManager : public moveit_controller_manager::MoveItCo void initialize(const rclcpp::Node::SharedPtr& node) override { node_ = node; - const auto param_prefix = "moveit_simple_controller_manager"; - param_listener_ = std::make_shared(node_, param_prefix); - params_ = param_listener_->get_params(); - // ************** generate param library has checks already in place. Add catch block so that the code does not - // segfault ************ if (!node_->has_parameter(makeParameterName(PARAM_BASE_NAME, "controller_names"))) - // { - // RCLCPP_ERROR_STREAM(LOGGER, "No controller_names specified."); - // return; - // } - // rclcpp::Parameter controller_names_param; - // node_->get_parameter(makeParameterName(PARAM_BASE_NAME, "controller_names"), controller_names_param); - // if (controller_names_param.get_type() != rclcpp::ParameterType::PARAMETER_STRING_ARRAY) - // { - // RCLCPP_ERROR(LOGGER, "Parameter controller_names should be specified as a string array"); - // return; - // } - std::vector controller_names = params_.controller_names; - - /* actually create each controller */ - for (const std::string& controller_name : controller_names) + try { - try - { - std::string action_ns; - const std::string& action_ns_param = makeParameterName(PARAM_BASE_NAME, controller_name, "action_ns"); - if (!node_->get_parameter(action_ns_param, action_ns)) - { - RCLCPP_ERROR_STREAM(LOGGER, "No action namespace specified for controller `" - << controller_name << "` through parameter `" << action_ns_param << '`'); - continue; - } + const auto controller_manager_param_prefix = "moveit_simple_controller_manager"; + param_listener_ = + std::make_shared(node_, controller_manager_param_prefix); + params_ = param_listener_->get_params(); - std::string type; - if (!node_->get_parameter(makeParameterName(PARAM_BASE_NAME, controller_name, "type"), type)) - { - RCLCPP_ERROR_STREAM(LOGGER, "No type specified for controller " << controller_name); - continue; - } + std::vector controller_names = params_.controller_names; - std::vector controller_joints; - if (!node_->get_parameter(makeParameterName(PARAM_BASE_NAME, controller_name, "joints"), controller_joints) || - controller_joints.empty()) - { - RCLCPP_ERROR_STREAM(LOGGER, "No joints specified for controller " << controller_name); - continue; - } + /* actually create each controller */ + for (const auto& controller : params_.controller_names_map) + { + const std::string controller_name = controller.first; + const std::string action_ns = controller.second.action_ns; + const std::string controller_type = controller.second.type; + const std::vector controller_joints = controller.second.joints; ActionBasedControllerHandleBasePtr new_handle; - if (type == "GripperCommand") + if (controller_type == "GripperCommand") { - double max_effort; - const std::string& max_effort_param = makeParameterName(PARAM_BASE_NAME, controller_name, "max_effort"); - if (!node->get_parameter(max_effort_param, max_effort)) - { - RCLCPP_INFO_STREAM(LOGGER, "Max effort set to 0.0"); - max_effort = 0.0; - } + const double max_effort = controller.second.max_effort; + RCLCPP_INFO_STREAM(LOGGER, "Max effort set to " << max_effort); new_handle = std::make_shared(node_, controller_name, action_ns, max_effort); - bool parallel_gripper = false; - if (node_->get_parameter(makeParameterName(PARAM_BASE_NAME, "parallel"), parallel_gripper) && parallel_gripper) + + bool parallel_gripper = controller.second.parallel; + if (parallel_gripper) { if (controller_joints.size() != 2) { RCLCPP_ERROR_STREAM(LOGGER, "Parallel Gripper requires exactly two joints, " << controller_joints.size() << " are specified"); - continue; } static_cast(new_handle.get()) ->setParallelJawGripper(controller_joints[0], controller_joints[1]); } else { - std::string command_joint; - if (!node_->get_parameter(makeParameterName(PARAM_BASE_NAME, "command_joint"), command_joint)) + std::string command_joint = controller.second.command_joint; + if (command_joint.empty()) + { command_joint = controller_joints[0]; - + } static_cast(new_handle.get())->setCommandJoint(command_joint); } - bool allow_failure; - node_->get_parameter_or(makeParameterName(PARAM_BASE_NAME, "allow_failure"), allow_failure, false); + const bool allow_failure = controller.second.allow_failure; static_cast(new_handle.get())->allowFailure(allow_failure); RCLCPP_INFO_STREAM(LOGGER, "Added GripperCommand controller for " << controller_name); controllers_[controller_name] = new_handle; } - else if (type == "FollowJointTrajectory") + else if (controller_type == "FollowJointTrajectory") { new_handle = std::make_shared(node_, controller_name, action_ns); RCLCPP_INFO_STREAM(LOGGER, "Added FollowJointTrajectory controller for " << controller_name); @@ -192,7 +157,7 @@ class MoveItSimpleControllerManager : public moveit_controller_manager::MoveItCo } else { - RCLCPP_ERROR_STREAM(LOGGER, "Unknown controller type: " << type); + RCLCPP_ERROR_STREAM(LOGGER, "Unknown controller type: " << controller_type); continue; } if (!controllers_[controller_name]) @@ -202,8 +167,7 @@ class MoveItSimpleControllerManager : public moveit_controller_manager::MoveItCo } moveit_controller_manager::MoveItControllerManager::ControllerState state; - node_->get_parameter_or(makeParameterName(PARAM_BASE_NAME, controller_name, "default"), state.default_, false); - state.active_ = true; + state.active_ = controller.second.make_default; controller_states_[controller_name] = state; @@ -211,12 +175,13 @@ class MoveItSimpleControllerManager : public moveit_controller_manager::MoveItCo for (const std::string& controller_joint : controller_joints) new_handle->addJoint(controller_joint); } - catch (...) - { - RCLCPP_ERROR_STREAM(LOGGER, "Caught unknown exception while parsing controller information"); - } + } + catch (...) + { + RCLCPP_ERROR_STREAM(LOGGER, "Caught unknown exception while parsing controller information"); } } + /* * Get a controller, by controller name (which was specified in the controllers.yaml */ diff --git a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager_parameters.yaml b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager_parameters.yaml index dd4cb0ff10..9b6c26b0ee 100644 --- a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager_parameters.yaml +++ b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager_parameters.yaml @@ -7,3 +7,59 @@ moveit_simple_controller_manager: not_empty<>: [] } } + __map_controller_names: + action_ns: { + type: string, + default_value: "", + description: "follow_joint_trajectory or gripper_cmd", + validation: { + not_empty<>: [] + } + } + type: { + type: string, + default_value: "", + description: "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 + default makes MoveIt prefer this controller when multiple options are available.", + validation: { + not_empty<>: [] + } + } + joints: { + type: string_array, + default_value: [], + description: "list of joints to actuate", + validation: { + not_empty<>: [] + } + } + # GripperCommand parameters + max_effort: { + type: double, + default_value: 0.0, + description: "Parameter to be set if using GripperCommand" + } + parallel: { + type: bool, + default_value: false, + description: "Parameter to be set if using GripperCommand" + } + command_joint: { + type: string, + default_value: "", + description: "Parameter to be set if using GripperCommand" + } + allow_failure: { + type: bool, + default_value: false, + description: "Parameter to be set if using GripperCommand" + } + # FollowJointTrajectory parameters From 6489d19340236b8acf748331847ec3bb53255d10 Mon Sep 17 00:00:00 2001 From: Abishalini Date: Wed, 6 Dec 2023 15:35:51 -0700 Subject: [PATCH 3/5] Add goal time tolerance as parameter --- ...ollow_joint_trajectory_controller_handle.h | 5 +++ ...low_joint_trajectory_controller_handle.cpp | 14 +++++++ .../src/moveit_simple_controller_manager.cpp | 8 +++- ..._simple_controller_manager_parameters.yaml | 42 ++++++++++++++++++- 4 files changed, 66 insertions(+), 3 deletions(-) diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h index 70ae825680..43f10fb551 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h @@ -63,6 +63,11 @@ class FollowJointTrajectoryControllerHandle // TODO(JafarAbdi): Revise parameter lookup // void configure(XmlRpc::XmlRpcValue& config) override; + void setPathTolerance(double path_tolerance); + + void setGoalTolerance(double goal_tolerance); + + void setGoalTimeTolerance(double goal_time_tolerance); protected: static control_msgs::msg::JointTolerance& getTolerance(std::vector& tolerances, diff --git a/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp b/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp index c7b49e0751..2c5f6d6b89 100644 --- a/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp +++ b/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp @@ -36,6 +36,7 @@ /* Author: Michael Ferguson, Ioan Sucan, E. Gil Jones */ #include +#include using namespace std::placeholders; @@ -97,6 +98,19 @@ bool FollowJointTrajectoryControllerHandle::sendTrajectory(const moveit_msgs::ms return true; } +void FollowJointTrajectoryControllerHandle::setPathTolerance(double path_tolerance) +{ +} + +void FollowJointTrajectoryControllerHandle::setGoalTolerance(double goal_tolerance) +{ +} + +void FollowJointTrajectoryControllerHandle::setGoalTimeTolerance(double goal_time_tolerance) +{ + goal_template_.goal_time_tolerance = rclcpp::Duration::from_seconds(goal_time_tolerance); +} + // TODO(JafarAbdi): Revise parameter lookup // void FollowJointTrajectoryControllerHandle::configure(XmlRpc::XmlRpcValue& config) //{ diff --git a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp index d62fc7d8b0..3fa17bfef1 100644 --- a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp +++ b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp @@ -152,6 +152,12 @@ class MoveItSimpleControllerManager : public moveit_controller_manager::MoveItCo else if (controller_type == "FollowJointTrajectory") { new_handle = std::make_shared(node_, controller_name, action_ns); + + // static_cast(new_handle.get())->setPathTolerance(controller.second.path_tolerance); + // static_cast(new_handle.get())->setGoalTolerance(controller.second.goal_tolerance); + static_cast(new_handle.get()) + ->setGoalTimeTolerance(controller.second.goal_time_tolerance); + RCLCPP_INFO_STREAM(LOGGER, "Added FollowJointTrajectory controller for " << controller_name); controllers_[controller_name] = new_handle; } @@ -178,7 +184,7 @@ class MoveItSimpleControllerManager : public moveit_controller_manager::MoveItCo } catch (...) { - RCLCPP_ERROR_STREAM(LOGGER, "Caught unknown exception while parsing controller information"); + RCLCPP_ERROR_STREAM(LOGGER, "Caught exception while parsing controller information"); } } diff --git a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager_parameters.yaml b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager_parameters.yaml index 9b6c26b0ee..33e9679252 100644 --- a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager_parameters.yaml +++ b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager_parameters.yaml @@ -41,7 +41,7 @@ moveit_simple_controller_manager: not_empty<>: [] } } - # GripperCommand parameters + # parameters for gripper controllers max_effort: { type: double, default_value: 0.0, @@ -62,4 +62,42 @@ moveit_simple_controller_manager: default_value: false, description: "Parameter to be set if using GripperCommand" } - # FollowJointTrajectory parameters + # parameters for follow joint trajectory controllers + goal_time_tolerance: { + type: double, + default_value: 0.0, + description: "Parameter to be set if using FollowJointTrajectory" + } + # __map_joints: + # path_tolerance: + # position: { + # type: double, + # default_value: 0.0, + # description: "Parameter to be set if using FollowJointTrajectory" + # } + # velocity: { + # type: double, + # default_value: 0.0, + # description: "Parameter to be set if using FollowJointTrajectory" + # } + # acceleration: { + # type: double, + # default_value: 0.0, + # description: "Parameter to be set if using FollowJointTrajectory" + # } + # goal_tolerance: + # position: { + # type: double, + # default_value: 0.0, + # description: "Parameter to be set if using FollowJointTrajectory" + # } + # velocity: { + # type: double, + # default_value: 0.0, + # description: "Parameter to be set if using FollowJointTrajectory" + # } + # acceleration: { + # type: double, + # default_value: 0.0, + # description: "Parameter to be set if using FollowJointTrajectory" + # } From c4ea98b9696691c01787db035f1433f8977a0c3c Mon Sep 17 00:00:00 2001 From: Abishalini Date: Wed, 6 Dec 2023 15:49:48 -0700 Subject: [PATCH 4/5] Comment out unused function args --- .../src/follow_joint_trajectory_controller_handle.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp b/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp index 2c5f6d6b89..dacfc37634 100644 --- a/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp +++ b/moveit_plugins/moveit_simple_controller_manager/src/follow_joint_trajectory_controller_handle.cpp @@ -98,11 +98,11 @@ bool FollowJointTrajectoryControllerHandle::sendTrajectory(const moveit_msgs::ms return true; } -void FollowJointTrajectoryControllerHandle::setPathTolerance(double path_tolerance) +void FollowJointTrajectoryControllerHandle::setPathTolerance(double /*path_tolerance*/) { } -void FollowJointTrajectoryControllerHandle::setGoalTolerance(double goal_tolerance) +void FollowJointTrajectoryControllerHandle::setGoalTolerance(double /*goal_tolerance*/) { } From edaaac180ed10dff1be16bd6316dfadc3d81ed38 Mon Sep 17 00:00:00 2001 From: Abishalini Date: Thu, 7 Dec 2023 10:18:37 -0700 Subject: [PATCH 5/5] Fix up parameter description --- .../src/moveit_simple_controller_manager.cpp | 1 + .../moveit_simple_controller_manager_parameters.yaml | 12 ++++++------ 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp index 3fa17bfef1..27ad1e2ddb 100644 --- a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp +++ b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp @@ -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(new_handle.get()) ->setParallelJawGripper(controller_joints[0], controller_joints[1]); diff --git a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager_parameters.yaml b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager_parameters.yaml index 33e9679252..68dfbd595b 100644 --- a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager_parameters.yaml +++ b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager_parameters.yaml @@ -11,7 +11,7 @@ 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<>: [] } @@ -19,7 +19,7 @@ moveit_simple_controller_manager: type: { type: string, default_value: "", - description: "FollowJointTrajectory or GripperCommand", + description: "Controller type. FollowJointTrajectory or GripperCommand", validation: { not_empty<>: [] } @@ -27,7 +27,7 @@ moveit_simple_controller_manager: 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<>: [] @@ -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,