move_group.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2012, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
00036 
00037 #ifndef MOVEIT_MOVE_GROUP_INTERFACE_MOVE_GROUP_
00038 #define MOVEIT_MOVE_GROUP_INTERFACE_MOVE_GROUP_
00039 
00040 #include <moveit/robot_state/robot_state.h>
00041 #include <moveit_msgs/RobotTrajectory.h>
00042 #include <moveit_msgs/RobotState.h>
00043 #include <moveit_msgs/PlannerInterfaceDescription.h>
00044 #include <moveit_msgs/Constraints.h>
00045 #include <manipulation_msgs/Grasp.h>
00046 #include <manipulation_msgs/PlaceLocation.h>
00047 #include <geometry_msgs/PoseStamped.h>
00048 #include <boost/shared_ptr.hpp>
00049 #include <tf/tf.h>
00050 
00051 namespace moveit
00052 {
00053 
00055 namespace planning_interface
00056 {
00057 
00059 class MoveGroup
00060 {
00061 public:
00062 
00064   static const std::string ROBOT_DESCRIPTION;
00065 
00067   struct Options
00068   {
00069     Options(const std::string &group_name,
00070             const std::string &desc = ROBOT_DESCRIPTION) :
00071       group_name_(group_name),
00072       robot_description_(desc)
00073     {
00074     }
00075 
00077     std::string group_name_;
00078 
00080     std::string robot_description_;
00081 
00083     robot_model::RobotModelConstPtr robot_model_;
00084   };
00085 
00087   struct Plan
00088   {
00090     moveit_msgs::RobotState start_state_;
00091 
00093     moveit_msgs::RobotTrajectory trajectory_;
00094   };
00095 
00099   MoveGroup(const Options &opt, const boost::shared_ptr<tf::Transformer> &tf = boost::shared_ptr<tf::Transformer>(),
00100             const ros::Duration &wait_for_server = ros::Duration(0, 0));
00101 
00105   MoveGroup(const std::string &group, const boost::shared_ptr<tf::Transformer> &tf = boost::shared_ptr<tf::Transformer>(),
00106             const ros::Duration &wait_for_server = ros::Duration(0, 0));
00107 
00108   ~MoveGroup();
00109 
00111   const std::string& getName() const;
00112 
00114   const std::string& getPlanningFrame() const;
00115 
00117   const std::vector<std::string>& getJoints() const;
00118 
00120   unsigned int getVariableCount() const;
00121 
00123   bool getInterfaceDescription(moveit_msgs::PlannerInterfaceDescription &desc);
00124 
00126   void setPlannerId(const std::string &planner_id);
00127 
00129   void setPlanningTime(double seconds);
00130 
00132   double getPlanningTime() const;
00133 
00135   double getGoalJointTolerance() const;
00136 
00138   double getGoalPositionTolerance() const;
00139 
00141   double getGoalOrientationTolerance() const;
00142 
00149   void setGoalTolerance(double tolerance);
00150 
00152   void setGoalJointTolerance(double tolerance);
00153 
00155   void setGoalPositionTolerance(double tolerance);
00156 
00158   void setGoalOrientationTolerance(double tolerance);
00159 
00163   void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz);
00164 
00166   void setStartState(const robot_state::RobotState &start_state);
00167 
00169   void setStartStateToCurrentState();
00170 
00172   void setSupportSurfaceName(const std::string &name);
00173 
00180   bool setJointValueTarget(const std::vector<double> &group_variable_values);
00181 
00183   bool setJointValueTarget(const std::map<std::string, double> &variable_values);
00184 
00187   bool setJointValueTarget(const robot_state::RobotState &robot_state);
00188 
00191   bool setJointValueTarget(const robot_state::JointStateGroup &joint_state_group);
00192 
00194   bool setJointValueTarget(const robot_state::JointState &joint_state);
00195 
00197   bool setJointValueTarget(const std::string &joint_name, const std::vector<double> &values);
00198 
00200   bool setJointValueTarget(const std::string &joint_name, double value);
00201 
00203   bool setJointValueTarget(const sensor_msgs::JointState &state);
00204 
00206   void setRandomTarget();
00207 
00210   bool setNamedTarget(const std::string &name);
00211 
00213   const robot_state::JointStateGroup& getJointValueTarget() const;
00214 
00225   bool setPositionTarget(double x, double y, double z, const std::string &end_effector_link = "");
00226 
00228   bool setRPYTarget(double roll, double pitch, double yaw, const std::string &end_effector_link = "");
00229 
00232   bool setOrientationTarget(double x, double y, double z, double w, const std::string &end_effector_link = "");
00233 
00236   bool setPoseTarget(const Eigen::Affine3d &end_effector_pose, const std::string &end_effector_link = "");
00237 
00240   bool setPoseTarget(const geometry_msgs::Pose &target, const std::string &end_effector_link = "");
00241 
00244   bool setPoseTarget(const geometry_msgs::PoseStamped &target, const std::string &end_effector_link = "");
00245 
00248   bool setPoseTargets(const EigenSTL::vector_Affine3d &end_effector_pose, const std::string &end_effector_link = "");
00249 
00252   bool setPoseTargets(const std::vector<geometry_msgs::Pose> &target, const std::string &end_effector_link = "");
00253 
00256   bool setPoseTargets(const std::vector<geometry_msgs::PoseStamped> &target, const std::string &end_effector_link = "");
00257 
00259   void setPoseReferenceFrame(const std::string &pose_reference_frame);
00260 
00262   bool setEndEffectorLink(const std::string &link_name);
00263 
00265   bool setEndEffector(const std::string &eef_name);
00266 
00268   void clearPoseTarget(const std::string &end_effector_link = "");
00269 
00271   void clearPoseTargets();
00272 
00275   const geometry_msgs::PoseStamped& getPoseTarget(const std::string &end_effector_link = "") const;
00276 
00280   const std::vector<geometry_msgs::PoseStamped>& getPoseTargets(const std::string &end_effector_link = "") const;
00281 
00286   const std::string& getEndEffectorLink() const;
00287 
00291   const std::string& getEndEffector() const;
00292 
00294   const std::string& getPoseReferenceFrame() const;
00295 
00305   bool asyncMove();
00306 
00309   bool move();
00310 
00313   bool plan(Plan &plan);
00314 
00316   bool asyncExecute(const Plan &plan);
00317 
00319   bool execute(const Plan &plan);
00320 
00328   double computeCartesianPath(const std::vector<geometry_msgs::Pose> &waypoints, double eef_step, double jump_threshold,
00329                   moveit_msgs::RobotTrajectory &trajectory,  bool avoid_collisions = true);
00330 
00332   void stop();
00333 
00335   void allowLooking(bool flag);
00336 
00338   void allowReplanning(bool flag);
00339 
00348   bool pick(const std::string &object);
00349 
00351   bool pick(const std::string &object, const manipulation_msgs::Grasp &grasp);
00352 
00354   bool pick(const std::string &object, const std::vector<manipulation_msgs::Grasp> &grasps);
00355 
00357   bool place(const std::string &object);
00358 
00360   bool place(const std::string &object, const std::vector<manipulation_msgs::PlaceLocation> &locations);
00361 
00363   bool place(const std::string &object, const std::vector<geometry_msgs::PoseStamped> &poses);
00364 
00366   bool place(const std::string &object, const geometry_msgs::PoseStamped &pose);
00367 
00376   std::vector<double> getCurrentJointValues();
00377 
00379   robot_state::RobotStatePtr getCurrentState();
00380 
00383   geometry_msgs::PoseStamped getCurrentPose(const std::string &end_effector_link = "");
00384 
00387   std::vector<double> getCurrentRPY(const std::string &end_effector_link = "");
00388 
00390   std::vector<double> getRandomJointValues();
00391 
00394   geometry_msgs::PoseStamped getRandomPose(const std::string &end_effector_link = "");
00395 
00404   void rememberJointValues(const std::string &name);
00405 
00407   void rememberJointValues(const std::string &name, const std::vector<double> &values);
00408 
00410   const std::map<std::string, std::vector<double> >& getRememberedJointValues() const
00411   {
00412     return remembered_joint_values_;
00413   }
00414 
00416   void forgetJointValues(const std::string &name);
00417 
00426   void setConstraintsDatabase(const std::string &host, unsigned int port);
00427 
00429   std::vector<std::string> getKnownConstraints() const;
00430 
00432   bool setPathConstraints(const std::string &constraint);
00433 
00435   void setPathConstraints(const moveit_msgs::Constraints &constraint);
00436 
00438   void clearPathConstraints();
00439 
00442 private:
00443 
00444   std::map<std::string, std::vector<double> > remembered_joint_values_;
00445   class MoveGroupImpl;
00446   MoveGroupImpl *impl_;
00447 
00448 };
00449 
00450 }
00451 }
00452 // for backward compatibility; remove in hydro
00453 namespace move_group_interface=moveit::planning_interface;
00454 
00455 #endif


planning_interface
Author(s): Ioan Sucan
autogenerated on Mon Oct 6 2014 02:33:28