sensor_base.h
Go to the documentation of this file.
1 /******************************************************************************
2  STDR Simulator - Simple Two DImensional Robot Simulator
3  Copyright (C) 2013 STDR Simulator
4  This program is free software; you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation; either version 3 of the License, or
7  (at your option) any later version.
8  This program is distributed in the hope that it will be useful,
9  but WITHOUT ANY WARRANTY; without even the implied warranty of
10  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  GNU General Public License for more details.
12  You should have received a copy of the GNU General Public License
13  along with this program; if not, write to the Free Software Foundation,
14  Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
15 
16  Authors :
17  * Manos Tsardoulias, etsardou@gmail.com
18  * Aris Thallas, aris.thallas@gmail.com
19  * Chris Zalidis, zalidis@gmail.com
20 ******************************************************************************/
21 
22 #ifndef SENSOR_H
23 #define SENSOR_H
24 
25 #include <ros/ros.h>
26 #include <tf/transform_listener.h>
27 #include <nav_msgs/OccupancyGrid.h>
28 #include <geometry_msgs/Pose2D.h>
29 
34 namespace stdr_robot {
35 
40  class Sensor {
41 
42  public:
43 
49  virtual void updateSensorCallback(void) = 0;
50 
55  inline geometry_msgs::Pose2D getSensorPose(void) const
56  {
57  return _sensorPose;
58  }
59 
64  inline std::string getFrameId(void) const
65  {
66  return _namespace + "_" + _sensorFrameId;
67  }
68 
73  virtual ~Sensor(void)
74  {
75  }
76 
77  protected:
78 
89  Sensor(
90  const nav_msgs::OccupancyGrid& map,
91  const std::string& name,
92  ros::NodeHandle& n,
93  const geometry_msgs::Pose2D& sensorPose,
94  const std::string& sensorFrameId,
95  float updateFrequency);
96 
102  void checkAndUpdateSensor(const ros::TimerEvent& ev);
103 
109  void updateTransform(const ros::TimerEvent& ev);
110 
111  protected:
112 
114  const std::string& _namespace;
116  const nav_msgs::OccupancyGrid& _map;
117 
119  const geometry_msgs::Pose2D _sensorPose;
121  const float _updateFrequency;
123  const std::string _sensorFrameId;
124 
129 
136 
139  };
140 
142  typedef std::vector<SensorPtr> SensorPtrVector;
143 
144 }
145 
146 #endif
const std::string & _namespace
< The base for the sensor frame_id
Definition: sensor_base.h:114
tf::TransformListener _tfListener
ROS transform from sensor to map.
Definition: sensor_base.h:133
const geometry_msgs::Pose2D _sensorPose
Update frequency of _timer.
Definition: sensor_base.h:119
std::string getFrameId(void) const
Getter function for returning the sensor frame id.
Definition: sensor_base.h:64
std::vector< SensorPtr > SensorPtrVector
Definition: sensor_base.h:142
void checkAndUpdateSensor(const ros::TimerEvent &ev)
Checks if transform is available and calls updateSensorCallback()
Definition: sensor_base.cpp:63
The main namespace for STDR Robot.
Definition: exceptions.h:27
const float _updateFrequency
Sensor frame id.
Definition: sensor_base.h:121
A class that provides sensor abstraction.
Definition: sensor_base.h:40
boost::shared_ptr< Sensor > SensorPtr
Definition: sensor_base.h:141
void updateTransform(const ros::TimerEvent &ev)
Function for updating the sensor tf transform.
Definition: sensor_base.cpp:76
ros::Timer _timer
A ROS timer for updating the sensor tf.
Definition: sensor_base.h:126
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.
Definition: sensor_base.cpp:36
tf::StampedTransform _sensorTransform
True if sensor got the _sensorTransform.
Definition: sensor_base.h:135
const nav_msgs::OccupancyGrid & _map
Sensor pose relative to robot.
Definition: sensor_base.h:116
ros::Timer _tfTimer
ROS publisher for posting the sensor measurements.
Definition: sensor_base.h:128
const std::string _sensorFrameId
A ROS timer for updating the sensor values.
Definition: sensor_base.h:123
geometry_msgs::Pose2D getSensorPose(void) const
Getter function for returning the sensor pose relatively to robot.
Definition: sensor_base.h:55
ros::Publisher _publisher
ROS tf listener.
Definition: sensor_base.h:131
virtual ~Sensor(void)
Default destructor.
Definition: sensor_base.h:73


stdr_robot
Author(s): Manos Tsardoulias, Chris Zalidis, Aris Thallas
autogenerated on Mon Jun 10 2019 15:15:10