Open dtonda8 opened 1 month ago
https://www.notion.so/monashcav/PX2-Crashing-Log-d0107668d4d749c79db9f16338c26796
this link has majority of the information,
TLDR - Camera Port A2 is not working, all cameras work individually. There are 12 ports for 8 cameras so technically we can make it work?
The YT link above seems to show 8 cams working via rviz/ros.
Perhaps it was done using one of our ros gmsl repos: https://github.com/Monash-Connected-Autonomous-Vehicle?q=ros_gmsl&type=all&language=&sort= (scroll to bottom and search for ros_gmsl):
running sample_camera_multiple_gmsl works by running: ./sample_camera_multiple_gmsl selector-mask=101111111000
The selector mask follows the format: A3 A2 A1 A0 B3 B2 B1 B0 C3 C2 C1 C0 Where A3 A2 A1... matches the ports displayed/written/etched on to the PX2 ports itself Replace A3 A2 ...etc with 1 for on and 0 for off
Legendary! If you're still on campus have a shot at some of the ros gmsl programs. If it works with ros then we could potentially stream all cams to the alienware 👀
I believe from a previous thread somewhere on notion and/or github, using ros_gmsl_driver has building issues when trying to build the package.
`Install space: /root/catkin_ws/install
make[2]: Warning: File 'ros_gmsl_driver/CMakeFiles/gmsl_n_cameras_node.dir/depend.make' has modification time 1178 s in the future
make[2]: warning: Clock skew detected. Your build may be incomplete.
make[2]: Warning: File 'ros_gmsl_driver/CMakeFiles/gmsl_n_cameras_node.dir/depend.make' has modification time 1178 s in the future
[ 12%] Building CXX object ros_gmsl_driver/CMakeFiles/gmsl_n_cameras_node.dir/src/main.cpp.o
/root/catkin_ws/src/ros_gmsl_driver/src/main.cpp: In function ‘void threadCameraPipeline(Camera, uint32_t, dwContextHandle_t, WindowBase)’:
/root/catkin_ws/src/ros_gmsl_driver/src/main.cpp:169:1: error: ‘ensorHandle_t’ was not declared in this scope
ensorHandle_t cameraSensor,
^
/root/catkin_ws/src/ros_gmsl_driver/src/main.cpp:180:67: error: ‘DW_CAMERA_PROCESSED_IMAGE’ was not declared in this scope
dwSensorCamera_getImageProperties(&cameraImageProperties, DW_CAMERA_PROCESSED_IMAGE,
^
/root/catkin_ws/src/ros_gmsl_driver/src/main.cpp:183:32: error: ‘dwImageProperties {aka struct dwImageProperties}’ has no member named ‘pxlFormat’
displayImageProperties.pxlFormat = DW_IMAGE_RGBA;
^
/root/catkin_ws/src/ros_gmsl_driver/src/main.cpp:183:52: error: ‘DW_IMAGE_RGBA’ was not declared in this scope
displayImageProperties.pxlFormat = DW_IMAGE_RGBA;
^
/root/catkin_ws/src/ros_gmsl_driver/src/main.cpp:184:32: error: ‘dwImageProperties {aka struct dwImageProperties}’ has no member named ‘planeCount’
displayImageProperties.planeCount = 1;
^
/root/catkin_ws/src/ros_gmsl_driver/src/main.cpp:187:100: error: ‘dwImageFormatConverter_initialize’ was not declared in this scope
result = dwImageFormatConverter_initialize(&cameraSensor->yuv2rgba, DW_IMAGE_NVMEDIA , sdk);
^
/root/catkin_ws/src/ros_gmsl_driver/src/main.cpp:198:83: error: ‘dwImageNvMedia_create’ was not declared in this scope
result = dwImageNvMedia_create(&rgba, &displayImageProperties, sdk);
^
/root/catkin_ws/src/ros_gmsl_driver/src/main.cpp:301:63: error: ‘dwImageFormatConverter_release’ was not declared in this scope
dwImageFormatConverter_release(&cameraSensor->yuv2rgba);
^
/root/catkin_ws/src/ros_gmsl_driver/src/main.cpp:305:56: error: ‘dwImageNvMedia_destroy’ was not declared in this scope
dwStatus result = dwImageNvMedia_destroy(&frame);
^
/root/catkin_ws/src/ros_gmsl_driver/src/main.cpp: In function ‘void initSdk(dwContextObject, WindowBase)’:
/root/catkin_ws/src/ros_gmsl_driver/src/main.cpp:587:27: error: ‘DW_VERSION’ was not declared in this scope
dwInitialize(context, DW_VERSION, &sdkParams);
^
/root/catkin_ws/src/ros_gmsl_driver/src/main.cpp: In function ‘void initSensors(std::vector
Seems like main.cpp in the src folder of the package is just completely incorrect from the ones on github i need to re-clone the entire repo for now (someone must've edited/deleted or something happened to corrupt the file)
Re-cloned at home/nvidia/catkin_ws/src using catkin_make, getting the following error CMake Error at ros_gmsl_driver_beckerfelix/ros_gmsl_driver/cmake/LibFindMacros.cmake:261 (message): REQUIRED PACKAGE NOT FOUND
We could not find development headers for Driveworks. Do you have the necessary dev package installed? This package is REQUIRED and you need to install it or adjust CMake configuration in order to continue building Project.
Relevant CMake configuration variables:
Driveworks_INCLUDE_DIR=<not found>
Driveworks_LIBRARY=<not found>
You may use CMake GUI, cmake -D or ccmake to modify the values. Delete CMakeCache.txt to discard all values and force full re-detection if necessary.
Call Stack (most recent call first): ros_gmsl_driver_beckerfelix/ros_gmsl_driver/cmake/FindDriveworks.cmake:67 (libfind_process) ros_gmsl_driver_beckerfelix/ros_gmsl_driver/CMakeLists.txt:22 (find_package)
-- Configuring incomplete, errors occurred! See also "/home/nvidia/catkin_ws/build/CMakeFiles/CMakeOutput.log". See also "/home/nvidia/catkin_ws/build/CMakeFiles/CMakeError.log". Invoking "cmake" failed
Now just need to somehow specify the path...
Making progress on the Nvidia Tegra with IP address (192.168.1.180
):
mkdir -p ros_gmsl_ws/src/
git clone https://github.com/Monash-Connected-Autonomous-Vehicle/ros_gmsl_driver
cd ..
catkin_make
Assuming internet access (or scp
)
One of the tegra's (with IP 192.168.1.181
) can build the ros_gmsl_driver, but cannot even run the sample single camera (/usr/local/driveworks/bin/sample_camera_gmsl
). I think the cams are not connected.
Whereas the other Tegra (with IP 192.168.1.180
) can run sample single camera, but cannot (yet) build the catkin package above. Error now. Might need to go back to the ros 1 basics. If you need wifi get an ehternet ports and connect it to the PX 2.
So, we'll either need to figure out how to connect cams to the first tegra or fix catkin with the second tegra.
Instruction for streaming cameras to ros topics:
For px2 with ip 192.168.1.181, go to ./Documents/ros_gmsl_ws
and source devel:
cd ~/Documents/ros_gmsl_ws
source devel/setup.bash
Then run the command
roslaunch gmsl_n_cameras gmsl_n_cameras.launch
Output of rostopic list
to see those topics:
/gmsl_camera/port_0/cam_0/camera_info
/gmsl_camera/port_0/cam_0/image_raw
/gmsl_camera/port_0/cam_0/image_raw/compressed
/gmsl_camera/port_0/cam_0/image_raw/compressed/parameter_descriptions
/gmsl_camera/port_0/cam_0/image_raw/compressed/parameter_updates
/gmsl_camera/port_0/cam_0/image_raw/compressedDepth
/gmsl_camera/port_0/cam_0/image_raw/compressedDepth/parameter_descriptions
/gmsl_camera/port_0/cam_0/image_raw/compressedDepth/parameter_updates
/gmsl_camera/port_0/cam_0/image_raw/theora
/gmsl_camera/port_0/cam_0/image_raw/theora/parameter_descriptions
/gmsl_camera/port_0/cam_0/image_raw/theora/parameter_updates
/gmsl_camera/port_0/cam_1/camera_info
/gmsl_camera/port_0/cam_1/image_raw
/gmsl_camera/port_0/cam_1/image_raw/compressed
/gmsl_camera/port_0/cam_1/image_raw/compressed/parameter_descriptions
/gmsl_camera/port_0/cam_1/image_raw/compressed/parameter_updates
/gmsl_camera/port_0/cam_1/image_raw/compressedDepth
/gmsl_camera/port_0/cam_1/image_raw/compressedDepth/parameter_descriptions
/gmsl_camera/port_0/cam_1/image_raw/compressedDepth/parameter_updates
/gmsl_camera/port_0/cam_1/image_raw/theora
/gmsl_camera/port_0/cam_1/image_raw/theora/parameter_descriptions
/gmsl_camera/port_0/cam_1/image_raw/theora/parameter_updates
/gmsl_camera/port_1/cam_0/camera_info
/gmsl_camera/port_1/cam_0/image_raw
/gmsl_camera/port_1/cam_0/image_raw/compressed
/gmsl_camera/port_1/cam_0/image_raw/compressed/parameter_descriptions
/gmsl_camera/port_1/cam_0/image_raw/compressed/parameter_updates
/gmsl_camera/port_1/cam_0/image_raw/compressedDepth
/gmsl_camera/port_1/cam_0/image_raw/compressedDepth/parameter_descriptions
/gmsl_camera/port_1/cam_0/image_raw/compressedDepth/parameter_updates
/gmsl_camera/port_1/cam_0/image_raw/theora
/gmsl_camera/port_1/cam_0/image_raw/theora/parameter_descriptions
/gmsl_camera/port_1/cam_0/image_raw/theora/parameter_updates
/gmsl_camera/port_1/cam_1/camera_info
/gmsl_camera/port_1/cam_1/image_raw
/gmsl_camera/port_1/cam_1/image_raw/compressed
/gmsl_camera/port_1/cam_1/image_raw/compressed/parameter_descriptions
/gmsl_camera/port_1/cam_1/image_raw/compressed/parameter_updates
/gmsl_camera/port_1/cam_1/image_raw/compressedDepth
/gmsl_camera/port_1/cam_1/image_raw/compressedDepth/parameter_descriptions
/gmsl_camera/port_1/cam_1/image_raw/compressedDepth/parameter_updates
/gmsl_camera/port_1/cam_1/image_raw/theora
/gmsl_camera/port_1/cam_1/image_raw/theora/parameter_descriptions
/gmsl_camera/port_1/cam_1/image_raw/theora/parameter_updates
/gmsl_camera/port_1/cam_2/camera_info
/gmsl_camera/port_1/cam_2/image_raw
/gmsl_camera/port_1/cam_2/image_raw/compressed
/gmsl_camera/port_1/cam_2/image_raw/compressed/parameter_descriptions
/gmsl_camera/port_1/cam_2/image_raw/compressed/parameter_updates
/gmsl_camera/port_1/cam_2/image_raw/compressedDepth
/gmsl_camera/port_1/cam_2/image_raw/compressedDepth/parameter_descriptions
/gmsl_camera/port_1/cam_2/image_raw/compressedDepth/parameter_updates
/gmsl_camera/port_1/cam_2/image_raw/theora
/gmsl_camera/port_1/cam_2/image_raw/theora/parameter_descriptions
/gmsl_camera/port_1/cam_2/image_raw/theora/parameter_updates
/gmsl_camera/port_1/cam_3/camera_info
/gmsl_camera/port_1/cam_3/image_raw
/gmsl_camera/port_1/cam_3/image_raw/compressed
/gmsl_camera/port_1/cam_3/image_raw/compressed/parameter_descriptions
/gmsl_camera/port_1/cam_3/image_raw/compressed/parameter_updates
/gmsl_camera/port_1/cam_3/image_raw/compressedDepth
/gmsl_camera/port_1/cam_3/image_raw/compressedDepth/parameter_descriptions
/gmsl_camera/port_1/cam_3/image_raw/compressedDepth/parameter_updates
/gmsl_camera/port_1/cam_3/image_raw/theora
/gmsl_camera/port_1/cam_3/image_raw/theora/parameter_descriptions
/gmsl_camera/port_1/cam_3/image_raw/theora/parameter_updates
/gmsl_camera/port_2/cam_0/camera_info
/gmsl_camera/port_2/cam_0/image_raw
/gmsl_camera/port_2/cam_0/image_raw/compressed
/gmsl_camera/port_2/cam_0/image_raw/compressed/parameter_descriptions
/gmsl_camera/port_2/cam_0/image_raw/compressed/parameter_updates
/gmsl_camera/port_2/cam_0/image_raw/compressedDepth
/gmsl_camera/port_2/cam_0/image_raw/compressedDepth/parameter_descriptions
/gmsl_camera/port_2/cam_0/image_raw/compressedDepth/parameter_updates
/gmsl_camera/port_2/cam_0/image_raw/theora
/gmsl_camera/port_2/cam_0/image_raw/theora/parameter_descriptions
/gmsl_camera/port_2/cam_0/image_raw/theora/parameter_updates
/gmsl_camera/port_2/cam_1/camera_info
/gmsl_camera/port_2/cam_1/image_raw
/gmsl_camera/port_2/cam_1/image_raw/compressed
/gmsl_camera/port_2/cam_1/image_raw/compressed/parameter_descriptions
/gmsl_camera/port_2/cam_1/image_raw/compressed/parameter_updates
/gmsl_camera/port_2/cam_1/image_raw/compressedDepth
/gmsl_camera/port_2/cam_1/image_raw/compressedDepth/parameter_descriptions
/gmsl_camera/port_2/cam_1/image_raw/compressedDepth/parameter_updates
/gmsl_camera/port_2/cam_1/image_raw/theora
/gmsl_camera/port_2/cam_1/image_raw/theora/parameter_descriptions
/gmsl_camera/port_2/cam_1/image_raw/theora/parameter_updates
/rosout
/rosout_agg
If it is working, we can visualise all the cameras using: rosrun rqt_image_view rqt_image_view
(this part only works directly on px 2)
Currently, only 6 of 8 cameras are being streamed, will attempt to change that to 8 out of 8
Got all 8 working by: Changing how cameras should be connected: for each port, camera should always be connected at 0 and in ascending order, thus if camera 0 1 and 3 are connected, camera 3 wont be detected. The changed the cameras to port A: 0, 1 port B: 0, 1, 2, 3 port C: 0, 1
Using selector mask 001111110011 in gmsl_n_cameras.launch and building the package again. We can now run roslaunch gmsl_n_cameras gmsl_n_cameras.launch and all 8 cameras will be on.
Image of ports:
Final thing to do before closing this issue: Broadcast ROS 1 (from PX 2) to ROS 2 (Alienware): https://github.com/ros2/ros1_bridge. This should hopefully be the easy part
Hi guys, we'll need a machine in the network (most likely alienware laptop) to run ros1 and ros2, the version of ubuntu that can do this is ubuntu 20. Fortunately, someone made a good set of instructions for a docker solution: https://github.com/TommyChangUMD/ros-humble-ros1-bridge-builder/. Worth having a look at.
A few years a ago our team managed to launch all cameras with little lag here, with what looks like ros1. Right now we're using gstreamer and ros to be able to stream a single camera to the alienware. Perhaps we can directly stream the gmsl camera to ros and subcribe to the topics from the alienware?