panda_autograsp.moveit_collision_objects

Module that contains a number of constraint object classes that can be used to add constraint to the moveit planning scene. It was created since the moveit_commander doesn’t yet contain a addCollisionObjects method. As a result using the standard collision_object_msgs and shape_msgs was not ideal.

Classes

Box(name[, size_x, size_y, size_z, x_pos, …]) Moveit Box collision object class.
Cylinder(name[, height, radius, x_pos, …]) Moveit cylinder collision object class.
Mesh(name, file_name[, x_pos, y_pos, z_pos, …]) Moveit mesh collision object class.
Plane(name[, normal_x, normal_y, normal_z, …]) Moveit Cube collision object class.
Sphere(name[, radius, x_pos, y_pos, z_pos, …]) Moveit sphere collision object class.
class panda_autograsp.moveit_collision_objects.Box(name, size_x=1.0, size_y=1.0, size_z=1.0, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]

Moveit Box collision object class.

type

Collision object type.

Type:str
name

The name of the object.

Type:str
size

The size of the box specified as (x, y, z).

Type:tuple
pose

The pose of the collision object.

Type:geometry_msgs.PoseStamed
__init__(name, size_x=1.0, size_y=1.0, size_z=1.0, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]
Parameters:
  • name (str) – The name of the object.
  • size_x (float, optional) – The x-dimensions size of the box, by default 1.0
  • size_y (float, optional) – The y-dimensions size of the box, by default 1.0
  • size_z (float, optional) – The z-dimensions size of the box, by default 1.0
  • x_pos (float, optional) – The x position in link_name frame, by default 0.0.
  • y_pos (float, optional) – The y position in link_name frame, by default 0.0.
  • z_pos (float, optional) – The z position in link_name frame, by default 0.0.
  • x_rot (float, optional) – The x orientation relative to the link_name frame, by default 0.0.
  • y_rot (float, optional) – The y orientation relative to the link_name frame, by default 0.0.
  • z_rot (float, optional) – The z orientation relative to the link_name frame, by default 0.0.
  • w_rot (float, optional) – The w orientation relative to the link_name frame, by default 1.0.
  • reference_frame (str, optional) – The frame in which the pose is expressed, by default world.
size

Get the size of the collision object.

class panda_autograsp.moveit_collision_objects.Plane(name, normal_x=0.0, normal_y=0.0, normal_z=1.0, offset=0.0, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]

Moveit Cube collision object class.

Note

This class uses the plane equation Ax+Bx+Cz + D = 0 to construct the plane. In this A,B,C represent the the coordinates of the plane normal (Orientation) and D the offset to the normal.

type

Collision object type.

Type:str
name

The name of the object.

Type:str
normal

Plane normal specified as (x, y, z).

Type:list
offset

Plane offset relative to the normal.

Type:float
pose

The pose of the collision object.

Type:geometry_msgs.PoseStamed
__init__(name, normal_x=0.0, normal_y=0.0, normal_z=1.0, offset=0.0, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]
Parameters:
  • name (str) – The name of the object.
  • normal_x (float, optional) – The normal vector x coordinate, by default 0.0.
  • normal_y (float, optional) – The normal vector y coordinate, by default 0.0.
  • normal_z (float, optional) – The normal vector z coordinate, by default 1.0.
  • offset (py:obj:float, optional) – Plane offset relative to the normal, by default 0.0
  • x_pos (float, optional) – The x position in link_name frame, by default 0.0.
  • y_pos (float, optional) – The y position in link_name frame, by default 0.0.
  • z_pos (float, optional) – The z position in link_name frame, by default 0.0.
  • x_rot (float, optional) – The x orientation relative to the link_name frame, by default 0.0.
  • y_rot (float, optional) – The y orientation relative to the link_name frame, by default 0.0.
  • z_rot (float, optional) – The z orientation relative to the link_name frame, by default 0.0.
  • w_rot (float, optional) – The w orientation relative to the link_name frame, by default 1.0.
  • reference_frame (str, optional) – The frame in which the pose is expressed, by default world.
normal

The plane normal.

class panda_autograsp.moveit_collision_objects.Cylinder(name, height=1.0, radius=1.0, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]

Moveit cylinder collision object class.

type

Collision object type.

Type:str
name

The name of the object.

Type:str
height

The height of the cylinder.

Type:float
radius

The radius of the cylinder.

Type:float
x_pos

The x position in link_name frame.

Type:float
y_pos

The y position in link_name frame.

Type:float
z_pos

The z position in link_name frame.

Type:float
x_rot

The x orientation relative to the link_name frame.

Type:float
y_rot

The y orientation relative to the link_name frame.

Type:float
z_rot

The z orientation relative to the link_name frame.

Type:float
w_rot

The w orientation relative to the link_name frame.

Type:float
pose

The object pose.

Type:geometry_msgs.PoseStamped
__init__(name, height=1.0, radius=1.0, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]
Parameters:
  • name (str) – The name of the object.
  • height (float, optional) – The height of the cylinder, by default 1.0
  • radius (float, optional) – The radius of the cylinder, by default 1.0.
  • x_pos (float, optional) – The x position in link_name frame, by default 0.0.
  • y_pos (float, optional) – The y position in link_name frame, by default 0.0.
  • z_pos (float, optional) – The z position in link_name frame, by default 0.0.
  • x_rot (float, optional) – The x orientation relative to the link_name frame, by default 0.0.
  • y_rot (float, optional) – The y orientation relative to the link_name frame, by default 0.0.
  • z_rot (float, optional) – The z orientation relative to the link_name frame, by default 0.0.
  • w_rot (float, optional) – The w orientation relative to the link_name frame, by default 1.0.
  • reference_frame (str, optional) – The frame in which the pose is expressed, by default world.
class panda_autograsp.moveit_collision_objects.Sphere(name, radius=1.0, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]

Moveit sphere collision object class.

type

Collision object type.

Type:str
name

The name of the object.

Type:str
radius

The radius of the sphere.

Type:float
x_pos

The x position in link_name frame.

Type:float
y_pos

The y position in link_name frame.

Type:float
z_pos

The z position in link_name frame.

Type:float
x_rot

The x orientation relative to the link_name frame.

Type:float
y_rot

The y orientation relative to the link_name frame.

Type:float
z_rot

The z orientation relative to the link_name frame.

Type:float
w_rot

The w orientation relative to the link_name frame.

Type:float
pose

The object pose.

Type:geometry_msgs.PoseStamped
__init__(name, radius=1.0, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]
Parameters:
  • name (str) – The name of the object.
  • radius (float, optional) – The radius of the sphere, by default 1.0.
  • x_pos (float, optional) – The x position in link_name frame, by default 0.0.
  • y_pos (float, optional) – The y position in link_name frame, by default 0.0.
  • z_pos (float, optional) – The z position in link_name frame, by default 0.0.
  • x_rot (float, optional) – The x orientation relative to the link_name frame, by default 0.0.
  • y_rot (float, optional) – The y orientation relative to the link_name frame, by default 0.0.
  • z_rot (float, optional) – The z orientation relative to the link_name frame, by default 0.0.
  • w_rot (float, optional) – The w orientation relative to the link_name frame, by default 1.0.
  • reference_frame (str, optional) – The frame in which the pose is expressed, by default world.
class panda_autograsp.moveit_collision_objects.Mesh(name, file_name, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]

Moveit mesh collision object class.

type

Collision object type.

Type:str
name

The name of the object.

Type:str
file_name

The location of the mesh file.

Type:str
x_pos

The x position in link_name frame.

Type:float
y_pos

The y position in link_name frame.

Type:float
z_pos

The z position in link_name frame.

Type:float
x_rot

The x orientation relative to the link_name frame.

Type:float
y_rot

The y orientation relative to the link_name frame.

Type:float
z_rot

The z orientation relative to the link_name frame.

Type:float
w_rot

The w orientation relative to the link_name frame.

Type:float
pose

The object pose.

Type:geometry_msgs.PoseStamped
__init__(name, file_name, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]
Parameters:
  • name (str) – The name of the object
  • file_name (str) – The location of the mesh file.
  • x_pos (float, optional) – The x position in link_name frame, by default 0.0.
  • y_pos (float, optional) – The y position in link_name frame, by default 0.0.
  • z_pos (float, optional) – The z position in link_name frame, by default 0.0.
  • x_rot (float, optional) – The x orientation relative to the link_name frame, by default 0.0.
  • y_rot (float, optional) – The y orientation relative to the link_name frame, by default 0.0.
  • z_rot (float, optional) – The z orientation relative to the link_name frame, by default 0.0.
  • w_rot (float, optional) – The w orientation relative to the link_name frame, by default 1.0.
  • reference_frame (str, optional) – The frame in which the pose is expressed, by default world.