Go to the documentation of this file.00001 #ifndef _MOVEIT_GOAL_BUILDER_BUILDER_H_
00002 #define _MOVEIT_GOAL_BUILDER_BUILDER_H_
00003
00004 #include <map>
00005 #include <string>
00006
00007 #include "geometry_msgs/Pose.h"
00008 #include "moveit/robot_state/robot_state.h"
00009 #include "moveit_msgs/Constraints.h"
00010 #include "moveit_msgs/MoveGroupGoal.h"
00011 #include "moveit_msgs/OrientationConstraint.h"
00012 #include "moveit_msgs/WorkspaceParameters.h"
00013
00014 namespace moveit_goal_builder {
00015 enum ActiveTargetType { JOINT, POSE, POSITION, ORIENTATION };
00016
00017 const char kRRTConnect[] = "RRTConnectkConfigDefault";
00018
00041 class Builder {
00042 public:
00049 Builder(const std::string& planning_frame, const std::string& group_name);
00050
00054 void Build(moveit_msgs::MoveGroupGoal* goal) const;
00055
00059 void GetJointGoal(std::map<std::string, double>* joint_goal) const;
00060
00069 void SetJointGoal(const std::map<std::string, double>& joints);
00070
00078 void GetPoseGoals(
00079 std::map<std::string, geometry_msgs::Pose>* pose_goals) const;
00080
00092 void SetPoseGoals(
00093 const std::map<std::string, geometry_msgs::Pose>& pose_goals);
00094
00096 void ClearPoseGoals();
00097
00110 void AddPoseGoal(const std::string& ee_link, const geometry_msgs::Pose& goal);
00111
00115 void GetPathConstraints(moveit_msgs::Constraints* constraints) const;
00116
00120 void SetPathConstraints(const moveit_msgs::Constraints& constraints);
00121
00123 void ClearPathConstraints();
00124
00128 void AddPathOrientationConstraint(
00129 const moveit_msgs::OrientationConstraint& oc);
00130
00134 robot_state::RobotStatePtr StartState() const;
00135
00139 void SetStartState(const robot_state::RobotState& start_state);
00140
00142 void SetStartStateToCurrentState();
00143
00145 std::string planning_frame;
00146
00148 std::string group_name;
00149
00151 bool plan_only;
00152
00154 moveit_msgs::WorkspaceParameters workspace_parameters;
00155
00157 double planning_time;
00158
00160 std::string planner_id;
00161
00163 unsigned int num_planning_attempts;
00164
00166 double max_velocity_scaling_factor;
00167
00169 double max_acceleration_scaling_factor;
00170
00172 bool can_look;
00173
00176 bool can_replan;
00177
00179 int replan_attempts;
00180
00182 double replan_delay;
00183
00186 double joint_tolerance;
00187
00189 double position_tolerance;
00190
00193 double orientation_tolerance;
00194
00195 private:
00196
00197 std::map<std::string, double> joint_goal_;
00198
00199
00200 std::map<std::string, geometry_msgs::Pose> pose_goals_;
00201
00202
00203 moveit_msgs::Constraints path_constraints_;
00204
00205 robot_state::RobotStatePtr start_state_;
00206
00207 ActiveTargetType active_target_;
00208 };
00209 }
00210
00211 #endif // _MOVEIT_GOAL_BUILDER_BUILDER_H_