Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
fastrack::environment::OccupancyMap< M, P > Class Template Referenceabstract

#include <occupancy_map.h>

Inheritance diagram for fastrack::environment::OccupancyMap< M, P >:
Inheritance graph
[legend]

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 &params) 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_
 

Detailed Description

template<typename M, typename P>
class fastrack::environment::OccupancyMap< M, P >

Definition at line 70 of file occupancy_map.h.

Constructor & Destructor Documentation

template<typename M, typename P>
virtual fastrack::environment::OccupancyMap< M, P >::~OccupancyMap ( )
inlinevirtual

Definition at line 72 of file occupancy_map.h.

template<typename M, typename P>
fastrack::environment::OccupancyMap< M, P >::OccupancyMap ( )
inlineexplicitprotected

Definition at line 98 of file occupancy_map.h.

Member Function Documentation

template<typename M, typename P>
bool fastrack::environment::OccupancyMap< M, P >::IsValid ( const Vector3d &  position,
const TrackingBound &  bound,
double  time = std::numeric_limits<double>::quiet_NaN() 
) const
inlinevirtual

Implements fastrack::environment::Environment< M, P >.

Definition at line 76 of file occupancy_map.h.

template<typename M , typename P >
bool fastrack::environment::OccupancyMap< M, P >::LoadParameters ( const ros::NodeHandle &  n)
protectedvirtual

Reimplemented from fastrack::environment::Environment< M, P >.

Reimplemented in fastrack::environment::BallsInBoxOccupancyMap.

Definition at line 119 of file occupancy_map.h.

template<typename M, typename P>
virtual double fastrack::environment::OccupancyMap< M, P >::OccupancyProbability ( const Vector3d &  position,
double  time = std::numeric_limits< double >::quiet_NaN() 
) const
pure virtual
template<typename M, typename P>
virtual double fastrack::environment::OccupancyMap< M, P >::OccupancyProbability ( const Vector3d &  position,
const TrackingBound &  bound,
double  time = std::numeric_limits< double >::quiet_NaN() 
) const
pure virtual
template<typename M, typename P>
virtual void fastrack::environment::OccupancyMap< M, P >::SensorCallback ( const typename M::ConstPtr &  msg)
protectedpure virtual
template<typename M, typename P>
virtual M fastrack::environment::OccupancyMap< M, P >::SimulateSensor ( const P &  params) const
pure virtual
template<typename M, typename P>
virtual void fastrack::environment::OccupancyMap< M, P >::Visualize ( ) const
pure virtual

Member Data Documentation

template<typename M, typename P>
double fastrack::environment::OccupancyMap< M, P >::free_space_threshold_
protected

Definition at line 111 of file occupancy_map.h.


The documentation for this class was generated from the following file:


fastrack
Author(s): David Fridovich-Keil
autogenerated on Mon Aug 3 2020 21:28:37