Closed ghost closed 8 months ago
Found the error!
Apparently, sensor-id doesn't expect an int
but a string
...
For those who might find it helpful, the working launch file:
<launch>
<arg name="left_camera" default="0"/>
<arg name="right_camera" default="1"/>
<arg name="width" default="3280"/>
<arg name="height" default="2464"/>
<arg name="fps" default="20/1"/>
<arg name="format" default="NV12"/>
<group ns="left">
<node pkg="gscam" type="gscam" name="gscam">
<param name="camera_name" value="default"/>
<param name="gscam_config" value="nvarguscamerasrc sensor-id=$(arg left_camera) ! video/x-raw(memory:NVMM), width=(int)$(arg width), height=(int)$(arg height), format=(string)$(arg format), framerate=(fraction)$(arg fps) ! nvvidconv flip-method=6 ! video/x-raw, format=(string)BGRx ! videoconvert"/>
<param name="camera_info_url" value="file://$(find my_stereo_camera)/config/calibration/uncalibrated_parameters.ini"/>
<param name="frame_id" value="/left_frame"/>
<param name="sync_sink" value="false"/>
<remap from="camera/image_raw" to="image_raw"/>
<remap from="camera/camera_info" to="camera_info"/>
</node>
</group>
<group ns="right">
<node pkg="gscam" type="gscam" name="gscam">
<param name="camera_name" value="default"/>
<param name="gscam_config" value="nvarguscamerasrc sensor-id=$(arg right_camera) ! video/x-raw(memory:NVMM), width=(int)$(arg width), height=(int)$(arg height), format=(string)$(arg format), framerate=(fraction)$(arg fps) ! nvvidconv flip-method=6 ! video/x-raw, format=(string)BGRx ! videoconvert"/>
<param name="camera_info_url" value="file://$(find my_stereo_camera)/config/calibration/uncalibrated_parameters.ini"/>
<param name="frame_id" value="/right_frame"/>
<param name="sync_sink" value="false"/>
<remap from="camera/image_raw" to="image_raw"/>
<remap from="camera/camera_info" to="camera_info"/>
</node>
</group>
</launch>
Hello everyone, I'm working with a Jetson Nano Dev Kit B01 (Ubuntu 18.04 & ROS melodic) and a pair of IMX219 cameras, trying to publish their raw image into the ROS network.
I've written the following launch file, so that I can run a
gscam
node for each camera at once. The problem is that it won't let me have 2gscam
nodes running at the same time, and I can't seem to find the error.I've successfully launched a very similar launch file for a single camera (commenting out the "right" group). I've also tried creating a launch file for each camera, but when I launch the second one in a new terminal, one of them fails. The node that fails seems to be randomly selected, in a way that it doesn't appear to have anything to do with the order in which I launched them.
Launch file:
Error message:
Any help will be much appreciated :)