Closed shiba24 closed 1 year ago
I assume you want to externally trigger your event camera, correct? You would modify the launch file to have an additional line
<param name="trigger_in_mode" value="external"/>
See the driver_node.launch
file as an example.
Your trigger_pins.yaml
file looks reasonable, but I would try 'external: 0'. That's the default and works for my SilkEVCam HD.
NOTE: loopback triggering no longer works for Gen4+ sensors. It was a handy debugging feature but is now discontinued. You will have to really provide an external trigger.
As far as recording goes: you only have to record /event_camera/events. Trigger events and regular events (CDEvents) come over the same topic in one encoded stream. The driver originally decoded the event stream so it could separately publish trigger and CD events, but the CPU load was too high. The driver now simply packetizes and republishes the raw encoded event stream as it comes from the camera. To find out if triggering is working, use the event_array_tools repo which has a tool that decodes and measures the performance:
rosrun event_array_tools perf /event_camera/events
msgs: 250.00/s drp: 0 del: 4.17ms drft: 0.0044s ev: 0.2421 M/s %ON: 51 tr: 800.01 1/s %UP: 50
If you don't see the trigger rate "tr: " then your triggering is not working.
Hi @berndpfrommer , thank you for your quick reply! I checked that when I change <param name="trigger_in_mode" value="external"/>
in driver_node.launch and external: 0 then the event_array_tool perf displays
msgs: 217.47/s drp: 0 del: 4.56ms drft: 0.0039s ev: 2.5035 M/s %ON: 54 tr: 52.49 1/s %UP: 50
So I think it's working.
Sorry the last question - should I modify the same thing in recording_driver.launch
? (just adding param there caused error)
Maybe this is more a ROS question, but I'm not super familiar with ROS so would appreciate your help :pray:
You must do the same thing in recording_driver.launch if you want triggers enabled. Please post the modifications you made to the file and the error you are getting. This should work without problem.
Sure, thank you.
The modification is to add the followings to recording_driver.launch. I tried inserting here, not working (the launch is fine but event_array_tools does not show the trigger stats), and here, raising the error pasted below.
<param name="trigger_in_mode" value="external"/>
<rosparam command="load" file="$(find metavision_ros_driver)/config/trigger_pins.yaml"/>
The error for the second trial is:
setting /run_id to ed66724a-aa05-11ed-bf9d-e5a8ef226418
process[rosout-1]: started with pid [1828311]
started core service [/rosout]
process[recording_driver-2]: started with pid [1828319]
process[recorder_nodelet-3]: started with pid [1828320]
process[event_camera-4]: started with pid [1828321]
[ INFO] [1676117795.828452490]: Loading nodelet /recorder_nodelet of type nodelet_rosbag/NodeletRosbag to manager recording_driver with the following remappings:
[ INFO] [1676117795.829362339]: waitForService: Service [/recording_driver/load_nodelet] has not been advertised, waiting...
[ INFO] [1676117795.831464480]: Loading nodelet /event_camera of type metavision_ros_driver/DriverNodelet to manager recording_driver with the following remappings:
[ INFO] [1676117795.832273072]: waitForService: Service [/recording_driver/load_nodelet] has not been advertised, waiting...
[ INFO] [1676117795.833884198]: Initializing nodelet with 8 worker threads.
[ INFO] [1676117795.850388421]: waitForService: Service [/recording_driver/load_nodelet] is now available.
[ INFO] [1676117795.853092023]: waitForService: Service [/recording_driver/load_nodelet] is now available.
[ INFO] [1676117795.869339176]: sync mode: standalone
[ERROR] [1676117795.870107668]: got invalid config, no trigger parameter with name recording_driver/ros__parameters/prophesee_pin_config
[ERROR] [1676117795.870116374]: node name recording_driver must match pin config yaml file!
[FATAL] [1676117795.870261481]: Failed to load nodelet '/event_camera` of type `metavision_ros_driver/DriverNodelet` to manager `recording_driver'
[event_camera-4] process has died [pid 1828321, exit code 255, cmd /opt/ros/noetic/lib/nodelet/nodelet load metavision_ros_driver/DriverNodelet recording_driver __name:=event_camera __log:=/home/shintaro/.ros/log/ed66724a-aa05-11ed-bf9d-e5a8ef226418/event_camera-4.log].
log file: /home/shintaro/.ros/log/ed66724a-aa05-11ed-bf9d-e5a8ef226418/event_camera-4*.log
^C[recorder_nodelet-3] killing on exit
[recording_driver-2] killing on exit
[ INFO] [1676117803.879774682]: Unloading nodelet /recorder_nodelet from manager recording_driver
[rosout-1] killing on exit
[master] killing on exit
shutting down processing monitor...
... shutting down processing monitor complete
The second approach (put it into the driver, not the recorder not) is the correct one. The error message:
[ERROR] [1676117795.870107668]: got invalid config, no trigger parameter with name recording_driver/ros__parameters/prophesee_pin_config
[ERROR] [1676117795.870116374]: node name recording_driver must match pin config yaml file!
says that the node name doesn't match. This is because the node name is "recording_driver" does not match the node name in the trigger_pins.yaml file.
So the steps are then to first make a copy of the trigger pins yaml file in the config directory, where you change the name first line (event_camera:
) to recording driver:
such that it matches your node name (that's where the error message comes from). Then inside the launch file (again the driver node, not the recorder) you load that config file with a line like this:
`
`
Thank you, now it comes almost! Recording seems fine now after your advice, and I would like to decode and check if it works (successfully decode, matching timestamp with events, etc..) After using https://github.com/berndpfrommer/event_array_py, what I see now is something like
[(0, 14043172, 0)]
I guess the second is the timestamp, what are the first and third, respectively?
The definition can be found here
PYBIND11_NUMPY_DTYPE(EventCD, x, y, p, t);
PYBIND11_NUMPY_DTYPE(EventExtTrig, p, t, id);
I think this follows the metavision sdk convention: p = flank type (up/down), the 'id' says who triggered the event.
Hi, thank you for all your help! I confirmed the decoded data.
Hi, thank you for this great work! It's very useful. I have questions regarding external trigger.
Environment: ROS1, Noetic
The above is the result of running
roslaunch metavision_ros_driver driver_nodelet.launch trigger_in_mode:=external
. I have configured trigger_pins.yaml such asBut I'm not sure if this is correct way. The trigger itself should be working as we checked it before with the metavision software.
Sorry, but could you give me a bit more detailed example of
roslaunch metavision_ros_driver driver_nodelet.launch
with the external trigger configuration?roslaunch metavision_ros_driver recording_driver.launch
with the trigger recorded as the topic too?Thank you for your help!