22 #include "../range.cpp" 24 #include "../image.cpp" 25 #include "../stereo_image.cpp" 28 #include <mrpt/obs/CRawlog.h> 29 #include <mrpt/system/filesystem.h> 49 int main(
int argc,
char **argv)
51 ros::init(argc, argv,
"testing_MRPT_bridge");
62 for(
int i=0 ; i<num_ranges ; i++)
65 ss <<
"range_publisher" << i;
66 string topic_name = ss.str();
67 range_pub[i] = n.
advertise<sensor_msgs::Range>(topic_name, 1000);
69 sensor_msgs::Imu ros_Imu;
70 sensor_msgs::Range *ros_Range;
71 sensor_msgs::NavSatFix ros_GPS;
72 sensor_msgs::Image ros_Image;
73 sensor_msgs::Image ros_Image_left;
74 sensor_msgs::Image ros_Image_right;
76 CObservationGPS mrpt_GPS;
77 CObservationIMU mrpt_IMU;
78 CObservationRange mrpt_Range;
79 CObservationImage mrpt_Image;
80 CObservationImage mrpt_Image_left;
81 CObservationImage mrpt_Image_right;
85 header.frame_id =
"map";
88 mrpt_Range.maxSensorDistance = 500;
89 mrpt_Range.minSensorDistance = 60;
90 mrpt_Range.sensorConeApperture = (float) M_PI/3;
92 for(
int i=0 ; i<num_ranges ; i++)
94 CObservationRange::TMeasurement measurement;
95 measurement.sensedDistance = i*1.0;
96 mrpt_Range.sensedData.push_back(measurement);
99 ros_Range =
new sensor_msgs::Range[num_ranges];
103 mrpt_IMU.rawMeasurements.at(IMU_ORI_QUAT_X) = 1;
104 mrpt_IMU.rawMeasurements.at(IMU_ORI_QUAT_Y) = 1;
105 mrpt_IMU.rawMeasurements.at(IMU_ORI_QUAT_Z) = 1;
106 mrpt_IMU.rawMeasurements.at(IMU_ORI_QUAT_W) = 1;
108 mrpt_IMU.rawMeasurements.at(IMU_X_ACC_GLOBAL) = 1;
109 mrpt_IMU.rawMeasurements.at(IMU_Y_ACC_GLOBAL) = 1;
110 mrpt_IMU.rawMeasurements.at(IMU_Z_ACC_GLOBAL) = 1;
112 mrpt_IMU.rawMeasurements.at(IMU_X_VEL) = 1;
113 mrpt_IMU.rawMeasurements.at(IMU_Y_VEL) = 1;
114 mrpt_IMU.rawMeasurements.at(IMU_Z_VEL) = 1;
117 CObservationImage image;
120 vector<string> files;
121 vector<string> files_fullpath;
124 string file_path1 =
"/home/raghavender/catkin_ws/src/mrpt_navigation/mrpt_bridge/src/images";
126 dir = opendir(file_path1.c_str());
127 while((pdir = readdir(dir)))
128 files.push_back(pdir->d_name);
129 for(
unsigned int i=0,j=0 ; i<files.size() ; i++)
131 if(files.at(i).size() > 4)
133 files_fullpath.push_back(file_path1 +
"/" + files.at(i));
138 sort(files_fullpath.begin(),files_fullpath.end());
144 CObservationImage image1, image2;
146 dirent *pdir1, *pdir2;
147 vector<string> files1, files2;
148 vector<string> files_fullpath1, files_fullpath2;
151 string file_path_left =
"/home/raghavender/catkin_ws/src/mrpt_navigation/mrpt_bridge/src/stereo_images/left";
152 string file_path_right =
"/home/raghavender/catkin_ws/src/mrpt_navigation/mrpt_bridge/src/stereo_images/right";
154 dir1 = opendir(file_path_left.c_str());
155 while((pdir1 = readdir(dir1)))
156 files1.push_back(pdir1->d_name);
157 for(
unsigned int i=0,j=0 ; i<files1.size() ; i++)
159 if(files1.at(i).size() > 4)
161 files_fullpath1.push_back(file_path_left +
"/" + files1.at(i));
165 sort(files_fullpath1.begin(),files_fullpath1.end());
168 dir2 = opendir(file_path_right.c_str());
169 while((pdir2 = readdir(dir2)))
170 files2.push_back(pdir2->d_name);
171 for(
unsigned int i=0,j=0 ; i<files2.size() ; i++)
173 if(files2.at(i).size() > 4)
175 files_fullpath2.push_back(file_path_right +
"/" + files2.at(i));
179 sort(files_fullpath2.begin(),files_fullpath2.end());
181 ROS_INFO(
"Range Message Conversion STARTED..!!");
193 mrpt_Image.image.loadFromFile(files_fullpath.at(i%(files_fullpath.size()-1)));
195 image_pub.publish(ros_Image);
198 mrpt_Image_left.image.loadFromFile(files_fullpath1.at(i%(files_fullpath1.size()-1)));
200 image_pub_left.publish(ros_Image_left);
202 mrpt_Image_right.image.loadFromFile(files_fullpath2.at(i%(files_fullpath2.size()-1)));
204 image_pub_right.publish(ros_Image_right);
208 mrpt_IMU.rawMeasurements.at(IMU_ORI_QUAT_X) = i*0.1;
209 mrpt_IMU.rawMeasurements.at(IMU_ORI_QUAT_Y) = i*0.1;
210 mrpt_IMU.rawMeasurements.at(IMU_ORI_QUAT_Z) = i*0.1;
211 mrpt_IMU.rawMeasurements.at(IMU_ORI_QUAT_W) = i*-0.1;
212 mrpt_IMU.rawMeasurements.at(IMU_X_ACC_GLOBAL) = i * 0.1;
213 mrpt_IMU.rawMeasurements.at(IMU_Y_ACC_GLOBAL) = i*0.1;
214 mrpt_IMU.rawMeasurements.at(IMU_Z_ACC_GLOBAL) = 9.8+ i*0.003;
215 mrpt_IMU.rawMeasurements.at(IMU_X_VEL) = i*0.1 * i*0.2;
216 mrpt_IMU.rawMeasurements.at(IMU_Y_VEL) = i*0.1 * i*0.2;
217 mrpt_IMU.rawMeasurements.at(IMU_Z_VEL) = 0;
223 mrpt::obs::gnss::Message_NMEA_GGA gga;
224 gga.fields.altitude_meters = 2;
225 gga.fields.latitude_degrees = i*0.001;
226 gga.fields.longitude_degrees = i*0.03 + 43;
227 gga.fields.fix_quality = 1;
228 mrpt_GPS.setMsg(gga);
230 navSatFix_pub.publish(ros_GPS);
235 ROS_INFO(
" published %d",i);
237 for(
int i=0 ; i<num_ranges ; i++)
238 range_pub[i].publish(ros_Range[i]);
bool mrpt2ros(const CObservationIMU &obj, const std_msgs::Header &msg_header, sensor_msgs::Imu &msg)
void publish(const boost::shared_ptr< M > &message) const
bool mrpt2ros(const CObservationGPS &obj, const std_msgs::Header &msg_header, sensor_msgs::NavSatFix &msg)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool mrpt2ros(const CObservationImage &obj, const std_msgs::Header &msg_header, sensor_msgs::Image &msg)
bool mrpt2ros(const CObservationRange &obj, const std_msgs::Header &msg_header, sensor_msgs::Range *msg)
ROSCPP_DECL void spinOnce()
int main(int argc, char **argv)