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