#include <occupancy_map.h>
Public Member Functions | |
bool | IsValid (const Vector3d &position, const TrackingBound &bound, double time=std::numeric_limits< double >::quiet_NaN()) const |
virtual double | OccupancyProbability (const Vector3d &position, double time=std::numeric_limits< double >::quiet_NaN()) const =0 |
virtual double | OccupancyProbability (const Vector3d &position, const TrackingBound &bound, double time=std::numeric_limits< double >::quiet_NaN()) const =0 |
virtual M | SimulateSensor (const P ¶ms) const =0 |
virtual void | Visualize () const =0 |
virtual | ~OccupancyMap () |
Public Member Functions inherited from fastrack::environment::Environment< M, P > | |
bool | AreValid (const std::vector< Vector3d > &positions, const TrackingBound &bound, double time=std::numeric_limits< double >::quiet_NaN()) const |
bool | Initialize (const ros::NodeHandle &n) |
virtual | ~Environment () |
Protected Member Functions | |
virtual bool | LoadParameters (const ros::NodeHandle &n) |
OccupancyMap () | |
virtual void | SensorCallback (const typename M::ConstPtr &msg)=0 |
Protected Member Functions inherited from fastrack::environment::Environment< M, P > | |
Environment () | |
virtual bool | RegisterCallbacks (const ros::NodeHandle &n) |
Protected Attributes | |
double | free_space_threshold_ |
Protected Attributes inherited from fastrack::environment::Environment< M, P > | |
std::string | fixed_frame_ |
bool | initialized_ |
Vector3d | lower_ |
std::string | name_ |
ros::Subscriber | sensor_sub_ |
std::string | sensor_topic_ |
ros::Publisher | updated_pub_ |
std::string | updated_topic_ |
Vector3d | upper_ |
ros::Publisher | vis_pub_ |
std::string | vis_topic_ |
Definition at line 70 of file occupancy_map.h.
|
inlinevirtual |
Definition at line 72 of file occupancy_map.h.
|
inlineexplicitprotected |
Definition at line 98 of file occupancy_map.h.
|
inlinevirtual |
Implements fastrack::environment::Environment< M, P >.
Definition at line 76 of file occupancy_map.h.
|
protectedvirtual |
Reimplemented from fastrack::environment::Environment< M, P >.
Reimplemented in fastrack::environment::BallsInBoxOccupancyMap.
Definition at line 119 of file occupancy_map.h.
|
pure virtual |
Implemented in fastrack::environment::BallsInBoxOccupancyMap.
|
pure virtual |
Implemented in fastrack::environment::BallsInBoxOccupancyMap.
|
protectedpure virtual |
Implements fastrack::environment::Environment< M, P >.
Implemented in fastrack::environment::BallsInBoxOccupancyMap.
|
pure virtual |
Implements fastrack::environment::Environment< M, P >.
Implemented in fastrack::environment::BallsInBoxOccupancyMap.
|
pure virtual |
Implements fastrack::environment::Environment< M, P >.
Implemented in fastrack::environment::BallsInBoxOccupancyMap.
|
protected |
Definition at line 111 of file occupancy_map.h.