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
00027 #include <navigability_map/navigability_map.h>
00028 #include "representation_rviz.h"
00040
00041 Navigability_Map *g_NavMap;
00042 bool cloud_arrived=false;
00043
00044 ros::Publisher elevation_map_pub;
00045 ros::Publisher normals_pub;
00046 ros::Publisher accessibility_map_pub;
00047 ros::Publisher polygon_pub;
00048 ros::Publisher obstacle_pub;
00049
00050 pcl::PointCloud<pcl::PointXYZ>::Ptr pc_filter (new pcl::PointCloud<pcl::PointXYZ>);
00051
00052 tf::TransformListener *p_listener;
00053
00060 void pointcloud_cb (sensor_msgs::PointCloud2 pcmsg_in)
00061 {
00062 visualization_msgs::MarkerArray grid_markers_elavationmap, accessibility_markers;
00063 visualization_msgs::Marker marker_normals;
00064 visualization_msgs::Marker marker_polygon;
00065 visualization_msgs::Marker marker_obstacle;
00066
00067
00068 pcl::PointCloud<pcl::PointXYZ> pc_in;
00069 pcl::fromROSMsg(pcmsg_in,pc_in);
00070 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in (new pcl::PointCloud<pcl::PointXYZ>);
00071 *cloud_in=pc_in;
00072
00073
00074 g_NavMap->Filter_PointCloud(cloud_in,pc_filter);
00075
00076
00077 std::cout<<"Normal Estimation"<<std::endl;
00078 g_NavMap->Normal_Estimation(pc_filter);
00079
00080 double max_Xval=g_NavMap->Xmax_filter;
00081 double max_Yval=max(abs(g_NavMap->Ymin_filter),g_NavMap->Ymax_filter);
00082
00083
00084 g_NavMap->setGrid_parameter(max_Xval,max_Yval);
00085
00086
00087 g_NavMap->inicialize_grid();
00088
00089
00090 g_NavMap->setGrid_data(*pc_filter);
00091
00092
00093 g_NavMap->calcGrid_data();
00094
00095
00096 g_NavMap->fill_data_cells();
00097
00098
00099 g_NavMap->set_Cells_accessibility();
00100
00101
00102
00103
00104
00105
00106
00107 grid_markers_elavationmap.markers=create_Markers_ElavationMap(*g_NavMap, pc_filter->header.frame_id );
00108
00109 marker_normals=create_Markers_Normals(*g_NavMap, pc_filter->header.frame_id);
00110
00111 accessibility_markers.markers=create_Markers_AccessibilityMap(*g_NavMap, pc_filter->header.frame_id);
00112
00113
00114 elevation_map_pub.publish(grid_markers_elavationmap);
00115 normals_pub.publish(marker_normals);
00116 accessibility_map_pub.publish(accessibility_markers);
00117
00118
00119
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134 cloud_arrived=true;
00135 }
00136
00137 int main(int argc, char **argv)
00138 {
00139 ros::init(argc, argv, "navigability_map");
00140 ros::NodeHandle n("~");
00141
00142 tf::TransformListener listener(n,ros::Duration(1000));
00143 p_listener=&listener;
00144
00145
00146 Navigability_Map navmap;
00147 g_NavMap=&navmap;
00148
00149 double output_freq;
00150
00151
00152 n.param("output_frequency", output_freq, 200.0);
00153 n.param("PointCLoud_Xmin_filter",g_NavMap->Xmin_filter,0.0);
00154 n.param("PointCLoud_Xmax_filter",g_NavMap->Xmax_filter,22.5);
00155 n.param("PointCLoud_Ymax_filter",g_NavMap->Ymax_filter,22.5);
00156 n.param("PointCLoud_Ymin_filter",g_NavMap->Ymin_filter,-22.5);
00157 n.param("PointCLoud_Zmin_filter",g_NavMap->Zmin_filter,-15.0);
00158 n.param("PointCLoud_Zmax_filter",g_NavMap->Zmax_filter,2.0);
00159 n.param("Grid_Sx",g_NavMap->Sx,0.2);
00160 n.param("Grid_Sy",g_NavMap->Sy,0.2);
00161 n.param("Radius_neighbors",g_NavMap->Radius_neighbors,0.3);
00162 n.param("K_neighbors",g_NavMap->K_neighbors,10);
00163 n.param("Use_Radius_Search",g_NavMap->Use_Radius_Search,1);
00164 n.param("Zmax_heigh_difference",g_NavMap->Zmax_heigh_difference,0.1);
00165 n.param("angleX_max_difference",g_NavMap->angleX_max_difference,0.1);
00166 n.param("angleY_max_difference",g_NavMap->angleY_max_difference,0.1);
00167 n.param("angleZ_max_difference",g_NavMap->angleZ_max_difference,0.1);
00168 n.param("debug_accessibility",g_NavMap->debug_accessibility,1);
00169 n.param("default_confidence",g_NavMap->default_confidence,0.5);
00170 n.param("fator_confidence_neighbour_limit",g_NavMap->fator_confidence_neighbour_limit,1.5);
00171 n.param("Standard_Deviation_max_confidence",g_NavMap->Standard_Deviation_max,0.2);
00172 n.param("Standard_Deviation_anglex_max_confidence",g_NavMap->Standard_Deviation_anglex_max_confidence,0.2);
00173 n.param("Standard_Deviation_angley_max_confidence",g_NavMap->Standard_Deviation_angley_max_confidence,0.2);
00174 n.param("Standard_Deviation_anglez_max_confidence",g_NavMap->Standard_Deviation_anglez_max_confidence,0.2);
00175
00176
00177 ros::Subscriber sub_phiversion = n.subscribe ("/pointcloud0", 1, pointcloud_cb);
00178
00179
00180
00181 normals_pub = n.advertise<visualization_msgs::Marker>("/normals", 1);
00182
00183 ros::Publisher pub = n.advertise<sensor_msgs::PointCloud2>("/pc_filter_navmap", 1);
00184
00185 elevation_map_pub = n.advertise<visualization_msgs::MarkerArray>("/elevation_map", 1);
00186 accessibility_map_pub = n.advertise<visualization_msgs::MarkerArray>("/accessibility_map", 1);
00187
00188
00189 polygon_pub = n.advertise<visualization_msgs::Marker>("/polygon", 1);
00190 obstacle_pub = n.advertise<visualization_msgs::Marker>("/obstacle", 1);
00191
00192 ros::Rate loop_rate(output_freq);
00193
00194 while (n.ok())
00195 {
00196 ros::spinOnce();
00197
00198 if (cloud_arrived)
00199 {
00200 sensor_msgs::PointCloud2 pcmsg_out;
00201 pcl::toROSMsg(*pc_filter, pcmsg_out);
00202 pcmsg_out.header.stamp = ros::Time::now();
00203
00204 pub.publish(pcmsg_out);
00205
00206 cloud_arrived=false;
00207 }
00208 loop_rate.sleep();
00209 }
00210 }