Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013 #ifndef ROSINTERFACE_H_
00014 #define ROSINTERFACE_H_
00015
00016
00017 #include "SimulatorConfig.h"
00018
00019 #include "URDFRobot.h"
00020 #include "SimulatedIAUV.h"
00021 #include "VirtualCamera.h"
00022 #include "VirtualRangeSensor.h"
00023 #include "PressureSensor.h"
00024 #include "GPSSensor.h"
00025 #include "DVLSensor.h"
00026 #include "HUDCamera.h"
00027 #include "MultibeamSensor.h"
00028 #include "UWSimUtils.h"
00029 #include "BulletPhysics.h"
00030
00031
00032 #include <OpenThreads/Thread>
00033 #include <osg/PrimitiveSet>
00034 #include <osg/Geode>
00035 #include <osg/Vec3>
00036 #include <osg/Vec4>
00037 #include <osg/Drawable>
00038 #include <osg/Geometry>
00039
00040
00041 #include <vector>
00042
00043 #include <boost/shared_ptr.hpp>
00044
00045
00046 #include <ros/ros.h>
00047 #include <tf/transform_broadcaster.h>
00048 #include <tf/transform_listener.h>
00049 #include <sensor_msgs/JointState.h>
00050 #include <nav_msgs/Odometry.h>
00051 #include <sensor_msgs/Image.h>
00052 #include <sensor_msgs/CameraInfo.h>
00053 #include <sensor_msgs/distortion_models.h>
00054 #include <sensor_msgs/Range.h>
00055 #include <image_transport/image_transport.h>
00056 #include <geometry_msgs/TwistStamped.h>
00057 #include <geometry_msgs/Pose.h>
00058
00059 #include <robot_state_publisher/robot_state_publisher.h>
00060
00061
00062 #define MAX_ELAPSED 1
00063
00064 class ROSInterface : public OpenThreads::Thread
00065 {
00066 protected:
00067 std::string topic;
00068 ros::NodeHandle nh_;
00069 static ros::Time current_time_;
00070
00071 public:
00072 ROSInterface(std::string topic)
00073 {
00074 this->topic = topic;
00075 }
00076
00077 virtual ~ROSInterface()
00078 {
00079 }
00080
00085 static void setROSTime(const ros::Time& time)
00086 {
00087 current_time_ = time;
00088 }
00089
00095 static ros::Time getROSTime()
00096 {
00097 return current_time_;
00098 }
00099 };
00100
00101 class ROSSubscriberInterface : public ROSInterface
00102 {
00103 protected:
00104 ros::Subscriber sub_;
00105 public:
00106 ROSSubscriberInterface(std::string topic);
00107
00108 virtual void createSubscriber(ros::NodeHandle &nh)=0;
00109
00110
00111 void run();
00112
00113 ~ROSSubscriberInterface();
00114 };
00115
00116 class ROSOdomToPAT : public ROSSubscriberInterface
00117 {
00118 osg::ref_ptr<osg::MatrixTransform> transform;
00119 ros::WallTime last;
00120 int started;
00121
00122 public:
00123 ROSOdomToPAT(osg::Group *rootNode, std::string topic, std::string vehicleName);
00124
00125 virtual void createSubscriber(ros::NodeHandle &nh);
00126
00127 virtual void processData(const nav_msgs::Odometry::ConstPtr& odom);
00128 ~ROSOdomToPAT();
00129 };
00130
00131 class ROSTwistToPAT : public ROSSubscriberInterface
00132 {
00133 osg::ref_ptr<osg::MatrixTransform> transform;
00134 ros::WallTime last;
00135 int started;
00136 public:
00137 ROSTwistToPAT(osg::Group *rootNode, std::string topic, std::string vehicleName);
00138
00139 virtual void createSubscriber(ros::NodeHandle &nh);
00140
00141 virtual void processData(const geometry_msgs::TwistStamped::ConstPtr& odom);
00142 ~ROSTwistToPAT();
00143 };
00144
00145 class ROSPoseToPAT : public ROSSubscriberInterface
00146 {
00147 osg::ref_ptr<osg::MatrixTransform> transform;
00148 public:
00149 ROSPoseToPAT(osg::Group *rootNode, std::string topic, std::string vehicleName);
00150
00151 virtual void createSubscriber(ros::NodeHandle &nh);
00152
00153 virtual void processData(const geometry_msgs::Pose::ConstPtr& odom);
00154 ~ROSPoseToPAT();
00155 };
00156
00157
00158
00159
00160
00161
00162
00163
00164
00165
00166
00167
00168
00169
00170
00171
00172
00173
00174
00175
00176
00177
00178
00179
00180
00181
00182
00183
00184
00185
00186
00187
00188
00189
00190
00191
00192
00193
00194
00195
00196
00197
00198
00199
00200
00201
00202
00203
00204
00205
00206
00207
00208
00209 class ROSJointStateToArm : public ROSSubscriberInterface
00210 {
00211 boost::shared_ptr<SimulatedIAUV> arm;
00212 public:
00213 ROSJointStateToArm(std::string topic, boost::shared_ptr<SimulatedIAUV> arm);
00214 virtual void createSubscriber(ros::NodeHandle &nh);
00215
00216 virtual void processData(const sensor_msgs::JointState::ConstPtr& js);
00217 ~ROSJointStateToArm();
00218 };
00219
00220 class ROSImageToHUDCamera : public ROSSubscriberInterface
00221 {
00222 boost::shared_ptr<HUDCamera> cam;
00223 boost::shared_ptr<image_transport::ImageTransport> it;
00224 image_transport::Subscriber image_sub;
00225 std::string image_topic;
00226 public:
00227 ROSImageToHUDCamera(std::string topic, std::string info_topic, boost::shared_ptr<HUDCamera> camera);
00228
00229 virtual void createSubscriber(ros::NodeHandle &nh);
00230
00231 virtual void processData(const sensor_msgs::ImageConstPtr& msg);
00232 ~ROSImageToHUDCamera();
00233 };
00234
00235 class ROSPublisherInterface : public ROSInterface
00236 {
00237 protected:
00238 int publish_rate;
00239 ros::Publisher pub_;
00240 public:
00241 ROSPublisherInterface(std::string topic, int publish_rate);
00242
00243 virtual void createPublisher(ros::NodeHandle &nh)=0;
00244 virtual void publish()=0;
00245
00246
00247 void run();
00248
00249 ~ROSPublisherInterface();
00250 };
00251
00252 class PATToROSOdom : public ROSPublisherInterface
00253 {
00254 osg::ref_ptr<osg::MatrixTransform> transform;
00255 public:
00256 PATToROSOdom(osg::Group *rootNode, std::string vehicleName, std::string topic, int rate);
00257
00258 void createPublisher(ros::NodeHandle &nh);
00259
00260 void publish();
00261
00262 ~PATToROSOdom();
00263 };
00264
00265 class WorldToROSTF : public ROSPublisherInterface
00266 {
00267 std::vector< osg::ref_ptr<osg::MatrixTransform> > transforms_;
00268 std::vector< boost::shared_ptr<robot_state_publisher::RobotStatePublisher> > robot_pubs_;
00269 boost::shared_ptr<tf::TransformBroadcaster> tfpub_;
00270 std::vector< boost::shared_ptr<SimulatedIAUV> > iauvFile_;
00271 std::vector<osg::ref_ptr<osg::Node> > objects_;
00272 std::string worldRootName_;
00273 unsigned int enableObjects_;
00274 osg::Group *rootNode_;
00275 public:
00276 WorldToROSTF(osg::Group *rootNode, std::vector<boost::shared_ptr<SimulatedIAUV> > iauvFile, std::vector<osg::ref_ptr<osg::Node> > objects, std::string worldRootName, unsigned int enableObjects, int rate);
00277
00278 void createPublisher(ros::NodeHandle &nh);
00279
00280 void publish();
00281
00282 ~WorldToROSTF();
00283 };
00284
00285 class ImuToROSImu : public ROSPublisherInterface
00286 {
00287 InertialMeasurementUnit *imu_;
00288
00289 public:
00290 ImuToROSImu(InertialMeasurementUnit *imu, std::string topic, int rate);
00291
00292 void createPublisher(ros::NodeHandle &nh);
00293
00294 void publish();
00295
00296 ~ImuToROSImu();
00297 };
00298
00299 class PressureSensorToROS : public ROSPublisherInterface
00300 {
00301 PressureSensor *sensor_;
00302
00303 public:
00304 PressureSensorToROS(PressureSensor *sensor, std::string topic, int rate);
00305
00306 void createPublisher(ros::NodeHandle &nh);
00307
00308 void publish();
00309
00310 ~PressureSensorToROS();
00311 };
00312
00313 class GPSSensorToROS : public ROSPublisherInterface
00314 {
00315 GPSSensor *sensor_;
00316
00317 public:
00318 GPSSensorToROS(GPSSensor *sensor, std::string topic, int rate) :
00319 ROSPublisherInterface(topic, rate), sensor_(sensor)
00320 {
00321 }
00322
00323 void createPublisher(ros::NodeHandle &nh);
00324
00325 void publish();
00326
00327 ~GPSSensorToROS()
00328 {
00329 }
00330 };
00331
00332 class DVLSensorToROS : public ROSPublisherInterface
00333 {
00334 DVLSensor *sensor_;
00335
00336 public:
00337 DVLSensorToROS(DVLSensor *sensor, std::string topic, int rate) :
00338 ROSPublisherInterface(topic, rate), sensor_(sensor)
00339 {
00340 }
00341
00342 void createPublisher(ros::NodeHandle &nh);
00343
00344 void publish();
00345
00346 ~DVLSensorToROS()
00347 {
00348 }
00349 };
00350
00351 class ArmToROSJointState : public ROSPublisherInterface
00352 {
00353 boost::shared_ptr<URDFRobot> arm;
00354 public:
00355 ArmToROSJointState(SimulatedIAUV *arm, std::string topic, int rate);
00356
00357 void createPublisher(ros::NodeHandle &nh);
00358
00359 void publish();
00360
00361 ~ArmToROSJointState();
00362 };
00363
00364 class VirtualCameraToROSImage : public ROSPublisherInterface
00365 {
00366 VirtualCamera *cam;
00367 boost::shared_ptr<image_transport::ImageTransport> it;
00368 image_transport::Publisher img_pub_;
00369 std::string image_topic;
00370 int depth;
00371 int bw;
00372 public:
00373 VirtualCameraToROSImage(VirtualCamera *camera, std::string topic, std::string info_topic, int rate, int depth);
00374
00375 void createPublisher(ros::NodeHandle &nh);
00376
00377 void publish();
00378
00379 ~VirtualCameraToROSImage();
00380 };
00381
00382 class RangeSensorToROSRange : public ROSPublisherInterface
00383 {
00384 VirtualRangeSensor *rs;
00385 public:
00386 RangeSensorToROSRange(VirtualRangeSensor *rangesensor, std::string topic, int rate);
00387
00388 void createPublisher(ros::NodeHandle &nh);
00389
00390 void publish();
00391
00392 ~RangeSensorToROSRange();
00393 };
00394
00395 class MultibeamSensorToROS : public ROSPublisherInterface
00396 {
00397 MultibeamSensor *MB;
00398 public:
00399 MultibeamSensorToROS(MultibeamSensor *multibeamSensor, std::string topic, int rate);
00400
00401 void createPublisher(ros::NodeHandle &nh);
00402
00403 void publish();
00404
00405 ~MultibeamSensorToROS();
00406 };
00407
00408 class contactSensorToROS : public ROSPublisherInterface
00409 {
00410 BulletPhysics * physics;
00411 std::string target;
00412 osg::Group *rootNode;
00413 public:
00414 contactSensorToROS(osg::Group *rootNode, BulletPhysics * physics, std::string target, std::string topic, int rate);
00415
00416 void createPublisher(ros::NodeHandle &nh);
00417
00418 void publish();
00419
00420 ~contactSensorToROS();
00421 };
00422 #endif
00423