diff --git a/include/structs_definitions.h b/include/structs_definitions.h index 05773cace21782c672405d860e3e678283e9ae30..5263d124b4b8300858ec0558726c206c14e0da5d 100644 --- a/include/structs_definitions.h +++ b/include/structs_definitions.h @@ -10,6 +10,10 @@ #include <pcl/point_types.h> +const int TITS_EVALUATION = 0; +const int TRAVEL_EVALUATION = 1; +const int KATA_EVALUATION = 2; + const float OUT_OF_RANGE = 1000.0; const float MAX_RANGE = 100.0; @@ -94,6 +98,10 @@ const uint8_t R_CLASS_KITTI_OBSTACLE = 0; const uint8_t G_CLASS_KITTI_OBSTACLE = 255; const uint8_t B_CLASS_KITTI_OBSTACLE = 255; +const uint8_t R_CLASS_NON_TRAVERSABLE = 255; +const uint8_t G_CLASS_NON_TRAVERSABLE = 0; +const uint8_t B_CLASS_NON_TRAVERSABLE = 255; + // Key obstacles like cars, pedestrians and so on are the rest of the classes so we will not explicitly write them here //Custom labels not present in Kitti semantic diff --git a/src/kf_based_terrain_analysis.cpp b/src/kf_based_terrain_analysis.cpp index 1e3f454116f650309f37d17ca1eeaa94e45ea415..d8ab35d0a83ba8629a6f37b44cf251433de9b737 100644 --- a/src/kf_based_terrain_analysis.cpp +++ b/src/kf_based_terrain_analysis.cpp @@ -893,9 +893,9 @@ void CKf_Based_Terrain_Analysis::createDenseGroundCloud( float min_std_dev = 1000.0; float max_std_dev = -1.0; - for (float i = -40.0; i < 40.0; i += 0.2) + for (float i = -80.0; i < 80.0; i += 0.4) { - for (float j = -40.0; j < 40.0; j += 0.2) + for (float j = -80.0; j < 80.0; j += 0.4) { pcl::PointXYZRGBNormal point; point.x = i; @@ -990,11 +990,11 @@ void CKf_Based_Terrain_Analysis::fastLabelPointcloudUsingGroundModel( for (pcl::PointCloud<pcl::PointXYZRGBNormal>::iterator i = elevation_cloud_ptr->begin(); i != elevation_cloud_ptr->end(); ++i) { - pcl::PointXYZRGBNormal point_in_sensor_frame = *i; + pcl::PointXYZRGBNormal elevation_cloud_point = *i; // We pick the reference that made the best prediction for this point in the elevation cloud int reference_index = (int)std::floor( - point_in_sensor_frame.data_c[DATA_C_2_INDEX_OF_GROUND_REF_THAT_MADE_THE_LABEL]); + elevation_cloud_point.data_c[DATA_C_2_INDEX_OF_GROUND_REF_THAT_MADE_THE_LABEL]); if (reference_index != INDEX_UNKNOWN) { @@ -1006,9 +1006,9 @@ void CKf_Based_Terrain_Analysis::fastLabelPointcloudUsingGroundModel( // ground classification std::vector<int> features_indexes_in_pcl_cloud_ptr; - std::vector<double> rgb_values; - std::vector<double> hsv_values; - std::vector<double> local_binary_patterns; + std::vector<double> rgb_values; // Currently not in use, but we left it here for future research in sensor fusion + std::vector<double> hsv_values; // Currently not in use, but we left it here for future research in sensor fusion + std::vector<double> local_binary_patterns; // Currently not in use, but we left it here for future research in sensor fusion std::vector<double> squared_distances; std::vector<double> incidence_angles; @@ -1020,7 +1020,7 @@ void CKf_Based_Terrain_Analysis::fastLabelPointcloudUsingGroundModel( // 2) We point to the vector of indices related to the elevation_cloud point under evaluation std::vector<std::vector<int>>::const_iterator index_iterator = correspondence_indexes.begin() - + point_in_sensor_frame.data_c[DATA_C_3_ORIGINAL_INDEX]; + + elevation_cloud_point.data_c[DATA_C_3_ORIGINAL_INDEX]; // and iterate over this vector for (std::vector<int>::const_iterator point_iterator = index_iterator->begin(); @@ -1050,9 +1050,9 @@ void CKf_Based_Terrain_Analysis::fastLabelPointcloudUsingGroundModel( features_indexes_in_pcl_cloud_ptr.push_back(*point_iterator); // Index to modify the classification in a later step //std::cout << "Index saved = " << *point_iterator << std::endl; - rgb_values.push_back(point_to_evaluate.data_n[DATA_N_1_INTENSITY_VARIANCE]); // Feature! - hsv_values.push_back(point_to_evaluate.data_n[DATA_N_2_Z_MEAN]); // Feature! - local_binary_patterns.push_back(point_to_evaluate.data_n[DATA_N_3_Z_VARIANCE]); // Feature! + rgb_values.push_back(point_to_evaluate.data_n[DATA_N_1_INTENSITY_VARIANCE]); // Feature! // Currently not in use, but we left it here for future research in sensor fusion + hsv_values.push_back(point_to_evaluate.data_n[DATA_N_2_Z_MEAN]); // Feature! // Currently not in use, but we left it here for future research in sensor fusion + local_binary_patterns.push_back(point_to_evaluate.data_n[DATA_N_3_Z_VARIANCE]); // Feature! // Currently not in use, but we left it here for future research in sensor fusion squared_distances.push_back( (double)(point_to_evaluate.x * point_to_evaluate.x + point_to_evaluate.y * point_to_evaluate.y @@ -1084,7 +1084,9 @@ void CKf_Based_Terrain_Analysis::fastLabelPointcloudUsingGroundModel( } else { - if ((pcl_cloud_ptr->points[*point_iterator].z - point_in_sensor_frame.z) + //if ((pcl_cloud_ptr->points[*point_iterator].z - elevation_cloud_point.z) + // < filtering_configuration.robot_height) + if (euclideanDistance(reference_in_sensor_frame, pcl_cloud_ptr->points[*point_iterator]) < filtering_configuration.robot_height) { // TODO: when passing the point cloud through a ROS topic, @@ -1128,7 +1130,7 @@ void CKf_Based_Terrain_Analysis::fastLabelPointcloudUsingGroundModel( && (filtering_configuration.use_neural_network || filtering_configuration.extract_data_to_external_training_of_the_network)) { - int total_num_of_points = correspondence_indexes[point_in_sensor_frame.data_c[DATA_C_3_ORIGINAL_INDEX]].size(); + int total_num_of_points = correspondence_indexes[elevation_cloud_point.data_c[DATA_C_3_ORIGINAL_INDEX]].size(); //std::cout << "total_num_of_points = " << total_num_of_points << std::endl; double ratio_ground_points = (double)num_of_ground_points / (double)total_num_of_points; // Feature! @@ -1220,63 +1222,80 @@ void CKf_Based_Terrain_Analysis::fastLabelPointcloudUsingGroundModel( int predicted_class = nn_.predict(features); - if (predicted_class == CLASS_OBSTACLE) + switch (nn_.number_of_neurons_in_output_layer_) { - pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].data_c[DATA_C_1_ID_CLASS] = - (float)predicted_class + 0.0; + case (2): + if (predicted_class == CLASS_OBSTACLE) + { + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].data_c[DATA_C_1_ID_CLASS] = + (float)predicted_class + 0.0; + + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].r = R_CLASS_NON_TRAVERSABLE; + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].g = G_CLASS_NON_TRAVERSABLE; + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].b = B_CLASS_NON_TRAVERSABLE; + } + else + { + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].data_c[DATA_C_1_ID_CLASS] = + (float)predicted_class + (float)scores[n]; + + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].r = R_CLASS_GROUND; + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].g = G_CLASS_GROUND; + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].b = B_CLASS_GROUND; + } + //std::cout << "Class + score = " << pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].data_c[DATA_C_1_ID_CLASS] << std::endl; + break; - pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].r = R_CLASS_OBSTACLE; - pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].g = G_CLASS_OBSTACLE; - pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].b = B_CLASS_OBSTACLE; - } - else - { - pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].data_c[DATA_C_1_ID_CLASS] = - (float)predicted_class + (float)scores[n]; + case (5): + switch (predicted_class) + { + case ROAD: + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].r = R_CLASS_ROAD; + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].g = G_CLASS_ROAD; + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].b = B_CLASS_ROAD; + //std::cout << "NN says point is road!" << std::endl; + break; + + case SIDEWALK: + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].r = R_CLASS_SIDEWALK; + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].g = G_CLASS_SIDEWALK; + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].b = B_CLASS_SIDEWALK; + //std::cout << "NN says point is sidewalk!" << std::endl; + break; + + case TERRAIN: + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].r = R_CLASS_TERRAIN; + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].g = G_CLASS_TERRAIN; + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].b = B_CLASS_TERRAIN; + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].data_c[DATA_C_1_ID_CLASS] = + (float)CLASS_OBSTACLE + 0.0; + //std::cout << "NN says point is terrain!" << std::endl; + break; + + case VEGETATION: + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].r = R_CLASS_VEGETATION; + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].g = G_CLASS_VEGETATION; + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].b = B_CLASS_VEGETATION; + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].data_c[DATA_C_1_ID_CLASS] = + (float)CLASS_OBSTACLE + 0.0; + //std::cout << "NN says point is vegetation!" << std::endl; + break; + + case CLASS_OBSTACLE: + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].r = R_CLASS_KITTI_OBSTACLE; + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].g = G_CLASS_KITTI_OBSTACLE; + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].b = B_CLASS_KITTI_OBSTACLE; + pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].data_c[DATA_C_1_ID_CLASS] = + (float)CLASS_OBSTACLE + 0.0; + //std::cout << "NN says point is Obstacle!" << std::endl; + break; + } + break; - pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].r = R_CLASS_GROUND; - pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].g = G_CLASS_GROUND; - pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].b = B_CLASS_GROUND; + default: + assert("ERROR in CKf_Based_Terrain_Analysis::fastLabelPointcloudUsingGroundModel: Unrecognized number of outputs in Shallow Neural Network" && false); + break; } - //std::cout << "Class + score = " << pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].data_c[DATA_C_1_ID_CLASS] << std::endl; - -// switch (predicted_class) -// { -// case ROAD: -// pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].r = R_CLASS_ROAD; -// pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].g = G_CLASS_ROAD; -// pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].b = B_CLASS_ROAD; -// //std::cout << "NN says point is road!" << std::endl; -// break; -// -// case SIDEWALK: -// pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].r = R_CLASS_SIDEWALK; -// pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].g = G_CLASS_SIDEWALK; -// pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].b = B_CLASS_SIDEWALK; -// //std::cout << "NN says point is sidewalk!" << std::endl; -// break; -// -// case TERRAIN: -// pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].r = R_CLASS_TERRAIN; -// pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].g = G_CLASS_TERRAIN; -// pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].b = B_CLASS_TERRAIN; -// //std::cout << "NN says point is terrain!" << std::endl; -// break; -// -// case VEGETATION: -// pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].r = R_CLASS_VEGETATION; -// pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].g = G_CLASS_VEGETATION; -// pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].b = B_CLASS_VEGETATION; -// //std::cout << "NN says point is vegetation!" << std::endl; -// break; -// -// case CLASS_OBSTACLE: -// pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].r = R_CLASS_KITTI_OBSTACLE; -// pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].g = G_CLASS_KITTI_OBSTACLE; -// pcl_cloud_ptr->points[features_indexes_in_pcl_cloud_ptr[n]].b = B_CLASS_KITTI_OBSTACLE; -// //std::cout << "NN says point is Obstacle!" << std::endl; -// break; -// } } } @@ -1369,79 +1388,80 @@ void CKf_Based_Terrain_Analysis::fastLabelPointcloudUsingGroundModel( } else // if we don't have enough information to try to predict the ground level at this point { - if (filtering_configuration.classify_not_labeled_points_as_obstacles) - { - std::vector<std::vector<int>>::const_iterator index_iterator = correspondence_indexes.begin() - + point_in_sensor_frame.data_c[DATA_C_3_ORIGINAL_INDEX]; + std::vector<std::vector<int>>::const_iterator index_iterator = correspondence_indexes.begin() + + elevation_cloud_point.data_c[DATA_C_3_ORIGINAL_INDEX]; - for (std::vector<int>::const_iterator point_iterator = index_iterator->begin(); - point_iterator != index_iterator->end(); ++point_iterator) - { - // We now copy the data that is common to every point in the vector (because are statistics extracted - // from the points in the vector) - - // in data_n[0] we have the point intensity, so nothing to change - // in data_n[1] we will store the intensity variance in the elevation cloud cell - pcl_cloud_ptr->points[*point_iterator].data_n[DATA_N_1_INTENSITY_VARIANCE] = - point_in_sensor_frame.data_n[DATA_N_1_INTENSITY_VARIANCE]; - - // in data_n[2] we store the mean z value in the elevation cell - pcl_cloud_ptr->points[*point_iterator].data_n[DATA_N_2_Z_MEAN] = - point_in_sensor_frame.data_n[DATA_N_2_Z_MEAN]; - - // in data_n[3] we store the z variance in the elevation cell - pcl_cloud_ptr->points[*point_iterator].data_n[DATA_N_3_Z_VARIANCE] = - point_in_sensor_frame.data_n[DATA_N_3_Z_VARIANCE]; - - // TODO: we copy the mean intensity value in the channel reserved for the color, we do this because - // we have detected a problem with pcl conversions: when passing the point cloud through a ROS topic, - // channels c2 and c3 get corrupted, so we avoid to use them, we will investigate this problem in the - // future (hopefully) - // pcl_cloud_ptr->points[*point_iterator].data_c[DATA_C_2_MEAN_INTENSITY] = - // point_in_sensor_frame.data_n[DATA_N_0_INTENSITY]; + for (std::vector<int>::const_iterator point_iterator = index_iterator->begin(); + point_iterator != index_iterator->end(); ++point_iterator) + { + // We now copy the data that is common to every point in the vector (because are statistics extracted + // from the points in the vector) + + // in data_n[0] we have the point intensity, so nothing to change + // in data_n[1] we will store the intensity variance in the elevation cloud cell + pcl_cloud_ptr->points[*point_iterator].data_n[DATA_N_1_INTENSITY_VARIANCE] = + elevation_cloud_point.data_n[DATA_N_1_INTENSITY_VARIANCE]; + + // in data_n[2] we store the mean z value in the elevation cell + pcl_cloud_ptr->points[*point_iterator].data_n[DATA_N_2_Z_MEAN] = elevation_cloud_point.data_n[DATA_N_2_Z_MEAN]; + + // in data_n[3] we store the z variance in the elevation cell + pcl_cloud_ptr->points[*point_iterator].data_n[DATA_N_3_Z_VARIANCE] = + elevation_cloud_point.data_n[DATA_N_3_Z_VARIANCE]; + + // TODO: we copy the mean intensity value in the channel reserved for the color, we do this because + // we have detected a problem with pcl conversions: when passing the point cloud through a ROS topic, + // channels c2 and c3 get corrupted, so we avoid to use them, we will investigate this problem in the + // future (hopefully) + // pcl_cloud_ptr->points[*point_iterator].data_c[DATA_C_2_MEAN_INTENSITY] = + // elevation_cloud_point.data_n[DATA_N_0_INTENSITY]; // pcl_cloud_ptr->points[*point_iterator].data_c[DATA_C_0_RGB_CAST_INTO_FLOAT] = -// point_in_sensor_frame.data_n[DATA_N_0_INTENSITY]; - - if ((pcl_cloud_ptr->points[*point_iterator].z - point_in_sensor_frame.z) +// elevation_cloud_point.data_n[DATA_N_0_INTENSITY]; + if (filtering_configuration.classify_not_labeled_points_as_obstacles) + { + if ((pcl_cloud_ptr->points[*point_iterator].z - elevation_cloud_point.z) < filtering_configuration.ground_threshold_in_not_analyzed_areas) { // TODO: when passing the point cloud through a ROS topic, // channels c2 and c3 get corrupted, so we avoid to use them, we are temporarily the c0 channel // which is the one storing RGB values packed as a float, so colour is disabled at the moment - pcl_cloud_ptr->points[*point_iterator].r = 255;//R_CLASS_GROUND; // We use instead the r g b channels directly - pcl_cloud_ptr->points[*point_iterator].g = 255;//G_CLASS_GROUND; - pcl_cloud_ptr->points[*point_iterator].b = 0;//B_CLASS_GROUND; + pcl_cloud_ptr->points[*point_iterator].r = R_CLASS_GROUND; // 255 // We use instead the r g b channels directly + pcl_cloud_ptr->points[*point_iterator].g = G_CLASS_GROUND; // 0 + pcl_cloud_ptr->points[*point_iterator].b = B_CLASS_GROUND; // 255 float score = 0.0; // we don't have too much confidence in these points, because they are not analyzed pcl_cloud_ptr->points[*point_iterator].data_c[DATA_C_1_ID_CLASS] = (float)CLASS_GROUND + score; } - else if ((pcl_cloud_ptr->points[*point_iterator].z - point_in_sensor_frame.z) + else if ((pcl_cloud_ptr->points[*point_iterator].z - elevation_cloud_point.z) < filtering_configuration.robot_height) { - // TODO: when passing the point cloud through a ROS topic, - // channels c2 and c3 get corrupted, so we avoid to use them, we are temporarily the c0 channel - // which is the one storing RGB values packed as a float, so colour is disabled at the moment - pcl_cloud_ptr->points[*point_iterator].r = 255;//R_CLASS_OBSTACLE; - pcl_cloud_ptr->points[*point_iterator].g = 255;//G_CLASS_OBSTACLE; - pcl_cloud_ptr->points[*point_iterator].b = 0;//B_CLASS_OBSTACLE; + pcl_cloud_ptr->points[*point_iterator].r = R_CLASS_OBSTACLE; // 255 + pcl_cloud_ptr->points[*point_iterator].g = G_CLASS_OBSTACLE; // 0 + pcl_cloud_ptr->points[*point_iterator].b = B_CLASS_OBSTACLE; // 255 float score = 0.0; pcl_cloud_ptr->points[*point_iterator].data_c[DATA_C_1_ID_CLASS] = (float)CLASS_OBSTACLE + score; } else { - // TODO: when passing the point cloud through a ROS topic, - // channels c2 and c3 get corrupted, so we avoid to use them, we are temporarily the c0 channel - // which is the one storing RGB values packed as a float, so colour is disabled at the moment - pcl_cloud_ptr->points[*point_iterator].r = 255;//R_CLASS_OVERHANGING_OBSTACLE; - pcl_cloud_ptr->points[*point_iterator].g = 255;//G_CLASS_OVERHANGING_OBSTACLE; - pcl_cloud_ptr->points[*point_iterator].b = 0;//B_CLASS_OVERHANGING_OBSTACLE; + pcl_cloud_ptr->points[*point_iterator].r = R_CLASS_OVERHANGING_OBSTACLE; // 255 + pcl_cloud_ptr->points[*point_iterator].g = G_CLASS_OVERHANGING_OBSTACLE; // 0 + pcl_cloud_ptr->points[*point_iterator].b = B_CLASS_OVERHANGING_OBSTACLE; // 255 float score = 0.0; pcl_cloud_ptr->points[*point_iterator].data_c[DATA_C_1_ID_CLASS] = (float)CLASS_OVERHANGING_OBSTACLE + score; } } + else + { + pcl_cloud_ptr->points[*point_iterator].r = R_CLASS_UNKNOWN; + pcl_cloud_ptr->points[*point_iterator].g = G_CLASS_UNKNOWN; + pcl_cloud_ptr->points[*point_iterator].b = B_CLASS_UNKNOWN; + + float score = 0.0; + pcl_cloud_ptr->points[*point_iterator].data_c[DATA_C_1_ID_CLASS] = (float)CLASS_UNKNOWN + score; + } } } }