diff --git a/params/iri_ground_segmentation.yaml b/params/iri_ground_segmentation.yaml index 9626478273bbf474c7b5e80ac89cb35201be669b..594e5870456276c4860b20b08251b1cd5e994f5f 100644 --- a/params/iri_ground_segmentation.yaml +++ b/params/iri_ground_segmentation.yaml @@ -9,7 +9,7 @@ iri_ground_segmentation: { ROI_delta_x_and_y: 3.0, #4.0, ## This value sets the size of the ROIs: ROI_size = (2*ROI_delta_x_and_y)^2 ROI_shadow_area: 7.0, #6.5, ## This value is the same that the above, but only used in the root vertex to overcome the shadow area - ground_reference_search_resolution_deg: 12, #40.0, #6.0, #12.00, ## It is the angular resolution when generating new ground references (graph nodes), + ground_reference_search_resolution_deg: 40.0, #6.0, #12.00, ## It is the angular resolution when generating new ground references (graph nodes), ## it will affect the number of nodes in the graph: lower values generate more nodes elevation_grid_resolution: 2.1, #1.2, #1.5, #1.0 #0.5, ## This value is used to create the "elevation point cloud" which is a reduction of the original pointcloud, where @@ -46,16 +46,16 @@ iri_ground_segmentation: { # labeling parameters max_pred_std_dev_for_labelling: 0.333, ## ONLY IN USE TO GIVE COLOUR TO DENSE RECONSTRUCTION - score_threshold: 0.475, #0.0 when using neural net ## for assigning ground class label: one means maha. dist. equal to zero, zero means mahalanobis dist equal to maha. thres + score_threshold: 0.0, #0.0 when using neural net ## for assigning ground class label: one means maha. dist. equal to zero, zero means mahalanobis dist equal to maha. thres classify_not_labeled_points_as_obstacles: false, ## when a point has no reference satisfying the max_pred_std_dev_for_labelling threshold we can leave as unknown or label it as obstacle ground_threshold_in_not_analyzed_areas: 0.1, ## when it is not possible to make a local analysis of the data, we will use the lowest point (the one in elevation_cloud) as ground height, and ## all the points above it and below this threshold will be classified as ground # low obstacle detection parameters use_low_obstacle_detection: true, - low_obstacle_min_height: 0.05, + low_obstacle_min_height: 0.1, sensor_best_resolution_deg: 0.2, # Best resolution, either horizontal or vertical - max_navigation_slope: 0.5, + max_navigation_slope: 0.2, # visualization and debug parameters evaluate_segmentation: true, diff --git a/src/ground_segmentation_alg_node.cpp b/src/ground_segmentation_alg_node.cpp index 2750fc1154028e6069c84554fe0039a84846f286..84b8e67324664579804f3f71f4a8e4e677487c42 100644 --- a/src/ground_segmentation_alg_node.cpp +++ b/src/ground_segmentation_alg_node.cpp @@ -795,12 +795,11 @@ void GroundSegmentationAlgNode::detectLowObstacles(float h, float res_deg, float { if (grid[x][y].label == 1) { - i->data_c[DATA_C_1_ID_CLASS] == CLASS_LOW_OBSTACLE; + i->data_c[DATA_C_1_ID_CLASS] = CLASS_LOW_OBSTACLE; i->r = R_CLASS_LOW_OBSTACLE; i->g = G_CLASS_LOW_OBSTACLE; i->b = B_CLASS_LOW_OBSTACLE; } - //std::cout << "Low obstacle found!" << std::endl; } } } @@ -826,9 +825,10 @@ void GroundSegmentationAlgNode::evaluateSegmentation(void) // Extracting info from our segmentation algorithm //std::cout << "Detected class + score as comes in the message = " << (float)it->data_c[DATA_C_1_ID_CLASS] << std::endl; - int detected_class = (int)std::floor(i->data_c[DATA_C_1_ID_CLASS]); + int detected_class = (int)std::floor(classified_point.data_c[DATA_C_1_ID_CLASS]); //std::cout << "detected_class = " << detected_class << std::endl; - float detection_score = i->data_c[DATA_C_1_ID_CLASS] - (float)detected_class; //we package the score_thres as decimal part of the label + + float detection_score = classified_point.data_c[DATA_C_1_ID_CLASS] - (float)detected_class; //we package the score_thres as decimal part of the label //std::cout << "detection_score = " << detection_score << std::endl; bool flag_not_analyzed_point = false; // Just to keep track of which TN and FN are due to the unknown points