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::core::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 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 kinematics::KinematicsQueryOptions &options=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 kinematics::KinematicsQueryOptions &options=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 kinematics::KinematicsQueryOptions &options=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 kinematics::KinematicsQueryOptions &options=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 kinematics::KinematicsQueryOptions &options=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
 

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 kinematics::KinematicsQueryOptions &  options = kinematics::KinematicsQueryOptions() 
) const
override

◆ initialize()

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

◆ 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 kinematics::KinematicsQueryOptions &  options = 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 kinematics::KinematicsQueryOptions &  options = 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 kinematics::KinematicsQueryOptions &  options = 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 kinematics::KinematicsQueryOptions &  options = kinematics::KinematicsQueryOptions() 
) const
override

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