#include <op3_kdl.h>
|
void | finalize () |
|
void | initialize (Eigen::MatrixXd pelvis_position, Eigen::MatrixXd pelvis_orientation) |
|
| OP3Kinematics () |
|
void | setJointPosition (Eigen::VectorXd rleg_joint_position, Eigen::VectorXd lleg_joint_position) |
|
void | solveForwardKinematics (std::vector< double_t > &rleg_position, std::vector< double_t > &rleg_orientation, std::vector< double_t > &lleg_position, std::vector< double_t > &lleg_orientation) |
|
bool | solveInverseKinematics (std::vector< double_t > &rleg_output, Eigen::MatrixXd rleg_target_position, Eigen::Quaterniond rleg_target_orientation, std::vector< double_t > &lleg_output, Eigen::MatrixXd lleg_target_position, Eigen::Quaterniond lleg_target_orientation) |
|
virtual | ~OP3Kinematics () |
|
Definition at line 47 of file op3_kdl.h.
OP3Kinematics::OP3Kinematics |
( |
| ) |
|
OP3Kinematics::~OP3Kinematics |
( |
| ) |
|
|
virtual |
void OP3Kinematics::finalize |
( |
| ) |
|
void OP3Kinematics::initialize |
( |
Eigen::MatrixXd |
pelvis_position, |
|
|
Eigen::MatrixXd |
pelvis_orientation |
|
) |
| |
void OP3Kinematics::setJointPosition |
( |
Eigen::VectorXd |
rleg_joint_position, |
|
|
Eigen::VectorXd |
lleg_joint_position |
|
) |
| |
void OP3Kinematics::solveForwardKinematics |
( |
std::vector< double_t > & |
rleg_position, |
|
|
std::vector< double_t > & |
rleg_orientation, |
|
|
std::vector< double_t > & |
lleg_position, |
|
|
std::vector< double_t > & |
lleg_orientation |
|
) |
| |
bool OP3Kinematics::solveInverseKinematics |
( |
std::vector< double_t > & |
rleg_output, |
|
|
Eigen::MatrixXd |
rleg_target_position, |
|
|
Eigen::Quaterniond |
rleg_target_orientation, |
|
|
std::vector< double_t > & |
lleg_output, |
|
|
Eigen::MatrixXd |
lleg_target_position, |
|
|
Eigen::Quaterniond |
lleg_target_orientation |
|
) |
| |
geometry_msgs::Pose OP3Kinematics::lleg_ft_pose_ |
|
protected |
Eigen::VectorXd OP3Kinematics::lleg_joint_position_ |
|
protected |
geometry_msgs::Pose OP3Kinematics::lleg_pose_ |
|
protected |
geometry_msgs::Pose OP3Kinematics::rleg_ft_pose_ |
|
protected |
Eigen::VectorXd OP3Kinematics::rleg_joint_position_ |
|
protected |
geometry_msgs::Pose OP3Kinematics::rleg_pose_ |
|
protected |
The documentation for this class was generated from the following files: