A MoveGroup action goal builder. More...
#include <builder.h>
Public Member Functions | |
void | AddPathOrientationConstraint (const moveit_msgs::OrientationConstraint &oc) |
Adds an orientation constraint to this goal. | |
void | AddPoseGoal (const std::string &ee_link, const geometry_msgs::Pose &goal) |
Sets a single pose goal for a single end-effector. | |
void | Build (moveit_msgs::MoveGroupGoal *goal) const |
Builds the goal. | |
Builder (const std::string &planning_frame, const std::string &group_name) | |
Constructor. | |
void | ClearPathConstraints () |
Clears all path constraints for this goal. | |
void | ClearPoseGoals () |
Clears any pose goals that were set. | |
void | GetJointGoal (std::map< std::string, double > *joint_goal) const |
Gets the joint goal that was last added to the builder. | |
void | GetPathConstraints (moveit_msgs::Constraints *constraints) const |
Returns the path constraints on the goal. | |
void | GetPoseGoals (std::map< std::string, geometry_msgs::Pose > *pose_goals) const |
Gets the pose goals that were set. | |
void | SetJointGoal (const std::map< std::string, double > &joints) |
Sets a joint goal. | |
void | SetPathConstraints (const moveit_msgs::Constraints &constraints) |
Sets the path constraints on the goal. | |
void | SetPoseGoals (const std::map< std::string, geometry_msgs::Pose > &pose_goals) |
Sets a pose goal, one for each end-effector. | |
void | SetStartState (const robot_state::RobotState &start_state) |
Sets the robot's start state for planning. | |
void | SetStartStateToCurrentState () |
Sets the robot's start state to be its current state. | |
robot_state::RobotStatePtr | StartState () const |
Returns the robot's start state. | |
Public Attributes | |
bool | can_look |
Whether the robot should be allowed to look around. | |
bool | can_replan |
std::string | group_name |
Group name, e.g, "arms", "right_arm", etc. | |
double | joint_tolerance |
double | max_acceleration_scaling_factor |
Scaling factor in (0, 1] for the maximum joint acceleration. | |
double | max_velocity_scaling_factor |
Scaling factor in (0, 1] for the maximum joint speed. | |
unsigned int | num_planning_attempts |
The number of times to compute a plan. The shortest plan will be used. | |
double | orientation_tolerance |
bool | plan_only |
Whether to compute a plan without executing it. | |
std::string | planner_id |
The name of the planner to use. | |
std::string | planning_frame |
MoveIt planning frame (e.g., "odom_combined" or "base_link"). | |
double | planning_time |
The maximum time to spend finding a plan, in seconds. | |
double | position_tolerance |
Tolerance radius for the position (applies only to pose goals), in meters. | |
int | replan_attempts |
Maximum number of times to replan. | |
double | replan_delay |
Time to wait in between replanning attempts, in seconds.. | |
moveit_msgs::WorkspaceParameters | workspace_parameters |
The workspace boundaries of the robot. | |
Private Attributes | |
ActiveTargetType | active_target_ |
std::map< std::string, double > | joint_goal_ |
moveit_msgs::Constraints | path_constraints_ |
std::map< std::string, geometry_msgs::Pose > | pose_goals_ |
robot_state::RobotStatePtr | start_state_ |
A MoveGroup action goal builder.
This is used to invoke the MoveGroup action through a custom action client rather than through MoveIt's MoveGroup class. The main reason to do so is if you want to poll the progress of the action.
To use the builder, set either a pose goal or a joint goal, then set all of the planning properties, which are exposed as public variables.
Example:
moveit_goal_builder::Builder builder("base_link", "arms"); builder.AddPoseGoal("r_wrist_roll_link", pose); builder.AddPathOrientationConstraint(orientation_constraint); builder.planning_time = 10.0; builder.num_planning_attempts = 3; builder.can_replan = true; builder.replan_attempts = 3; moveit_msgs::MoveGroupGoal goal; builder.Build(&goal);
moveit_goal_builder::Builder::Builder | ( | const std::string & | planning_frame, |
const std::string & | group_name | ||
) |
Constructor.
[in] | planning_frame | The planning frame of the robot, according to the robot's MoveIt configuration (e.g., "base_link" or "odom_combined". |
[in] | group_name | The name of the group to build the goal for (e.g., "arm") |
Definition at line 22 of file builder.cpp.
void moveit_goal_builder::Builder::AddPathOrientationConstraint | ( | const moveit_msgs::OrientationConstraint & | oc | ) |
Adds an orientation constraint to this goal.
[in] | oc | The orientation constraint to add. |
Definition at line 165 of file builder.cpp.
void moveit_goal_builder::Builder::AddPoseGoal | ( | const std::string & | ee_link, |
const geometry_msgs::Pose & | goal | ||
) |
Sets a single pose goal for a single end-effector.
This can be called multiple times with different end-effectors. Calling this multiple times with the same end-effector will replace the goal for that end-effector.
[in] | ee_link | The name of the end-effector link, e.g., "r_wrist_roll_link" |
[in] | goal | The pose goal for that end-effector, in the planning frame. |
Definition at line 144 of file builder.cpp.
void moveit_goal_builder::Builder::Build | ( | moveit_msgs::MoveGroupGoal * | goal | ) | const |
Builds the goal.
[out] | goal | The completed goal. |
Definition at line 45 of file builder.cpp.
Clears all path constraints for this goal.
Definition at line 158 of file builder.cpp.
Clears any pose goals that were set.
Definition at line 142 of file builder.cpp.
void moveit_goal_builder::Builder::GetJointGoal | ( | std::map< std::string, double > * | joint_goal | ) | const |
Gets the joint goal that was last added to the builder.
[out] | joint_goal | The most recently added joint goal. |
Definition at line 122 of file builder.cpp.
void moveit_goal_builder::Builder::GetPathConstraints | ( | moveit_msgs::Constraints * | constraints | ) | const |
Returns the path constraints on the goal.
[out] | constraints | The constraints on the path. |
Definition at line 150 of file builder.cpp.
void moveit_goal_builder::Builder::GetPoseGoals | ( | std::map< std::string, geometry_msgs::Pose > * | pose_goals | ) | const |
Gets the pose goals that were set.
[out] | pose_goals | A mapping from end-effector name (the end-effector link name, e.g., "r_wrist_roll_link") to the pose goal for that end-effector. The pose is specified in the planning frame. |
Definition at line 131 of file builder.cpp.
void moveit_goal_builder::Builder::SetJointGoal | ( | const std::map< std::string, double > & | joints | ) |
Sets a joint goal.
Does not check that the joint names are valid or that the values are within limits. Setting a joint goal overrides any pose goals that were previously set.
[in] | joints | A mapping between joint names and joint angle/position values. |
Definition at line 126 of file builder.cpp.
void moveit_goal_builder::Builder::SetPathConstraints | ( | const moveit_msgs::Constraints & | constraints | ) |
Sets the path constraints on the goal.
[out] | constraints | The constraints on the path. |
Definition at line 154 of file builder.cpp.
void moveit_goal_builder::Builder::SetPoseGoals | ( | const std::map< std::string, geometry_msgs::Pose > & | pose_goals | ) |
Sets a pose goal, one for each end-effector.
Specify the end-effector link and the pose it should reach. The pose should be specified in the planning frame. Setting a pose goal overrides any previously set orientation goals.
[in] | pose_goals | A mapping from end-effector name (the end-effector link name, e.g., "r_wrist_roll_link") to the pose goal for that end-effector. The pose must be specified in the planning frame. |
Definition at line 136 of file builder.cpp.
void moveit_goal_builder::Builder::SetStartState | ( | const robot_state::RobotState & | start_state | ) |
Sets the robot's start state for planning.
[in] | start_state | The start state for the plan. |
Definition at line 172 of file builder.cpp.
Sets the robot's start state to be its current state.
Definition at line 176 of file builder.cpp.
robot_state::RobotStatePtr moveit_goal_builder::Builder::StartState | ( | ) | const |
Returns the robot's start state.
Definition at line 170 of file builder.cpp.
std::string moveit_goal_builder::Builder::group_name |
std::map<std::string, double> moveit_goal_builder::Builder::joint_goal_ [private] |
unsigned int moveit_goal_builder::Builder::num_planning_attempts |
moveit_msgs::Constraints moveit_goal_builder::Builder::path_constraints_ [private] |
std::string moveit_goal_builder::Builder::planner_id |
std::string moveit_goal_builder::Builder::planning_frame |
std::map<std::string, geometry_msgs::Pose> moveit_goal_builder::Builder::pose_goals_ [private] |
robot_state::RobotStatePtr moveit_goal_builder::Builder::start_state_ [private] |
moveit_msgs::WorkspaceParameters moveit_goal_builder::Builder::workspace_parameters |