27 #include <nav_msgs/OccupancyGrid.h> 28 #include <geometry_msgs/Pose2D.h> 90 const nav_msgs::OccupancyGrid& map,
91 const std::string& name,
93 const geometry_msgs::Pose2D& sensorPose,
94 const std::string& sensorFrameId,
95 float updateFrequency);
116 const nav_msgs::OccupancyGrid&
_map;
const std::string & _namespace
< The base for the sensor frame_id
tf::TransformListener _tfListener
ROS transform from sensor to map.
const geometry_msgs::Pose2D _sensorPose
Update frequency of _timer.
std::string getFrameId(void) const
Getter function for returning the sensor frame id.
std::vector< SensorPtr > SensorPtrVector
void checkAndUpdateSensor(const ros::TimerEvent &ev)
Checks if transform is available and calls updateSensorCallback()
The main namespace for STDR Robot.
const float _updateFrequency
Sensor frame id.
A class that provides sensor abstraction.
boost::shared_ptr< Sensor > SensorPtr
void updateTransform(const ros::TimerEvent &ev)
Function for updating the sensor tf transform.
ros::Timer _timer
A ROS timer for updating the sensor tf.
virtual void updateSensorCallback(void)=0
Virtual function for sensor value callback. Implement this function on derived class to publish senso...
Sensor(const nav_msgs::OccupancyGrid &map, const std::string &name, ros::NodeHandle &n, const geometry_msgs::Pose2D &sensorPose, const std::string &sensorFrameId, float updateFrequency)
Default constructor.
tf::StampedTransform _sensorTransform
True if sensor got the _sensorTransform.
const nav_msgs::OccupancyGrid & _map
Sensor pose relative to robot.
ros::Timer _tfTimer
ROS publisher for posting the sensor measurements.
const std::string _sensorFrameId
A ROS timer for updating the sensor values.
geometry_msgs::Pose2D getSensorPose(void) const
Getter function for returning the sensor pose relatively to robot.
ros::Publisher _publisher
ROS tf listener.
virtual ~Sensor(void)
Default destructor.