#include <constrained_ik_plugin.h>
Public Member Functions | |
ConstrainedIKPlugin () | |
const std::vector< std::string > & | getJointNames () const |
Return all the joint names in the order they are used internally. | |
const std::vector< std::string > & | getLinkNames () const |
Return all the link names in the order they are represented internally. | |
virtual bool | getPositionFK (const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const |
virtual 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 |
virtual bool | initialize (const std::string &robot_description, const std::string &group_name, const std::string &base_name, const std::string &tip_name, double search_discretization) |
Initialization function for the kinematics. | |
bool | isActive () |
bool | isActive () const |
virtual 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 |
virtual 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 |
virtual 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 |
virtual 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 |
Protected Attributes | |
bool | active_ |
int | dimension_ |
std::vector< std::string > | joint_names_ |
basic_kin::BasicKin | kin_ |
std::vector< std::string > | link_names_ |
Definition at line 40 of file constrained_ik_plugin.h.
Definition at line 49 of file constrained_ik_plugin.cpp.
const std::vector< std::string > & constrained_ik::ConstrainedIKPlugin::getJointNames | ( | ) | const [virtual] |
Return all the joint names in the order they are used internally.
Implements kinematics::KinematicsBase.
Definition at line 292 of file constrained_ik_plugin.cpp.
const std::vector< std::string > & constrained_ik::ConstrainedIKPlugin::getLinkNames | ( | ) | const [virtual] |
Return all the link names in the order they are represented internally.
Implements kinematics::KinematicsBase.
Definition at line 298 of file constrained_ik_plugin.cpp.
bool constrained_ik::ConstrainedIKPlugin::getPositionFK | ( | const std::vector< std::string > & | link_names, |
const std::vector< double > & | joint_angles, | ||
std::vector< geometry_msgs::Pose > & | poses | ||
) | const [virtual] |
Implements kinematics::KinematicsBase.
Definition at line 254 of file constrained_ik_plugin.cpp.
bool constrained_ik::ConstrainedIKPlugin::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 [virtual] |
Implements kinematics::KinematicsBase.
Definition at line 102 of file constrained_ik_plugin.cpp.
bool constrained_ik::ConstrainedIKPlugin::initialize | ( | const std::string & | robot_description, |
const std::string & | group_name, | ||
const std::string & | base_name, | ||
const std::string & | tip_name, | ||
double | search_discretization | ||
) | [virtual] |
Initialization function for the kinematics.
Implements kinematics::KinematicsBase.
Definition at line 69 of file constrained_ik_plugin.cpp.
Definition at line 53 of file constrained_ik_plugin.cpp.
bool constrained_ik::ConstrainedIKPlugin::isActive | ( | ) | const |
Definition at line 61 of file constrained_ik_plugin.cpp.
bool constrained_ik::ConstrainedIKPlugin::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 [virtual] |
Implements kinematics::KinematicsBase.
Definition at line 155 of file constrained_ik_plugin.cpp.
bool constrained_ik::ConstrainedIKPlugin::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 [virtual] |
Implements kinematics::KinematicsBase.
Definition at line 167 of file constrained_ik_plugin.cpp.
bool constrained_ik::ConstrainedIKPlugin::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 [virtual] |
Implements kinematics::KinematicsBase.
Definition at line 179 of file constrained_ik_plugin.cpp.
bool constrained_ik::ConstrainedIKPlugin::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 [virtual] |
Implements kinematics::KinematicsBase.
Definition at line 191 of file constrained_ik_plugin.cpp.
bool constrained_ik::ConstrainedIKPlugin::active_ [protected] |
Definition at line 113 of file constrained_ik_plugin.h.
int constrained_ik::ConstrainedIKPlugin::dimension_ [protected] |
Definition at line 115 of file constrained_ik_plugin.h.
std::vector<std::string> constrained_ik::ConstrainedIKPlugin::joint_names_ [protected] |
Definition at line 116 of file constrained_ik_plugin.h.
Definition at line 114 of file constrained_ik_plugin.h.
std::vector<std::string> constrained_ik::ConstrainedIKPlugin::link_names_ [protected] |
Definition at line 116 of file constrained_ik_plugin.h.