Go to the documentation of this file.
30 #ifndef EXOTICA_CORE_TASK_MAPS_IDENTITY_H_
31 #define EXOTICA_CORE_TASK_MAPS_IDENTITY_H_
35 #include <exotica_core_task_maps/joint_pose_initializer.h>
61 #endif // EXOTICA_CORE_TASK_MAPS_IDENTITY_H_
int num_controlled_joints_
Definition: joint_pose.h:54
Definition: task_map.h:52
std::vector< int > joint_map_
! Number of controlled joints
Definition: joint_pose.h:55
void Update(Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi) override
const Eigen::VectorXd & get_joint_ref() const
Definition: property.h:110
Definition: cartpole_dynamics_solver.h:38
Definition: joint_pose.h:39
std::shared_ptr< Scene > ScenePtr
Definition: scene.h:246
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
int TaskSpaceDim() override
const std::vector< int > & get_joint_map() const
Eigen::VectorXd joint_ref_
! Subset selection matrix
Definition: joint_pose.h:56
void set_joint_ref(Eigen::VectorXdRefConst ref)
void Initialize()
! Joint reference value
void AssignScene(ScenePtr scene) override