59 std::string l_name, r_name;
60 nh.
param<std::string>(
"l_gripper_joint", l_name,
"l_gripper_finger_joint");
61 nh.
param<std::string>(
"r_gripper_joint", r_name,
"r_gripper_finger_joint");
70 "Unable to retreive joint (%s), Namespace: %s/l_gripper_joint",
78 "Unable to retreive joint (%s), Namespace: %s/r_gripper_joint",
112 "Unable to start, not initialized.");
119 "Unable to start, action server is not active.");
161 double position =
left_->getPosition() +
right_->getPosition();
163 if (
goal_ < position)
170 left_->setEffort(effort - offset);
171 right_->setEffort(effort + offset);
182 control_msgs::GripperCommandFeedback feedback;
183 control_msgs::GripperCommandResult
result;
187 server_->setAborted(result,
"Controller is not initialized.");
193 server_->setAborted(result,
"Cannot execute, unable to start controller.");
195 "Cannot execute, unable to start controller.");
200 if (goal->command.max_effort <= 0.0 || goal->command.max_effort >
max_effort_)
206 effort_ = goal->command.max_effort;
214 else if (goal->command.position < 0.0)
220 goal_ = goal->command.position;
224 float last_position =
left_->getPosition() +
right_->getPosition();
239 feedback.position =
left_->getPosition() +
right_->getPosition();
240 feedback.effort =
left_->getEffort() +
right_->getEffort();
241 feedback.reached_goal =
false;
242 feedback.stalled =
false;
243 server_->publishFeedback(feedback);
246 if (fabs(feedback.position - goal->command.position) < 0.002)
248 result.position = feedback.position;
249 result.effort = feedback.effort;
250 result.reached_goal =
true;
251 result.stalled =
false;
258 if (fabs(feedback.position - last_position) > 0.005)
260 last_position = feedback.position;
267 result.position = feedback.position;
268 result.effort = feedback.effort;
269 result.reached_goal =
false;
270 result.stalled =
true;
271 ROS_DEBUG_NAMED(
"ParallelGripperController",
"Gripper stalled, but succeeding.");
283 std::vector<std::string> names;
284 names.push_back(
left_->getName());
285 names.push_back(
right_->getName());
actionlib::SimpleActionServer< control_msgs::GripperCommandAction > server_t
virtual int requestStart(const std::string &name)
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
virtual bool reset()
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves...
#define ROS_DEBUG_NAMED(name,...)
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ControllerManager * manager_
double update(double error, double dt)
Run PID calculation and return control result.
Controller for a parallel jaw gripper, is really only intended for use in simulation.
virtual void update(const ros::Time &now, const ros::Duration &dt)
This is the update loop for the controller.
robot_controllers::PID centering_pid_
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
const std::string & getNamespace() const
bool use_centering_controller_
virtual bool stop(bool force)
Attempt to stop the controller. This should be called only by the ControllerManager instance...
#define ROS_ERROR_NAMED(name,...)
virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
JointHandlePtr getJointHandle(const std::string &name)
void executeCb(const control_msgs::GripperCommandGoalConstPtr &goal)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
boost::shared_ptr< server_t > server_
bool init(const ros::NodeHandle &nh)
initialize gain settings from ROS parameter values