Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef SIMSENSORS_HPP_
00038 #define SIMSENSORS_HPP_
00039 #include <ros/ros.h>
00040 #include <tf/transform_broadcaster.h>
00041 #include <tf/transform_listener.h>
00042
00043 namespace labust
00044 {
00045 namespace simulation
00046 {
00047 class RBModel;
00048
00052 class SimSensorInterface
00053 {
00054 public:
00055 struct Hook
00056 {
00057 Hook(const RBModel& model,
00058 tf::TransformBroadcaster& broadcaster,
00059 tf::TransformListener& listener,
00060 bool noisy = false):
00061 model(model),
00062 broadcaster(broadcaster),
00063 listener(listener),
00064 noisy(noisy){};
00065
00066 const RBModel& model;
00067 tf::TransformBroadcaster& broadcaster;
00068 tf::TransformListener& listener;
00069 bool noisy;
00070 mutable double originLat, originLon;
00071 };
00072
00073 typedef boost::shared_ptr<SimSensorInterface> Ptr;
00074 virtual ~SimSensorInterface(){};
00075 virtual void step(const Hook& data) = 0;
00076 virtual void configure(ros::NodeHandle& nh, const std::string& topic_name) = 0;
00077 };
00078
00079 template <class ROSMsg, class functor>
00080 class BasicSensor : public SimSensorInterface
00081 {
00082 public:
00083 BasicSensor(){};
00084 ~BasicSensor(){};
00085
00086 void configure(ros::NodeHandle& nh, const std::string& topic_name)
00087 {
00088 pub = nh.advertise<ROSMsg>(topic_name,1);
00089 };
00090
00091 void step(const Hook& data)
00092 {
00093 typename ROSMsg::Ptr msg(new ROSMsg());
00094 sensor(msg, data);
00095 pub.publish(msg);
00096 }
00097
00098 private:
00099 ros::Publisher pub;
00100 functor sensor;
00101 };
00102 }
00103 }
00104
00105
00106 #endif