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
00036 #ifndef _texturize_polygon_primitives_CPP_
00037 #define _texturize_polygon_primitives_CPP_
00038
00039
00040 #include "texturize_polygon_primitives.h"
00041
00042 #define _USE_THREADS_ 0
00043
00044 void handler_cam_roof_fc(const sensor_msgs::ImageConstPtr& msg)
00045 {
00046 try
00047 {
00048 cam_roof_fc.cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::TYPE_8UC3);
00049 }
00050 catch (cv_bridge::Exception& e)
00051 {
00052 ROS_ERROR("cv_bridge exception: %s", e.what());
00053 return;
00054 }
00055
00056 cam_roof_fc.image_ts = msg->header.stamp;
00057 cam_roof_fc.msg_received = true;
00058 cam_roof_fc.image = cam_roof_fc.cv_ptr->image;
00059 }
00060
00061 void handler_cam_roof_fl(const sensor_msgs::ImageConstPtr& msg)
00062 {
00063 try
00064 {
00065 cam_roof_fl.cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::TYPE_8UC3);
00066 }
00067 catch (cv_bridge::Exception& e)
00068 {
00069 ROS_ERROR("cv_bridge exception: %s", e.what());
00070 return;
00071 }
00072
00073 cam_roof_fl.image_ts = msg->header.stamp;
00074 cam_roof_fl.msg_received = true;
00075 cam_roof_fl.image = cam_roof_fl.cv_ptr->image;
00076 }
00077
00078 void handler_cam_roof_fr(const sensor_msgs::ImageConstPtr& msg)
00079 {
00080 try
00081 {
00082 cam_roof_fr.cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::TYPE_8UC3);
00083 }
00084 catch (cv_bridge::Exception& e)
00085 {
00086 ROS_ERROR("cv_bridge exception: %s", e.what());
00087 return;
00088 }
00089
00090 cam_roof_fr.image_ts = msg->header.stamp;
00091 cam_roof_fr.msg_received = true;
00092 cam_roof_fr.image = cam_roof_fr.cv_ptr->image;
00093 }
00094
00095 void handler_cam_roof_rc(const sensor_msgs::ImageConstPtr& msg)
00096 {
00097 try
00098 {
00099 cam_roof_rc.cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::TYPE_8UC3);
00100 }
00101 catch (cv_bridge::Exception& e)
00102 {
00103 ROS_ERROR("cv_bridge exception: %s", e.what());
00104 return;
00105 }
00106
00107 cam_roof_rc.image_ts = msg->header.stamp;
00108 cam_roof_rc.msg_received = true;
00109 cam_roof_rc.image = cam_roof_rc.cv_ptr->image;
00110 }
00111
00112 void handler_cam_roof_fc_6mm(const sensor_msgs::ImageConstPtr& msg)
00113 {
00114 try
00115 {
00116 cam_roof_fc_6mm.cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::TYPE_8UC3);
00117 }
00118 catch (cv_bridge::Exception& e)
00119 {
00120 ROS_ERROR("cv_bridge exception: %s", e.what());
00121 return;
00122 }
00123
00124 cam_roof_fc_6mm.image_ts = msg->header.stamp;
00125 cam_roof_fc_6mm.msg_received = true;
00126 cam_roof_fc_6mm.image = cam_roof_fc_6mm.cv_ptr->image;
00127 }
00128
00129 int add_camera_projection_to_polygon(std::string cam_name, t_cam* cam, c_polygon_primitive_with_texture* plg)
00130 {
00131 if (cam->msg_received)
00132 {
00133 ros::Time t = ros::Time::now();
00134 ROS_INFO("Building local mesh for camera %s to plg %s",cam_name.c_str(), plg->data.misc.name);
00135
00136
00137 try
00138 {
00139 p_listener->lookupTransform("/tf_" + cam_name, "/world", cam->image_ts, cam->tf);
00140 }
00141 catch (tf::TransformException ex){ROS_ERROR("%s",ex.what()); return -1;}
00142
00143 char str[1024];
00144 ros::Duration dur = ros::Time::now() - mission_start;
00145 sprintf(str,"{%s, %s, %0.1f}", plg->data.misc.name,cam_name.c_str(), dur.toSec());
00146 std::string projection_name = str;
00147
00148 int v = plg->add_camera_projection_known_camera(&cam->image, cam->image_ts, cam->tf, cam_name, projection_name, plg->colormap->cv_color(plg->cp.size()));
00149
00150 if (v!=-1)
00151 {
00152 ros::Duration d = ros::Time::now() - t;
00153 ROS_INFO("Successfully build of local mesh (%ld faces) for camera projection %s to plg %s (%f seconds)",plg->cp[v].mesh.number_of_faces(), cam_name.c_str(),plg->data.misc.name, d.toSec());
00154 return v;
00155 }
00156 else
00157 {
00158 ROS_INFO("Could not build local mesh for camera %s to plg %s",cam_name.c_str(),plg->data.misc.name);
00159 return v;
00160 }
00161 }
00162 else
00163 {
00164 ROS_INFO("Did not receive any new image from camera %s. Cannot create local mesh",cam_name.c_str());
00165 return -1;
00166 }
00167
00168 return -1;
00169 }
00170
00171
00172 void* process_polygon_primitive(void* ptr)
00173 {
00174 c_polygon_primitive_with_texture* plg = (c_polygon_primitive_with_texture*) ptr;
00175
00176 #if _USE_THREADS_
00177 ROS_INFO("\n__________________________________\nStart processing thread plg %s\n__________________________________\n", plg->data.misc.name);
00178 pthread_mutex_lock(&plg->mutex);
00179 #endif
00180
00181
00182
00183 add_camera_projection_to_polygon("cam_roof_fc_6mm", &cam_roof_fc_6mm, plg);
00184
00185
00186
00187
00188
00189
00190
00191
00192 plg->build_global_mesh(p_markerarray_pub);
00193 #if _USE_THREADS_
00194 pthread_mutex_unlock(&plg->mutex);
00195 ROS_INFO("\n__________________________________\nFinished processing thread plg %s\n__________________________________\n", plg->data.misc.name);
00196 #endif
00197 return NULL;
00198 }
00199
00205 void polygon_primitive_received_handler(const polygon_primitive_msg::polygon_primitive& input)
00206 {
00207
00208 ros::Duration(0.1).sleep();
00209
00210 ROS_INFO("Received a new polygon primitive msg. Polygon name %s", input.name.c_str());
00211
00212
00213
00214
00215 if (input.name!="p1")
00216 return;
00217
00218
00219
00220
00221 c_polygon_primitive_with_texture* plg = NULL;
00222 std::map<std::string, c_polygon_primitive_with_texture>::iterator it;
00223 it = pmap.find(input.name);
00224
00225
00226
00227
00228 if (it != pmap.end())
00229 {
00230 ROS_INFO("have a key with code %s . Will addapt polygon", input.name.c_str());
00231
00232 it->second.readapt_to_new_plane((polygon_primitive_msg::polygon_primitive*)&input);
00233
00234
00235
00236
00237
00238
00239
00240 plg = &it->second;
00241
00242 }
00243 else
00244 {
00245 ROS_INFO("have no key with code %s . Will add polygon to pmap", input.name.c_str());
00246
00247
00248 c_polygon_primitive_with_texture new_plg_from_msg(p_node);
00249 new_plg_from_msg.import_from_polygon_primitive_msg((polygon_primitive_msg::polygon_primitive*) &input);
00250
00251
00252 std::pair< std::map<std::string, c_polygon_primitive_with_texture>::iterator, bool> ret;
00253 ret = pmap.insert(std::pair<std::string, c_polygon_primitive_with_texture>(input.name, new_plg_from_msg));
00254 if (ret.second==false)
00255 {
00256 plg=NULL;
00257 ROS_ERROR("Error, could not insert polygon to map");
00258 }
00259 else
00260 {
00261 plg = &ret.first->second;
00262 }
00263 }
00264
00265 #if _USE_THREADS_
00266 pthread_create(&plg->thread,NULL,process_polygon_primitive,(void*) plg);
00267 #else
00268 process_polygon_primitive((void*)plg);
00269 #endif
00270 }
00271
00278 int main(int argc, char **argv)
00279 {
00280 ros::init(argc, argv, "texturize_polygon_primitives");
00281 ros::NodeHandle n;
00282 p_node = &n;
00283 ros::Rate r(10);
00284 ros::Rate r1(1);
00285
00286 cv::startWindowThread();
00287
00288 tf::TransformListener listener;
00289 p_listener = &listener;
00290
00291 image_transport::ImageTransport it(n);
00292 image_transport::Subscriber sub_fc = it.subscribe("/cam_roof_fc", 1, handler_cam_roof_fc);
00293 while(n.ok()){ros::spinOnce(); if (cam_roof_fc.msg_received) break; ROS_INFO("Waiting for first topic /cam_roof_fc");r1.sleep();}
00294
00295 image_transport::Subscriber sub_fl = it.subscribe("/cam_roof_fl", 1, handler_cam_roof_fl);
00296
00297
00298 image_transport::Subscriber sub_fr = it.subscribe("/cam_roof_fr", 1, handler_cam_roof_fr);
00299
00300
00301 image_transport::Subscriber sub_rc = it.subscribe("/cam_roof_rc", 1, handler_cam_roof_rc);
00302
00303
00304 image_transport::Subscriber sub_fc_6mm = it.subscribe("/cam_roof_fc_6mm", 1, handler_cam_roof_fc_6mm);
00305
00306
00307 ros::Subscriber sub_polygon_primitive = n.subscribe("/polygon_primitive", 10, polygon_primitive_received_handler);
00308 ros::Publisher markerarray_pub = n.advertise<visualization_msgs::MarkerArray>("/PolygonMarkers_with_texture", 5);
00309 p_markerarray_pub = &markerarray_pub;
00310
00311 ROS_INFO("Waiting for topic /polygon_primitive");
00312 mission_start = ros::Time::now();
00313
00314 ros::Time t=ros::Time::now();
00315 while(n.ok())
00316 {
00317 ros::Duration d = ros::Time::now()-t;
00318
00319 if (d.toSec()>5)
00320 {
00321
00322
00323
00324 std::vector<visualization_msgs::Marker> marker_vec;
00325 visualization_msgs::MarkerArray marker_array_msg;
00326 std::map<std::string, c_polygon_primitive_with_texture>::iterator it;
00327
00328 ROS_INFO("Sending textured polygon primitives to RVIZ");
00329 for (it=pmap.begin(); it!=pmap.end();++it)
00330 {
00331 visualization_msgs::MarkerArray marker_vec;
00332
00333
00334
00335 #if _USE_THREADS_
00336 if (pthread_mutex_trylock(&it->second.mutex))
00337 {
00338 #endif
00339 ROS_INFO("Sending tpp %s", it->second.data.misc.name);
00340 it->second.create_textures_vizualization_msg(&marker_vec, false);
00341
00342 p_markerarray_pub->publish(marker_vec);
00343
00344 for (size_t i=0; i<it->second.cp.size();i++)
00345 {
00346 cv::namedWindow(it->second.cp[i].projection_name);
00347 cv::imshow(it->second.cp[i].projection_name,it->second.cp[i].image_gui);
00348
00349
00350 }
00351
00352 #if _USE_THREADS_
00353 pthread_mutex_unlock(&it->second.mutex);
00354 }
00355 else
00356 {
00357 ROS_WARN("Could not send tpp %s. Thread locked", it->second.data.misc.name);
00358 }
00359 #endif
00360
00361 }
00362
00363 cv::waitKey(50);
00364
00365 t=ros::Time::now();
00366 }
00367
00368 r.sleep();
00369 ros::spinOnce();
00370 }
00371
00372 PFLN
00373
00374 return 0;
00375 }
00376 #endif
00377