#include <eff_axis_alignment.h>
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void | AssignScene (ScenePtr scene) override |
|
Eigen::Vector3d | GetAxis (const std::string &frame_name) const |
|
Eigen::Vector3d | GetDirection (const std::string &frame_name) const |
|
void | SetAxis (const std::string &frame_name, const Eigen::Vector3d &axis_in) |
|
void | SetDirection (const std::string &frame_name, const Eigen::Vector3d &dir_in) |
|
int | TaskSpaceDim () override |
|
void | Update (Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi) override |
|
void | Update (Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian) override |
|
std::vector< KinematicFrameRequest > | GetFrames () const |
|
virtual std::vector< TaskVectorEntry > | GetLieGroupIndices () |
|
virtual void | InstantiateBase (const Initializer &init) |
|
virtual void | PreUpdate () |
|
virtual int | TaskSpaceJacobianDim () |
|
virtual void | Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRefConst u, Eigen::VectorXdRef phi, Eigen::MatrixXdRef dphi_dx, Eigen::MatrixXdRef dphi_du) |
|
virtual void | Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRefConst u, Eigen::VectorXdRef phi) |
|
virtual void | Update (Eigen::VectorXdRefConst x, Eigen::VectorXdRefConst u, Eigen::VectorXdRef phi, Eigen::MatrixXdRef dphi_dx, Eigen::MatrixXdRef dphi_du, HessianRef ddphi_ddx, HessianRef ddphi_ddu, HessianRef ddphi_dxdu) |
|
virtual void | Update (Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian, HessianRef hessian) |
|
std::string | GetObjectName () |
|
void | InstantiateObject (const Initializer &init) |
|
| Object () |
|
virtual std::string | Print (const std::string &prepend) const |
|
virtual std::string | type () const |
|
virtual | ~Object () |
|
| InstantiableBase ()=default |
|
virtual | ~InstantiableBase ()=default |
|
std::vector< Initializer > | GetAllTemplates () const override |
|
Initializer | GetInitializerTemplate () override |
|
const EffAxisAlignmentInitializer & | GetParameters () const |
|
virtual void | Instantiate (const EffAxisAlignmentInitializer &init) |
|
void | InstantiateInternal (const Initializer &init) override |
|
Definition at line 42 of file eff_axis_alignment.h.
void exotica::EffAxisAlignment::AssignScene |
( |
ScenePtr |
scene | ) |
|
|
overridevirtual |
Eigen::Vector3d exotica::EffAxisAlignment::GetAxis |
( |
const std::string & |
frame_name | ) |
const |
Eigen::Vector3d exotica::EffAxisAlignment::GetDirection |
( |
const std::string & |
frame_name | ) |
const |
void exotica::EffAxisAlignment::Initialize |
( |
| ) |
|
|
private |
void exotica::EffAxisAlignment::SetAxis |
( |
const std::string & |
frame_name, |
|
|
const Eigen::Vector3d & |
axis_in |
|
) |
| |
void exotica::EffAxisAlignment::SetDirection |
( |
const std::string & |
frame_name, |
|
|
const Eigen::Vector3d & |
dir_in |
|
) |
| |
int exotica::EffAxisAlignment::TaskSpaceDim |
( |
| ) |
|
|
overridevirtual |
Eigen::Matrix3Xd exotica::EffAxisAlignment::axis_ |
|
private |
Eigen::Matrix3Xd exotica::EffAxisAlignment::dir_ |
|
private |
Eigen::Vector3d exotica::EffAxisAlignment::link_axis_position_in_base_ |
|
private |
Eigen::Vector3d exotica::EffAxisAlignment::link_position_in_base_ |
|
private |
visualization_msgs::MarkerArray exotica::EffAxisAlignment::msg_debug_ |
|
private |
int exotica::EffAxisAlignment::N |
int exotica::EffAxisAlignment::n_frames_ |
|
private |
The documentation for this class was generated from the following files: