44 #ifndef FASTRACK_ENVIRONMENT_BALLS_IN_BOX_H 45 #define FASTRACK_ENVIRONMENT_BALLS_IN_BOX_H 49 #include <fastrack_msgs/SensedSpheres.h> 51 #include <geometry_msgs/Point.h> 52 #include <geometry_msgs/Vector3.h> 54 #include <visualization_msgs/Marker.h> 57 namespace environment {
63 :
public Environment<fastrack_msgs::SensedSpheres, SphereSensorParams> {
67 :
Environment<fastrack_msgs::SensedSpheres, SphereSensorParams>() {}
72 bool IsValid(
const Vector3d &position,
const TrackingBound &bound,
73 double time = std::numeric_limits<double>::quiet_NaN())
const;
77 const SphereSensorParams ¶ms)
const;
90 void SensorCallback(
const fastrack_msgs::SensedSpheres::ConstPtr &msg);
94 unsigned int seed = 0);
bool LoadParameters(const ros::NodeHandle &n)
std::vector< Vector3d > centers_
fastrack_msgs::SensedSpheres SimulateSensor(const SphereSensorParams ¶ms) const
void GenerateObstacles(size_t num, double min_radius, double max_radius, unsigned int seed=0)
std::vector< double > radii_
bool IsValid(const Vector3d &position, const TrackingBound &bound, double time=std::numeric_limits< double >::quiet_NaN()) const
void SensorCallback(const fastrack_msgs::SensedSpheres::ConstPtr &msg)