Please provide the following info (tick the boxes after creating this topic):
Software Version
[*] DRIVE OS 6.0.10.0
DRIVE OS 6.0.8.1
DRIVE OS 6.0.6
DRIVE OS 6.0.5
DRIVE OS 6.0.4 (rev. 1)
DRIVE OS 6.0.4 SDK
other
Target Operating System
Linux
QNX
other
Hardware Platform
[*] DRIVE AGX Orin Developer Kit (940-63710-0010-300)
DRIVE AGX Orin Developer Kit (940-63710-0010-200)
DRIVE AGX Orin Developer Kit (940-63710-0010-100)
DRIVE AGX Orin Developer Kit (940-63710-0010-D00)
DRIVE AGX Orin Developer Kit (940-63710-0010-C00)
DRIVE AGX Orin Developer Kit (not sure its number)
other
SDK Manager Version
2.1.0
other
Host Machine Version
native Ubuntu Linux 20.04 Host installed with SDK Manager
native Ubuntu Linux 20.04 Host installed with DRIVE OS Docker Containers
native Ubuntu Linux 18.04 Host installed with DRIVE OS Docker Containers
other
Issue Description
<Please provide details about your query/application pipeline/usecase/pictures here >
Error String
< Please provide just the error messages here >
Logs
Provide logs in text box instead of image
Please paste the complete application log here. If there are multiple logs, please use multiple text box
In the drive os 6.0.9 version, we tried to integrate the DriveWorks library into ROS2 and compile the code directly on the Orin. In the 5.16 version of DriveWorks, we could obtain camera data through DriveWorks and transmit the data through a ROS2 topic. However, when we upgraded the Drive OS on the Orin to 6.0.10 and updated the DriveWorks in our code to version 5.20, we encountered an error where the dwSensorManager_start function failed to run. After updating the Drive OS on the Orin to 6.0.10, we have updated the corresponding camera driver and tested the rig file using the sample_camera, which can obtain data normally. We have also tested that using the same function in our code to obtain camera data as in sample_camera is normal. However, there is a problem with using SensorManager. We do not have an NVOnline license, so please help us take a look.
this->declare_parameter<std::string>("rig", "");
RCLCPP_INFO(this->get_logger(), this->get_parameter("rig").as_string().data());
dwContextParameters sdkParams = {};
dwStatus status;
status = dwInitialize(&m_context, DW_VERSION, &sdkParams);
if (status != DW_SUCCESS)
{
RCLCPP_ERROR(this->get_logger(), "Failed to init Driveworks SDK. Error: %s", dwGetStatusName(status));
return;
}
status = dwSAL_initialize(&m_sal, m_context);
if (status != DW_SUCCESS)
{
RCLCPP_ERROR(this->get_logger(), "Failed to create HAL module of Driveworks SDK. Error: %s", dwGetStatusName(status));
return;
}
dwRigHandle_t rig_config{};
dwRig_initializeFromFile(&rig_config, m_context, this->get_parameter("rig").as_string().data());
uint32_t cnt = 0;
CHECK_DW_ERROR(dwRig_getSensorCountOfType(&cnt, DW_SENSOR_CAMERA, rig_config));
dwSensorManagerParams smParams{};
for (uint32_t i = 0; i < cnt; i++)
{
uint32_t camera_sensor_idx = 0;
CHECK_DW_ERROR(dwRig_findSensorByTypeIndex(&camera_sensor_idx, DW_SENSOR_CAMERA, i, rig_config));
smParams.enableSensors[i] = camera_sensor_idx;
smParams.numEnableSensors++;
const char *camera_name;
CHECK_DW_ERROR(dwRig_getSensorName(&camera_name, camera_sensor_idx, rig_config));
m_idx_name_map[camera_sensor_idx] = {std::string(camera_name), i};
}
CHECK_DW_ERROR(dwSensorManager_initializeFromRigWithParams(&m_sensor_manager, rig_config, &smParams, 1024, m_sal));
for (const auto &pair : m_idx_name_map)
{
uint32_t camera_sensor_idx = pair.first;
dwSensorHandle_t camera_sensor = DW_NULL_HANDLE;
CHECK_DW_ERROR(dwSensorManager_getSensorHandle(&camera_sensor, camera_sensor_idx, m_sensor_manager));
dwImageProperties image_properties{};
CHECK_DW_ERROR(dwSensorCamera_getImageProperties(&image_properties, DW_CAMERA_OUTPUT_CUDA_RGBA_UINT8, camera_sensor));
image_properties.format = DW_IMAGE_FORMAT_RGB_UINT8;
uint32_t camera_sensor_id = pair.second.second;
CHECK_DW_ERROR(dwImage_create(&m_cuda_rgb_frame[camera_sensor_id], image_properties, m_context));
CHECK_DW_ERROR(dwImageStreamer_initialize(&m_streamer_cuda_to_cpu[camera_sensor_id], &image_properties, DW_IMAGE_CPU, m_context));
m_publisher[camera_sensor_id] = this->create_publisher<sensor_msgs::msg::Image>(pair.second.first, 10);
}
CHECK_DW_ERROR(dwSensorManager_start(m_sensor_manager));
zhangzs@tegra-ubuntu:~/adas_ws$ ros2 launch camera multiple_camera_publisher_launch.py
[INFO] [launch]: All log files can be found below /home/zhangzs/.ros/log/2024-10-28-14-05-00-378753-tegra-ubuntu-16236
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [multiple_camera_publisher-1]: process started with pid [16241]
[multiple_camera_publisher-1] [INFO] [1730095500.673194880] [multiple_camera_publisher]: src/camera/config/rig.json
[multiple_camera_publisher-1] terminate called after throwing an instance of 'std::runtime_error'
[multiple_camera_publisher-1] what(): [2024-10-28 14:05:02] DW Error DW_INTERNAL_ERROR executing DW function:
[multiple_camera_publisher-1] dwSensorManager_start(m_sensor_manager)
[multiple_camera_publisher-1] at /home/zhangzs/adas_ws/src/camera/src/multiple_camera_publisher.cpp:74
[ERROR] [multiple_camera_publisher-1]: process has died [pid 16241, exit code -6, cmd '/home/zhangzs/adas_ws/install/camera/lib/camera/multiple_camera_publisher --ros-args -r __node:=multiple_camera_publisher --params-file /tmp/launch_params_w6qp8c1a'].