38 #ifndef MOVEIT_MOVE_GROUP_INTERFACE_MOVE_GROUP_INTERFACE_ 39 #define MOVEIT_MOVE_GROUP_INTERFACE_MOVE_GROUP_INTERFACE_ 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> 77 explicit operator bool()
const 79 return val == moveit_msgs::MoveItErrorCodes::SUCCESS;
107 Options(
const std::string& group_name,
const std::string& desc = ROBOT_DESCRIPTION,
109 : group_name_(group_name), robot_description_(
desc), node_handle_(node_handle)
181 const std::string&
getName()
const;
185 const std::vector<std::string> getNamedTargets();
188 robot_model::RobotModelConstPtr getRobotModel()
const;
194 const std::string& getPlanningFrame()
const;
197 const std::vector<std::string>& getJointNames();
200 const std::vector<std::string>& getLinkNames();
203 std::map<std::string, double> getNamedTargetValues(
const std::string& name);
206 const std::vector<std::string>& getActiveJoints()
const;
209 const std::vector<std::string>& getJoints()
const;
213 unsigned int getVariableCount()
const;
216 bool getInterfaceDescription(moveit_msgs::PlannerInterfaceDescription& desc);
219 std::map<std::string, std::string> getPlannerParams(
const std::string& planner_id,
const std::string& group =
"");
222 void setPlannerParams(
const std::string& planner_id,
const std::string& group,
223 const std::map<std::string, std::string>& params,
bool bReplace =
false);
226 std::string getDefaultPlannerId(
const std::string& group =
"")
const;
229 void setPlannerId(
const std::string& planner_id);
232 const std::string& getPlannerId()
const;
235 void setPlanningTime(
double seconds);
239 void setNumPlanningAttempts(
unsigned int num_planning_attempts);
246 void setMaxVelocityScalingFactor(
double max_velocity_scaling_factor);
253 void setMaxAccelerationScalingFactor(
double max_acceleration_scaling_factor);
256 double getPlanningTime()
const;
260 double getGoalJointTolerance()
const;
264 double getGoalPositionTolerance()
const;
268 double getGoalOrientationTolerance()
const;
276 void setGoalTolerance(
double tolerance);
280 void setGoalJointTolerance(
double tolerance);
283 void setGoalPositionTolerance(
double tolerance);
286 void setGoalOrientationTolerance(
double tolerance);
292 void setWorkspace(
double minx,
double miny,
double minz,
double maxx,
double maxy,
double maxz);
296 void setStartState(
const moveit_msgs::RobotState& start_state);
300 void setStartState(
const robot_state::RobotState& start_state);
303 void setStartStateToCurrentState();
307 void setSupportSurfaceName(
const std::string& name);
339 bool setJointValueTarget(
const std::vector<double>& group_variable_values);
356 bool setJointValueTarget(
const std::map<std::string, double>& variable_values);
367 bool setJointValueTarget(
const robot_state::RobotState& robot_state);
380 bool setJointValueTarget(
const std::string& joint_name,
const std::vector<double>& values);
393 bool setJointValueTarget(
const std::string& joint_name,
double value);
405 bool setJointValueTarget(
const sensor_msgs::JointState& state);
418 bool setJointValueTarget(
const geometry_msgs::Pose& eef_pose,
const std::string& end_effector_link =
"");
431 bool setJointValueTarget(
const geometry_msgs::PoseStamped& eef_pose,
const std::string& end_effector_link =
"");
444 bool setJointValueTarget(
const Eigen::Affine3d& eef_pose,
const std::string& end_effector_link =
"");
456 bool setApproximateJointValueTarget(
const geometry_msgs::Pose& eef_pose,
const std::string& end_effector_link =
"");
468 bool setApproximateJointValueTarget(
const geometry_msgs::PoseStamped& eef_pose,
469 const std::string& end_effector_link =
"");
481 bool setApproximateJointValueTarget(
const Eigen::Affine3d& eef_pose,
const std::string& end_effector_link =
"");
487 void setRandomTarget();
491 bool setNamedTarget(
const std::string& name);
494 const robot_state::RobotState& getJointValueTarget()
const;
517 bool setPositionTarget(
double x,
double y,
double z,
const std::string& end_effector_link =
"");
526 bool setRPYTarget(
double roll,
double pitch,
double yaw,
const std::string& end_effector_link =
"");
536 bool setOrientationTarget(
double x,
double y,
double z,
double w,
const std::string& end_effector_link =
"");
545 bool setPoseTarget(
const Eigen::Affine3d& end_effector_pose,
const std::string& end_effector_link =
"");
554 bool setPoseTarget(
const geometry_msgs::Pose& target,
const std::string& end_effector_link =
"");
563 bool setPoseTarget(
const geometry_msgs::PoseStamped& target,
const std::string& end_effector_link =
"");
603 bool setPoseTargets(
const std::vector<geometry_msgs::Pose>& target,
const std::string& end_effector_link =
"");
623 bool setPoseTargets(
const std::vector<geometry_msgs::PoseStamped>& target,
const std::string& end_effector_link =
"");
626 void setPoseReferenceFrame(
const std::string& pose_reference_frame);
631 bool setEndEffectorLink(
const std::string& end_effector_link);
635 bool setEndEffector(
const std::string& eef_name);
638 void clearPoseTarget(
const std::string& end_effector_link =
"");
641 void clearPoseTargets();
649 const geometry_msgs::PoseStamped& getPoseTarget(
const std::string& end_effector_link =
"")
const;
656 const std::vector<geometry_msgs::PoseStamped>& getPoseTargets(
const std::string& end_effector_link =
"")
const;
663 const std::string& getEndEffectorLink()
const;
670 const std::string& getEndEffector()
const;
674 const std::string& getPoseReferenceFrame()
const;
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);
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);
745 void allowLooking(
bool flag);
748 void allowReplanning(
bool flag);
752 void constructMotionPlanRequest(moveit_msgs::MotionPlanRequest& request);
764 MoveItErrorCode pick(
const std::string&
object,
bool plan_only =
false);
767 MoveItErrorCode pick(
const std::string&
object,
const moveit_msgs::Grasp& grasp,
bool plan_only =
false);
772 MoveItErrorCode pick(
const std::string&
object,
const std::vector<moveit_msgs::Grasp>& grasps,
773 bool plan_only =
false);
778 MoveItErrorCode planGraspsAndPick(
const std::string&
object =
"",
bool plan_only =
false);
783 MoveItErrorCode planGraspsAndPick(
const moveit_msgs::CollisionObject&
object,
bool plan_only =
false);
786 MoveItErrorCode place(
const std::string&
object,
bool plan_only =
false);
789 MoveItErrorCode place(
const std::string&
object,
const std::vector<moveit_msgs::PlaceLocation>& locations,
790 bool plan_only =
false);
793 MoveItErrorCode place(
const std::string&
object,
const std::vector<geometry_msgs::PoseStamped>& poses,
794 bool plan_only =
false);
797 MoveItErrorCode place(
const std::string&
object,
const geometry_msgs::PoseStamped& pose,
bool plan_only =
false);
805 bool attachObject(
const std::string&
object,
const std::string& link =
"");
815 bool attachObject(
const std::string&
object,
const std::string& link,
const std::vector<std::string>& touch_links);
822 bool detachObject(
const std::string& name =
"");
836 bool startStateMonitor(
double wait = 1.0);
839 std::vector<double> getCurrentJointValues();
842 robot_state::RobotStatePtr getCurrentState(
double wait = 1);
847 geometry_msgs::PoseStamped getCurrentPose(
const std::string& end_effector_link =
"");
852 std::vector<double> getCurrentRPY(
const std::string& end_effector_link =
"");
855 std::vector<double> getRandomJointValues();
860 geometry_msgs::PoseStamped getRandomPose(
const std::string& end_effector_link =
"");
873 void rememberJointValues(
const std::string& name);
879 void rememberJointValues(
const std::string& name,
const std::vector<double>& values);
884 return remembered_joint_values_;
888 void forgetJointValues(
const std::string&
name);
898 void setConstraintsDatabase(
const std::string& host,
unsigned int port);
901 std::vector<std::string> getKnownConstraints()
const;
906 moveit_msgs::Constraints getPathConstraints()
const;
911 bool setPathConstraints(
const std::string& constraint);
916 void setPathConstraints(
const moveit_msgs::Constraints& constraint);
920 void clearPathConstraints();
922 moveit_msgs::TrajectoryConstraints getTrajectoryConstraints()
const;
923 void setTrajectoryConstraints(
const moveit_msgs::TrajectoryConstraints& constraint);
924 void clearTrajectoryConstraints();
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's URDF. Set to 'robot_description'.
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
moveit::planning_interface::MoveGroup MOVEIT_DEPRECATED
bool operator==(const int c) const
std::map< std::string, std::vector< double > > remembered_joint_values_
std::string getName(void *handle)
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)
bool operator!=(const int c) const
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())
MoveGroupInterfaceImpl * impl_
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.
MoveItErrorCode(int code)
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)
ros::NodeHandle node_handle_
MOVEIT_CLASS_FORWARD(MoveGroupInterface)