本帖最后由 zembil 于 2025-6-13 02:13 编辑
Hello,
I am currently using the miivii_gmsl_camera ROS2 package and have encountered a timing issue that I cannot resolve without access to the internal implementation details of the image capture process. Here are my system specifications:
Device: MIIVII APEX DUAL ORIN 5.1.2-2.2.0.122
Camera: Leopard Imaging LI-IMX490-GW5400-GMSL2-065H, connected to /dev/video0 of the master.
The camera's ISP has been updated (with help from Leopard Imaging) to support frame sync.
I use miivii_gmsl_camera with the commit id: 3bc9f9be9548d58917f9b48a7708bff8b4a98703, the latest one on the master branch.
The only changes I made to the given package are the following:
- Uncommented the StartTimer() function inside the constructor of the MiiviiGmslCamera object.
- Updated the DeclareParameters() function with the following parameters, since I have only one camera connected to the device for my tests:
declare_parameter<double>("publish_rate", 25);
declare_parameter<int>("sync_camera_number", 1);
declare_parameter<int>("async_camera_number", 0);
declare_parameter<int>("sync_freq", 25);
declare_parameter<int>("async_freq", 0);
declare_parameter<int>("sync_trigger", 0x01);
declare_parameter<int>("async_trigger", 0);
- Added timestamp prints to the timer_callback() function to see how much time getting the image, creating the message, and publishing it takes:
uint8_t *outbuf[this->active_camera_num];
uint64_t timestamp;
uint8_t camera_no = ctx[this->active_camera_num - 1].dev_node[10] - 0x30;
rclcpp::Clock clock;
std::cout << "BEFORE IMAGE POINTER CLOCK: " << clock.now().nanoseconds() << std::endl;
bool res = this->mvcam->GetImagePtr(outbuf, timestamp, camera_no, this->g_camera_dev);
std::cout << "TIMESTAMP OF THE IMAGE : " << timestamp << std::endl;
std::cout << "AFTER IMAGE POINTER CLOCK: " << clock.now().nanoseconds() << std::endl;
(...)
step_factor = 4;
}
std::cout << "PUBLISHED TIME MESSAGE: " << clock.now().nanoseconds() << std::endl;
sensor_msgs::msg::Image image;
(...)
image.data = std::move(image_data);
std::cout << "WILL PUBLISH IMAGE: " << clock.now().nanoseconds() << std::endl;
image_publisher_->publish(image);
std::cout << "DID PUBLISH IMAGE: " << clock.now().nanoseconds() << std::endl;
I also tried to attach my version of the "miivii_gmsl_camera.cpp" to this post.
miivii_gmsl_camera.cpp.zip
(3.68 KB, 下载次数: 3)
Here is the launch file I use:
<launch>
<node pkg="miivii_gmsl_camera" exec="miivii_gmsl_camera_node" name="miivii_gmsl_camera_node" output="screen">
<param name="video0.active" value="true"/>
<param name="video0.camera_res" value="2880x1860"/>
<param name="video0.output_res" value="2880x1860"/>
</node>
<node pkg="rviz2" exec="rviz2" name="rviz2" output="screen" args="-d $(find-pkg-share miivii_gmsl_camera)/config/multi.rviz"/>
</launch>
When I launch the node, I monitor both the console output and the topic /miivii_gmsl/image0 using ros2 topic echo --field header. I have observed that the timestamp associated with the image returned by the GetImagePtr function is approximately 170 ms older than the time at which the timer_callback is triggered, screenshots of which can be found below:
Since my camera is configured to operate at 25 Hz, I expect a new frame every 40 ms. However, in this case, the retrieved frame appears to be delayed by more than four frame intervals, which is a significant issue for my time-sensitive application. Since I do not have visibility into the internal behavior of the miivii::MvGmslCamera class, I cannot determine whether this delay is caused by internal buffering, scheduling, or another mechanism. Ideally, I would like to have the ability to trigger the camera on demand and receive the corresponding frame with minimal latency.
I would greatly appreciate your guidance on the following:
- Why is the image older than the time the callback was called? Do the images get read continuously, and whenever we use GetImagePtr, we get the latest one that was read and stored beforehand?
- Is there a way to retrieve the most recent frame with lower latency? Preferably, read a frame that gets created after I call the GetImagePtr function.
- Is triggering image capture on demand supported, or can it be implemented?
- If possible, can I have access to the implementation or detailed behavior description of the miivii::MvGmslCamera class to better understand the internal pipeline and timing characteristics?
Thank you in advance.
|
|
|
|
|
共 0 个关于本帖的回复 最后回复于 2025-6-13 02:08