Public Member Functions | Public Attributes | Private Attributes
moveit_goal_builder::Builder Class Reference

A MoveGroup action goal builder. More...

#include <builder.h>

List of all members.

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_

Detailed Description

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);

Definition at line 41 of file builder.h.


Constructor & Destructor Documentation

moveit_goal_builder::Builder::Builder ( const std::string &  planning_frame,
const std::string &  group_name 
)

Constructor.

Parameters:
[in]planning_frameThe planning frame of the robot, according to the robot's MoveIt configuration (e.g., "base_link" or "odom_combined".
[in]group_nameThe name of the group to build the goal for (e.g., "arm")

Definition at line 22 of file builder.cpp.


Member Function Documentation

void moveit_goal_builder::Builder::AddPathOrientationConstraint ( const moveit_msgs::OrientationConstraint &  oc)

Adds an orientation constraint to this goal.

Parameters:
[in]ocThe 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.

Parameters:
[in]ee_linkThe name of the end-effector link, e.g., "r_wrist_roll_link"
[in]goalThe pose goal for that end-effector, in the planning frame.
See also:
SetPoseGoals

Definition at line 144 of file builder.cpp.

void moveit_goal_builder::Builder::Build ( moveit_msgs::MoveGroupGoal *  goal) const

Builds the goal.

Parameters:
[out]goalThe 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.

Parameters:
[out]joint_goalThe 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.

Parameters:
[out]constraintsThe 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.

Parameters:
[out]pose_goalsA 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.
See also:
AddPoseGoal, SetPoseGoals

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.

Parameters:
[in]jointsA 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.

Parameters:
[out]constraintsThe 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.

Parameters:
[in]pose_goalsA 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.
See also:
AddPoseGoal

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.

Parameters:
[in]start_stateThe 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.

Returns:
The start state for this planning goal.

Definition at line 170 of file builder.cpp.


Member Data Documentation

Definition at line 207 of file builder.h.

Whether the robot should be allowed to look around.

Definition at line 172 of file builder.h.

If the plan fails at execution time, allows the robot to replan and execute automatically.

Definition at line 176 of file builder.h.

Group name, e.g, "arms", "right_arm", etc.

Definition at line 148 of file builder.h.

std::map<std::string, double> moveit_goal_builder::Builder::joint_goal_ [private]

Definition at line 197 of file builder.h.

Tolerance for the joint angles (applies only to joint angle goals), in radians.

Definition at line 186 of file builder.h.

Scaling factor in (0, 1] for the maximum joint acceleration.

Definition at line 169 of file builder.h.

Scaling factor in (0, 1] for the maximum joint speed.

Definition at line 166 of file builder.h.

The number of times to compute a plan. The shortest plan will be used.

Definition at line 163 of file builder.h.

Angle tolerance from the X/Y/Z axes of the planning frame, in radians. Applies only to pose goals.

Definition at line 193 of file builder.h.

moveit_msgs::Constraints moveit_goal_builder::Builder::path_constraints_ [private]

Definition at line 203 of file builder.h.

Whether to compute a plan without executing it.

Definition at line 151 of file builder.h.

The name of the planner to use.

Definition at line 160 of file builder.h.

MoveIt planning frame (e.g., "odom_combined" or "base_link").

Definition at line 145 of file builder.h.

The maximum time to spend finding a plan, in seconds.

Definition at line 157 of file builder.h.

Definition at line 200 of file builder.h.

Tolerance radius for the position (applies only to pose goals), in meters.

Definition at line 189 of file builder.h.

Maximum number of times to replan.

Definition at line 179 of file builder.h.

Time to wait in between replanning attempts, in seconds..

Definition at line 182 of file builder.h.

robot_state::RobotStatePtr moveit_goal_builder::Builder::start_state_ [private]

Definition at line 205 of file builder.h.

moveit_msgs::WorkspaceParameters moveit_goal_builder::Builder::workspace_parameters

The workspace boundaries of the robot.

Definition at line 154 of file builder.h.


The documentation for this class was generated from the following files:


moveit_goal_builder
Author(s):
autogenerated on Sat Jun 8 2019 18:52:57