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 
00034 #include "representation_rviz.h"
00035 
00036 vector<visualization_msgs::Marker> create_Markers_ElavationMap(Navigability_Map& nav_map, std::string grid_frame)
00037 {
00038         static Markers marker_list;
00039         grid_nodePtr node_data;
00040         double Zmin=nav_map.Zmin_filter;
00041         double Zmax=nav_map.Zmax_filter;
00042         int colorrange=nav_map.colorrange;
00043         
00044         
00045         marker_list.decrement();
00046         
00047         
00048         
00049         class_colormap colormap_positive("jet",colorrange, 1, false);
00050         class_colormap colormap_negative("pink",colorrange, 1, false);
00051         
00052         
00053         visualization_msgs::Marker marker_cell;
00054         
00055         marker_cell.header.frame_id = grid_frame;
00056     marker_cell.header.stamp = ros::Time::now();;
00057         marker_cell.ns = "elvation_cell";
00058         marker_cell.action = visualization_msgs::Marker::ADD;
00059         marker_cell.type = visualization_msgs::Marker::CUBE;
00060         marker_cell.pose.orientation.x = 0;     marker_cell.pose.orientation.y = 0.0;   marker_cell.pose.orientation.z = 0;     marker_cell.pose.orientation.w = 1;
00061         
00062         marker_cell.scale.x = nav_map.Sx;
00063         marker_cell.scale.y = nav_map.Sy;
00064 
00065         geometry_msgs::Point p;
00066         
00067         
00068         visualization_msgs::Marker marker_text;
00069         
00070         marker_text.header.frame_id = grid_frame;
00071     marker_text.header.stamp = ros::Time::now();;
00072         marker_text.ns = "confidence_cell";
00073         marker_text.action = visualization_msgs::Marker::ADD;
00074         marker_text.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
00075         marker_text.scale.x = 0.07;
00076         marker_text.scale.y = 0.07;
00077         marker_text.scale.z = 0.07;
00078         marker_text.color.a = 1.0;    
00079     marker_text.color.r = 0.0;   
00080     marker_text.color.g = 0.0;
00081     marker_text.color.b = 0.0;
00082         
00083         
00084         uint counter=0;
00085         for(uint row=0;row<nav_map.grid.rows();row++)
00086         {
00087                 
00088                 p.x = row*nav_map.Sx+nav_map.Sx/2;
00089                 
00090                 for(uint col=0;col<nav_map.grid.cols();col++)
00091                 {
00092                         
00093                         node_data = nav_map.grid(row,col);
00094                         
00095                         if (node_data->num_points>0 || node_data->interpolate_z_data) 
00096                         {
00097                                 
00098                                 marker_cell.id = counter;
00099                                 
00100                                 
00101                                 p.y = col*nav_map.Sy-nav_map.CARaxis_col*nav_map.Sy;
00102                                 
00103                                 
00104                                 
00105                                 p.z= node_data->Zmed/2;
00106                                 marker_cell.scale.z = node_data->Zmed;
00107                                 
00108                                 
00109                                 if (node_data->Zmed>=0 )
00110                                         marker_cell.color = colormap_positive.color((colorrange*node_data->Zmed)/Zmax);
00111                                 else
00112                                         marker_cell.color =colormap_positive.color((colorrange*abs(node_data->Zmed))/abs(Zmin));                                
00113                                         
00114                                 
00115                                 marker_cell.pose.position=p;
00116                                 
00117                                 
00118                                 marker_list.update(marker_cell);
00119                                         
00120                                 
00121 
00122                                 
00123                                 marker_text.id = counter;
00124                                 
00125                                 
00126                                 marker_text.pose.position.x = p.x;
00127                                 marker_text.pose.position.y = p.y;
00128                                 if (p.z>=0)
00129                                         marker_text.pose.position.z = node_data->Zmed+0.05; 
00130                                 else
00131                                         marker_text.pose.position.z = 0.05; 
00132                                 
00133                                 
00134                                 boost::format fm("%d");
00135                                 fm % node_data->Z_confidence;
00136 
00137 
00138                                 marker_text.text = fm.str();
00139                                 
00140                                 
00141 
00142 
00143                                 
00144                                 
00145                         }       
00146                         counter++;
00147                 }
00148         }
00149 
00150         
00151         marker_list.clean();
00152         
00153         
00154         return marker_list.getOutgoingMarkers();
00155 }
00156 
00157 
00158 
00159 visualization_msgs::Marker create_Markers_Normals(Navigability_Map& nav_map, std::string grid_frame)
00160 {
00161         grid_nodePtr node_data;
00162         double px_aux=0;
00163         double py_aux=0;
00164         double pz_aux=0;
00165         
00166         visualization_msgs::Marker mk; 
00167         
00168         geometry_msgs::Point p;
00169         std_msgs::ColorRGBA color;
00170 
00171         mk.header.frame_id = grid_frame; mk.header.stamp = ros::Time::now();    mk.ns = "normals";
00172         mk.action = visualization_msgs::Marker::ADD;    mk.type = visualization_msgs::Marker::LINE_LIST; mk.id = 0;
00173         mk.pose.position.x = 0; mk.pose.position.y = 0; mk.pose.position.z = 0;
00174         mk.pose.orientation.x = 0;      mk.pose.orientation.y = 0;      mk.pose.orientation.z = 0;      mk.pose.orientation.w = 1;
00175         mk.scale.x = 0.01; mk.scale.y = 0.01; mk.scale.z = 0;
00176         mk.color.r = 0.7; mk.color.g = 0; mk.color.b = 0; mk.color.a = 1;
00177 
00178         for(uint row=0;row<nav_map.grid.rows();row++)
00179         {
00180                 for(uint col=0;col<nav_map.grid.cols();col++)
00181                 {
00182                         node_data = nav_map.grid(row,col);
00183                         
00184                         if (node_data->has_normal) 
00185                         {
00186                                 
00187                                 p.x = row*nav_map.Sx+nav_map.Sx/2;
00188                                 px_aux = p.x;
00189                                 
00190                                 
00191                                 p.y = col*nav_map.Sy-nav_map.CARaxis_col*nav_map.Sy;
00192                                 py_aux = p.y;
00193                                 
00194                                 
00195                                 p.z= node_data->Zmed;
00196                                 if (p.z>=0)
00197                                         pz_aux=p.z; 
00198                                 else
00199                                 {
00200                                         p.z =0;
00201                                         pz_aux = 0; 
00202                                 }
00203                                         
00204                                 mk.points.push_back(p); 
00205 
00206                                 double rat=0.5;
00207 
00208                                 p.x = px_aux + (cos(node_data->med_angle_X))*rat;
00209                                 p.y = py_aux + (cos(node_data->med_angle_Y))*rat;
00210                                 p.z = pz_aux + (cos(node_data->med_angle_Z))*rat;
00211                 
00212                                 mk.points.push_back(p); 
00213                         }
00214                 }
00215         }
00216         
00217         return mk;
00218 }
00219 
00220 vector<visualization_msgs::Marker> create_Markers_AccessibilityMap(Navigability_Map& nav_map, std::string grid_frame)
00221 {
00222         static Markers marker_list;
00223         grid_nodePtr node_data;
00224 
00225         int colorrange=nav_map.colorrange;
00226         
00227         
00228         marker_list.decrement();
00229         
00230         
00231         
00232         class_colormap colormap_positive("jet",colorrange, 1, false);
00233         
00234         
00235         visualization_msgs::Marker marker_cell;
00236         
00237         marker_cell.header.frame_id = grid_frame;
00238     marker_cell.header.stamp = ros::Time::now();;
00239         marker_cell.ns = "accessibility_cell";
00240         marker_cell.action = visualization_msgs::Marker::ADD;
00241         marker_cell.type = visualization_msgs::Marker::CUBE;
00242         marker_cell.pose.orientation.x = 0;     marker_cell.pose.orientation.y = 0.0;   marker_cell.pose.orientation.z = 0;     marker_cell.pose.orientation.w = 1;
00243         
00244         marker_cell.scale.x = nav_map.Sx;
00245         marker_cell.scale.y = nav_map.Sy;
00246 
00247         geometry_msgs::Point p;
00248         
00249         
00250         
00251         visualization_msgs::Marker marker_text;
00252         
00253         marker_text.header.frame_id = grid_frame;
00254     marker_text.header.stamp = ros::Time::now();;
00255         marker_text.ns = "debug_cell";
00256         marker_text.action = visualization_msgs::Marker::ADD;
00257         marker_text.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
00258         marker_text.scale.x = 0.07;
00259         marker_text.scale.y = 0.07;
00260         marker_text.scale.z = 0.07;
00261         marker_text.color.a = 1.0;    
00262     marker_text.color.r = 0.0;   
00263     marker_text.color.g = 0.0;
00264     marker_text.color.b = 0.0;
00265         
00266         
00267         uint counter=0;
00268         for(uint row=0;row<nav_map.grid.rows();row++)
00269         {
00270                 
00271                 p.x = row*nav_map.Sx+nav_map.Sx/2;
00272                 
00273                 for(uint col=0;col<nav_map.grid.cols();col++)
00274                 {
00275                         
00276                         node_data = nav_map.grid(row,col);
00277                         
00278                         if (node_data->num_points>0 || node_data->interpolate_z_data) 
00279                         {
00280                                 
00281                                 marker_cell.id = counter;
00282                                 
00283                                 
00284                                 p.y = col*nav_map.Sy-nav_map.CARaxis_col*nav_map.Sy;
00285                                 
00286 
00287                                 if (nav_map.debug_accessibility==1)
00288                                         p.z=(1-node_data->z_accessibility)/2;
00289                                 else if (nav_map.debug_accessibility==2)
00290                                         p.z=(1-node_data->angleX_accessibility)/2;
00291                                 else if (nav_map.debug_accessibility==3)
00292                                         p.z=(1-node_data->angleY_accessibility)/2;
00293                                 else if (nav_map.debug_accessibility==4)
00294                                         p.z=(1-node_data->angleZ_accessibility)/2;
00295                                 else if (nav_map.debug_accessibility==5)
00296                                         p.z=(1-node_data->total_accessibility)/2;
00297                                 
00298                                 if (nav_map.debug_accessibility==1)
00299                                         marker_cell.scale.z =1-node_data->z_accessibility;
00300                                 else if (nav_map.debug_accessibility==2)
00301                                         marker_cell.scale.z =1-node_data->angleX_accessibility;
00302                                 else if (nav_map.debug_accessibility==3)
00303                                         marker_cell.scale.z =1-node_data->angleY_accessibility;
00304                                 else if (nav_map.debug_accessibility==4)
00305                                         marker_cell.scale.z =1-node_data->angleZ_accessibility;
00306                                 else if (nav_map.debug_accessibility==5)
00307                                         marker_cell.scale.z =1-node_data->total_accessibility;
00308                                 
00309                                 
00310                                 if (nav_map.debug_accessibility==1)
00311                                         marker_cell.color = colormap_positive.color(colorrange*(1-node_data->z_accessibility)-1);
00312                                 else if (nav_map.debug_accessibility==2)
00313                                         marker_cell.color = colormap_positive.color(colorrange*(1-node_data->angleX_accessibility)-1);
00314                                 else if (nav_map.debug_accessibility==3)
00315                                         marker_cell.color = colormap_positive.color(colorrange*(1-node_data->angleY_accessibility)-1);
00316                                 else if (nav_map.debug_accessibility==4)
00317                                         marker_cell.color = colormap_positive.color(colorrange*(1-node_data->angleZ_accessibility)-1);
00318                                 else if (nav_map.debug_accessibility==5)
00319                                         marker_cell.color = colormap_positive.color(colorrange*(1-node_data->total_accessibility)-1);
00320 
00321                                 
00322                                 
00323                                 marker_cell.pose.position=p;
00324                                 
00325                                 
00326                                 marker_list.update(marker_cell);
00327                                 
00328                                 
00329                                 
00330 
00331                                 marker_text.id = counter;
00332                                 
00333                                 
00334                                 marker_text.pose.position.x = p.x;
00335                                 marker_text.pose.position.y = p.y;
00336                                 
00337                                 if (nav_map.debug_accessibility==1)
00338                                         marker_text.pose.position.z = (1-node_data->z_accessibility)+0.1; 
00339                                 else if (nav_map.debug_accessibility==2)
00340                                         marker_text.pose.position.z = (1-node_data->angleX_accessibility)+0.1; 
00341                                 else if (nav_map.debug_accessibility==3)
00342                                         marker_text.pose.position.z = (1-node_data->angleY_accessibility)+0.1; 
00343                                 else if (nav_map.debug_accessibility==4)
00344                                         marker_text.pose.position.z = (1-node_data->angleZ_accessibility)+0.1; 
00345                                 else if (nav_map.debug_accessibility==5)
00346                                         marker_text.pose.position.z = (1-node_data->total_accessibility)+0.1;
00347                                 
00348                                 
00349                                 boost::format fm("%d");
00350                                 if (nav_map.debug_accessibility==1)
00351                                         fm % node_data->z_accessibility;
00352                                 else if (nav_map.debug_accessibility==2)
00353                                         fm % node_data->angleX_accessibility;
00354                                 else if (nav_map.debug_accessibility==3)
00355                                         fm % node_data->angleY_accessibility;
00356                                 else if (nav_map.debug_accessibility==4)
00357                                         fm % node_data->angleZ_accessibility;
00358                                 else if (nav_map.debug_accessibility==5)
00359                                         fm % node_data->total_accessibility;
00360                         
00361                                 marker_text.text = fm.str();
00362                                 
00363 
00364                                 
00365                         }
00366                         counter++;
00367                 }       
00368         }
00369 
00370         
00371         marker_list.clean();
00372         
00373         
00374         return marker_list.getOutgoingMarkers();        
00375 }
00376 
00377 
00378 
00379 visualization_msgs::Marker create_Markers_Polygon(Navigability_Map& nav_map, std::string grid_frame)
00380 {
00381         
00382         visualization_msgs::Marker mk; 
00383         
00384         std_msgs::ColorRGBA color;
00385 
00386         mk.header.frame_id = grid_frame; mk.header.stamp = ros::Time::now();    mk.ns = "polygon";
00387         mk.action = visualization_msgs::Marker::ADD;    mk.type = visualization_msgs::Marker::LINE_STRIP; mk.id = 0;
00388         mk.pose.position.x = 0; mk.pose.position.y = 0; mk.pose.position.z = 0;
00389         mk.pose.orientation.x = 0;      mk.pose.orientation.y = 0;      mk.pose.orientation.z = 0;      mk.pose.orientation.w = 1;
00390         mk.scale.x = 0.08; mk.scale.y = 0.01; mk.scale.z = 0;
00391         mk.color.r = 0; mk.color.g = 1; mk.color.b = 0; mk.color.a = 1;
00392 
00393         
00394         for (uint i=0; i<nav_map.polygon_points.size(); i++)
00395                 mk.points.push_back(nav_map.polygon_points[i]); 
00396         
00397         nav_map.polygon_points.erase(nav_map.polygon_points.begin(),nav_map.polygon_points.end());
00398         return mk;
00399 }
00400 
00401 visualization_msgs::Marker create_Markers_Obstacle(Navigability_Map& nav_map, std::string grid_frame)
00402 {
00403         
00404         visualization_msgs::Marker mk; 
00405         
00406         std_msgs::ColorRGBA color;
00407 
00408         mk.header.frame_id = grid_frame; mk.header.stamp = ros::Time::now();    mk.ns = "polygon_obstacle";
00409         mk.action = visualization_msgs::Marker::ADD;    mk.type = visualization_msgs::Marker::LINE_STRIP; mk.id = 0;
00410         mk.pose.position.x = 0; mk.pose.position.y = 0; mk.pose.position.z = 0;
00411         mk.pose.orientation.x = 0;      mk.pose.orientation.y = 0;      mk.pose.orientation.z = 0;      mk.pose.orientation.w = 1;
00412         mk.scale.x = 0.08; mk.scale.y = 0.01; mk.scale.z = 0;
00413         mk.color.r = 1; mk.color.g = 0; mk.color.b = 0; mk.color.a = 1;
00414 
00415         
00416         for (uint i=0; i<nav_map.obstacle_points.size(); i++)
00417                 mk.points.push_back(nav_map.obstacle_points[i]);        
00418         
00419         nav_map.obstacle_points.erase(nav_map.obstacle_points.begin(),nav_map.obstacle_points.end());
00420         return mk;
00421 }