Public Member Functions | Protected Attributes
constrained_ik::ConstrainedIKPlugin Class Reference

This class represents the CLIK IK Solver plugin for moveit. More...

#include <constrained_ik_plugin.h>

Inheritance diagram for constrained_ik::ConstrainedIKPlugin:
Inheritance graph
[legend]

List of all members.

Public Member Functions

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.
bool getPositionFK (const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const override
 See base class for documentation.
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
 See base class for documentation.
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) override
 See base class for documentation.
virtual bool isActive () const
 Indicates whether a solver is active.
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
 See base class for documentation.
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
 See base class for documentation.
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
 See base class for documentation.
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
 See base class for documentation.

Protected Attributes

bool active_
int dimension_
std::vector< std::string > joint_names_
basic_kin::BasicKin kin_
std::vector< std::string > link_names_
planning_scene::PlanningScenePtr planning_scene_
robot_model::RobotModelPtr robot_model_ptr_
moveit::core::RobotStatePtr robot_state_
boost::shared_ptr< Constrained_IKsolver_

Detailed Description

This class represents the CLIK IK Solver plugin for moveit.

Definition at line 41 of file constrained_ik_plugin.h.


Member Function Documentation

Indicates whether a solver is active.

Returns:
True if currently solving, otherwise false

Definition at line 47 of file constrained_ik_plugin.cpp.


Member Data Documentation

Indicates status of the kinematic solver

Definition at line 117 of file constrained_ik_plugin.h.

Number of joints

Definition at line 119 of file constrained_ik_plugin.h.

std::vector<std::string> constrained_ik::ConstrainedIKPlugin::joint_names_ [protected]

list of joint names

Definition at line 121 of file constrained_ik_plugin.h.

Constrained IK kinematics object

Definition at line 118 of file constrained_ik_plugin.h.

std::vector<std::string> constrained_ik::ConstrainedIKPlugin::link_names_ [protected]

List of link names

Definition at line 120 of file constrained_ik_plugin.h.

planning_scene::PlanningScenePtr constrained_ik::ConstrainedIKPlugin::planning_scene_ [protected]

Pointer to planning scene which is used for collision queries

Definition at line 122 of file constrained_ik_plugin.h.

robot_model::RobotModelPtr constrained_ik::ConstrainedIKPlugin::robot_model_ptr_ [protected]

Robot Model Ptr

Definition at line 124 of file constrained_ik_plugin.h.

moveit::core::RobotStatePtr constrained_ik::ConstrainedIKPlugin::robot_state_ [protected]

Robot State Ptr

Definition at line 123 of file constrained_ik_plugin.h.

Constrained IK Solver

Definition at line 125 of file constrained_ik_plugin.h.


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


constrained_ik
Author(s): Chris Lewis , Jeremy Zoss , Dan Solomon
autogenerated on Sat Jun 8 2019 19:23:45