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_ void Update(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) override
int TaskSpaceDim() override
Eigen::Ref< Eigen::VectorXd > VectorXdRef
void Instantiate(const EffBoxInitializer &init) override
void PublishObjectsAsMarkerArray()
Eigen::VectorXd eff_lower_
End-effector lower x, y, z limit.
Eigen::VectorXd eff_upper_
End-effector upper x, y, z limit.
Eigen::Vector3d GetUpperLimit(const int eff_id) const
const Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
Eigen::Vector3d GetLowerLimit(const int eff_id) const
ros::Publisher pub_markers_
Three multiplied by the number of end-effectors.
Limits every given end-effector motion to a box in some reference frame.
int n_effs_
Number of end-effectors.