Go to the documentation of this file.
30 #ifndef EXOTICA_CORE_TASK_MAPS_INTERACTION_MESH_H_
31 #define EXOTICA_CORE_TASK_MAPS_INTERACTION_MESH_H_
36 #include <exotica_core_task_maps/interaction_mesh_initializer.h>
38 #include <visualization_msgs/Marker.h>
48 void Instantiate(
const InteractionMeshInitializer& init)
override;
55 void SetWeight(
int i,
int j,
double weight);
56 void SetWeights(
const Eigen::MatrixXd& weights);
76 #endif // EXOTICA_CORE_TASK_MAPS_INTERACTION_MESH_H_
void Debug(Eigen::VectorXdRefConst phi)
int eff_size_
Definition: interaction_mesh.h:69
Definition: task_map.h:52
void SetWeight(int i, int j, double weight)
static Eigen::VectorXd ComputeLaplace(Eigen::VectorXdRefConst eff_Phi, Eigen::MatrixXdRefConst weights, Eigen::MatrixXd *dist=nullptr, Eigen::VectorXd *wsum=nullptr)
visualization_msgs::Marker imesh_mark_
Definition: interaction_mesh.h:72
Definition: property.h:110
Eigen::MatrixXd weights_
Definition: interaction_mesh.h:68
Definition: cartpole_dynamics_solver.h:38
virtual ~InteractionMesh()
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
const typedef Eigen::Ref< const Eigen::MatrixXd > & MatrixXdRefConst
Definition: conversions.h:53
void ComputeGoalLaplace(const Eigen::VectorXd &x, Eigen::VectorXd &goal)
int TaskSpaceDim() override
ros::Publisher imesh_mark_pub_
Definition: interaction_mesh.h:71
void Update(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) override
void SetWeights(const Eigen::MatrixXd &weights)
void AssignScene(ScenePtr scene) override
void InitializeDebug(std::string ref)
Definition: interaction_mesh.h:42
void Instantiate(const InteractionMeshInitializer &init) override
Eigen::MatrixXd GetWeights()