Go to the documentation of this file.
30 #ifndef EXOTICA_CORE_TASK_MAPS_VARIABLE_SIZE_COLLISION_DISTANCE_H_
31 #define EXOTICA_CORE_TASK_MAPS_VARIABLE_SIZE_COLLISION_DISTANCE_H_
38 #include <exotica_core_task_maps/variable_size_collision_distance_initializer.h>
62 #endif // EXOTICA_CORE_TASK_MAPS_VARIABLE_SIZE_COLLISION_DISTANCE_H_
double world_margin_
Definition: variable_size_collision_distance.h:53
void AssignScene(ScenePtr scene) override
Definition: task_map.h:52
std::size_t dim_
Definition: variable_size_collision_distance.h:55
Definition: property.h:110
Definition: cartpole_dynamics_solver.h:38
void UpdateInternal(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi, Eigen::MatrixXdRef J, bool updateJacobian=true)
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
int TaskSpaceDim() override
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
Definition: conversions.h:55
void Update(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) override
std::shared_ptr< CollisionScene > CollisionScenePtr
Definition: collision_scene.h:341
CollisionScenePtr cscene_
Definition: variable_size_collision_distance.h:56
Definition: variable_size_collision_distance.h:42