Exotica
|
#include <eff_axis_alignment.h>
Public Member Functions | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void | AssignScene (ScenePtr scene) override |
void | Update (Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi) override |
void | Update (Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian) override |
int | TaskSpaceDim () override |
void | SetDirection (const std::string &frame_name, const Eigen::Vector3d &dir_in) |
Eigen::Vector3d | GetDirection (const std::string &frame_name) const |
void | SetAxis (const std::string &frame_name, const Eigen::Vector3d &axis_in) |
Eigen::Vector3d | GetAxis (const std::string &frame_name) const |
Public Member Functions inherited from exotica::TaskMap | |
virtual void | InstantiateBase (const Initializer &init) |
virtual void | Update (Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian, HessianRef hessian) |
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) |
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 int | TaskSpaceJacobianDim () |
virtual void | PreUpdate () |
virtual std::vector< TaskVectorEntry > | GetLieGroupIndices () |
std::vector< KinematicFrameRequest > | GetFrames () const |
Public Member Functions inherited from exotica::Object | |
Object () | |
virtual | ~Object () |
virtual std::string | type () const |
Type Information wrapper: must be virtual so that it is polymorphic... More... | |
std::string | GetObjectName () |
void | InstantiateObject (const Initializer &init) |
virtual std::string | Print (const std::string &prepend) const |
Public Member Functions inherited from exotica::InstantiableBase | |
InstantiableBase ()=default | |
virtual | ~InstantiableBase ()=default |
virtual std::vector< Initializer > | GetAllTemplates () const =0 |
Public Member Functions inherited from exotica::Instantiable< EffAxisAlignmentInitializer > | |
void | InstantiateInternal (const Initializer &init) override |
Initializer | GetInitializerTemplate () override |
std::vector< Initializer > | GetAllTemplates () const override |
virtual void | Instantiate (const EffAxisAlignmentInitializer &init) |
const EffAxisAlignmentInitializer & | GetParameters () const |
Public Attributes | |
int | N |
Public Attributes inherited from exotica::TaskMap | |
std::vector< KinematicSolution > | kinematics = std::vector<KinematicSolution>(1) |
int | id = -1 |
int | start = -1 |
int | length = -1 |
int | start_jacobian = -1 |
int | length_jacobian = -1 |
bool | is_used = false |
Public Attributes inherited from exotica::Object | |
std::string | ns_ |
std::string | object_name_ |
bool | debug_ |
Private Member Functions | |
void | Initialize () |
Private Attributes | |
ros::Publisher | pub_debug_ |
visualization_msgs::MarkerArray | msg_debug_ |
int | n_frames_ |
Eigen::Matrix3Xd | axis_ |
Eigen::Matrix3Xd | dir_ |
Eigen::Vector3d | link_position_in_base_ |
Eigen::Vector3d | link_axis_position_in_base_ |
Additional Inherited Members | |
Protected Attributes inherited from exotica::TaskMap | |
std::vector< KinematicFrameRequest > | frames_ |
ScenePtr | scene_ = nullptr |
Protected Attributes inherited from exotica::Instantiable< EffAxisAlignmentInitializer > | |
EffAxisAlignmentInitializer | parameters_ |
|
overridevirtual |
Reimplemented from exotica::TaskMap.
Eigen::Vector3d exotica::EffAxisAlignment::GetAxis | ( | const std::string & | frame_name | ) | const |
Eigen::Vector3d exotica::EffAxisAlignment::GetDirection | ( | const std::string & | frame_name | ) | const |
|
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 | ||
) |
|
overridevirtual |
Implements exotica::TaskMap.
|
overridevirtual |
Implements exotica::TaskMap.
|
overridevirtual |
Reimplemented from exotica::TaskMap.
|
private |
|
private |
|
private |
|
private |
|
private |
int exotica::EffAxisAlignment::N |
|
private |
|
private |