|
| void | bindCartesianPlanning (pybind11::module &parent) |
| |
| void | bindKinematics (pybind11::module &m) |
| |
| std::shared_ptr< pose_ik_plugin::PoseIKPlugin > | registerPoseIKSolver (std::shared_ptr< moveit_pro::base::RobotModel > robot_model, const std::string &group_name, const std::string &tip_frame) |
| | Programmatically registers a PoseIKPlugin solver for a specified joint group.
|
| |
| std::tuple< cartesian_planning::JointSpacePath, std::string > | pathIK (moveit_pro::base::RobotState &robot_state, const moveit_pro::base::JointModelGroup &group, const std::vector< std::string > &tip_names, const cartesian_planning::Path &reference_path, const cartesian_planning::PathIKOptions &options) |
| |
| Eigen::MatrixXd | computeMultiTipJacobian (const moveit_pro::base::RobotState &state, const std::string &group_name, const std::vector< std::string > &tip_link_names, const std::vector< Eigen::Ref< Eigen::Vector3d > > &tip_offsets) |
| |
| void | bindCartesianPlanning (py::module &parent) |
| |
| Eigen::VectorXd | solve_ik (const moveit_pro::base::RobotState &robot_state, const moveit_pro::base::JointModelGroup &group, const std::vector< pose_ik::PoseTarget > &targets, const Eigen::Ref< const Eigen::VectorXd > &seed, double timeout_seconds, const pose_ik::IKValidationFunction &validation_fn, const pose_ik::Params ¶ms) |
| |
| void | bindKinematics (py::module &m) |
| |
| std::shared_ptr< pose_ik_plugin::PoseIKPlugin > moveit_pro_py::kinematics::registerPoseIKSolver |
( |
std::shared_ptr< moveit_pro::base::RobotModel > |
robot_model, |
|
|
const std::string & |
group_name, |
|
|
const std::string & |
tip_frame |
|
) |
| |
Programmatically registers a PoseIKPlugin solver for a specified joint group.
This function creates and initializes a PoseIKPlugin instance and registers it with the robot model as the kinematics solver for the specified group. This allows using PoseIK without needing to load it as a plugin or create a ROS 2 node.
The base frame is automatically set to the first link in the group.
IK parameters can be set directly using setParams() on the returned solver instance, otherwise defaults will be used.
- Parameters
-
| robot_model | The robot model to register the solver with (must not be null) |
| group_name | Name of the joint model group to solve IK for (must exist in robot model) |
| tip_frame | Tip frame name for the IK solver |
- Returns
- Shared pointer to the registered PoseIKPlugin instance.
- Exceptions
-