|
| PR2ArmKinematicsPlugin () |
|
bool | isActive () |
| Specifies if the node is active or not.
|
|
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 |
| Given a desired pose of the end-effector, compute the joint angles to reach it.
|
|
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 |
| Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).
|
|
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 |
| Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).
|
|
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 |
| Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines).
|
|
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 |
| Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solutions by stepping through the redundancy (or other numerical routines). The consistency_limit specifies that only certain redundancy positions around those specified in the seed state are admissible and need to be searched.
|
|
bool | getPositionFK (const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::msg::Pose > &poses) const override |
| Given a set of joint angles and a set of links, compute their pose.
|
|
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 |
| Initialization function for the kinematics.
|
|
const std::vector< std::string > & | getJointNames () const override |
| Return all the joint names in the order they are used internally.
|
|
const std::vector< std::string > & | getLinkNames () const override |
| Return all the link names in the order they are represented internally.
|
|
virtual bool | getPositionIK (const std::vector< geometry_msgs::msg::Pose > &ik_poses, const std::vector< double > &ik_seed_state, std::vector< std::vector< double > > &solutions, KinematicsResult &result, const kinematics::KinematicsQueryOptions &options) const |
| Given the desired poses of all end-effectors, compute joint angles that are able to reach it.
|
|
virtual bool | searchPositionIK (const std::vector< geometry_msgs::msg::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::msg::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const moveit::core::RobotState *context_state=nullptr) const |
| Given a set of desired poses for a planning group with multiple end-effectors, search for the joint angles required to reach them. This is useful for e.g. biped robots that need to perform whole-body IK. Not necessary for most robots that have kinematic chains. This particular method is intended for "searching" for a solution by stepping through the redundancy (or other numerical routines).
|
|
virtual bool | searchPositionIK (const std::vector< geometry_msgs::msg::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, const IKCostFn &cost_function, moveit_msgs::msg::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const moveit::core::RobotState *context_state=nullptr) const |
| Given a set of desired poses for a planning group with multiple end-effectors, search for the joint angles required to reach them. This is useful for e.g. biped robots that need to perform whole-body IK. Not necessary for most robots that have kinematic chains. This particular method is intended for "searching" for a solution by stepping through the redundancy (or other numerical routines).
|
|
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) |
| Set the parameters for the solver, for use with non-chain IK solvers.
|
|
virtual const std::string & | getGroupName () const |
| Return the name of the group that the solver is operating on.
|
|
virtual const std::string & | getBaseFrame () const |
| Return the name of the frame in which the solver is operating. This is usually a link name. No namespacing (e.g., no "/" prefix) should be used.
|
|
virtual const std::string & | getTipFrame () const |
| Return the name of the tip frame of the chain on which the solver is operating. This is usually a link name. No namespacing (e.g., no "/" prefix) should be used.
|
|
virtual const std::vector< std::string > & | getTipFrames () const |
| Return the names of the tip frames of the kinematic tree on which the solver is operating. This is usually a link name. No namespacing (e.g., no "/" prefix) should be used.
|
|
virtual bool | setRedundantJoints (const std::vector< unsigned int > &redundant_joint_indices) |
| Set a set of redundant joints for the kinematics solver to use. This can fail, depending on the IK solver and choice of redundant joints!. Also, it sets the discretization values for each redundant joint to a default value.
|
|
bool | setRedundantJoints (const std::vector< std::string > &redundant_joint_names) |
| Set a set of redundant joints for the kinematics solver to use. This function is just a convenience function that calls the previous definition of setRedundantJoints()
|
|
virtual void | getRedundantJoints (std::vector< unsigned int > &redundant_joint_indices) const |
| Get the set of redundant joints.
|
|
virtual bool | supportsGroup (const moveit::core::JointModelGroup *jmg, std::string *error_text_out=nullptr) const |
| Check if this solver supports a given JointModelGroup.
|
|
void | setSearchDiscretization (double sd) |
| Set the search discretization value for all the redundant joints.
|
|
void | setSearchDiscretization (const std::map< int, double > &discretization) |
| Sets individual discretization values for each redundant joint.
|
|
double | getSearchDiscretization (int joint_index=0) const |
| Get the value of the search discretization.
|
|
std::vector< DiscretizationMethod > | getSupportedDiscretizationMethods () const |
| Returns the set of supported kinematics discretization search types. This implementation only supports the DiscretizationMethods::ONE search.
|
|
void | setDefaultTimeout (double timeout) |
| For functions that require a timeout specified but one is not specified using arguments, a default timeout is used, as set by this function (and initialized to KinematicsBase::DEFAULT_TIMEOUT)
|
|
double | getDefaultTimeout () const |
| For functions that require a timeout specified but one is not specified using arguments, this default timeout is used.
|
|
virtual | ~KinematicsBase () |
| Virtual destructor for the interface.
|
|
| KinematicsBase () |
|