43 #ifndef FASTRACK_BOUND_TRACKING_BOUND_H 44 #define FASTRACK_BOUND_TRACKING_BOUND_H 49 #include <visualization_msgs/Marker.h> 56 virtual bool Initialize(
const std::vector<double>& params) = 0;
60 virtual bool OverlapsSphere(
const Vector3d& p,
const Vector3d& center,
61 double radius)
const = 0;
62 virtual bool OverlapsBox(
const Vector3d& p,
const Vector3d& lower,
63 const Vector3d& upper)
const = 0;
68 const Vector3d& upper)
const = 0;
71 virtual void Visualize(
const ros::Publisher& pub,
72 const std::string& frame)
const = 0;
virtual bool Initialize(const std::vector< double > ¶ms)=0
virtual bool OverlapsBox(const Vector3d &p, const Vector3d &lower, const Vector3d &upper) const =0
virtual void Visualize(const ros::Publisher &pub, const std::string &frame) const =0
virtual bool ContainedWithinBox(const Vector3d &p, const Vector3d &lower, const Vector3d &upper) const =0
virtual bool OverlapsSphere(const Vector3d &p, const Vector3d ¢er, double radius) const =0