Go to the documentation of this file.
30 #ifndef EXOTICA_CORE_TASK_MAPS_EFF_FRAME_H_
31 #define EXOTICA_CORE_TASK_MAPS_EFF_FRAME_H_
35 #include <exotica_core_task_maps/eff_frame_initializer.h>
42 void Instantiate(
const EffFrameInitializer& init)
override;
61 #endif // EXOTICA_CORE_TASK_MAPS_EFF_FRAME_H_
const RotationType & get_rotation_type() const
Definition: task_map.h:52
void Instantiate(const EffFrameInitializer &init) override
Definition: property.h:110
Definition: cartpole_dynamics_solver.h:38
RotationType rotation_type_
Definition: eff_frame.h:57
Eigen::Ref< Eigen::VectorXd > VectorXdRef
Definition: conversions.h:54
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Convenience wrapper for storing references to sub-matrices/vectors.
Definition: conversions.h:52
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
Definition: conversions.h:55
Eigen::Ref< Hessian > HessianRef
Definition: conversions.h:160
Definition: eff_frame.h:39
int TaskSpaceDim() override
int TaskSpaceJacobianDim() override
int big_stride_
Definition: eff_frame.h:55
std::vector< TaskVectorEntry > GetLieGroupIndices() override
RotationType
Definition: conversions.h:79
void Update(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) override
int small_stride_
Definition: eff_frame.h:56