Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
srv_kinematics_plugin::SrvKinematicsPlugin Class Reference

Specific implementation of kinematics using ROS service calls to communicate with external IK solvers. This version can be used with any robot. Supports non-chain kinematic groups. More...

#include <srv_kinematics_plugin.h>

Inheritance diagram for srv_kinematics_plugin::SrvKinematicsPlugin:
Inheritance graph
[legend]

Public Member Functions

const std::vector< std::string > & getJointNames () const override
 Return all the joint names in the order they are used internally. More...
 
const std::vector< std::string > & getLinkNames () const override
 Return all the link names in the order they are represented internally. More...
 
bool getPositionFK (const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const override
 
bool getPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
 
const std::vector< std::string > & getVariableNames () const
 Return all the variable names in the order they are represented internally. More...
 
bool initialize (const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_name, const std::vector< std::string > &tip_frames, double search_discretization) override
 
bool searchPositionIK (const geometry_msgs::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::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
 
bool searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
 
bool searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
 
bool searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
 
bool searchPositionIK (const std::vector< geometry_msgs::Pose > &ik_poses, 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::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const moveit::core::RobotState *context_state=nullptr) const override
 
 SrvKinematicsPlugin ()
 Default constructor. More...
 
- Public Member Functions inherited from kinematics::KinematicsBase
virtual const std::string & getBaseFrame () const
 
double getDefaultTimeout () const
 
virtual const std::string & getGroupName () const
 
virtual bool getPositionIK (const std::vector< geometry_msgs::Pose > &ik_poses, const std::vector< double > &ik_seed_state, std::vector< std::vector< double > > &solutions, KinematicsResult &result, const kinematics::KinematicsQueryOptions &options) const
 
virtual void getRedundantJoints (std::vector< unsigned int > &redundant_joint_indices) const
 
double getSearchDiscretization (int joint_index=0) const
 
std::vector< DiscretizationMethodgetSupportedDiscretizationMethods () const
 
virtual const std::string & getTipFrame () const
 
virtual const std::vector< std::string > & getTipFrames () const
 
virtual bool initialize (const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)
 
virtual bool initialize (const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization)
 
 KinematicsBase ()
 
void setDefaultTimeout (double timeout)
 
bool setRedundantJoints (const std::vector< std::string > &redundant_joint_names)
 
void setSearchDiscretization (const std::map< int, double > &discretization)
 
void setSearchDiscretization (double sd)
 
virtual void setValues (const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)
 
virtual void setValues (const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization)
 
virtual bool supportsGroup (const moveit::core::JointModelGroup *jmg, std::string *error_text_out=nullptr) const
 
virtual ~KinematicsBase ()
 

Protected Member Functions

bool setRedundantJoints (const std::vector< unsigned int > &redundant_joint_indices) override
 
- Protected Member Functions inherited from kinematics::KinematicsBase
bool lookupParam (const std::string &param, T &val, const T &default_val) const
 
void storeValues (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)
 

Private Member Functions

int getJointIndex (const std::string &name) const
 
bool isRedundantJoint (unsigned int index) const
 
bool timedOut (const ros::WallTime &start_time, double duration) const
 

Private Attributes

bool active_
 
unsigned int dimension_
 
moveit_msgs::KinematicSolverInfo ik_group_info_
 
std::shared_ptr< ros::ServiceClientik_service_client_
 
const moveit::core::JointModelGroupjoint_model_group_
 
int num_possible_redundant_joints_
 
moveit::core::RobotStatePtr robot_state_
 

Additional Inherited Members

- Public Types inherited from kinematics::KinematicsBase
typedef boost::function< void(const geometry_msgs::Pose &, const std::vector< double > &, moveit_msgs::MoveItErrorCodes &)> IKCallbackFn
 
- Static Public Attributes inherited from kinematics::KinematicsBase
static const MOVEIT_KINEMATICS_BASE_EXPORT double DEFAULT_SEARCH_DISCRETIZATION
 
static const MOVEIT_KINEMATICS_BASE_EXPORT double DEFAULT_TIMEOUT
 
- Protected Attributes inherited from kinematics::KinematicsBase
std::string base_frame_
 
double default_timeout_
 
std::string group_name_
 
std::map< int, double > redundant_joint_discretization_
 
std::vector< unsigned int > redundant_joint_indices_
 
std::string robot_description_
 
moveit::core::RobotModelConstPtr robot_model_
 
double search_discretization_
 
std::vector< DiscretizationMethodsupported_methods_
 
std::string tip_frame_
 
std::vector< std::string > tip_frames_
 

Detailed Description

Specific implementation of kinematics using ROS service calls to communicate with external IK solvers. This version can be used with any robot. Supports non-chain kinematic groups.

Definition at line 97 of file srv_kinematics_plugin.h.

Constructor & Destructor Documentation

◆ SrvKinematicsPlugin()

srv_kinematics_plugin::SrvKinematicsPlugin::SrvKinematicsPlugin ( )

Default constructor.

Definition at line 83 of file srv_kinematics_plugin.cpp.

Member Function Documentation

◆ getJointIndex()

int srv_kinematics_plugin::SrvKinematicsPlugin::getJointIndex ( const std::string &  name) const
private

Definition at line 187 of file srv_kinematics_plugin.cpp.

◆ getJointNames()

const std::vector< std::string > & srv_kinematics_plugin::SrvKinematicsPlugin::getJointNames ( ) const
overridevirtual

Return all the joint names in the order they are used internally.

Implements kinematics::KinematicsBase.

Definition at line 418 of file srv_kinematics_plugin.cpp.

◆ getLinkNames()

const std::vector< std::string > & srv_kinematics_plugin::SrvKinematicsPlugin::getLinkNames ( ) const
overridevirtual

Return all the link names in the order they are represented internally.

Implements kinematics::KinematicsBase.

Definition at line 423 of file srv_kinematics_plugin.cpp.

◆ getPositionFK()

bool srv_kinematics_plugin::SrvKinematicsPlugin::getPositionFK ( const std::vector< std::string > &  link_names,
const std::vector< double > &  joint_angles,
std::vector< geometry_msgs::Pose > &  poses 
) const
overridevirtual

Implements kinematics::KinematicsBase.

Definition at line 397 of file srv_kinematics_plugin.cpp.

◆ getPositionIK()

bool srv_kinematics_plugin::SrvKinematicsPlugin::getPositionIK ( const geometry_msgs::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
std::vector< double > &  solution,
moveit_msgs::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const
overridevirtual

Implements kinematics::KinematicsBase.

Definition at line 202 of file srv_kinematics_plugin.cpp.

◆ getVariableNames()

const std::vector< std::string > & srv_kinematics_plugin::SrvKinematicsPlugin::getVariableNames ( ) const

Return all the variable names in the order they are represented internally.

Definition at line 428 of file srv_kinematics_plugin.cpp.

◆ initialize()

bool srv_kinematics_plugin::SrvKinematicsPlugin::initialize ( const moveit::core::RobotModel robot_model,
const std::string &  group_name,
const std::string &  base_name,
const std::vector< std::string > &  tip_frames,
double  search_discretization 
)
overridevirtual

Reimplemented from kinematics::KinematicsBase.

Definition at line 87 of file srv_kinematics_plugin.cpp.

◆ isRedundantJoint()

bool srv_kinematics_plugin::SrvKinematicsPlugin::isRedundantJoint ( unsigned int  index) const
private

Definition at line 179 of file srv_kinematics_plugin.cpp.

◆ searchPositionIK() [1/5]

bool srv_kinematics_plugin::SrvKinematicsPlugin::searchPositionIK ( const geometry_msgs::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::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const
overridevirtual

Implements kinematics::KinematicsBase.

Definition at line 243 of file srv_kinematics_plugin.cpp.

◆ searchPositionIK() [2/5]

bool srv_kinematics_plugin::SrvKinematicsPlugin::searchPositionIK ( const geometry_msgs::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
const std::vector< double > &  consistency_limits,
std::vector< double > &  solution,
moveit_msgs::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const
overridevirtual

Implements kinematics::KinematicsBase.

Definition at line 223 of file srv_kinematics_plugin.cpp.

◆ searchPositionIK() [3/5]

bool srv_kinematics_plugin::SrvKinematicsPlugin::searchPositionIK ( const geometry_msgs::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
std::vector< double > &  solution,
const IKCallbackFn solution_callback,
moveit_msgs::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const
overridevirtual

Implements kinematics::KinematicsBase.

Definition at line 232 of file srv_kinematics_plugin.cpp.

◆ searchPositionIK() [4/5]

bool srv_kinematics_plugin::SrvKinematicsPlugin::searchPositionIK ( const geometry_msgs::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
std::vector< double > &  solution,
moveit_msgs::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const
overridevirtual

Implements kinematics::KinematicsBase.

Definition at line 212 of file srv_kinematics_plugin.cpp.

◆ searchPositionIK() [5/5]

bool srv_kinematics_plugin::SrvKinematicsPlugin::searchPositionIK ( const std::vector< geometry_msgs::Pose > &  ik_poses,
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::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions(),
const moveit::core::RobotState context_state = nullptr 
) const
overridevirtual

Reimplemented from kinematics::KinematicsBase.

Definition at line 257 of file srv_kinematics_plugin.cpp.

◆ setRedundantJoints()

bool srv_kinematics_plugin::SrvKinematicsPlugin::setRedundantJoints ( const std::vector< unsigned int > &  redundant_joint_indices)
overrideprotectedvirtual

Reimplemented from kinematics::KinematicsBase.

Definition at line 163 of file srv_kinematics_plugin.cpp.

◆ timedOut()

bool srv_kinematics_plugin::SrvKinematicsPlugin::timedOut ( const ros::WallTime start_time,
double  duration 
) const
private

Definition at line 197 of file srv_kinematics_plugin.cpp.

Member Data Documentation

◆ active_

bool srv_kinematics_plugin::SrvKinematicsPlugin::active_
private

Definition at line 202 of file srv_kinematics_plugin.h.

◆ dimension_

unsigned int srv_kinematics_plugin::SrvKinematicsPlugin::dimension_
private

Stores information for the inverse kinematics solver

Definition at line 206 of file srv_kinematics_plugin.h.

◆ ik_group_info_

moveit_msgs::KinematicSolverInfo srv_kinematics_plugin::SrvKinematicsPlugin::ik_group_info_
private

Internal variable that indicates whether solvers are configured and ready

Definition at line 204 of file srv_kinematics_plugin.h.

◆ ik_service_client_

std::shared_ptr<ros::ServiceClient> srv_kinematics_plugin::SrvKinematicsPlugin::ik_service_client_
private

Definition at line 214 of file srv_kinematics_plugin.h.

◆ joint_model_group_

const moveit::core::JointModelGroup* srv_kinematics_plugin::SrvKinematicsPlugin::joint_model_group_
private

Dimension of the group

Definition at line 208 of file srv_kinematics_plugin.h.

◆ num_possible_redundant_joints_

int srv_kinematics_plugin::SrvKinematicsPlugin::num_possible_redundant_joints_
private

Definition at line 212 of file srv_kinematics_plugin.h.

◆ robot_state_

moveit::core::RobotStatePtr srv_kinematics_plugin::SrvKinematicsPlugin::robot_state_
private

Definition at line 210 of file srv_kinematics_plugin.h.


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


moveit_kinematics
Author(s): Dave Coleman , Ioan Sucan , Sachin Chitta
autogenerated on Fri May 3 2024 02:29:33