Skip to content

Commit

Permalink
feat(simple_controller_manager): add max_effort parameter to Grippe…
Browse files Browse the repository at this point in the history
…rCommand action

This commit adds the `max_effort` parameter to the GripperCommand
declaration in the `controller_list` (see issue moveit#2956). This value is
only used when effort is set in the requested gripper trajectory.
  • Loading branch information
rickstaa committed Dec 7, 2021
1 parent 32a1883 commit cc92dff
Show file tree
Hide file tree
Showing 2 changed files with 20 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -51,10 +51,11 @@ class GripperControllerHandle : public ActionBasedControllerHandle<control_msgs:
{
public:
/* Topics will map to name/ns/goal, name/ns/result, etc */
GripperControllerHandle(const std::string& name, const std::string& ns)
GripperControllerHandle(const std::string& name, const std::string& ns, const double& max_effort = 0.0)
: ActionBasedControllerHandle<control_msgs::GripperCommandAction>(name, ns)
, allow_failure_(false)
, parallel_jaw_gripper_(false)
, max_effort_(max_effort)
{
}

Expand Down Expand Up @@ -110,7 +111,6 @@ class GripperControllerHandle : public ActionBasedControllerHandle<control_msgs:
// goal to be sent
control_msgs::GripperCommandGoal goal;
goal.command.position = 0.0;
goal.command.max_effort = 0.0;

// send last point
int tpoint = trajectory.joint_trajectory.points.size() - 1;
Expand All @@ -129,8 +129,11 @@ class GripperControllerHandle : public ActionBasedControllerHandle<control_msgs:
}
goal.command.position += trajectory.joint_trajectory.points[tpoint].positions[idx];

if (trajectory.joint_trajectory.points[tpoint].effort.size() > idx)
if (trajectory.joint_trajectory.points[tpoint].effort.size() > idx) {
goal.command.max_effort = trajectory.joint_trajectory.points[tpoint].effort[idx];
} else {
goal.command.max_effort = max_effort_;
}
}

controller_action_client_->sendGoal(
Expand Down Expand Up @@ -202,6 +205,12 @@ class GripperControllerHandle : public ActionBasedControllerHandle<control_msgs:
*/
bool parallel_jaw_gripper_;

/*
* The ``max_effort`` used in the GripperCommand message when no ``max_effort`` was
* specified in the requested trajectory. Defaults to ``0.0``.
*/
double max_effort_;

/*
* A GripperCommand message has only a single float64 for the
* "command", thus only a single joint angle can be sent -- however,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
#include <pluginlib/class_list_macros.hpp>
#include <algorithm>
#include <map>
#include <boost/thread/thread.hpp>

using namespace moveit::core;

Expand All @@ -55,6 +56,10 @@ class MoveItSimpleControllerManager : public moveit_controller_manager::MoveItCo
public:
MoveItSimpleControllerManager() : node_handle_("~")
{
int t = 0;
while(t == 0)
boost::this_thread::sleep( boost::posix_time::seconds(1) );

if (!node_handle_.hasParam("controller_list"))
{
ROS_ERROR_STREAM_NAMED(LOGNAME, "No controller_list specified.");
Expand Down Expand Up @@ -94,7 +99,9 @@ class MoveItSimpleControllerManager : public moveit_controller_manager::MoveItCo
ActionBasedControllerHandleBasePtr new_handle;
if (type == "GripperCommand")
{
new_handle = std::make_shared<GripperControllerHandle>(name, action_ns);
double max_effort = controller_list[i].hasMember("max_effort") ? double(controller_list[i]["max_effort"]) : 0.0;

new_handle = std::make_shared<GripperControllerHandle>(name, action_ns, max_effort);
if (static_cast<GripperControllerHandle*>(new_handle.get())->isConnected())
{
if (controller_list[i].hasMember("parallel"))
Expand Down

0 comments on commit cc92dff

Please sign in to comment.