lardemua / atom

Calibration tools for multi-sensor, multi-modal robotic systems
GNU General Public License v3.0
245 stars 28 forks source link

Collect data crashes when not using overwrite flag. #925

Closed brunofavs closed 2 months ago

brunofavs commented 2 months ago

When collecting data

roslaunch softbot_calibration collect_data.launch output_folder:=$ATOM_DATASETS/softbot/long_train_dataset1

Without using overwrite flag when the directory already exists but it's empty results in a bunch of errors.

When giving this error ...

Error: Dataset /home/bruno/datasets/softbot/long_train_dataset1 exists.
If you want to replace it add a "--overwrite" flag.

Shouldn't the program just end? This should be a easy fix.

Traceback (most recent call last):
  File "/home/bruno/atom_ws/src/atom/atom_calibration/src/atom_calibration/collect/rgb_labeler", line 195, in <module>
    main()
  File "/home/bruno/atom_ws/src/atom/atom_calibration/src/atom_calibration/collect/rgb_labeler", line 189, in main
    rgb_labeler = RGBLabeler(config, sensor_name=args['sensor_name'], debug=args['debug'], color=args['color'])
  File "/home/bruno/atom_ws/src/atom/atom_calibration/src/atom_calibration/collect/rgb_labeler", line 56, in __init__
    self.msg_type_str, self.msg_type = getMessageTypeFromTopic(self.sensor_config['topic_name'])
  File "/home/bruno/atom_ws/src/atom/atom_core/src/atom_core/ros_utils.py", line 31, in getMessageTypeFromTopic
    msg = rospy.wait_for_message(topic, rospy.AnyMsg)
  File "/opt/ros/noetic/lib/python3/dist-packages/rospy/client.py", line 428, in wait_for_message
    raise rospy.exceptions.ROSInterruptException("rospy shutdown")
rospy.exceptions.ROSInterruptException: rospy shutdown
Traceback (most recent call last):
  File "/home/bruno/atom_ws/src/atom/atom_calibration/src/atom_calibration/collect/rgb_labeler", line 195, in <module>
    main()
  File "/home/bruno/atom_ws/src/atom/atom_calibration/src/atom_calibration/collect/rgb_labeler", line 189, in main
    rgb_labeler = RGBLabeler(config, sensor_name=args['sensor_name'], debug=args['debug'], color=args['color'])
  File "/home/bruno/atom_ws/src/atom/atom_calibration/src/atom_calibration/collect/rgb_labeler", line 56, in __init__
    self.msg_type_str, self.msg_type = getMessageTypeFromTopic(self.sensor_config['topic_name'])
  File "/home/bruno/atom_ws/src/atom/atom_core/src/atom_core/ros_utils.py", line 31, in getMessageTypeFromTopic
    msg = rospy.wait_for_message(topic, rospy.AnyMsg)
  File "/opt/ros/noetic/lib/python3/dist-packages/rospy/client.py", line 428, in wait_for_message
    raise rospy.exceptions.ROSInterruptException("rospy shutdown")
rospy.exceptions.ROSInterruptException: rospy shutdown
File "/home/bruno/atom_ws/src/atom/atom_calibration/src/atom_calibration/collect/rgb_labeler", line 195, in <module>
    main()
  File "/home/bruno/atom_ws/src/atom/atom_calibration/src/atom_calibration/collect/rgb_labeler", line 189, in main
    rgb_labeler = RGBLabeler(config, sensor_name=args['sensor_name'], debug=args['debug'], color=args['color'])
  File "/home/bruno/atom_ws/src/atom/atom_calibration/src/atom_calibration/collect/rgb_labeler", line 56, in __init__
    self.msg_type_str, self.msg_type = getMessageTypeFromTopic(self.sensor_config['topic_name'])
  File "/home/bruno/atom_ws/src/atom/atom_core/src/atom_core/ros_utils.py", line 31, in getMessageTypeFromTopic
    msg = rospy.wait_for_message(topic, rospy.AnyMsg)
  File "/opt/ros/noetic/lib/python3/dist-packages/rospy/client.py", line 428, in wait_for_message
    raise rospy.exceptions.ROSInterruptException("rospy shutdown")
rospy.exceptions.ROSInterruptException: rospy shutdown
Traceback (most recent call last):
  File "/home/bruno/atom_ws/src/atom/atom_calibration/src/atom_calibration/collect/rgb_labeler", line 195, in <module>
    main()
  File "/home/bruno/atom_ws/src/atom/atom_calibration/src/atom_calibration/collect/rgb_labeler", line 189, in main
    rgb_labeler = RGBLabeler(config, sensor_name=args['sensor_name'], debug=args['debug'], color=args['color'])
  File "/home/bruno/atom_ws/src/atom/atom_calibration/src/atom_calibration/collect/rgb_labeler", line 56, in __init__
    self.msg_type_str, self.msg_type = getMessageTypeFromTopic(self.sensor_config['topic_name'])
  File "/home/bruno/atom_ws/src/atom/atom_core/src/atom_core/ros_utils.py", line 31, in getMessageTypeFromTopic
    msg = rospy.wait_for_message(topic, rospy.AnyMsg)
  File "/opt/ros/noetic/lib/python3/dist-packages/rospy/client.py", line 428, in wait_for_message
    raise rospy.exceptions.ROSInterruptException("rospy shutdown")
rospy.exceptions.ROSInterruptException: rospy shutdown
brunofavs commented 2 months ago

Hmm ..

I added this exit() in the script causing the crash but it doesn't help.

if os.path.exists(self.output_folder) and not args['overwrite']:  # dataset path exists, abort
            print('\n' + Fore.RED + 'Error: Dataset ' + self.output_folder +
                  ' exists.\nIf you want to replace it add a "--overwrite" flag.' + Style.RESET_ALL + '\n')
            rospy.signal_shutdown()
            exit()

The launch file already has the "required=true" flag on the node causing the crash, so I guess it has some delay so those error messages are unavoidable :c

miguelriemoliveira commented 2 months ago

spy.signal_shutdown() exit()

Hi @brunofavs ,

This was because before the data_collector was a mess of complicated nodes.

Now it should be possible to simplify this.

I will work on it ...

miguelriemoliveira commented 2 months ago

@brunofavs , just changed. Can you test and see if its better?

miguelriemoliveira commented 2 months ago

Added shutdown callbacks on the labelers. Now it looks a bit better. Not perfect though.

Hit space to toggle paused, or 's' to step.
 [RUNNING]  Bag Time:   1913.119180   Duration: 0.303180 / 30.604000               
ATOM Error: 
Error: Dataset /home/mike/datasets/softbot/long_train_dataset1 exists.
If you want to replace it add a "--overwrite" flag.

/front_left_camera/rgb/image_raw141   Duration: 0.321141 / 30.604000               
Waiting for camera_info message on topic /front_left_camera/rgb/camera_info ... 
/front_right_camera/rgb/image_raw
Waiting for camera_info message on topic /front_right_camera/rgb/camera_info ... 
Created interactive marker for point clouds.on: 0.353676 / 30.604000               
received!]  Bag Time:   1913.280660   Duration: 0.464660 / 30.604000               
received!]  Bag Time:   1913.310977   Duration: 0.494977 / 30.604000               
[ WARN] [1713190968.277318025, 1913.815217864]: Interactive marker 'lidar3d' contains unnormalized quaternions. This warning will only be output once but may be true for others; enable DEBUG messages for ros.rviz.quaternions to see more details.
================================================================================REQUIRED process [collect_data-10] has died!
process has finished cleanly
log file: /home/mike/.ros/log/9fb180b4-fb33-11ee-a481-093d120ebbe2/collect_data-10*.log
Initiating shutdown!
================================================================================
[automatic_data_collector-14] killing on exitn: 1.190662 / 30.604000               
[lidar3d_labeler-13] killing on exit
[front_right_camera_labeler-12] killing on exit
[front_left_camera_labeler-11] killing on exit
[collect_data-10] killing on exit
[rviz-9] killing on exit
[decompressor_front_right_camera-8] killing on exit
ATOM Warn: lidar3d_lidar3d_labeler shutting down.
[decompressor_front_left_camera-7] killing on exit
[rosbag_play-6] killing on exit
[robot_state_publisher-5] killing on exit
ATOM Warn: front_left_camera_rgb_labeler shutting down.
[throttler_lidar3d-4] killing on exit
ATOM Warn: front_right_camera_rgb_labeler shutting down.
 [RUNNING]  Bag Time:   1914.137705   Duration: 1.321705 / 30.604000               
[throttler_front_right_camera-3] killing on exit
[throttler_front_left_camera-2] killing on exit
[rosout-1] killing on exit
[master] killing on exit
brunofavs commented 2 months ago

Hey @miguelriemoliveira.

Yes that seemed to do the trick. The shutdown is clean now.

I'm now in the midst of labeling a dataset with 43 collections preparing for the batch experiments.

Adding noise to the odom tf seems to really impact negatively the calibration, with 0.05 translation and rotation its already pretty bad.

Im assuming this is due to testing it on a really small dataset with 5 collections though, I will keep you posted

miguelriemoliveira commented 2 months ago

Im assuming this is due to testing it on a really small dataset with 5 collections though, I will keep you posted

a dataset with 5 collections will always be inconclusive.