Go to the documentation of this file.
30 #ifndef EXOTICA_CORE_TASK_MAPS_COM_H_
31 #define EXOTICA_CORE_TASK_MAPS_COM_H_
35 #include <exotica_core_task_maps/center_of_mass_initializer.h>
37 #include <visualization_msgs/MarkerArray.h>
66 #endif // EXOTICA_CORE_TASK_MAPS_COM_H_
bool enable_z_
Definition: center_of_mass.h:61
void Update(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) override
ros::Publisher com_pub_
Definition: center_of_mass.h:56
Definition: task_map.h:52
ros::Publisher com_links_pub_
Definition: center_of_mass.h:55
Definition: center_of_mass.h:41
ros::Publisher goal_pub_
Definition: center_of_mass.h:57
Definition: property.h:110
Definition: cartpole_dynamics_solver.h:38
int dim_
Definition: center_of_mass.h:62
void AssignScene(ScenePtr scene) override
visualization_msgs::Marker com_links_marker_
Definition: center_of_mass.h:58
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
visualization_msgs::Marker com_marker_
Definition: center_of_mass.h:59
Eigen::VectorXd mass_
Definition: center_of_mass.h:54
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
Definition: conversions.h:55
visualization_msgs::Marker goal_marker_
Definition: center_of_mass.h:60
int TaskSpaceDim() override