API Reference¶
Body¶
-
raveutils.body.
enable_body
(body, enable)[source]¶ Enables all the links of a body.
Parameters: - body (orpy.KinBody) – The OpenRAVE body
- enable (bool) – If true, will enable all the links.
-
raveutils.body.
get_bounding_box_corners
(body, transform=None, scale=1.0)[source]¶ Get the bounding box corners (8 corners) for the given body. If
transform
is given the corners are transformed properly. Thescale
parameters is a factor used to scale the extents of the bounding box.Parameters: - body (orpy.KinBody) – The OpenRAVE body
- transform (array_like) – Homogeneous transformation of the body. If
None
, the corners are given using the current pose of the body in OpenRAVE. - scale (float) – The scale factor to modify the extents of the bounding box.
Returns: corners – List containing the 8 box corners. Each corner is a XYZ
np.array
Return type: list
-
raveutils.body.
set_body_transparency
(body, transparency=0.0, links=None)[source]¶ Set the transparency value of all the body’s geometries
Parameters: - body (orpy.KinBody) – The OpenRAVE body
- transparency (float) – The transparency value. If it’s out of range [0.0, 1.0], it’ll be clipped.
- links (list) – List of links to be modified. By default all the links are.
Camera¶
-
class
raveutils.camera.
CameraFOV
(camera_info, maxdist, transform=None)[source]¶ Bases:
object
Base class for the field-of-view of a Pin hole camera.
Parameters: - camera_info (sensor_msgs/CameraInfo) – Meta information of the camera. For more details check the sensor_msgs/CameraInfo documentation.
- maxdist (float) – Maximum distance the FOV covers in the Z direction of the camera frame.
- transform (array_like) – Homogenous transformation of the camera reference frame. If None then the identity matrix is used.
-
contains
(points)[source]¶ Check if all the XYZ points are inside the camera field of view
Parameters: points (array_like) – List of XYZ points Returns: all_inside – True if all the points are inside the FOV. False otherwise. Return type: bool
-
get_corners
()[source]¶ Get the five corners of the camera field of view
Returns: corners – A 5x3 array with the five corners of the camera field of view Return type: array_like
Conversions¶
Kinematics¶
-
raveutils.kinematics.
check_joint_limits
(robot, q=None)[source]¶ Check if the provided joint configuration exceeds the joint limits
Parameters: - robot (orpy.Robot) – The OpenRAVE robot
- q (array_like (optional)) – The joint configuration to check. If q is None, the current joint configuration of the robot is used.
Returns: result – True if the given joint configuration is within the joint limits of the robot. False otherwise.
Return type:
-
raveutils.kinematics.
compute_jacobian
(robot, link_name=None, link_idx=None, translation_only=False)[source]¶ Compute the Jacobian matrix
Parameters: - robot (orpy.Robot) – The OpenRAVE robot
- link_name (str, optional) – The name of link. If it’s None, the manipulator frame will be used
- link_idx (int, optional) – The index of link. If it’s None, the manipulator frame will be used
- translation_only (bool, optional) – If set, only the translation Jacobian is computed
Returns: J – The computed Jacobian matrix
Return type: array_like
Notes
If both link_idx and link_name are given, link_idx will have priority.
-
raveutils.kinematics.
compute_yoshikawa_index
(robot, link_name=None, translation_only=False, penalize_jnt_limits=True)[source]¶ Compute the Yoshikawa index (manipulability index)
Parameters: - robot (orpy.Robot) – The OpenRAVE robot
- link_name (str, optional) – The name of link. If it’s None, the last link of the kinematic chain is used.
- translation_only (bool, optional) – If True use only the translation part of the Jacobian matrix to compute the index. If False use the translation and rotation.
- penalize_jnt_limits (bool, optional) – If True penalize/attenuate the manipulability proportionally to the distance to the joint limits of the robot
Returns: index – The Yoshikawa manipulability index
Return type:
-
raveutils.kinematics.
find_ik_solutions
(robot, target, iktype, collision_free=True, freeinc=0.1)[source]¶ Find all the possible IK solutions
Parameters: - robot (orpy.Robot) – The OpenRAVE robot
- target (array_like or orpy.Ray) – The target in the task space (Cartesian). A target can be defined as a Ray (position and direction) which is 5D or as an homogeneous transformation which is 6D.
- iktype (orpy.IkParameterizationType) – Inverse kinematics type to use. Supported values: orpy.IkParameterizationType.Transform6D and orpy.IkParameterizationType.TranslationDirection5D
- collision_free (bool, optional) – If true, find only collision-free solutions
- freeinc (float, optional) – The free increment (discretization) to be used for the free DOF when the target is 5D.
Returns: solutions – The list of IK solutions found
Return type: list
-
raveutils.kinematics.
load_ikfast
(robot, iktype, freejoints=['J6'], freeinc=[0.01], autogenerate=True)[source]¶ Load the IKFast solver
Parameters: - robot (orpy.Robot) – The OpenRAVE robot
- iktype (orpy.IkParameterizationType) – Inverse kinematics type to be used
- freeinc (list) – The increment (discretization) to be used for the free DOF when the target iktype is TranslationDirection5D
- autogenerate (bool, optional) – If true, auto-generate the IKFast solver
Returns: success – True if succeeded, False otherwise
Return type:
-
raveutils.kinematics.
load_link_stats
(robot, xyzdelta=0.01, autogenerate=True)[source]¶ Load/generate the Link Statistics database which contains statistics on body links like swept volumes.
When using link statics, it is possible to set the joints weights and resolutions so that planning is fastest. The xyzdelta parameter specifies the smallest object that can be found in the environment, this becomes the new discretization factor when checking collision. Higher values mean faster planning.
Parameters: Returns: success – True if succeeded, False otherwise
Return type:
Meshes¶
-
raveutils.mesh.
trimesh_from_point_cloud
(cloud)[source]¶ Convert a point cloud into a convex hull trimesh
Parameters: cloud (array_like) – The input point cloud. It can be pcl.Cloud
ornumpy.array
Returns: - vertices (array_like) – The trimesh vertices
- faces (array_like) – The trimesh faces
See also
scipy.spatial.ConvexHull
- For more details about convex hulls
Planning¶
-
raveutils.planning.
plan_cartesian_twist
(robot, twist, num_waypoints=10)[source]¶ Plan the cartesian trajectory to apply the given twist to the current robot configuration
Parameters: - robot (orpy.Robot) – The OpenRAVE robot
- twist (array_like) – The twist to be applied to the end-effector
- num_waypoints (int) – Number of waypoints to be used by the trajectory
Returns: traj – Planned trajectory. If plan fails, this function returns None.
Return type: orpy.Trajectory
-
raveutils.planning.
plan_to_joint_configuration
(robot, qgoal, pname='BiRRT', max_iters=20, max_ppiters=40, try_swap=False)[source]¶ Plan a trajectory to the given qgoal configuration.
Parameters: - robot (orpy.Robot) – The OpenRAVE robot
- qgoal (array_like) – The goal configuration
- pname (str) – Name of the planning algorithm. Available options are: BasicRRT, BiRRT
- max_iters (float) – Maximum iterations for the planning stage
- max_ppiters (float) – Maximum iterations for the post-processing stage. It will use a parabolic smoother wich short-cuts the trajectory and then smooths it
- try_swap (bool) – If set, will compute the direct and reversed trajectory. The minimum duration trajectory is used.
Returns: traj – Planned trajectory. If plan fails, this function returns None.
Return type: orpy.Trajectory
-
raveutils.planning.
retime_trajectory
(robot, traj, method)[source]¶ Retime an OpenRAVE trajectory using the specified method.
Parameters: - robot (orpy.Robot) – The OpenRAVE robot
- traj (orpy.Trajectory) – The traj to be retimed. The time paremetrization will be overwritten.
- method (str) – Retiming method. Available options are: LinearTrajectoryRetimer, ParabolicTrajectoryRetimer, CubicTrajectoryRetimer
Returns: status – Flag indicating the status of the trajectory retiming. It can be: Failed, HasSolution, Interrupted or InterruptedWithSolution.
Return type: orpy.PlannerStatus
-
raveutils.planning.
ros_trajectory_from_openrave
(robot_name, traj)[source]¶ Convert an OpenRAVE trajectory into a ROS JointTrajectory message.
Parameters: - robot_name (str) – The robot name in OpenRAVE
- traj (orpy.Trajectory) – The input OpenRAVE trajectory
Returns: ros_traj – The equivalent ROS JointTrajectory message
Return type: trajectory_msgs/JointTrajectory
-
raveutils.planning.
trajectory_from_waypoints
(robot, waypoints)[source]¶ Generate an OpenRAVE trajectory using the given waypoints.
Parameters: - robot (orpy.Robot) – The OpenRAVE robot
- waypoints (list) – List of waypoints (joint configurations)
Returns: traj – Resulting OpenRAVE trajectory.
Return type: orpy.Trajectory
Transforms¶
-
raveutils.transforms.
compute_twist
(T0, T1)[source]¶ Compute the twist between two homogeneous transformations: twist = T1 - T0
Parameters: - T0 (array_like) – Initial homogeneous transformation
- T1 (array_like) – Final homogeneous transformation
-
raveutils.transforms.
counterclockwise_hull
(hull)[source]¶ Make the edges counterclockwise order
Parameters: hull (scipy.spatial.ConvexHull) – Convex hull to be re-ordered.
Visual¶
-
raveutils.visual.
draw_axes
(env, transform, dist=0.03, linewidth=2)[source]¶ Draw an RGB set of axes into the OpenRAVE environment.
Parameters: Returns: h – The total axes added to the scene.
Return type: orpy.GraphHandle
-
raveutils.visual.
draw_plane
(env, transform, extents=(4, 4), texture=None)[source]¶ Draw a plane into the OpenRAVE environment.
Parameters: - env (orpy.Environment) – The OpenRAVE environment
- transform (array_like) – Transform that represents the plane. The origin of the plane corresponds to the position of the transform. Axis Z of the transform is used as the plane normal
- extents (list) – The length and width of the plane (meters)
- texture (array_like) – Texture of the drawn plane. It must have a size N*M*4. The last dimension corresponds to the RGBA channels.
Returns: h – Handles holding the plot.
Return type: orpy.GraphHandle
-
raveutils.visual.
draw_point
(env, point, size=10, color=(0, 1, 0))[source]¶ Draw a colored point into the OpenRAVE environment.
Parameters: - env (orpy.Environment) – The OpenRAVE environment
- point (array_like) – XYZ position of the point
- size (float) – Size of the point (pixels)
- color (array_like) – Color of the point in the format (red, green, blue, alpha)
Returns: h – Handles of the plot. This is require for the point to stay on the environment
Return type: orpy.GraphHandle
-
raveutils.visual.
draw_ray
(env, ray, dist=0.03, linewidth=2, color=None)[source]¶ Draw a ray as an arrow + line into the OpenRAVE environment.
Parameters: - env (orpy.Environment) – The OpenRAVE environment
- ray (orpy.ray) – The input ray with the position and direction of the arrow
- dist (float) – Length of the line
- linewidth (float) – Linewidth of the arrow and line (pixels)
- color (array_like) – Color of the arrow in the format (red, green, blue, alpha)
Returns: h – Handles holding the plot.
Return type: orpy.GraphHandle