test_Bridge.cpp
Go to the documentation of this file.
00001 /* +------------------------------------------------------------------------+
00002    |                     Mobile Robot Programming Toolkit (MRPT)            |
00003    |                          http://www.mrpt.org/                          |
00004    |                                                                        |
00005    | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file     |
00006    | See: http://www.mrpt.org/Authors - All rights reserved.                |
00007    | Released under BSD License. See details in http://www.mrpt.org/License |
00008    +------------------------------------------------------------------------+ */
00009 
00010 /*---------------------------------------------------------------
00011         APPLICATION: mrpt_ros bridge
00012         FILE: test_Bridge.cpp
00013         AUTHOR: Raghavender Sahdev <raghavendersahdev@gmail.com>
00014   ---------------------------------------------------------------*/
00015 #include "mrpt_bridge/GPS.h"
00016 #include "mrpt_bridge/range.h"
00017 #include "mrpt_bridge/imu.h"
00018 #include "mrpt_bridge/image.h"
00019 #include "mrpt_bridge/stereo_image.h"
00020 
00021 #include "../GPS.cpp"
00022 #include "../range.cpp"
00023 #include "../imu.cpp"
00024 #include "../image.cpp"
00025 #include "../stereo_image.cpp"
00026 
00028 #include <mrpt/obs/CRawlog.h>
00029 #include <mrpt/system/filesystem.h>
00030 
00032 #include <dirent.h>
00033 
00034 
00035 using namespace sensor_msgs;
00036 using namespace mrpt::obs;
00037 using namespace mrpt::system;
00038 using namespace mrpt;
00039 using namespace std;
00040 using namespace cv;
00041 
00049 int main(int argc, char **argv)
00050 {
00051     ros::init(argc, argv, "testing_MRPT_bridge");
00052     ros::NodeHandle n;
00053 
00054     ros::Publisher imu_pub          = n.advertise<sensor_msgs::Imu>("imu_publisher", 1000);
00055     ros::Publisher navSatFix_pub    = n.advertise<sensor_msgs::NavSatFix>("navSatFix_publisher", 1000);
00056     ros::Publisher image_pub        = n.advertise<sensor_msgs::Image>("image_publisher", 1000);
00057     ros::Publisher image_pub_left   = n.advertise<sensor_msgs::Image>("left_image_publisher", 1000);
00058     ros::Publisher image_pub_right  = n.advertise<sensor_msgs::Image>("right_image_publisher", 1000);
00059 
00060     int num_ranges  = 10;
00061     ros::Publisher range_pub[num_ranges];
00062     for(int i=0 ; i<num_ranges ; i++)
00063     {
00064         stringstream ss;
00065         ss << "range_publisher" << i;
00066         string topic_name = ss.str();
00067         range_pub[i] = n.advertise<sensor_msgs::Range>(topic_name, 1000);
00068     }
00069     sensor_msgs::Imu        ros_Imu;
00070     sensor_msgs::Range      *ros_Range;
00071     sensor_msgs::NavSatFix  ros_GPS;
00072     sensor_msgs::Image      ros_Image;
00073     sensor_msgs::Image      ros_Image_left;
00074     sensor_msgs::Image      ros_Image_right;
00075 
00076     CObservationGPS     mrpt_GPS;
00077     CObservationIMU     mrpt_IMU;
00078     CObservationRange   mrpt_Range;
00079     CObservationImage   mrpt_Image;
00080     CObservationImage   mrpt_Image_left;
00081     CObservationImage   mrpt_Image_right;
00082 
00083     int i=0;
00084     std_msgs::Header header;
00085     header.frame_id = "map";
00086 
00088     mrpt_Range.maxSensorDistance      = 500;
00089     mrpt_Range.minSensorDistance      = 60;
00090     mrpt_Range.sensorConeApperture    = (float) M_PI/3;
00091     //initializing the measurement of each range value message in MRPT
00092     for(int i=0 ; i<num_ranges ; i++)
00093     {
00094         CObservationRange::TMeasurement measurement;
00095         measurement.sensedDistance = i*1.0;
00096         mrpt_Range.sensedData.push_back(measurement);
00097     }
00099     ros_Range = new sensor_msgs::Range[num_ranges];
00100 
00101 
00103     mrpt_IMU.rawMeasurements.at(IMU_ORI_QUAT_X)  = 1;
00104     mrpt_IMU.rawMeasurements.at(IMU_ORI_QUAT_Y)  = 1;
00105     mrpt_IMU.rawMeasurements.at(IMU_ORI_QUAT_Z)  = 1;
00106     mrpt_IMU.rawMeasurements.at(IMU_ORI_QUAT_W)  = 1;
00107 
00108     mrpt_IMU.rawMeasurements.at(IMU_X_ACC_GLOBAL) = 1;
00109     mrpt_IMU.rawMeasurements.at(IMU_Y_ACC_GLOBAL) = 1;
00110     mrpt_IMU.rawMeasurements.at(IMU_Z_ACC_GLOBAL) = 1;
00111 
00112     mrpt_IMU.rawMeasurements.at(IMU_X_VEL)   = 1;
00113     mrpt_IMU.rawMeasurements.at(IMU_Y_VEL)   = 1;
00114     mrpt_IMU.rawMeasurements.at(IMU_Z_VEL)   = 1;
00115 
00117     CObservationImage image;
00118     DIR *dir;
00119     dirent *pdir;
00120     vector<string> files;
00121     vector<string> files_fullpath;
00122 
00124     string file_path1 = "/home/raghavender/catkin_ws/src/mrpt_navigation/mrpt_bridge/src/images";
00125 
00126     dir = opendir(file_path1.c_str());
00127     while((pdir = readdir(dir)))
00128         files.push_back(pdir->d_name);
00129     for(unsigned int i=0,j=0 ; i<files.size() ; i++)
00130     {
00131         if(files.at(i).size() > 4) // this removes the . and .. in linux as all files will have size more than 4 .png .jpg etc.
00132         {
00133             files_fullpath.push_back(file_path1 + "/" + files.at(i));
00134             //cout << files_fullpath.at(j) << endl;
00135             j++;
00136         }
00137     } // end of for
00138     sort(files_fullpath.begin(),files_fullpath.end());
00139 
00140 
00141 
00144     CObservationImage image1, image2;
00145     DIR *dir1, *dir2;
00146     dirent *pdir1, *pdir2;
00147     vector<string> files1, files2;
00148     vector<string> files_fullpath1, files_fullpath2;
00149 
00151     string file_path_left = "/home/raghavender/catkin_ws/src/mrpt_navigation/mrpt_bridge/src/stereo_images/left";
00152     string file_path_right = "/home/raghavender/catkin_ws/src/mrpt_navigation/mrpt_bridge/src/stereo_images/right";
00153 
00154     dir1 = opendir(file_path_left.c_str());
00155     while((pdir1 = readdir(dir1)))
00156         files1.push_back(pdir1->d_name);
00157     for(unsigned int i=0,j=0 ; i<files1.size() ; i++)
00158     {
00159         if(files1.at(i).size() > 4) // this removes the . and .. in linux as all files will have size more than 4 .png .jpg etc.
00160         {
00161             files_fullpath1.push_back(file_path_left + "/" + files1.at(i));
00162             j++;
00163         }
00164     } // end of for
00165     sort(files_fullpath1.begin(),files_fullpath1.end());
00166 
00168     dir2 = opendir(file_path_right.c_str());
00169     while((pdir2 = readdir(dir2)))
00170         files2.push_back(pdir2->d_name);
00171     for(unsigned int i=0,j=0 ; i<files2.size() ; i++)
00172     {
00173         if(files2.at(i).size() > 4) // this removes the . and .. in linux as all files will have size more than 4 .png .jpg etc.
00174         {
00175             files_fullpath2.push_back(file_path_right + "/" + files2.at(i));
00176             j++;
00177         }
00178     } // end of for
00179     sort(files_fullpath2.begin(),files_fullpath2.end());
00180 
00181     ROS_INFO("Range Message Conversion STARTED..!!");
00182 
00183 
00184     ros::Rate loop_rate(10);
00185     while(ros::ok())
00186     {
00188         header.seq = i;
00189         header.stamp = ros::Time::now();
00190         i++;
00191 
00193         mrpt_Image.image.loadFromFile(files_fullpath.at(i%(files_fullpath.size()-1)));
00194         mrpt_bridge::image::mrpt2ros(mrpt_Image, header, ros_Image);
00195         image_pub.publish(ros_Image);
00196 
00198         mrpt_Image_left.image.loadFromFile(files_fullpath1.at(i%(files_fullpath1.size()-1)));
00199         mrpt_bridge::image::mrpt2ros(mrpt_Image_left, header, ros_Image_left);
00200         image_pub_left.publish(ros_Image_left);
00201 
00202         mrpt_Image_right.image.loadFromFile(files_fullpath2.at(i%(files_fullpath2.size()-1)));
00203         mrpt_bridge::image::mrpt2ros(mrpt_Image_left, header, ros_Image_right);
00204         image_pub_right.publish(ros_Image_right);
00205 
00206 
00208         mrpt_IMU.rawMeasurements.at(IMU_ORI_QUAT_X)  = i*0.1;
00209         mrpt_IMU.rawMeasurements.at(IMU_ORI_QUAT_Y)  = i*0.1;
00210         mrpt_IMU.rawMeasurements.at(IMU_ORI_QUAT_Z)  = i*0.1;
00211         mrpt_IMU.rawMeasurements.at(IMU_ORI_QUAT_W)  = i*-0.1;
00212         mrpt_IMU.rawMeasurements.at(IMU_X_ACC_GLOBAL) = i * 0.1;
00213         mrpt_IMU.rawMeasurements.at(IMU_Y_ACC_GLOBAL) = i*0.1;
00214         mrpt_IMU.rawMeasurements.at(IMU_Z_ACC_GLOBAL) = 9.8+ i*0.003;
00215         mrpt_IMU.rawMeasurements.at(IMU_X_VEL)   = i*0.1 * i*0.2;
00216         mrpt_IMU.rawMeasurements.at(IMU_Y_VEL)   = i*0.1 * i*0.2;
00217         mrpt_IMU.rawMeasurements.at(IMU_Z_VEL)   = 0;
00218         mrpt_bridge::imu::mrpt2ros(mrpt_IMU, header, ros_Imu);
00219         imu_pub.publish(ros_Imu);
00220 
00221 
00223         mrpt::obs::gnss::Message_NMEA_GGA gga;
00224         gga.fields.altitude_meters      = 2;
00225         gga.fields.latitude_degrees     = i*0.001;
00226         gga.fields.longitude_degrees    = i*0.03 + 43;
00227         gga.fields.fix_quality          = 1;
00228         mrpt_GPS.setMsg(gga);
00229         mrpt_bridge::GPS::mrpt2ros(mrpt_GPS, header, ros_GPS);
00230         navSatFix_pub.publish(ros_GPS);
00231 
00232 
00234         mrpt_bridge::range::mrpt2ros(mrpt_Range, header, ros_Range);
00235         ROS_INFO(" published %d",i);
00236         // publishing the ranges over num_ranges umber of topics
00237         for(int i=0 ; i<num_ranges ; i++)
00238             range_pub[i].publish(ros_Range[i]);
00239 
00240         ros::spinOnce();
00241         loop_rate.sleep();
00242     }
00243     return 0;
00244 }
00245 
00246 


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Fri Apr 27 2018 05:10:54