45 #ifndef FASTRACK_ENVIRONMENT_BALLS_IN_BOX_OCCUPANCY_MAP_H 46 #define FASTRACK_ENVIRONMENT_BALLS_IN_BOX_OCCUPANCY_MAP_H 52 #include <fastrack_msgs/SensedSpheres.h> 55 namespace environment {
58 using sensor::SphereSensorParams;
61 :
public OccupancyMap<fastrack_msgs::SensedSpheres, SphereSensorParams> {
65 :
OccupancyMap<fastrack_msgs::SensedSpheres, SphereSensorParams>(),
74 double time = std::numeric_limits<double>::quiet_NaN())
const;
76 const Vector3d& p,
const TrackingBound& bound,
77 double time = std::numeric_limits<double>::quiet_NaN())
const;
81 const SphereSensorParams& params)
const;
95 const typename fastrack_msgs::SensedSpheres::ConstPtr& msg);
fastrack_msgs::SensedSpheres SimulateSensor(const SphereSensorParams ¶ms) const
static constexpr double kUnknownProbability
double OccupancyProbability(const Vector3d &p, double time=std::numeric_limits< double >::quiet_NaN()) const
void SensorCallback(const typename fastrack_msgs::SensedSpheres::ConstPtr &msg)
~BallsInBoxOccupancyMap()
KdtreeMap< 3, double > sensor_fovs_
bool LoadParameters(const ros::NodeHandle &n)
static constexpr double kFreeProbability
static constexpr double kOccupiedProbability
KdtreeMap< 3, double > obstacles_
double largest_sensor_radius_
double largest_obstacle_radius_