moveit_goal_builder module

MoveItGoalBuilder

class moveit_goal_builder.moveit_goal_builder.MoveItGoalBuilder[source]

Bases: object

Builds a MoveGroupGoal.

Example:

# To do a reachability check from the current robot pose.
builder = MoveItGoalBuilder()
builder.set_pose_goal(pose_stamped)
builder.allowed_planning_time = 5
builder.plan_only = True
goal = builder.build()

# To move to a current robot pose with a few options changed.
builder = MoveItGoalBuilder()
builder.set_pose_goal(pose_stamped)
builder.replan = True
builder.replan_attempts = 10
goal = builder.build()

Use set_pose_goal or set_joint_goal to set the actual goal. Pose goals and joint goals are mutually exclusive; setting one will overwrite the other.

Most of the builder is configured by setting public members. Below is a list of all the public members you can set as well as their default values:

allowed_planning_time = 10.0
float. How much time to allow the planner, in seconds.
fixed_frame = ‘base_link’
string. The MoveIt planning frame.
gripper_frame = ‘wrist_roll_link’
string. The name of the end-effector link.
group_name = ‘arm’
string. The name of the MoveIt group to plan for.
planning_scene_diff
moveit_msgs.msg.PlanningScene. Changes to the planning scene to apply. By default this is set to an empty planning scene.
look_around = False
bool. Whether or not the robot can look around during execution.
max_acceleration_scaling_factor = 0
float. The scaling factor for the maximum joint acceleration, in the range [0, 1]. A value of 0 means there is no scaling factor.
max_velocity_scaling_factor = 0
float. Used to slow the executed action, this specifies the scaling factor for the maximum velocity, in the range [0, 1]. A value of 0 means there is no scaling factor.
num_planning_attempts = 1
int. How many times to compute the same plan (most planners are randomized). The shortest plan will be used.
plan_only = False
bool. Whether to only compute the plan but not execute it.
planner_id = ‘RRTConnectkConfigDefault’
string. The name of the planner to use. A list of planner names can be found using the rviz MotionPlanning plugin.
replan = False
bool. Whether to come up with a new plan if there was an error executing the original plan.
replan_attempts = 5
int. How many times to do replanning.
replan_delay = 1.0
float. How long to wait in between replanning, in seconds.
tolerance = 0.01:
float. The tolerance radius, in meters, for the goal pose. If the builder is used for a joint angle action, then tolerance specifies the joint angle tolerance (both above and below) in radians.
add_path_orientation_constraint(o_constraint)[source]

Adds an orientation constraint to the path.

Note

Make more advanced edits to the orientation constraints by modifying _orientation_constraints directly.

Parameters:o_constraint (moveit_msgs.msg.OrientationConstraint) – The orientation constraint to add.
build(tf_timeout=rospy.Duration[5000000000])[source]

Builds the goal message.

To set a pose or joint goal, call set_pose_goal or set_joint_goal before calling build. To add a path orientation constraint, call add_path_orientation_constraint first.

Parameters:tf_timeout (rospy.Duration) – How long to wait for a TF message. Only used with pose goals.
Returns:The MoveGroup action goal.
Return type:moveit_msgs.msg.MoveGroupGoal
set_joint_goal(joint_names, joint_positions)[source]

Sets a joint-space planning goal.

Parameters:
  • joint_names (list of strings) – The names of the joints in the goal.
  • joint_positions (list of floats) – The joint angles to achieve.
set_pose_goal(pose_stamped)[source]

Sets a pose goal.

Note

The pose will be transformed into the planning frame when build is called.

Parameters:pose_stamped (geometry_msgs.msg.PoseStamped) – The pose goal for the end-effector.

Table Of Contents

Previous topic

moveit_goal_builder

This Page