MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
pose_ik_plugin::PoseIKPlugin Class Reference

PickNik's implementation of a kinematics solver using MoveIt! native types. More...

#include <pose_ik_plugin.hpp>

Inheritance diagram for pose_ik_plugin::PoseIKPlugin:
Collaboration diagram for pose_ik_plugin::PoseIKPlugin:

Public Member Functions

 PoseIKPlugin ()=default
 
bool initialize (const rclcpp::Node::SharedPtr &node, const moveit_pro::base::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization) override
 
bool initialize (const moveit_pro::base::RobotModel &robot_model, const std::string &group_name, const std::string &tip_frame)
 Initialize the plugin without a ROS 2 node.
 
bool getPositionIK (const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const moveit_pro::base::kinematics::KinematicsQueryOptions &options=moveit_pro::base::kinematics::KinematicsQueryOptions()) const override
 
bool searchPositionIK (const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const moveit_pro::base::kinematics::KinematicsQueryOptions &options=moveit_pro::base::kinematics::KinematicsQueryOptions()) const override
 
bool searchPositionIK (const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const moveit_pro::base::kinematics::KinematicsQueryOptions &options=moveit_pro::base::kinematics::KinematicsQueryOptions()) const override
 
bool searchPositionIK (const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::msg::MoveItErrorCodes &error_code, const moveit_pro::base::kinematics::KinematicsQueryOptions &options=moveit_pro::base::kinematics::KinematicsQueryOptions()) const override
 
bool searchPositionIK (const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::msg::MoveItErrorCodes &error_code, const moveit_pro::base::kinematics::KinematicsQueryOptions &options=moveit_pro::base::kinematics::KinematicsQueryOptions()) const override
 
bool getPositionFK (const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::msg::Pose > &poses) const override
 
const std::vector< std::string > & getJointNames () const override
 
const std::vector< std::string > & getLinkNames () const override
 
void setParams (const pose_ik::Params &params)
 Set IK parameters directly, bypassing the ROS 2 parameter listener.
 

Detailed Description

PickNik's implementation of a kinematics solver using MoveIt! native types.

This class implements MoveIt's KinematicsBase interface around pose_ik::solveIK().

Constructor & Destructor Documentation

◆ PoseIKPlugin()

pose_ik_plugin::PoseIKPlugin::PoseIKPlugin ( )
default

Member Function Documentation

◆ getJointNames()

const std::vector< std::string > & pose_ik_plugin::PoseIKPlugin::getJointNames ( ) const
override

◆ getLinkNames()

const std::vector< std::string > & pose_ik_plugin::PoseIKPlugin::getLinkNames ( ) const
override

◆ getPositionFK()

bool pose_ik_plugin::PoseIKPlugin::getPositionFK ( const std::vector< std::string > &  link_names,
const std::vector< double > &  joint_angles,
std::vector< geometry_msgs::msg::Pose > &  poses 
) const
override

◆ getPositionIK()

bool pose_ik_plugin::PoseIKPlugin::getPositionIK ( const geometry_msgs::msg::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
std::vector< double > &  solution,
moveit_msgs::msg::MoveItErrorCodes &  error_code,
const moveit_pro::base::kinematics::KinematicsQueryOptions &  options = moveit_pro::base::kinematics::KinematicsQueryOptions() 
) const
override

◆ initialize() [1/2]

bool pose_ik_plugin::PoseIKPlugin::initialize ( const moveit_pro::base::RobotModel &  robot_model,
const std::string &  group_name,
const std::string &  tip_frame 
)

Initialize the plugin without a ROS 2 node.

This version of initialize does not create a parameter listener, so parameters must be set directly using setParams(), or otherwise defaults will be used. This is useful when you don't need ROS 2 parameter loading and want to avoid creating a node.

The base frame is automatically set to the first link in the group.

Parameters
robot_modelThe robot model
group_nameName of the joint model group
tip_frameTip frame name for the IK solver
Returns
true if initialization succeeds, false otherwise

◆ initialize() [2/2]

bool pose_ik_plugin::PoseIKPlugin::initialize ( const rclcpp::Node::SharedPtr &  node,
const moveit_pro::base::RobotModel &  robot_model,
const std::string &  group_name,
const std::string &  base_frame,
const std::vector< std::string > &  tip_frames,
double  search_discretization 
)
override

Implements the main MoveIt 2 initialize interface, requiring a ROS 2 node.

◆ searchPositionIK() [1/4]

bool pose_ik_plugin::PoseIKPlugin::searchPositionIK ( const geometry_msgs::msg::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
const std::vector< double > &  consistency_limits,
std::vector< double > &  solution,
const IKCallbackFn &  solution_callback,
moveit_msgs::msg::MoveItErrorCodes &  error_code,
const moveit_pro::base::kinematics::KinematicsQueryOptions &  options = moveit_pro::base::kinematics::KinematicsQueryOptions() 
) const
override

◆ searchPositionIK() [2/4]

bool pose_ik_plugin::PoseIKPlugin::searchPositionIK ( const geometry_msgs::msg::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
const std::vector< double > &  consistency_limits,
std::vector< double > &  solution,
moveit_msgs::msg::MoveItErrorCodes &  error_code,
const moveit_pro::base::kinematics::KinematicsQueryOptions &  options = moveit_pro::base::kinematics::KinematicsQueryOptions() 
) const
override

◆ searchPositionIK() [3/4]

bool pose_ik_plugin::PoseIKPlugin::searchPositionIK ( const geometry_msgs::msg::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
std::vector< double > &  solution,
const IKCallbackFn &  solution_callback,
moveit_msgs::msg::MoveItErrorCodes &  error_code,
const moveit_pro::base::kinematics::KinematicsQueryOptions &  options = moveit_pro::base::kinematics::KinematicsQueryOptions() 
) const
override

◆ searchPositionIK() [4/4]

bool pose_ik_plugin::PoseIKPlugin::searchPositionIK ( const geometry_msgs::msg::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
std::vector< double > &  solution,
moveit_msgs::msg::MoveItErrorCodes &  error_code,
const moveit_pro::base::kinematics::KinematicsQueryOptions &  options = moveit_pro::base::kinematics::KinematicsQueryOptions() 
) const
override

◆ setParams()

void pose_ik_plugin::PoseIKPlugin::setParams ( const pose_ik::Params &  params)

Set IK parameters directly, bypassing the ROS 2 parameter listener.

This allows programmatic configuration of IK solver behavior without needing to set ROS 2 parameters. Once set, these parameters will be used for all subsequent IK queries instead of loading from the parameter server.

Parameters
paramsThe IK parameters to use.

The documentation for this class was generated from the following files: