Go to the documentation of this file.
30 #ifndef EXOTICA_CORE_TASK_MAPS_EFF_BOX_H_
31 #define EXOTICA_CORE_TASK_MAPS_EFF_BOX_H_
35 #include <exotica_core_task_maps/eff_box_initializer.h>
36 #include <exotica_core_task_maps/frame_with_box_limits_initializer.h>
48 void Instantiate(
const EffBoxInitializer& init)
override;
67 #endif // EXOTICA_CORE_TASK_MAPS_EFF_BOX_H_
int n_effs_
Number of end-effectors.
Definition: eff_box.h:61
void Update(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) override
Definition: task_map.h:52
Eigen::VectorXd eff_lower_
End-effector lower x, y, z limit.
Definition: eff_box.h:59
Limits every given end-effector motion to a box in some reference frame.
Definition: eff_box.h:45
Eigen::VectorXd eff_upper_
End-effector upper x, y, z limit.
Definition: eff_box.h:60
void PublishObjectsAsMarkerArray()
Eigen::Vector3d GetLowerLimit(const int eff_id) const
Definition: property.h:110
int TaskSpaceDim() override
Definition: cartpole_dynamics_solver.h:38
void Instantiate(const EffBoxInitializer &init) override
Eigen::Vector3d GetUpperLimit(const int eff_id) const
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
int three_times_n_effs_
Definition: eff_box.h:62
ros::Publisher pub_markers_
Three multiplied by the number of end-effectors.
Definition: eff_box.h:63