#include <sphere_sensor.h>
Public Member Functions | |
SphereSensor () | |
~SphereSensor () | |
Public Member Functions inherited from fastrack::sensor::Sensor< E, fastrack_msgs::SensedSpheres, SphereSensorParams > | |
bool | Initialize (const ros::NodeHandle &n) |
virtual | ~Sensor () |
Private Member Functions | |
bool | LoadParameters (const ros::NodeHandle &n) |
void | UpdateParameters () |
void | Visualize () const |
Additional Inherited Members | |
Protected Member Functions inherited from fastrack::sensor::Sensor< E, fastrack_msgs::SensedSpheres, SphereSensorParams > | |
bool | RegisterCallbacks (const ros::NodeHandle &n) |
Sensor () | |
void | TimerCallback (const ros::TimerEvent &e) |
Protected Attributes inherited from fastrack::sensor::Sensor< E, fastrack_msgs::SensedSpheres, SphereSensorParams > | |
E | env_ |
std::string | fixed_frame_ |
bool | initialized_ |
std::string | name_ |
SphereSensorParams | 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_ |
Definition at line 54 of file sphere_sensor.h.
|
inline |
Definition at line 57 of file sphere_sensor.h.
|
inlineexplicit |
Definition at line 58 of file sphere_sensor.h.
|
privatevirtual |
Reimplemented from fastrack::sensor::Sensor< E, fastrack_msgs::SensedSpheres, SphereSensorParams >.
Definition at line 78 of file sphere_sensor.h.
|
privatevirtual |
Implements fastrack::sensor::Sensor< E, fastrack_msgs::SensedSpheres, SphereSensorParams >.
Definition at line 93 of file sphere_sensor.h.
|
privatevirtual |
Implements fastrack::sensor::Sensor< E, fastrack_msgs::SensedSpheres, SphereSensorParams >.
Definition at line 116 of file sphere_sensor.h.