This package contains the plugin implemenations of REACH kinematics, evaluation, and display interfaces
This plugin uses MoveIt! to calculate the manipulability of a robot pose. Higher manipulability results in higher pose score.
Parameters:
planning_group
- The name of the planning group with which to evaluate the manipulability of a given robot pose
This plugin uses the MoveIt! collision environment to calculate the distance to closest collision for a robot pose. That distance value is then used to score the robot pose. Larger distance to closest collision results in higher pose score.
Parameters:
planning_group
- The name of the planning group to be used to solve the robot's inverse kinematics
distance_threshold
- The distance between 2 closest surfaces to collision under which an inverse kinematics solution will be considered invalid
collision_mesh_filename
- The filename (in ROS package URI format) of the reach object mesh to be used to do collision checking
- Example: `package://<your_package>//.stl
collision_mesh_frame
- The name of the TF frame in which the collision mesh of the reach object should be placed
touch_links
- The names of the robot links with which the reach object mesh is allowed to collide
exponent
- score = (closest_distance_to_collision - distance_threshold)^exponent.
This plugin uses the MoveIt! robot model to calculate a robot pose score based on how much the pose deviates from the center of the joint range. Robot poses that are closer to the center of the joint range result in higher pose scores.
Parameters:
planning_group
- The name of the planning_group with which to evaluate the joint penalty
This plugin uses MoveIt! kinematics solvers and collision checking to produce collision aware IK solutions
Parameters:
planning_group
- Name of the planning group
distance_threshold
- The distance from nearest collision at which to invalidate an IK solution. For example, if this parameter is set to 0.1m, then IK solutions whose distance to nearest collision is less than 0.1m will be invalidated
collision_mesh_filename
- The file path to the collision mesh model of the workpiece, in the
package://
or 'file://' URI format
- The file path to the collision mesh model of the workpiece, in the
collision_mesh_frame
- The TF frame of reference of the collision mesh
touch_links
- The TF links that are allowed to be in contact with the collision mesh
evaluation_plugin
- The name (and parameters) of the evaluation plugin to be used to score IK solution poses
This plugin performs the same function as the MoveIt! IK solver plugin above, but calculates IK solutions for a target that has been discretized about its Z-axis by an input angle. The pose with the best score is returned.
Parameters:
planning_group
- Name of the planning group
distance_threshold
- The distance from nearest collision at which to invalidate an IK solution. For example, if this parameter is set to 0.1m, then IK solutions whose distance to nearest collision is less than 0.1m will be invalidated
collision_mesh_filename
- The file path to the collision mesh model of the workpiece, in the
package://
or 'file://' URI format
- The file path to the collision mesh model of the workpiece, in the
collision_mesh_frame
- The TF frame of reference of the collision mesh
touch_links
- The TF links that are allowed to be in contact with the collision mesh
evaluation_plugin
- The name (and parameters) of the evaluation plugin to be used to score IK solution poses
discretization_angle
- The angle (between 0 and pi, in radians) with which to sample each target pose about the Z-axis
This plugin uses the MoveIt! planning environment framework to display the results of the reach study
Parameters:
planning_group
- Name of the planning group
collision_mesh_filename
- The file path to the collision mesh model of the workpiece, in the
package://
or 'file://' URI format
- The file path to the collision mesh model of the workpiece, in the
collision_mesh_frame
- The TF frame of reference of the collision mesh
fixed_frame
- The fixed TF frame in which to display the interactive markers
marker_scale
- The length (in meters) of the arrow markers representing the target Cartesian points