Public Member Functions | Private Member Functions | List of all members
kinematics::SolverUsingCRAndSRJacobian Class Reference

#include <kinematics.h>

Inheritance diagram for kinematics::SolverUsingCRAndSRJacobian:
Inheritance graph
[legend]

Public Member Functions

virtual MatrixXd jacobian (Manipulator *manipulator, Name tool_name)
 
virtual void setOption (const void *arg)
 
virtual void solveForwardKinematics (Manipulator *manipulator)
 
virtual bool solveInverseKinematics (Manipulator *manipulator, Name tool_name, Pose target_pose, std::vector< JointValue > *goal_joint_value)
 
 SolverUsingCRAndSRJacobian ()
 
virtual ~SolverUsingCRAndSRJacobian ()
 
- Public Member Functions inherited from robotis_manipulator::Kinematics
 Kinematics ()
 
virtual ~Kinematics ()
 

Private Member Functions

void forwardSolverUsingChainRule (Manipulator *manipulator, Name component_name)
 
bool inverseSolverUsingSRJacobian (Manipulator *manipulator, Name tool_name, Pose target_pose, std::vector< JointValue > *goal_joint_value)
 

Detailed Description

Definition at line 59 of file kinematics.h.

Constructor & Destructor Documentation

kinematics::SolverUsingCRAndSRJacobian::SolverUsingCRAndSRJacobian ( )
inline

Definition at line 66 of file kinematics.h.

virtual kinematics::SolverUsingCRAndSRJacobian::~SolverUsingCRAndSRJacobian ( )
inlinevirtual

Definition at line 67 of file kinematics.h.

Member Function Documentation

void SolverUsingCRAndSRJacobian::forwardSolverUsingChainRule ( Manipulator manipulator,
Name  component_name 
)
private

Definition at line 242 of file kinematics.cpp.

bool SolverUsingCRAndSRJacobian::inverseSolverUsingSRJacobian ( Manipulator manipulator,
Name  tool_name,
Pose  target_pose,
std::vector< JointValue > *  goal_joint_value 
)
private

Definition at line 284 of file kinematics.cpp.

Eigen::MatrixXd SolverUsingCRAndSRJacobian::jacobian ( Manipulator manipulator,
Name  tool_name 
)
virtual

Implements robotis_manipulator::Kinematics.

Definition at line 185 of file kinematics.cpp.

void SolverUsingCRAndSRJacobian::setOption ( const void *  arg)
virtual

Implements robotis_manipulator::Kinematics.

Definition at line 183 of file kinematics.cpp.

void SolverUsingCRAndSRJacobian::solveForwardKinematics ( Manipulator manipulator)
virtual

Implements robotis_manipulator::Kinematics.

Definition at line 230 of file kinematics.cpp.

bool SolverUsingCRAndSRJacobian::solveInverseKinematics ( Manipulator manipulator,
Name  tool_name,
Pose  target_pose,
std::vector< JointValue > *  goal_joint_value 
)
virtual

Implements robotis_manipulator::Kinematics.

Definition at line 235 of file kinematics.cpp.


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


open_manipulator_libs
Author(s): Darby Lim , Hye-Jong KIM , Ryan Shim , Yong-Ho Na
autogenerated on Mon Jun 10 2019 14:12:00