Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #ifndef MOVEIT_PLUGINS_GRIPPER_CONTROLLER_HANDLE
00039 #define MOVEIT_PLUGINS_GRIPPER_CONTROLLER_HANDLE
00040
00041 #include <moveit_simple_controller_manager/action_based_controller_handle.h>
00042 #include <control_msgs/GripperCommandAction.h>
00043 #include <set>
00044
00045 namespace moveit_simple_controller_manager
00046 {
00047
00048
00049
00050
00051
00052 class GripperControllerHandle :
00053 public ActionBasedControllerHandle<control_msgs::GripperCommandAction>
00054 {
00055 public:
00056
00057 GripperControllerHandle(const std::string &name, const std::string &ns) :
00058 ActionBasedControllerHandle<control_msgs::GripperCommandAction>(name, ns),
00059 allow_failure_(false), parallel_jaw_gripper_(false)
00060 {
00061 }
00062
00063 virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory &trajectory)
00064 {
00065 ROS_DEBUG_STREAM_NAMED("GripperController",
00066 "Received new trajectory for " << name_);
00067
00068 if (!controller_action_client_)
00069 return false;
00070
00071 if (!trajectory.multi_dof_joint_trajectory.points.empty())
00072 {
00073 ROS_ERROR_NAMED("GripperController",
00074 "Gripper cannot execute multi-dof trajectories.");
00075 return false;
00076 }
00077
00078 if (trajectory.joint_trajectory.points.empty())
00079 {
00080 ROS_ERROR_NAMED("GripperController",
00081 "GripperController requires at least one joint trajectory point.");
00082 return false;
00083 }
00084
00085 if (trajectory.joint_trajectory.points.size() > 1)
00086 {
00087 ROS_DEBUG_STREAM_NAMED("GripperController","Trajectory: " << trajectory.joint_trajectory);
00088 }
00089
00090 if (trajectory.joint_trajectory.joint_names.empty())
00091 {
00092 ROS_ERROR_NAMED("GripperController", "No joint names specified");
00093 return false;
00094 }
00095
00096 std::vector<int> gripper_joint_indexes;
00097 for (std::size_t i = 0 ; i < trajectory.joint_trajectory.joint_names.size() ; ++i)
00098 {
00099 if (command_joints_.find(trajectory.joint_trajectory.joint_names[i]) != command_joints_.end())
00100 {
00101 gripper_joint_indexes.push_back(i);
00102 if (!parallel_jaw_gripper_)
00103 break;
00104 }
00105 }
00106
00107 if (gripper_joint_indexes.empty())
00108 {
00109 ROS_WARN_NAMED("GripperController",
00110 "No command_joint was specified for the MoveIt controller gripper handle. \
00111 Please see GripperControllerHandle::addCommandJoint() and \
00112 GripperControllerHandle::setCommandJoint(). Assuming index 0.");
00113 gripper_joint_indexes.push_back(0);
00114 }
00115
00116
00117 control_msgs::GripperCommandGoal goal;
00118 goal.command.position = 0.0;
00119 goal.command.max_effort = 0.0;
00120
00121
00122 int tpoint = trajectory.joint_trajectory.points.size() - 1;
00123 ROS_DEBUG_NAMED("GripperController",
00124 "Sending command from trajectory point %d",
00125 tpoint);
00126
00127
00128 for (std::size_t i = 0; i < gripper_joint_indexes.size(); ++i)
00129 {
00130 int idx = gripper_joint_indexes[i];
00131
00132 if (trajectory.joint_trajectory.points[tpoint].positions.size() <= idx)
00133 {
00134 ROS_ERROR_NAMED("GripperController",
00135 "GripperController expects a joint trajectory with one \
00136 point that specifies at least the position of joint \
00137 '%s', but insufficient positions provided",
00138 trajectory.joint_trajectory.joint_names[idx].c_str());
00139 return false;
00140 }
00141 goal.command.position += trajectory.joint_trajectory.points[tpoint].positions[idx];
00142
00143 if (trajectory.joint_trajectory.points[tpoint].effort.size() > idx)
00144 goal.command.max_effort = trajectory.joint_trajectory.points[tpoint].effort[idx];
00145 }
00146
00147 controller_action_client_->sendGoal(goal,
00148 boost::bind(&GripperControllerHandle::controllerDoneCallback, this, _1, _2),
00149 boost::bind(&GripperControllerHandle::controllerActiveCallback, this),
00150 boost::bind(&GripperControllerHandle::controllerFeedbackCallback, this, _1));
00151
00152 done_ = false;
00153 last_exec_ = moveit_controller_manager::ExecutionStatus::RUNNING;
00154 return true;
00155 }
00156
00157 void setCommandJoint(const std::string& name)
00158 {
00159 command_joints_.clear();
00160 addCommandJoint(name);
00161 }
00162
00163 void addCommandJoint(const std::string& name)
00164 {
00165 command_joints_.insert(name);
00166 }
00167
00168 void allowFailure(bool allow)
00169 {
00170 allow_failure_ = allow;
00171 }
00172
00173 void setParallelJawGripper(const std::string& left, const std::string& right)
00174 {
00175 addCommandJoint(left);
00176 addCommandJoint(right);
00177 parallel_jaw_gripper_ = true;
00178 }
00179
00180 private:
00181
00182 void controllerDoneCallback(const actionlib::SimpleClientGoalState& state,
00183 const control_msgs::GripperCommandResultConstPtr& result)
00184 {
00185 if (state == actionlib::SimpleClientGoalState::ABORTED && allow_failure_)
00186 finishControllerExecution(actionlib::SimpleClientGoalState::SUCCEEDED);
00187 else
00188 finishControllerExecution(state);
00189 }
00190
00191 void controllerActiveCallback()
00192 {
00193 ROS_DEBUG_STREAM_NAMED("GripperController", name_ << " started execution");
00194 }
00195
00196 void controllerFeedbackCallback(const control_msgs::GripperCommandFeedbackConstPtr& feedback)
00197 {
00198 }
00199
00200
00201
00202
00203
00204 bool allow_failure_;
00205
00206
00207
00208
00209
00210
00211
00212
00213
00214 bool parallel_jaw_gripper_;
00215
00216
00217
00218
00219
00220
00221
00222
00223
00224
00225
00226 std::set<std::string> command_joints_;
00227 };
00228
00229
00230 }
00231
00232 #endif // MOVEIT_PLUGINS_GRIPPER_CONTROLLER_HANDLE