roboplan_ros_py.kinematics
Classes
IK solver wrapper for roboplan Scene objects with ROS message support. |
Module Contents
- class roboplan_ros_py.kinematics.RoboPlanIK(scene, group_name, base_frame, tip_frame, options)
IK solver wrapper for roboplan Scene objects with ROS message support.
This class provides methods to solve IK given ROS Pose messages and returns results as JointState messages or numpy arrays.
Construct an IK solver.
A thin wrapper around the RoboPlan SimpleIK class that manages joint states and group indices. Callers can expect to use the full set of joint states for the Scene.
- Parameters:
scene (roboplan.core.Scene) – RoboPlan Scene object.
group_name (str) – Name of the joint group to use.
base_frame (str) – Base frame for IK.
tip_frame (str) – End effector/tip frame for IK.
options (roboplan.simple_ik.SimpleIkOptions) – Options for the IK solver.
- scene
- group_name
- base_frame
- tip_frame
- options
- _ik_solver
- _start
- _goal
- joint_group_info_
- _q_indices
- solve_ik(target_transform, seed_state=None)
Solve IK for a target transform.
- Parameters:
target_transform (numpy.ndarray) – A pin.SE3 4x4 transformation matrix.
seed_state (Optional[numpy.ndarray]) – Optional seed joint positions, defaults to current pose.
- Returns:
A set of joint positions for the desired pose, or else None.
- Return type:
Optional[numpy.ndarray]