move_group_interface.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014, SRI International
5  * Copyright (c) 2012, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Ioan Sucan, Sachin Chitta */
37 
38 #ifndef MOVEIT_MOVE_GROUP_INTERFACE_MOVE_GROUP_INTERFACE_
39 #define MOVEIT_MOVE_GROUP_INTERFACE_MOVE_GROUP_INTERFACE_
40 
43 #include <moveit_msgs/RobotTrajectory.h>
44 #include <moveit_msgs/RobotState.h>
45 #include <moveit_msgs/PlannerInterfaceDescription.h>
46 #include <moveit_msgs/Constraints.h>
47 #include <moveit_msgs/Grasp.h>
48 #include <moveit_msgs/PlaceLocation.h>
49 #include <moveit_msgs/PickupGoal.h>
50 #include <moveit_msgs/PlaceGoal.h>
51 #include <moveit_msgs/MotionPlanRequest.h>
52 #include <moveit_msgs/MoveGroupAction.h>
53 #include <geometry_msgs/PoseStamped.h>
55 #include <memory>
56 #include <tf2_ros/buffer.h>
57 
58 namespace moveit
59 {
61 namespace planning_interface
62 {
63 class MoveItErrorCode : public moveit_msgs::MoveItErrorCodes
64 {
65 public:
67  {
68  val = 0;
69  }
70  MoveItErrorCode(int code)
71  {
72  val = code;
73  }
74  MoveItErrorCode(const moveit_msgs::MoveItErrorCodes& code)
75  {
76  val = code.val;
77  }
78  explicit operator bool() const
79  {
80  return val == moveit_msgs::MoveItErrorCodes::SUCCESS;
81  }
82  bool operator==(const int c) const
83  {
84  return val == c;
85  }
86  bool operator!=(const int c) const
87  {
88  return val != c;
89  }
90 };
91 
92 MOVEIT_CLASS_FORWARD(MoveGroupInterface); // Defines MoveGroupInterfacePtr, ConstPtr, WeakPtr... etc
93 
100 {
101 public:
103  static const std::string ROBOT_DESCRIPTION;
104 
106  struct Options
107  {
108  Options(const std::string& group_name, const std::string& desc = ROBOT_DESCRIPTION,
109  const ros::NodeHandle& node_handle = ros::NodeHandle())
110  : group_name_(group_name), robot_description_(desc), node_handle_(node_handle)
111  {
112  }
113 
115  std::string group_name_;
116 
118  std::string robot_description_;
119 
121  robot_model::RobotModelConstPtr robot_model_;
122 
124  };
125 
127 
129  struct Plan
130  {
132  moveit_msgs::RobotState start_state_;
133 
135  moveit_msgs::RobotTrajectory trajectory_;
136 
139  };
140 
151  MoveGroupInterface(const Options& opt,
152  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>(),
153  const ros::WallDuration& wait_for_servers = ros::WallDuration());
154  [[deprecated]] MoveGroupInterface(const Options& opt, const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
155  const ros::Duration& wait_for_servers);
156 
164  MoveGroupInterface(const std::string& group,
165  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>(),
166  const ros::WallDuration& wait_for_servers = ros::WallDuration());
167  [[deprecated]] MoveGroupInterface(const std::string& group, const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
168  const ros::Duration& wait_for_servers);
169 
171 
177  MoveGroupInterface(const MoveGroupInterface&) = delete;
178  MoveGroupInterface& operator=(const MoveGroupInterface&) = delete;
179 
181  MoveGroupInterface& operator=(MoveGroupInterface&& other);
182 
184  const std::string& getName() const;
185 
188  const std::vector<std::string> getNamedTargets();
189 
191  robot_model::RobotModelConstPtr getRobotModel() const;
192 
194  const ros::NodeHandle& getNodeHandle() const;
195 
197  const std::string& getPlanningFrame() const;
198 
200  const std::vector<std::string>& getJointModelGroupNames() const;
201 
203  const std::vector<std::string>& getJointNames();
204 
206  const std::vector<std::string>& getLinkNames();
207 
209  std::map<std::string, double> getNamedTargetValues(const std::string& name);
210 
212  const std::vector<std::string>& getActiveJoints() const;
213 
215  const std::vector<std::string>& getJoints() const;
216 
219  unsigned int getVariableCount() const;
220 
222  bool getInterfaceDescription(moveit_msgs::PlannerInterfaceDescription& desc);
223 
225  std::map<std::string, std::string> getPlannerParams(const std::string& planner_id, const std::string& group = "");
226 
228  void setPlannerParams(const std::string& planner_id, const std::string& group,
229  const std::map<std::string, std::string>& params, bool bReplace = false);
230 
231  std::string getDefaultPlanningPipelineId() const;
232 
234  void setPlanningPipelineId(const std::string& pipeline_id);
235 
237  const std::string& getPlanningPipelineId() const;
238 
240  std::string getDefaultPlannerId(const std::string& group = "") const;
241 
243  void setPlannerId(const std::string& planner_id);
244 
246  const std::string& getPlannerId() const;
247 
249  void setPlanningTime(double seconds);
250 
253  void setNumPlanningAttempts(unsigned int num_planning_attempts);
254 
260  void setMaxVelocityScalingFactor(double max_velocity_scaling_factor);
261 
267  void setMaxAccelerationScalingFactor(double max_acceleration_scaling_factor);
268 
270  double getPlanningTime() const;
271 
274  double getGoalJointTolerance() const;
275 
278  double getGoalPositionTolerance() const;
279 
282  double getGoalOrientationTolerance() const;
283 
290  void setGoalTolerance(double tolerance);
291 
294  void setGoalJointTolerance(double tolerance);
295 
297  void setGoalPositionTolerance(double tolerance);
298 
300  void setGoalOrientationTolerance(double tolerance);
301 
306  void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz);
307 
310  void setStartState(const moveit_msgs::RobotState& start_state);
311 
314  void setStartState(const robot_state::RobotState& start_state);
315 
317  void setStartStateToCurrentState();
318 
321  void setSupportSurfaceName(const std::string& name);
322 
353  bool setJointValueTarget(const std::vector<double>& group_variable_values);
354 
370  bool setJointValueTarget(const std::map<std::string, double>& variable_values);
371 
381  bool setJointValueTarget(const robot_state::RobotState& robot_state);
382 
394  bool setJointValueTarget(const std::string& joint_name, const std::vector<double>& values);
395 
407  bool setJointValueTarget(const std::string& joint_name, double value);
408 
419  bool setJointValueTarget(const sensor_msgs::JointState& state);
420 
432  bool setJointValueTarget(const geometry_msgs::Pose& eef_pose, const std::string& end_effector_link = "");
433 
445  bool setJointValueTarget(const geometry_msgs::PoseStamped& eef_pose, const std::string& end_effector_link = "");
446 
458  bool setJointValueTarget(const Eigen::Isometry3d& eef_pose, const std::string& end_effector_link = "");
459 
470  bool setApproximateJointValueTarget(const geometry_msgs::Pose& eef_pose, const std::string& end_effector_link = "");
471 
482  bool setApproximateJointValueTarget(const geometry_msgs::PoseStamped& eef_pose,
483  const std::string& end_effector_link = "");
484 
495  bool setApproximateJointValueTarget(const Eigen::Isometry3d& eef_pose, const std::string& end_effector_link = "");
496 
501  void setRandomTarget();
502 
505  bool setNamedTarget(const std::string& name);
506 
508  const robot_state::RobotState& getJointValueTarget() const;
509 
531  bool setPositionTarget(double x, double y, double z, const std::string& end_effector_link = "");
532 
540  bool setRPYTarget(double roll, double pitch, double yaw, const std::string& end_effector_link = "");
541 
550  bool setOrientationTarget(double x, double y, double z, double w, const std::string& end_effector_link = "");
551 
559  bool setPoseTarget(const Eigen::Isometry3d& end_effector_pose, const std::string& end_effector_link = "");
560 
568  bool setPoseTarget(const geometry_msgs::Pose& target, const std::string& end_effector_link = "");
569 
577  bool setPoseTarget(const geometry_msgs::PoseStamped& target, const std::string& end_effector_link = "");
578 
597  bool setPoseTargets(const EigenSTL::vector_Isometry3d& end_effector_pose, const std::string& end_effector_link = "");
598 
617  bool setPoseTargets(const std::vector<geometry_msgs::Pose>& target, const std::string& end_effector_link = "");
618 
637  bool setPoseTargets(const std::vector<geometry_msgs::PoseStamped>& target, const std::string& end_effector_link = "");
638 
640  void setPoseReferenceFrame(const std::string& pose_reference_frame);
641 
645  bool setEndEffectorLink(const std::string& end_effector_link);
646 
649  bool setEndEffector(const std::string& eef_name);
650 
652  void clearPoseTarget(const std::string& end_effector_link = "");
653 
655  void clearPoseTargets();
656 
663  const geometry_msgs::PoseStamped& getPoseTarget(const std::string& end_effector_link = "") const;
664 
670  const std::vector<geometry_msgs::PoseStamped>& getPoseTargets(const std::string& end_effector_link = "") const;
671 
677  const std::string& getEndEffectorLink() const;
678 
684  const std::string& getEndEffector() const;
685 
688  const std::string& getPoseReferenceFrame() const;
689 
700  MoveItErrorCode asyncMove();
701 
706 
711  MoveItErrorCode move();
712 
716  MoveItErrorCode plan(Plan& plan);
717 
719  MoveItErrorCode asyncExecute(const Plan& plan);
720 
722  MoveItErrorCode asyncExecute(const moveit_msgs::RobotTrajectory& trajectory);
723 
725  MoveItErrorCode execute(const Plan& plan);
726 
728  MoveItErrorCode execute(const moveit_msgs::RobotTrajectory& trajectory);
729 
739  double computeCartesianPath(const std::vector<geometry_msgs::Pose>& waypoints, double eef_step, double jump_threshold,
740  moveit_msgs::RobotTrajectory& trajectory, bool avoid_collisions = true,
741  moveit_msgs::MoveItErrorCodes* error_code = NULL);
742 
755  double computeCartesianPath(const std::vector<geometry_msgs::Pose>& waypoints, double eef_step, double jump_threshold,
756  moveit_msgs::RobotTrajectory& trajectory,
757  const moveit_msgs::Constraints& path_constraints, bool avoid_collisions = true,
758  moveit_msgs::MoveItErrorCodes* error_code = NULL);
759 
761  void stop();
762 
765  void allowLooking(bool flag);
766 
768  void allowReplanning(bool flag);
769 
772  void constructMotionPlanRequest(moveit_msgs::MotionPlanRequest& request);
773 
775  moveit_msgs::PickupGoal constructPickupGoal(const std::string& object, std::vector<moveit_msgs::Grasp> grasps,
776  bool plan_only);
777 
779  moveit_msgs::PlaceGoal constructPlaceGoal(const std::string& object,
780  std::vector<moveit_msgs::PlaceLocation> locations, bool plan_only);
781 
783  std::vector<moveit_msgs::PlaceLocation> posesToPlaceLocations(const std::vector<geometry_msgs::PoseStamped>& poses);
784 
795  MoveItErrorCode pick(const std::string& object, bool plan_only = false)
796  {
797  return pick(constructPickupGoal(object, std::vector<moveit_msgs::Grasp>(), plan_only));
798  }
799 
801  MoveItErrorCode pick(const std::string& object, const moveit_msgs::Grasp& grasp, bool plan_only = false)
802  {
803  return pick(constructPickupGoal(object, { grasp }, plan_only));
804  }
805 
807  MoveItErrorCode pick(const std::string& object, std::vector<moveit_msgs::Grasp> grasps, bool plan_only = false)
808  {
809  return pick(constructPickupGoal(object, std::move(grasps), plan_only));
810  }
811 
816  MoveItErrorCode pick(const moveit_msgs::PickupGoal& goal);
817 
821  MoveItErrorCode planGraspsAndPick(const std::string& object = "", bool plan_only = false);
822 
826  MoveItErrorCode planGraspsAndPick(const moveit_msgs::CollisionObject& object, bool plan_only = false);
827 
829  MoveItErrorCode place(const std::string& object, bool plan_only = false)
830  {
831  return place(constructPlaceGoal(object, std::vector<moveit_msgs::PlaceLocation>(), plan_only));
832  }
833 
835  MoveItErrorCode place(const std::string& object, std::vector<moveit_msgs::PlaceLocation> locations,
836  bool plan_only = false)
837  {
838  return place(constructPlaceGoal(object, std::move(locations), plan_only));
839  }
840 
842  MoveItErrorCode place(const std::string& object, const std::vector<geometry_msgs::PoseStamped>& poses,
843  bool plan_only = false)
844  {
845  return place(constructPlaceGoal(object, posesToPlaceLocations(poses), plan_only));
846  }
847 
849  MoveItErrorCode place(const std::string& object, const geometry_msgs::PoseStamped& pose, bool plan_only = false)
850  {
851  return place(constructPlaceGoal(object, posesToPlaceLocations({ pose }), plan_only));
852  }
853 
858  MoveItErrorCode place(const moveit_msgs::PlaceGoal& goal);
859 
866  bool attachObject(const std::string& object, const std::string& link = "");
867 
876  bool attachObject(const std::string& object, const std::string& link, const std::vector<std::string>& touch_links);
877 
883  bool detachObject(const std::string& name = "");
884 
897  bool startStateMonitor(double wait = 1.0);
898 
900  std::vector<double> getCurrentJointValues();
901 
903  robot_state::RobotStatePtr getCurrentState(double wait = 1);
904 
908  geometry_msgs::PoseStamped getCurrentPose(const std::string& end_effector_link = "");
909 
913  std::vector<double> getCurrentRPY(const std::string& end_effector_link = "");
914 
916  std::vector<double> getRandomJointValues();
917 
921  geometry_msgs::PoseStamped getRandomPose(const std::string& end_effector_link = "");
922 
934  void rememberJointValues(const std::string& name);
935 
940  void rememberJointValues(const std::string& name, const std::vector<double>& values);
941 
943  const std::map<std::string, std::vector<double> >& getRememberedJointValues() const
944  {
945  return remembered_joint_values_;
946  }
947 
949  void forgetJointValues(const std::string& name);
950 
959  void setConstraintsDatabase(const std::string& host, unsigned int port);
960 
962  std::vector<std::string> getKnownConstraints() const;
963 
967  moveit_msgs::Constraints getPathConstraints() const;
968 
972  bool setPathConstraints(const std::string& constraint);
973 
977  void setPathConstraints(const moveit_msgs::Constraints& constraint);
978 
981  void clearPathConstraints();
982 
983  moveit_msgs::TrajectoryConstraints getTrajectoryConstraints() const;
984  void setTrajectoryConstraints(const moveit_msgs::TrajectoryConstraints& constraint);
985  void clearTrajectoryConstraints();
986 
989 private:
990  std::map<std::string, std::vector<double> > remembered_joint_values_;
993 };
994 } // namespace planning_interface
995 } // namespace moveit
996 
997 #endif
MoveItErrorCode(const moveit_msgs::MoveItErrorCodes &code)
MoveItErrorCode place(const std::string &object, std::vector< moveit_msgs::PlaceLocation > locations, bool plan_only=false)
Place an object at one of the specified possible locations.
moveit_msgs::RobotTrajectory trajectory_
The trajectory of the robot (may not contain joints that are the same as for the start_state_) ...
static const std::string ROBOT_DESCRIPTION
Default ROS parameter name from where to read the robot&#39;s URDF. Set to &#39;robot_description&#39;.
MoveItErrorCode place(const std::string &object, bool plan_only=false)
Place an object somewhere safe in the world (a safe location will be detected)
std::vector< double > values
std::map< std::string, std::vector< double > > remembered_joint_values_
void wait(int seconds)
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
name
MoveItErrorCode place(const std::string &object, const geometry_msgs::PoseStamped &pose, bool plan_only=false)
Place an object at one of the specified possible location.
Eigen::Isometry3d getRandomPose(random_numbers::RandomNumberGenerator &g)
MoveItErrorCode place(const std::string &object, const std::vector< geometry_msgs::PoseStamped > &poses, bool plan_only=false)
Place an object at one of the specified possible locations.
Specification of options to use when constructing the MoveGroupInterface class.
std::string robot_description_
The robot description parameter name (if different from default)
MOVEIT_STRUCT_FORWARD(CollisionGeometryData)
ROSCPP_DECL bool execute(const std::string &method, const XmlRpc::XmlRpcValue &request, XmlRpc::XmlRpcValue &response, XmlRpc::XmlRpcValue &payload, bool wait_for_master)
void attachObject()
Definition: demo.cpp:104
Options(const std::string &group_name, const std::string &desc=ROBOT_DESCRIPTION, const ros::NodeHandle &node_handle=ros::NodeHandle())
Client class to conveniently use the ROS interfaces provided by the move_group node.
robot_model::RobotModelConstPtr robot_model_
Optionally, an instance of the RobotModel to use can be also specified.
moveit_msgs::RobotState start_state_
The full starting state used for planning.
const std::map< std::string, std::vector< double > > & getRememberedJointValues() const
Get the currently remembered map of names to joint values.
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
MoveItErrorCode pick(const std::string &object, const moveit_msgs::Grasp &grasp, bool plan_only=false)
Pick up an object given a grasp pose.
std::string group_name_
The group to construct the class instance for.
MoveItErrorCode pick(const std::string &object, std::vector< moveit_msgs::Grasp > grasps, bool plan_only=false)
Pick up an object given possible grasp poses.
double planning_time_
The amount of time it took to generate the plan.
The representation of a motion plan (as ROS messasges)
MoveItErrorCode pick(const std::string &object, bool plan_only=false)
Pick up an object.
MOVEIT_CLASS_FORWARD(MoveGroupInterface)


planning_interface
Author(s): Ioan Sucan
autogenerated on Wed May 5 2021 02:54:38