collision prevention problem
-
@Eric-Katzfey We are conducting outdoor tests for collision prevention using the M0015 stereo camera. The main parameters we adjusted include ae_desired_msv in voxl-camera-server.conf and blur_size, post_median_size, and cost_threshold in voxl-dfs-server.conf. However, we have encountered some issues that have led to subpar performance in collision prevention. The problems are as follows:
- The influence of lighting conditions such as backlighting, glare, etc., can cause the stereo camera to malfunction and make it challenging to find a set of parameters that work well in all situations.
- When the drone stops in front of an obstacle, sometimes it suddenly moves forward a short distance and then stops again. I suspect it may be due to the drone's body offset or lighting conditions causing a momentary failure in obstacle detection by the stereo camera.
- Would higher resolution cameras better capture obstacle features and thus improve the effectiveness of collision prevention?
Regarding the above issues, do you have any suggestions or ideas? Any guidance you can provide would be greatly appreciated. Below are the parameters I'm currently using.
voxl-camera-server.conf
voxl-dfs-server.conf
-
Hey, happy to try and help!
Unfortunately a lot of what you're describing sounds like typical camera behavior. We've also struggled with lighting conditions in the past and don't have a great fix. What I'd recommend more than anything is using
voxl-logger
to collect some logs of what you're seeing through the camera stream. This should enable you to look at the output and see if you notice anything funky and share the logs with us so we can do the same.Sorry this isn't the greatest of responses, hope this at least helps some. If you can gather some logs of the behavior you're seeing I'd be happy to take a look at them.
Thanks,
Thomas -
@rogerli Also, a PX4 flight log would be helpful. But the SDLOG_PROFILE parameter needs to first be set such that vision and avoidance topics are included. Make sure that parameter is set correctly and then provide a log of a flight where you see a problem along with the voxl-logger output with all of the saved camera frames then that can help us debug what is going on.
-
I notice with auto exposure params if you are overexposing the image the lighter features stand out even more if there are darker areas in the image (since it's a mean sample value) but this could lead to issues with quality. Underexposing the image you end up getting dark images if there is a window or other large light source in the camera frame, resulting again in quality issues.
There is a case for image masking but I have not seen it been used in real applications: https://www.researchgate.net/publication/228405828_Automatic_camera_exposure_control
-
@thomas @Eric-Katzfey Although I haven't looked at the logs of VOXL2 and PX4 before, I will try to read them and identify the issues. Additionally, while conducting collision prevention, I would like to understand the range of obstacles detected in the image and the parameters which can adjust it when the drone is flying forward. Currently, I am considering modifying the code based on this range so that the exposure parameters can be automatically adjusted based on the brightness changes within the range. Would this approach be able to improve the exposure issues in collision prevention?
-
@Eric-Katzfey Sorry, I didn't save the stereo camera images from voxl-logger, so I can only provide the PX4 log file. Currently, I am addressing the exposure issue using the method I mentioned earlier, and it seems to have improved the effectiveness of collision prevention. Additionally, to ensure that the drone can stably stop in front of obstacles, I made the following modifications to the voxl-vision-hub code.
int pie_binner_filter_to_mavlink_msg(pie_binner_t* b, mavlink_message_t* msg) { int i,j; // final distance data for px4 uint16_t distances[72]; uint16_t dist_max_cm = b->dist_table.dist_max * 100.0f; // now set the bins to max_distance +1 means no obstacle is present. for(i=0;i<72;i++){ distances[i] = dist_max_cm - 10; } if(b->ringbuf.items_in_buf>0){ // scan bins for any that meet the criteria // for each angle.... for(i=0; i<b->rows; i++){ // scan the distances from inside out, remember we have one extra column // than we do distance bins for(j=0; j<(b->cols-EXTRA_BINS_TO_CHECK); j++){ // skip empty bins if(b->map_points[i][j] <= 0) continue; // sum up points in this bin, the two on either side // and the three behind it int sum = 0; for(int k=-1; k<=1; k++){ // row (angle) to inspect with wraparound check int ii = i-k; if(ii<0) ii+=b->rows; else if(ii>=b->rows) ii-=b->rows; // sum points in this bin plus extras for(int m=0; m<=EXTRA_BINS_TO_CHECK; m++){ sum += b->map_points[ii][j+m]; } } // check the sum of points in all the neighbors if(sum >= b->pie_threshold){ float dist_m = b->map_dist[i][j] / b->map_points[i][j]; // if(dist_m<0.1f) continue; // error check, not needed? uint16_t dist_cm = dist_m * 100.0f; if(dist_cm<150) continue; else if(dist_cm>=150){ distances[i] = dist_cm; last_dis[i] = distances[i]; zero_count[i] = 0; //printf("added a distance! i: %d j:%d dist: %5.1fm\n", i, j, (double)dist_m); break; // move onto next angle } // distances[i] = dist_cm; // break; } } if(zero_count[i]<30){ distances[i] = last_dis[i]; zero_count[i]++; } } } // TODO investigate if min distance changes px4 behavior or not #define MIN_DISTANCE_CM 0 // set other params for mavlink message uint64_t time_usec = 0; uint8_t increment_int = 0; // use the float field instead float increment_f = 360.0f / b->tan_table.n_bins; float angle_offset = 0.0f; // 0 means bin 0 is straight ahead along X mavlink_msg_obstacle_distance_pack(autopilot_monitor_get_sysid(), VOXL_COMPID,\ msg, time_usec, MAV_DISTANCE_SENSOR_UNKNOWN, distances, increment_int,\ MIN_DISTANCE_CM, dist_max_cm, increment_f, angle_offset, MAV_FRAME_BODY_FRD); return 0; }
However, during the drone's flight to the right, it suddenly pauses. The drone's distance sensors are only equipped with front-facing stereo cameras, so they shouldn't detect obstacles on the right side. Why is this happening? Is there a way to solve it?
Here is my PX4 log file
https://review.px4.io/plot_app?log=fb1ae613-4e56-49a2-a60f-bc272edd78c1