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 #pragma once
39 
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 <utility>
57 #include <tf2_ros/buffer.h>
58 
59 namespace moveit
60 {
62 namespace planning_interface
63 {
64 using MoveItErrorCode [[deprecated("Use moveit::core::MoveItErrorCode")]] = moveit::core::MoveItErrorCode;
65 
66 MOVEIT_CLASS_FORWARD(MoveGroupInterface); // Defines MoveGroupInterfacePtr, ConstPtr, WeakPtr... etc
67 
73 class MoveGroupInterface
74 {
75 public:
78  static constexpr double DEFAULT_GOAL_JOINT_TOLERANCE = 1e-4;
79 
82  static constexpr double DEFAULT_GOAL_POSITION_TOLERANCE = 1e-4;
83 
86  static constexpr double DEFAULT_GOAL_ORIENTATION_TOLERANCE = 1e-3;
87 
89  static constexpr double DEFAULT_ALLOWED_PLANNING_TIME = 5.0;
90 
92  static constexpr int DEFAULT_NUM_PLANNING_ATTEMPTS = 1;
93 
95  static const std::string ROBOT_DESCRIPTION;
96 
98  struct Options
99  {
100  Options(std::string group_name, std::string desc = ROBOT_DESCRIPTION,
101  const ros::NodeHandle& node_handle = ros::NodeHandle())
102  : group_name_(std::move(group_name)), robot_description_(std::move(desc)), node_handle_(node_handle)
103  {
104  }
105 
107  std::string group_name_;
108 
110  std::string robot_description_;
111 
113  moveit::core::RobotModelConstPtr robot_model_;
114 
116  };
117 
118  MOVEIT_STRUCT_FORWARD(Plan);
119 
121  struct Plan
122  {
124  moveit_msgs::RobotState start_state_;
125 
127  moveit_msgs::RobotTrajectory trajectory_;
128 
131  };
132 
143  MoveGroupInterface(const Options& opt,
144  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>(),
145  const ros::WallDuration& wait_for_servers = ros::WallDuration());
146  [[deprecated]] MoveGroupInterface(const Options& opt, const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
147  const ros::Duration& wait_for_servers);
148 
156  MoveGroupInterface(const std::string& group,
157  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer = std::shared_ptr<tf2_ros::Buffer>(),
158  const ros::WallDuration& wait_for_servers = ros::WallDuration());
159  [[deprecated]] MoveGroupInterface(const std::string& group, const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
160  const ros::Duration& wait_for_servers);
161 
163 
169  MoveGroupInterface(const MoveGroupInterface&) = delete;
171 
172  MoveGroupInterface(MoveGroupInterface&& other) noexcept;
175  const std::string& getName() const;
176 
179  const std::vector<std::string>& getNamedTargets() const;
180 
182  moveit::core::RobotModelConstPtr getRobotModel() const;
183 
185  const ros::NodeHandle& getNodeHandle() const;
186 
188  const std::string& getPlanningFrame() const;
189 
191  const std::vector<std::string>& getJointModelGroupNames() const;
192 
194  const std::vector<std::string>& getLinkNames() const;
195 
197  std::map<std::string, double> getNamedTargetValues(const std::string& name) const;
198 
203  const std::vector<std::string>& getJoints() const;
204 
205  [[deprecated("use getVariableNames")]] const std::vector<std::string>& getJointNames() const
206  {
207  return getVariableNames();
208  }
209 
217  const std::vector<std::string>& getVariableNames() const;
218 
226  const std::vector<std::string>& getActiveJoints() const;
227 
230  unsigned int getVariableCount() const;
231 
233  bool getInterfaceDescriptions(std::vector<moveit_msgs::PlannerInterfaceDescription>& desc) const;
234 
236  bool getInterfaceDescription(moveit_msgs::PlannerInterfaceDescription& desc) const;
237 
239  std::map<std::string, std::string> getPlannerParams(const std::string& planner_id,
240  const std::string& group = "") const;
241 
243  void setPlannerParams(const std::string& planner_id, const std::string& group,
244  const std::map<std::string, std::string>& params, bool bReplace = false);
245 
246  std::string getDefaultPlanningPipelineId() const;
247 
249  void setPlanningPipelineId(const std::string& pipeline_id);
250 
252  const std::string& getPlanningPipelineId() const;
253 
255  std::string getDefaultPlannerId(const std::string& group = "") const;
256 
258  void setPlannerId(const std::string& planner_id);
259 
261  const std::string& getPlannerId() const;
262 
264  void setPlanningTime(double seconds);
265 
268  void setNumPlanningAttempts(unsigned int num_planning_attempts);
269 
275  void setMaxVelocityScalingFactor(double max_velocity_scaling_factor);
276 
282  void setMaxAccelerationScalingFactor(double max_acceleration_scaling_factor);
283 
288  void limitMaxCartesianLinkSpeed(const double max_speed, const std::string& link_name = "");
289 
292 
294  double getPlanningTime() const;
295 
298  double getGoalJointTolerance() const;
299 
302  double getGoalPositionTolerance() const;
303 
306  double getGoalOrientationTolerance() const;
307 
314  void setGoalTolerance(double tolerance);
315 
318  void setGoalJointTolerance(double tolerance);
319 
321  void setGoalPositionTolerance(double tolerance);
322 
324  void setGoalOrientationTolerance(double tolerance);
325 
330  void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz);
331 
334  void setStartState(const moveit_msgs::RobotState& start_state);
335 
338  void setStartState(const moveit::core::RobotState& start_state);
339 
342 
345  void setSupportSurfaceName(const std::string& name);
346 
376  bool setJointValueTarget(const std::vector<double>& group_variable_values);
377 
393  bool setJointValueTarget(const std::map<std::string, double>& variable_values);
394 
410  bool setJointValueTarget(const std::vector<std::string>& variable_names, const std::vector<double>& variable_values);
411 
421  bool setJointValueTarget(const moveit::core::RobotState& robot_state);
422 
434  bool setJointValueTarget(const std::string& joint_name, const std::vector<double>& values);
435 
447  bool setJointValueTarget(const std::string& joint_name, double value);
448 
459  bool setJointValueTarget(const sensor_msgs::JointState& state);
460 
472  bool setJointValueTarget(const geometry_msgs::Pose& eef_pose, const std::string& end_effector_link = "");
473 
485  bool setJointValueTarget(const geometry_msgs::PoseStamped& eef_pose, const std::string& end_effector_link = "");
486 
498  bool setJointValueTarget(const Eigen::Isometry3d& eef_pose, const std::string& end_effector_link = "");
499 
510  bool setApproximateJointValueTarget(const geometry_msgs::Pose& eef_pose, const std::string& end_effector_link = "");
511 
522  bool setApproximateJointValueTarget(const geometry_msgs::PoseStamped& eef_pose,
523  const std::string& end_effector_link = "");
524 
535  bool setApproximateJointValueTarget(const Eigen::Isometry3d& eef_pose, const std::string& end_effector_link = "");
536 
541  void setRandomTarget();
542 
545  bool setNamedTarget(const std::string& name);
546 
548  void getJointValueTarget(std::vector<double>& group_variable_values) const;
549 
551  [[deprecated]] const moveit::core::RobotState& getJointValueTarget() const;
552 
574  bool setPositionTarget(double x, double y, double z, const std::string& end_effector_link = "");
575 
583  bool setRPYTarget(double roll, double pitch, double yaw, const std::string& end_effector_link = "");
584 
593  bool setOrientationTarget(double x, double y, double z, double w, const std::string& end_effector_link = "");
594 
602  bool setPoseTarget(const Eigen::Isometry3d& end_effector_pose, const std::string& end_effector_link = "");
603 
611  bool setPoseTarget(const geometry_msgs::Pose& target, const std::string& end_effector_link = "");
612 
620  bool setPoseTarget(const geometry_msgs::PoseStamped& target, const std::string& end_effector_link = "");
621 
640  bool setPoseTargets(const EigenSTL::vector_Isometry3d& end_effector_pose, const std::string& end_effector_link = "");
641 
660  bool setPoseTargets(const std::vector<geometry_msgs::Pose>& target, const std::string& end_effector_link = "");
661 
680  bool setPoseTargets(const std::vector<geometry_msgs::PoseStamped>& target, const std::string& end_effector_link = "");
681 
683  void setPoseReferenceFrame(const std::string& pose_reference_frame);
684 
688  bool setEndEffectorLink(const std::string& end_effector_link);
689 
692  bool setEndEffector(const std::string& eef_name);
693 
695  void clearPoseTarget(const std::string& end_effector_link = "");
696 
698  void clearPoseTargets();
699 
706  const geometry_msgs::PoseStamped& getPoseTarget(const std::string& end_effector_link = "") const;
707 
713  const std::vector<geometry_msgs::PoseStamped>& getPoseTargets(const std::string& end_effector_link = "") const;
714 
720  const std::string& getEndEffectorLink() const;
721 
727  const std::string& getEndEffector() const;
728 
731  const std::string& getPoseReferenceFrame() const;
732 
744 
749 
755 
760 
763 
765  moveit::core::MoveItErrorCode asyncExecute(const moveit_msgs::RobotTrajectory& trajectory);
766 
769 
771  moveit::core::MoveItErrorCode execute(const moveit_msgs::RobotTrajectory& trajectory);
772 
782  double computeCartesianPath(const std::vector<geometry_msgs::Pose>& waypoints, double eef_step, double jump_threshold,
783  moveit_msgs::RobotTrajectory& trajectory, bool avoid_collisions = true,
784  moveit_msgs::MoveItErrorCodes* error_code = nullptr);
785 
798  double computeCartesianPath(const std::vector<geometry_msgs::Pose>& waypoints, double eef_step, double jump_threshold,
799  moveit_msgs::RobotTrajectory& trajectory,
800  const moveit_msgs::Constraints& path_constraints, bool avoid_collisions = true,
801  moveit_msgs::MoveItErrorCodes* error_code = nullptr);
802 
804  void stop();
805 
807  void allowReplanning(bool flag);
808 
810  void setReplanAttempts(int32_t attempts);
811 
813  void setReplanDelay(double delay);
814 
817  void allowLooking(bool flag);
818 
820  void setLookAroundAttempts(int32_t attempts);
821 
824  void constructMotionPlanRequest(moveit_msgs::MotionPlanRequest& request);
825 
827  moveit_msgs::PickupGoal constructPickupGoal(const std::string& object, std::vector<moveit_msgs::Grasp> grasps,
828  bool plan_only) const;
829 
831  moveit_msgs::PlaceGoal constructPlaceGoal(const std::string& object,
832  std::vector<moveit_msgs::PlaceLocation> locations, bool plan_only) const;
833 
835  std::vector<moveit_msgs::PlaceLocation>
836  posesToPlaceLocations(const std::vector<geometry_msgs::PoseStamped>& poses) const;
837 
848  moveit::core::MoveItErrorCode pick(const std::string& object, bool plan_only = false)
849  {
850  return pick(constructPickupGoal(object, std::vector<moveit_msgs::Grasp>(), plan_only));
851  }
852 
854  moveit::core::MoveItErrorCode pick(const std::string& object, const moveit_msgs::Grasp& grasp, bool plan_only = false)
855  {
856  return pick(constructPickupGoal(object, { grasp }, plan_only));
857  }
858 
860  moveit::core::MoveItErrorCode pick(const std::string& object, std::vector<moveit_msgs::Grasp> grasps,
861  bool plan_only = false)
862  {
863  return pick(constructPickupGoal(object, std::move(grasps), plan_only));
864  }
865 
870  moveit::core::MoveItErrorCode pick(const moveit_msgs::PickupGoal& goal);
871 
875  moveit::core::MoveItErrorCode planGraspsAndPick(const std::string& object = "", bool plan_only = false);
876 
880  moveit::core::MoveItErrorCode planGraspsAndPick(const moveit_msgs::CollisionObject& object, bool plan_only = false);
881 
883  moveit::core::MoveItErrorCode place(const std::string& object, bool plan_only = false)
884  {
885  return place(constructPlaceGoal(object, std::vector<moveit_msgs::PlaceLocation>(), plan_only));
886  }
887 
889  moveit::core::MoveItErrorCode place(const std::string& object, std::vector<moveit_msgs::PlaceLocation> locations,
890  bool plan_only = false)
891  {
892  return place(constructPlaceGoal(object, std::move(locations), plan_only));
893  }
894 
896  moveit::core::MoveItErrorCode place(const std::string& object, const std::vector<geometry_msgs::PoseStamped>& poses,
897  bool plan_only = false)
898  {
899  return place(constructPlaceGoal(object, posesToPlaceLocations(poses), plan_only));
900  }
901 
903  moveit::core::MoveItErrorCode place(const std::string& object, const geometry_msgs::PoseStamped& pose,
904  bool plan_only = false)
905  {
906  return place(constructPlaceGoal(object, posesToPlaceLocations({ pose }), plan_only));
907  }
908 
913  moveit::core::MoveItErrorCode place(const moveit_msgs::PlaceGoal& goal);
914 
921  bool attachObject(const std::string& object, const std::string& link = "");
922 
931  bool attachObject(const std::string& object, const std::string& link, const std::vector<std::string>& touch_links);
932 
938  bool detachObject(const std::string& name = "");
939 
952  bool startStateMonitor(double wait = 1.0);
953 
955  std::vector<double> getCurrentJointValues() const;
956 
958  moveit::core::RobotStatePtr getCurrentState(double wait = 1) const;
959 
963  geometry_msgs::PoseStamped getCurrentPose(const std::string& end_effector_link = "") const;
964 
968  std::vector<double> getCurrentRPY(const std::string& end_effector_link = "") const;
969 
971  std::vector<double> getRandomJointValues() const;
972 
976  geometry_msgs::PoseStamped getRandomPose(const std::string& end_effector_link = "") const;
977 
989  void rememberJointValues(const std::string& name);
990 
995  void rememberJointValues(const std::string& name, const std::vector<double>& values);
996 
998  const std::map<std::string, std::vector<double> >& getRememberedJointValues() const
999  {
1000  return remembered_joint_values_;
1001  }
1002 
1004  void forgetJointValues(const std::string& name);
1005 
1014  void setConstraintsDatabase(const std::string& host, unsigned int port);
1015 
1017  std::vector<std::string> getKnownConstraints() const;
1018 
1022  moveit_msgs::Constraints getPathConstraints() const;
1023 
1027  bool setPathConstraints(const std::string& constraint);
1028 
1032  void setPathConstraints(const moveit_msgs::Constraints& constraint);
1033 
1036  void clearPathConstraints();
1037 
1038  moveit_msgs::TrajectoryConstraints getTrajectoryConstraints() const;
1039  void setTrajectoryConstraints(const moveit_msgs::TrajectoryConstraints& constraint);
1041 
1044 protected:
1047 
1048 private:
1049  std::map<std::string, std::vector<double> > remembered_joint_values_;
1050  class MoveGroupInterfaceImpl;
1051  MoveGroupInterfaceImpl* impl_;
1052 };
1053 } // namespace planning_interface
1054 } // namespace moveit
moveit::planning_interface::MoveGroupInterface::getEndEffector
const std::string & getEndEffector() const
Get the current end-effector name. This returns the value set by setEndEffector() (or indirectly by s...
Definition: move_group_interface.cpp:1916
moveit::planning_interface::MoveGroupInterface::setStartState
void setStartState(const moveit_msgs::RobotState &start_state)
If a different start state should be considered instead of the current state of the robot,...
Definition: move_group_interface.cpp:1692
moveit::planning_interface::MoveGroupInterface::getPlannerParams
std::map< std::string, std::string > getPlannerParams(const std::string &planner_id, const std::string &group="") const
Get the planner parameters for given group and planner_id.
Definition: move_group_interface.cpp:1520
moveit::planning_interface::MoveGroupInterface::setPoseTarget
bool setPoseTarget(const Eigen::Isometry3d &end_effector_pose, const std::string &end_effector_link="")
Set the goal pose of the end-effector end_effector_link.
Definition: move_group_interface.cpp:1948
moveit::planning_interface::MoveGroupInterface::setJointValueTarget
bool setJointValueTarget(const std::vector< double > &group_variable_values)
Set the JointValueTarget and use it for future planning requests.
Definition: move_group_interface.cpp:1776
moveit::planning_interface::MoveGroupInterface::getKnownConstraints
std::vector< std::string > getKnownConstraints() const
Get the names of the known constraints as read from the Mongo database, if a connection was achieved.
Definition: move_group_interface.cpp:2348
moveit::planning_interface::MoveGroupInterface::getDefaultPlanningPipelineId
std::string getDefaultPlanningPipelineId() const
Definition: move_group_interface.cpp:1532
moveit::planning_interface::MoveGroupInterface::getTrajectoryConstraints
moveit_msgs::TrajectoryConstraints getTrajectoryConstraints() const
Definition: move_group_interface.cpp:2373
EigenSTL::vector_Isometry3d
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
moveit::planning_interface::MoveGroupInterface::getJoints
const std::vector< std::string > & getJoints() const
Get names of all the joints in this group.
Definition: move_group_interface.cpp:2270
moveit::planning_interface::MoveGroupInterface::getMoveGroupClient
actionlib::SimpleActionClient< moveit_msgs::MoveGroupAction > & getMoveGroupClient() const
Get the move_group action client used by the MoveGroupInterface. The client can be used for querying ...
Definition: move_group_interface.cpp:1592
moveit::planning_interface::MoveGroupInterface::startStateMonitor
bool startStateMonitor(double wait=1.0)
When reasoning about the current state of a robot, a CurrentStateMonitor instance is automatically co...
Definition: move_group_interface.cpp:2168
moveit::planning_interface::MoveGroupInterface::setGoalOrientationTolerance
void setGoalOrientationTolerance(double tolerance)
Set the orientation tolerance that is used for reaching the goal when moving to a pose.
Definition: move_group_interface.cpp:2158
moveit::planning_interface::MoveGroupInterface::setOrientationTarget
bool setOrientationTarget(double x, double y, double z, double w, const std::string &end_effector_link="")
Set the goal orientation of the end-effector end_effector_link to be the quaternion (x,...
Definition: move_group_interface.cpp:2090
moveit::planning_interface::MoveGroupInterface::Plan
The representation of a motion plan (as ROS messasges)
Definition: move_group_interface.h:187
moveit::planning_interface::MoveGroupInterface::setStartStateToCurrentState
void setStartStateToCurrentState()
Set the starting state for planning to be that reported by the robot's joint state publication.
Definition: move_group_interface.cpp:1711
moveit::planning_interface::MoveGroupInterface::getCurrentState
moveit::core::RobotStatePtr getCurrentState(double wait=1) const
Get the current state of the robot within the duration specified by wait.
Definition: move_group_interface.cpp:2280
moveit::planning_interface::MoveGroupInterface
Client class to conveniently use the ROS interfaces provided by the move_group node.
Definition: move_group_interface.h:139
moveit::planning_interface::MoveGroupInterface::allowReplanning
void allowReplanning(bool flag)
Specify whether the robot is allowed to replan if it detects changes in the environment.
Definition: move_group_interface.cpp:2316
moveit::planning_interface::MoveGroupInterface::getVariableCount
unsigned int getVariableCount() const
Get the number of variables used to describe the state of this group. This is larger or equal to the ...
Definition: move_group_interface.cpp:2275
moveit::planning_interface::MoveGroupInterface::ROBOT_DESCRIPTION
static const std::string ROBOT_DESCRIPTION
Default ROS parameter name from where to read the robot's URDF. Set to 'robot_description'.
Definition: move_group_interface.h:161
moveit::planning_interface::MoveGroupInterface::asyncExecute
moveit::core::MoveItErrorCode asyncExecute(const Plan &plan)
Given a plan, execute it without waiting for completion.
Definition: move_group_interface.cpp:1602
moveit::planning_interface::MoveGroupInterface::forgetJointValues
void forgetJointValues(const std::string &name)
Forget the joint values remembered under name.
Definition: move_group_interface.cpp:2292
moveit::planning_interface::MoveGroupInterface::getPlanningFrame
const std::string & getPlanningFrame() const
Get the name of the frame in which the robot is planning.
Definition: move_group_interface.cpp:2415
moveit::planning_interface::MoveGroupInterface::setLookAroundAttempts
void setLookAroundAttempts(int32_t attempts)
How often is the system allowed to move the camera to update environment model when looking.
Definition: move_group_interface.cpp:2303
moveit::planning_interface::MoveGroupInterface::setPlannerId
void setPlannerId(const std::string &planner_id)
Specify a planner to be used for further planning.
Definition: move_group_interface.cpp:1552
moveit::planning_interface::MoveGroupInterface::setGoalJointTolerance
void setGoalJointTolerance(double tolerance)
Set the joint tolerance (for each joint) that is used for reaching the goal when moving to a joint va...
Definition: move_group_interface.cpp:2148
moveit::planning_interface::MoveGroupInterface::getCurrentRPY
std::vector< double > getCurrentRPY(const std::string &end_effector_link="") const
Get the roll-pitch-yaw (XYZ) for the end-effector end_effector_link. If end_effector_link is empty (t...
Definition: move_group_interface.cpp:2238
moveit::planning_interface::MoveGroupInterface::getJointModelGroupNames
const std::vector< std::string > & getJointModelGroupNames() const
Get the available planning group names.
Definition: move_group_interface.cpp:2420
buffer.h
moveit::planning_interface::MoveGroupInterface::setReplanDelay
void setReplanDelay(double delay)
Sleep this duration between replanning attempts (in walltime seconds)
Definition: move_group_interface.cpp:2335
moveit::planning_interface::MoveGroupInterface::asyncMove
moveit::core::MoveItErrorCode asyncMove()
Plan and execute a trajectory that takes the group of joints declared in the constructor to the speci...
Definition: move_group_interface.cpp:1587
moveit::core::RobotState
moveit::planning_interface::MoveGroupInterface::setRandomTarget
void setRandomTarget()
Set the joint state goal to a random joint configuration.
Definition: move_group_interface.cpp:1716
robot_state.h
moveit::planning_interface::MoveGroupInterface::getCurrentJointValues
std::vector< double > getCurrentJointValues() const
Get the current joint values for the joints planned for by this instance (see getJoints())
Definition: move_group_interface.cpp:2173
moveit::planning_interface::MoveGroupInterface::setPlanningTime
void setPlanningTime(double seconds)
Specify the maximum amount of time to use when planning.
Definition: move_group_interface.cpp:2399
moveit::planning_interface::MoveGroupInterface::clearPathConstraints
void clearPathConstraints()
Specify that no path constraints are to be used. This removes any path constraints set in previous ca...
Definition: move_group_interface.cpp:2368
moveit::planning_interface::MoveGroupInterface::getEndEffectorLink
const std::string & getEndEffectorLink() const
Get the current end-effector link. This returns the value set by setEndEffectorLink() (or indirectly ...
Definition: move_group_interface.cpp:1911
moveit::planning_interface::MoveGroupInterface::planGraspsAndPick
moveit::core::MoveItErrorCode planGraspsAndPick(const std::string &object="", bool plan_only=false)
Pick up an object.
Definition: move_group_interface.cpp:1652
moveit::planning_interface::MoveGroupInterface::clearPoseTargets
void clearPoseTargets()
Forget any poses specified for all end-effectors.
Definition: move_group_interface.cpp:1943
moveit::planning_interface::MoveGroupInterface::DEFAULT_GOAL_POSITION_TOLERANCE
static constexpr double DEFAULT_GOAL_POSITION_TOLERANCE
Default goal position tolerance (0.1mm) if not specified with {robot description name}_kinematics/{jo...
Definition: move_group_interface.h:148
moveit::planning_interface::MoveGroupInterface::getPoseTargets
const std::vector< geometry_msgs::PoseStamped > & getPoseTargets(const std::string &end_effector_link="") const
Definition: move_group_interface.cpp:2022
moveit::planning_interface::MoveGroupInterface::move
moveit::core::MoveItErrorCode move()
Plan and execute a trajectory that takes the group of joints declared in the constructor to the speci...
Definition: move_group_interface.cpp:1597
moveit::planning_interface::MoveGroupInterface::getTargetRobotState
const moveit::core::RobotState & getTargetRobotState() const
Definition: move_group_interface.cpp:1906
moveit::planning_interface::MoveGroupInterface::rememberJointValues
void rememberJointValues(const std::string &name)
Remember the current joint values (of the robot being monitored) under name. These can be used by set...
Definition: move_group_interface.cpp:2163
moveit::planning_interface::MoveGroupInterface::DEFAULT_GOAL_ORIENTATION_TOLERANCE
static constexpr double DEFAULT_GOAL_ORIENTATION_TOLERANCE
Default goal orientation tolerance (~0.1deg) if not specified with {robot description name}_kinematic...
Definition: move_group_interface.h:152
moveit::planning_interface::MoveGroupInterface::setPlannerParams
void setPlannerParams(const std::string &planner_id, const std::string &group, const std::map< std::string, std::string > &params, bool bReplace=false)
Set the planner parameters for given group and planner_id.
Definition: move_group_interface.cpp:1526
moveit::planning_interface::MoveGroupInterface::Options
Specification of options to use when constructing the MoveGroupInterface class.
Definition: move_group_interface.h:164
moveit::planning_interface::MoveGroupInterface::MOVEIT_STRUCT_FORWARD
MOVEIT_STRUCT_FORWARD(Plan)
moveit::planning_interface::MoveGroupInterface::setGoalPositionTolerance
void setGoalPositionTolerance(double tolerance)
Set the position tolerance that is used for reaching the goal when moving to a pose.
Definition: move_group_interface.cpp:2153
moveit::planning_interface::MoveGroupInterface::remembered_joint_values_
std::map< std::string, std::vector< double > > remembered_joint_values_
Definition: move_group_interface.h:1115
moveit::planning_interface::MoveGroupInterface::limitMaxCartesianLinkSpeed
void limitMaxCartesianLinkSpeed(const double max_speed, const std::string &link_name="")
Limit the maximum Cartesian speed for a given link. The unit of the speed is meter per second and mus...
Definition: move_group_interface.cpp:1577
moveit::planning_interface::MoveGroupInterface::Options::Options
Options(std::string group_name, std::string desc=ROBOT_DESCRIPTION, const ros::NodeHandle &node_handle=ros::NodeHandle())
Definition: move_group_interface.h:166
moveit::planning_interface::MoveGroupInterface::computeCartesianPath
double computeCartesianPath(const std::vector< geometry_msgs::Pose > &waypoints, double eef_step, double jump_threshold, moveit_msgs::RobotTrajectory &trajectory, bool avoid_collisions=true, moveit_msgs::MoveItErrorCodes *error_code=nullptr)
Compute a Cartesian path that follows specified waypoints with a step size of at most eef_step meters...
Definition: move_group_interface.cpp:1668
moveit::planning_interface::MoveGroupInterface::allowLooking
void allowLooking(bool flag)
Specify whether the robot is allowed to look around before moving if it determines it should (default...
Definition: move_group_interface.cpp:2297
moveit::planning_interface::MoveGroupInterface::setReplanAttempts
void setReplanAttempts(int32_t attempts)
Maximum number of replanning attempts.
Definition: move_group_interface.cpp:2322
moveit::planning_interface::MoveGroupInterface::getDefaultPlannerId
std::string getDefaultPlannerId(const std::string &group="") const
Get the default planner of the current planning pipeline for the given group (or the pipeline's defau...
Definition: move_group_interface.cpp:1547
moveit::planning_interface::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(MoveGroupInterface)
actionlib::SimpleActionClient
moveit::planning_interface::MoveGroupInterface::getPoseReferenceFrame
const std::string & getPoseReferenceFrame() const
Get the reference frame set by setPoseReferenceFrame(). By default this is the reference frame of the...
Definition: move_group_interface.cpp:2121
moveit::planning_interface::MoveGroupInterface::setConstraintsDatabase
void setConstraintsDatabase(const std::string &host, unsigned int port)
Specify where the database server that holds known constraints resides.
Definition: move_group_interface.cpp:2388
moveit::planning_interface::MoveGroupInterface::setPoseReferenceFrame
void setPoseReferenceFrame(const std::string &pose_reference_frame)
Specify which reference frame to assume for poses specified without a reference frame.
Definition: move_group_interface.cpp:2116
moveit::planning_interface::MoveGroupInterface::getRobotModel
moveit::core::RobotModelConstPtr getRobotModel() const
Get the RobotModel object.
Definition: move_group_interface.cpp:1500
moveit::planning_interface::MoveGroupInterface::place
moveit::core::MoveItErrorCode place(const std::string &object, bool plan_only=false)
Place an object somewhere safe in the world (a safe location will be detected)
Definition: move_group_interface.h:949
moveit::planning_interface::MoveGroupInterface::getRandomPose
geometry_msgs::PoseStamped getRandomPose(const std::string &end_effector_link="") const
Get a random reachable pose for the end-effector end_effector_link. If end_effector_link is empty (th...
Definition: move_group_interface.cpp:2189
moveit::planning_interface::MoveGroupInterface::Options::robot_model_
moveit::core::RobotModelConstPtr robot_model_
Optionally, an instance of the RobotModel to use can be also specified.
Definition: move_group_interface.h:179
moveit::core::MoveItErrorCode
moveit::planning_interface::MoveGroupInterface::getNodeHandle
const ros::NodeHandle & getNodeHandle() const
Get the ROS node handle of this instance operates on.
Definition: move_group_interface.cpp:1505
simple_action_client.h
moveit::planning_interface::MoveGroupInterface::~MoveGroupInterface
~MoveGroupInterface()
Definition: move_group_interface.cpp:1464
moveit::planning_interface::MoveGroupInterface::setMaxVelocityScalingFactor
void setMaxVelocityScalingFactor(double max_velocity_scaling_factor)
Set a scaling factor for optionally reducing the maximum joint velocity. Allowed values are in (0,...
Definition: move_group_interface.cpp:1567
moveit::planning_interface::MoveGroupInterface::plan
moveit::core::MoveItErrorCode plan(Plan &plan)
Compute a motion plan that takes the group declared in the constructor from the current state to the ...
Definition: move_group_interface.cpp:1622
moveit::planning_interface::MoveGroupInterface::getName
const std::string & getName() const
Get the name of the group this instance operates on.
Definition: move_group_interface.cpp:1488
moveit::planning_interface::MoveGroupInterface::setMaxAccelerationScalingFactor
void setMaxAccelerationScalingFactor(double max_acceleration_scaling_factor)
Set a scaling factor for optionally reducing the maximum joint acceleration. Allowed values are in (0...
Definition: move_group_interface.cpp:1572
moveit::planning_interface::MoveGroupInterface::Options::node_handle_
ros::NodeHandle node_handle_
Definition: move_group_interface.h:181
moveit::planning_interface::MoveGroupInterface::setGoalTolerance
void setGoalTolerance(double tolerance)
Set the tolerance that is used for reaching the goal. For joint state goals, this will be distance fo...
Definition: move_group_interface.cpp:2141
moveit::planning_interface::MoveGroupInterface::setApproximateJointValueTarget
bool setApproximateJointValueTarget(const geometry_msgs::Pose &eef_pose, const std::string &end_effector_link="")
Set the joint state goal for a particular joint by computing IK.
Definition: move_group_interface.cpp:1882
moveit::planning_interface::MoveGroupInterface::setEndEffectorLink
bool setEndEffectorLink(const std::string &end_effector_link)
Specify the parent link of the end-effector. This end_effector_link will be used in calls to pose tar...
Definition: move_group_interface.cpp:1921
moveit::planning_interface::MoveGroupInterface::setPlanningPipelineId
void setPlanningPipelineId(const std::string &pipeline_id)
Specify a planning pipeline to be used for further planning.
Definition: move_group_interface.cpp:1537
moveit::planning_interface::MoveGroupInterface::setRPYTarget
bool setRPYTarget(double roll, double pitch, double yaw, const std::string &end_effector_link="")
Set the goal orientation of the end-effector end_effector_link to be (roll,pitch,yaw) radians.
Definition: move_group_interface.cpp:2067
moveit::planning_interface::MoveItErrorCode
moveit::core::MoveItErrorCode MoveItErrorCode
Definition: move_group_interface.h:130
moveit::planning_interface::MoveGroupInterface::posesToPlaceLocations
std::vector< moveit_msgs::PlaceLocation > posesToPlaceLocations(const std::vector< geometry_msgs::PoseStamped > &poses) const
Convert a vector of PoseStamped to a vector of PlaceLocation.
Definition: move_group_interface.cpp:1642
moveit::planning_interface::MoveGroupInterface::DEFAULT_ALLOWED_PLANNING_TIME
static constexpr double DEFAULT_ALLOWED_PLANNING_TIME
Default allowed planning time (seconds)
Definition: move_group_interface.h:155
moveit::planning_interface::MoveGroupInterface::setTrajectoryConstraints
void setTrajectoryConstraints(const moveit_msgs::TrajectoryConstraints &constraint)
Definition: move_group_interface.cpp:2378
moveit::planning_interface::MoveGroupInterface::setPathConstraints
bool setPathConstraints(const std::string &constraint)
Specify a set of path constraints to use. The constraints are looked up by name from the Mongo databa...
Definition: move_group_interface.cpp:2358
moveit::planning_interface::MoveGroupInterface::stop
void stop()
Stop any trajectory execution, if one is active.
Definition: move_group_interface.cpp:1687
moveit::planning_interface::MoveGroupInterface::Options::robot_description_
std::string robot_description_
The robot description parameter name (if different from default)
Definition: move_group_interface.h:176
moveit::planning_interface::MoveGroupInterface::getPoseTarget
const geometry_msgs::PoseStamped & getPoseTarget(const std::string &end_effector_link="") const
Definition: move_group_interface.cpp:2016
moveit::planning_interface::MoveGroupInterface::DEFAULT_GOAL_JOINT_TOLERANCE
static constexpr double DEFAULT_GOAL_JOINT_TOLERANCE
Default goal joint tolerance (0.1mm) if not specified with {robot description name}_kinematics/{joint...
Definition: move_group_interface.h:144
moveit::planning_interface::MoveGroupInterface::execute
moveit::core::MoveItErrorCode execute(const Plan &plan)
Given a plan, execute it while waiting for completion.
Definition: move_group_interface.cpp:1612
moveit::planning_interface::MoveGroupInterface::getGoalJointTolerance
double getGoalJointTolerance() const
Get the tolerance that is used for reaching a joint goal. This is distance for each joint in configur...
Definition: move_group_interface.cpp:2126
moveit::planning_interface::MoveGroupInterface::clearMaxCartesianLinkSpeed
void clearMaxCartesianLinkSpeed()
Clear maximum Cartesian speed of the end effector.
Definition: move_group_interface.cpp:1582
moveit::planning_interface::MoveGroupInterface::getRandomJointValues
std::vector< double > getRandomJointValues() const
Get random joint values for the joints planned for by this instance (see getJoints())
Definition: move_group_interface.cpp:2182
moveit::planning_interface::MoveGroupInterface::getPlannerId
const std::string & getPlannerId() const
Get the current planner_id.
Definition: move_group_interface.cpp:1557
moveit::planning_interface::MoveGroupInterface::getJointValueTarget
const moveit::core::RobotState & getJointValueTarget() const
Get the currently set joint state goal, replaced by private getTargetRobotState()
Definition: move_group_interface.cpp:1901
moveit::planning_interface::MoveGroupInterface::operator=
MoveGroupInterface & operator=(const MoveGroupInterface &)=delete
moveit::planning_interface::MoveGroupInterface::clearTrajectoryConstraints
void clearTrajectoryConstraints()
Definition: move_group_interface.cpp:2383
moveit::planning_interface::MoveGroupInterface::constructPlaceGoal
moveit_msgs::PlaceGoal constructPlaceGoal(const std::string &object, std::vector< moveit_msgs::PlaceLocation > locations, bool plan_only) const
Build a PlaceGoal for an object named object and store it in goal_out.
Definition: move_group_interface.cpp:1634
moveit::planning_interface::MoveGroupInterface::getPlanningPipelineId
const std::string & getPlanningPipelineId() const
Get the current planning_pipeline_id.
Definition: move_group_interface.cpp:1542
moveit
moveit::planning_interface::MoveGroupInterface::getNamedTargets
const std::vector< std::string > & getNamedTargets() const
Get the names of the named robot states available as targets, both either remembered states or defaul...
Definition: move_group_interface.cpp:1493
moveit::planning_interface::MoveGroupInterface::getInterfaceDescriptions
bool getInterfaceDescriptions(std::vector< moveit_msgs::PlannerInterfaceDescription > &desc) const
Get the descriptions of all planning plugins loaded by the action server.
Definition: move_group_interface.cpp:1515
moveit::planning_interface::MoveGroupInterface::setSupportSurfaceName
void setSupportSurfaceName(const std::string &name)
For pick/place operations, the name of the support surface is used to specify the fact that attached ...
Definition: move_group_interface.cpp:2410
class_forward.h
moveit::planning_interface::MoveGroupInterface::clearPoseTarget
void clearPoseTarget(const std::string &end_effector_link="")
Forget pose(s) specified for end_effector_link.
Definition: move_group_interface.cpp:1938
moveit::planning_interface::MoveGroupInterface::setNumPlanningAttempts
void setNumPlanningAttempts(unsigned int num_planning_attempts)
Set the number of times the motion plan is to be computed from scratch before the shortest solution i...
Definition: move_group_interface.cpp:1562
std
moveit::planning_interface::MoveGroupInterface::getVariableNames
const std::vector< std::string > & getVariableNames() const
Get names of degrees of freedom in this group.
Definition: move_group_interface.cpp:1722
moveit::planning_interface::MoveGroupInterface::pick
moveit::core::MoveItErrorCode pick(const std::string &object, bool plan_only=false)
Pick up an object.
Definition: move_group_interface.h:914
planning_interface
moveit::planning_interface::MoveGroupInterface::setPositionTarget
bool setPositionTarget(double x, double y, double z, const std::string &end_effector_link="")
Set the goal position of the end-effector end_effector_link to be (x, y, z).
Definition: move_group_interface.cpp:2042
moveit::planning_interface::MoveGroupInterface::getInterfaceDescription
bool getInterfaceDescription(moveit_msgs::PlannerInterfaceDescription &desc) const
Get the description of the default planning plugin loaded by the action server.
Definition: move_group_interface.cpp:1510
moveit::planning_interface::MoveGroupInterface::Plan::trajectory_
moveit_msgs::RobotTrajectory trajectory_
The trajectory of the robot (may not contain joints that are the same as for the start_state_)
Definition: move_group_interface.h:193
moveit::planning_interface::MoveGroupInterface::Plan::planning_time_
double planning_time_
The amount of time it took to generate the plan.
Definition: move_group_interface.h:196
moveit::planning_interface::MoveGroupInterface::attachObject
bool attachObject(const std::string &object, const std::string &link="")
Given the name of an object in the planning scene, make the object attached to a link of the robot....
Definition: move_group_interface.cpp:2425
moveit::planning_interface::MoveGroupInterface::setWorkspace
void setWorkspace(double minx, double miny, double minz, double maxx, double maxy, double maxz)
Specify the workspace bounding box. The box is specified in the planning frame (i....
Definition: move_group_interface.cpp:2393
moveit::planning_interface::MoveGroupInterface::impl_
MoveGroupInterfaceImpl * impl_
Definition: move_group_interface.h:1116
moveit::planning_interface::MoveGroupInterface::getPathConstraints
moveit_msgs::Constraints getPathConstraints() const
Get the actual set of constraints in use with this MoveGroupInterface.
Definition: move_group_interface.cpp:2353
moveit::planning_interface::MoveGroupInterface::getPlanningTime
double getPlanningTime() const
Get the number of seconds set by setPlanningTime()
Definition: move_group_interface.cpp:2405
moveit::planning_interface::MoveGroupInterface::MoveGroupInterface
MoveGroupInterface(const Options &opt, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer=std::shared_ptr< tf2_ros::Buffer >(), const ros::WallDuration &wait_for_servers=ros::WallDuration())
Construct a MoveGroupInterface instance call using a specified set of options opt.
Definition: move_group_interface.cpp:1451
moveit::planning_interface::MoveGroupInterface::DEFAULT_NUM_PLANNING_ATTEMPTS
static constexpr int DEFAULT_NUM_PLANNING_ATTEMPTS
Default number of planning attempts.
Definition: move_group_interface.h:158
moveit::planning_interface::MoveGroupInterface::getActiveJoints
const std::vector< std::string > & getActiveJoints() const
Get names of joints with an active (actuated) DOF in this group.
Definition: move_group_interface.cpp:2265
moveit::planning_interface::MoveGroupInterface::getLinkNames
const std::vector< std::string > & getLinkNames() const
Get vector of names of links available in move group.
Definition: move_group_interface.cpp:1727
moveit::planning_interface::MoveGroupInterface::setPoseTargets
bool setPoseTargets(const EigenSTL::vector_Isometry3d &end_effector_pose, const std::string &end_effector_link="")
Set goal poses for end_effector_link.
Definition: move_group_interface.cpp:1972
moveit::planning_interface::MoveGroupInterface::setNamedTarget
bool setNamedTarget(const std::string &name)
Set the current joint values to be ones previously remembered by rememberJointValues() or,...
Definition: move_group_interface.cpp:1752
moveit::planning_interface::MoveGroupInterface::getRememberedJointValues
const std::map< std::string, std::vector< double > > & getRememberedJointValues() const
Get the currently remembered map of names to joint values.
Definition: move_group_interface.h:1064
moveit::planning_interface::MoveGroupInterface::getGoalOrientationTolerance
double getGoalOrientationTolerance() const
Get the tolerance that is used for reaching an orientation goal. This is the tolerance for roll,...
Definition: move_group_interface.cpp:2136
ros::WallDuration
moveit::planning_interface::MoveGroupInterface::Plan::start_state_
moveit_msgs::RobotState start_state_
The full starting state used for planning.
Definition: move_group_interface.h:190
moveit::planning_interface::MoveGroupInterface::getNamedTargetValues
std::map< std::string, double > getNamedTargetValues(const std::string &name) const
Get the joint angles for targets specified by name.
Definition: move_group_interface.cpp:1732
moveit::planning_interface::MoveGroupInterface::constructMotionPlanRequest
void constructMotionPlanRequest(moveit_msgs::MotionPlanRequest &request)
Build the MotionPlanRequest that would be sent to the move_group action with plan() or move() and sto...
Definition: move_group_interface.cpp:2441
ros::Duration
moveit::planning_interface::MoveGroupInterface::getCurrentPose
geometry_msgs::PoseStamped getCurrentPose(const std::string &end_effector_link="") const
Get the pose for the end-effector end_effector_link. If end_effector_link is empty (the default value...
Definition: move_group_interface.cpp:2214
moveit::planning_interface::MoveGroupInterface::detachObject
bool detachObject(const std::string &name="")
Detach an object. name specifies the name of the object attached to this group, or the name of the li...
Definition: move_group_interface.cpp:2436
moveit::planning_interface::MoveGroupInterface::setEndEffector
bool setEndEffector(const std::string &eef_name)
Specify the name of the end-effector to use. This is equivalent to setting the EndEffectorLink to the...
Definition: move_group_interface.cpp:1930
moveit::planning_interface::MoveGroupInterface::Options::group_name_
std::string group_name_
The group to construct the class instance for.
Definition: move_group_interface.h:173
moveit_error_code.h
ros::NodeHandle
moveit::planning_interface::MoveGroupInterface::constructPickupGoal
moveit_msgs::PickupGoal constructPickupGoal(const std::string &object, std::vector< moveit_msgs::Grasp > grasps, bool plan_only) const
Build a PickupGoal for an object named object and store it in goal_out.
Definition: move_group_interface.cpp:1627
moveit::planning_interface::MoveGroupInterface::getGoalPositionTolerance
double getGoalPositionTolerance() const
Get the tolerance that is used for reaching a position goal. This is be the radius of a sphere where ...
Definition: move_group_interface.cpp:2131
test_cleanup.group
group
Definition: test_cleanup.py:8
moveit::planning_interface::MoveGroupInterface::getJointNames
const std::vector< std::string > & getJointNames() const
Definition: move_group_interface.h:271


planning_interface
Author(s): Ioan Sucan
autogenerated on Thu Apr 18 2024 02:25:17