#include <sensor.h>
Public Member Functions | |
bool | Initialize (const ros::NodeHandle &n) |
virtual | ~Sensor () |
Protected Member Functions | |
virtual bool | LoadParameters (const ros::NodeHandle &n) |
bool | RegisterCallbacks (const ros::NodeHandle &n) |
Sensor () | |
void | TimerCallback (const ros::TimerEvent &e) |
virtual void | UpdateParameters ()=0 |
virtual void | Visualize () const =0 |
Protected Attributes | |
E | env_ |
std::string | fixed_frame_ |
bool | initialized_ |
std::string | name_ |
P | params_ |
std::string | sensor_frame_ |
ros::Publisher | sensor_pub_ |
std::string | sensor_topic_ |
tf2_ros::Buffer | tf_buffer_ |
tf2_ros::TransformListener | tf_listener_ |
double | time_step_ |
ros::Timer | timer_ |
ros::Publisher | vis_pub_ |
std::string | vis_topic_ |
|
inlinevirtual |
|
inlineexplicitprotected |
bool fastrack::sensor::Sensor< E, M, P >::Initialize | ( | const ros::NodeHandle & | n | ) |
|
protectedvirtual |
Reimplemented in fastrack::sensor::SphereSensor< E >.
|
protected |
|
protected |
|
protectedpure virtual |
Implemented in fastrack::sensor::SphereSensor< E >.
|
protectedpure virtual |
Implemented in fastrack::sensor::SphereSensor< E >.
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |