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 
44 #include <moveit_msgs/RobotTrajectory.h>
45 #include <moveit_msgs/RobotState.h>
46 #include <moveit_msgs/PlannerInterfaceDescription.h>
47 #include <moveit_msgs/Constraints.h>
48 #include <moveit_msgs/Grasp.h>
49 #include <moveit_msgs/PlaceLocation.h>
50 #include <moveit_msgs/MotionPlanRequest.h>
51 #include <moveit_msgs/MoveGroupAction.h>
52 #include <geometry_msgs/PoseStamped.h>
54 #include <boost/shared_ptr.hpp>
55 #include <tf/tf.h>
56 
57 namespace moveit
58 {
60 namespace planning_interface
61 {
62 class MoveItErrorCode : public moveit_msgs::MoveItErrorCodes
63 {
64 public:
66  {
67  val = 0;
68  }
69  MoveItErrorCode(int code)
70  {
71  val = code;
72  }
73  MoveItErrorCode(const moveit_msgs::MoveItErrorCodes& code)
74  {
75  val = code.val;
76  }
77  explicit operator bool() const
78  {
79  return val == moveit_msgs::MoveItErrorCodes::SUCCESS;
80  }
81  bool operator==(const int c) const
82  {
83  return val == c;
84  }
85  bool operator!=(const int c) const
86  {
87  return val != c;
88  }
89 };
90 
92 
99 {
100 public:
102  static const std::string ROBOT_DESCRIPTION;
103 
105  struct Options
106  {
107  Options(const std::string& group_name, const std::string& desc = ROBOT_DESCRIPTION,
108  const ros::NodeHandle& node_handle = ros::NodeHandle())
109  : group_name_(group_name), robot_description_(desc), node_handle_(node_handle)
110  {
111  }
112 
114  std::string group_name_;
115 
117  std::string robot_description_;
118 
120  robot_model::RobotModelConstPtr robot_model_;
121 
123  };
124 
126 
128  struct Plan
129  {
131  moveit_msgs::RobotState start_state_;
132 
134  moveit_msgs::RobotTrajectory trajectory_;
135 
138  };
139 
149  MoveGroupInterface(const Options& opt,
151  const ros::WallDuration& wait_for_servers = ros::WallDuration());
153  const ros::Duration& wait_for_servers);
154 
161  MoveGroupInterface(const std::string& group,
163  const ros::WallDuration& wait_for_servers = ros::WallDuration());
165  const ros::Duration& wait_for_servers);
166 
168 
174  MoveGroupInterface(const MoveGroupInterface&) = delete;
175  MoveGroupInterface& operator=(const MoveGroupInterface&) = delete;
176 
178  MoveGroupInterface& operator=(MoveGroupInterface&& other);
179 
181  const std::string& getName() const;
182 
185  const std::vector<std::string> getNamedTargets();
186 
188  robot_model::RobotModelConstPtr getRobotModel() const;
189 
191  const ros::NodeHandle& getNodeHandle() const;
192 
194  const std::string& getPlanningFrame() const;
195 
197  const std::vector<std::string>& getJointNames();
198 
200  const std::vector<std::string>& getLinkNames();
201 
203  std::map<std::string, double> getNamedTargetValues(const std::string& name);
204 
206  const std::vector<std::string>& getActiveJoints() const;
207 
209  const std::vector<std::string>& getJoints() const;
210 
213  unsigned int getVariableCount() const;
214 
216  bool getInterfaceDescription(moveit_msgs::PlannerInterfaceDescription& desc);
217 
219  std::map<std::string, std::string> getPlannerParams(const std::string& planner_id, const std::string& group = "");
220 
222  void setPlannerParams(const std::string& planner_id, const std::string& group,
223  const std::map<std::string, std::string>& params, bool bReplace = false);
224 
226  std::string getDefaultPlannerId(const std::string& group = "") const;
227 
229  void setPlannerId(const std::string& planner_id);
230 
232  const std::string& getPlannerId() const;
233 
235  void setPlanningTime(double seconds);
236 
239  void setNumPlanningAttempts(unsigned int num_planning_attempts);
240 
246  void setMaxVelocityScalingFactor(double max_velocity_scaling_factor);
247 
253  void setMaxAccelerationScalingFactor(double max_acceleration_scaling_factor);
254 
256  double getPlanningTime() const;
257 
260  double getGoalJointTolerance() const;
261 
264  double getGoalPositionTolerance() const;
265 
268  double getGoalOrientationTolerance() const;
269 
276  void setGoalTolerance(double tolerance);
277 
280  void setGoalJointTolerance(double tolerance);
281 
283  void setGoalPositionTolerance(double tolerance);
284 
286  void setGoalOrientationTolerance(double tolerance);
287 
292  void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz);
293 
296  void setStartState(const moveit_msgs::RobotState& start_state);
297 
300  void setStartState(const robot_state::RobotState& start_state);
301 
303  void setStartStateToCurrentState();
304 
307  void setSupportSurfaceName(const std::string& name);
308 
339  bool setJointValueTarget(const std::vector<double>& group_variable_values);
340 
356  bool setJointValueTarget(const std::map<std::string, double>& variable_values);
357 
367  bool setJointValueTarget(const robot_state::RobotState& robot_state);
368 
380  bool setJointValueTarget(const std::string& joint_name, const std::vector<double>& values);
381 
393  bool setJointValueTarget(const std::string& joint_name, double value);
394 
405  bool setJointValueTarget(const sensor_msgs::JointState& state);
406 
418  bool setJointValueTarget(const geometry_msgs::Pose& eef_pose, const std::string& end_effector_link = "");
419 
431  bool setJointValueTarget(const geometry_msgs::PoseStamped& eef_pose, const std::string& end_effector_link = "");
432 
444  bool setJointValueTarget(const Eigen::Affine3d& eef_pose, const std::string& end_effector_link = "");
445 
456  bool setApproximateJointValueTarget(const geometry_msgs::Pose& eef_pose, const std::string& end_effector_link = "");
457 
468  bool setApproximateJointValueTarget(const geometry_msgs::PoseStamped& eef_pose,
469  const std::string& end_effector_link = "");
470 
481  bool setApproximateJointValueTarget(const Eigen::Affine3d& eef_pose, const std::string& end_effector_link = "");
482 
487  void setRandomTarget();
488 
491  bool setNamedTarget(const std::string& name);
492 
494  const robot_state::RobotState& getJointValueTarget() const;
495 
517  bool setPositionTarget(double x, double y, double z, const std::string& end_effector_link = "");
518 
526  bool setRPYTarget(double roll, double pitch, double yaw, const std::string& end_effector_link = "");
527 
536  bool setOrientationTarget(double x, double y, double z, double w, const std::string& end_effector_link = "");
537 
545  bool setPoseTarget(const Eigen::Affine3d& end_effector_pose, const std::string& end_effector_link = "");
546 
554  bool setPoseTarget(const geometry_msgs::Pose& target, const std::string& end_effector_link = "");
555 
563  bool setPoseTarget(const geometry_msgs::PoseStamped& target, const std::string& end_effector_link = "");
564 
583  bool setPoseTargets(const EigenSTL::vector_Affine3d& end_effector_pose, const std::string& end_effector_link = "");
584 
603  bool setPoseTargets(const std::vector<geometry_msgs::Pose>& target, const std::string& end_effector_link = "");
604 
623  bool setPoseTargets(const std::vector<geometry_msgs::PoseStamped>& target, const std::string& end_effector_link = "");
624 
626  void setPoseReferenceFrame(const std::string& pose_reference_frame);
627 
631  bool setEndEffectorLink(const std::string& end_effector_link);
632 
635  bool setEndEffector(const std::string& eef_name);
636 
638  void clearPoseTarget(const std::string& end_effector_link = "");
639 
641  void clearPoseTargets();
642 
649  const geometry_msgs::PoseStamped& getPoseTarget(const std::string& end_effector_link = "") const;
650 
656  const std::vector<geometry_msgs::PoseStamped>& getPoseTargets(const std::string& end_effector_link = "") const;
657 
663  const std::string& getEndEffectorLink() const;
664 
670  const std::string& getEndEffector() const;
671 
674  const std::string& getPoseReferenceFrame() const;
675 
686  MoveItErrorCode asyncMove();
687 
692 
697  MoveItErrorCode move();
698 
702  MoveItErrorCode plan(Plan& plan);
703 
705  MoveItErrorCode asyncExecute(const Plan& plan);
706 
708  MoveItErrorCode execute(const Plan& plan);
709 
719  double computeCartesianPath(const std::vector<geometry_msgs::Pose>& waypoints, double eef_step, double jump_threshold,
720  moveit_msgs::RobotTrajectory& trajectory, bool avoid_collisions = true,
721  moveit_msgs::MoveItErrorCodes* error_code = NULL);
722 
735  double computeCartesianPath(const std::vector<geometry_msgs::Pose>& waypoints, double eef_step, double jump_threshold,
736  moveit_msgs::RobotTrajectory& trajectory,
737  const moveit_msgs::Constraints& path_constraints, bool avoid_collisions = true,
738  moveit_msgs::MoveItErrorCodes* error_code = NULL);
739 
741  void stop();
742 
745  void allowLooking(bool flag);
746 
748  void allowReplanning(bool flag);
749 
752  void constructMotionPlanRequest(moveit_msgs::MotionPlanRequest& request);
753 
764  MoveItErrorCode pick(const std::string& object, bool plan_only = false);
765 
767  MoveItErrorCode pick(const std::string& object, const moveit_msgs::Grasp& grasp, bool plan_only = false);
768 
772  MoveItErrorCode pick(const std::string& object, const std::vector<moveit_msgs::Grasp>& grasps,
773  bool plan_only = false);
774 
778  MoveItErrorCode planGraspsAndPick(const std::string& object = "", bool plan_only = false);
779 
783  MoveItErrorCode planGraspsAndPick(const moveit_msgs::CollisionObject& object, bool plan_only = false);
784 
786  MoveItErrorCode place(const std::string& object, bool plan_only = false);
787 
789  MoveItErrorCode place(const std::string& object, const std::vector<moveit_msgs::PlaceLocation>& locations,
790  bool plan_only = false);
791 
793  MoveItErrorCode place(const std::string& object, const std::vector<geometry_msgs::PoseStamped>& poses,
794  bool plan_only = false);
795 
797  MoveItErrorCode place(const std::string& object, const geometry_msgs::PoseStamped& pose, bool plan_only = false);
798 
805  bool attachObject(const std::string& object, const std::string& link = "");
806 
815  bool attachObject(const std::string& object, const std::string& link, const std::vector<std::string>& touch_links);
816 
822  bool detachObject(const std::string& name = "");
823 
836  bool startStateMonitor(double wait = 1.0);
837 
839  std::vector<double> getCurrentJointValues();
840 
842  robot_state::RobotStatePtr getCurrentState(double wait = 1);
843 
847  geometry_msgs::PoseStamped getCurrentPose(const std::string& end_effector_link = "");
848 
852  std::vector<double> getCurrentRPY(const std::string& end_effector_link = "");
853 
855  std::vector<double> getRandomJointValues();
856 
860  geometry_msgs::PoseStamped getRandomPose(const std::string& end_effector_link = "");
861 
873  void rememberJointValues(const std::string& name);
874 
879  void rememberJointValues(const std::string& name, const std::vector<double>& values);
880 
882  const std::map<std::string, std::vector<double> >& getRememberedJointValues() const
883  {
884  return remembered_joint_values_;
885  }
886 
888  void forgetJointValues(const std::string& name);
889 
898  void setConstraintsDatabase(const std::string& host, unsigned int port);
899 
901  std::vector<std::string> getKnownConstraints() const;
902 
906  moveit_msgs::Constraints getPathConstraints() const;
907 
911  bool setPathConstraints(const std::string& constraint);
912 
916  void setPathConstraints(const moveit_msgs::Constraints& constraint);
917 
920  void clearPathConstraints();
921 
922  moveit_msgs::TrajectoryConstraints getTrajectoryConstraints() const;
923  void setTrajectoryConstraints(const moveit_msgs::TrajectoryConstraints& constraint);
924  void clearTrajectoryConstraints();
925 
928 private:
929  std::map<std::string, std::vector<double> > remembered_joint_values_;
932 };
933 }
934 }
935 
936 #endif
MoveItErrorCode(const moveit_msgs::MoveItErrorCodes &code)
const std::map< std::string, std::vector< double > > & getRememberedJointValues() const
Get the currently remembered map of names to joint values.
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;.
desc
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
moveit::planning_interface::MoveGroup MOVEIT_DEPRECATED
void attachObject(void)
Definition: demo.cpp:104
std::map< std::string, std::vector< double > > remembered_joint_values_
std::string getName(void *handle)
name
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)
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.
std::string group_name_
The group to construct the class instance for.
double planning_time_
The amount of time it took to generate the plan.
The representation of a motion plan (as ROS messasges)
MOVEIT_CLASS_FORWARD(MoveGroupInterface)


planning_interface
Author(s): Ioan Sucan
autogenerated on Sun Oct 18 2020 13:18:50