Open mzahana opened 10 months ago
In the TensorRTNode
and the DNNImageEncoderNode
, there's a parameter called num_blocks
. This defaults to 40
. Could you try reducing it to say 20 or 10 and seeing if that improves the situation?
@kajananchinniahNV I tried num_blocks
20 and 10, but the issue is still there.
I need to run both isaac_ros_visual_slam
and yolov8. If I run visual slam alone, I don't get the over-current issue. If I run yolov8 alone, I get the over-current issue. If I run both, I get the over-current issue.
Hello,
I am working with @mzahana in the same project, and I added the ros bag for running both isaac_ros_vislam
and isaac_ros_yolov8
and you can see the poor performance for the Vislam
and the discontinuity. Also, added a ros bag for just running isaac_ros_yolov8
and you can see the lag in the detection.
ros bag for vislam
and yolov8
Here
ros bag for running yolov8
only Here
To clarify, we use our own model that we trained on Yolov8n.
Also, the isaac_ros_yolov8
package accept only input image with 640x640 size. So, in the isaac_ros_vislam
launch file, we added a node that to resize the image to 640x640
you can see the launch file in the first:
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
# ... (your license text)
import launch
from launch_ros.actions import ComposableNodeContainer, Node
from launch_ros.descriptions import ComposableNode
def generate_launch_description():
"""Launch file which brings up visual slam node configured for RealSense."""
realsense_camera_node = Node(
name='camera',
namespace='camera',
package='realsense2_camera',
executable='realsense2_camera_node',
parameters=[{
'enable_infra1': True,
'enable_infra2': True,
'enable_color': True,
'enable_depth': True,
'depth_module.emitter_enabled': 0,
'depth_module.profile': '640x360x90',
'enable_gyro': True,
'enable_accel': True,
'gyro_fps': 200,
'accel_fps': 200,
'unite_imu_method': 2
}]
)
visual_slam_node = ComposableNode(
name='visual_slam_node',
package='isaac_ros_visual_slam',
plugin='nvidia::isaac_ros::visual_slam::VisualSlamNode',
parameters=[{
'denoise_input_images': False,
'rectified_images': True,
'enable_debug_mode': False,
'debug_dump_path': '/tmp/cuvslam',
'enable_slam_visualization': True,
'enable_landmarks_view': True,
'enable_observations_view': True,
'map_frame': 'map',
'odom_frame': 'odom',
'base_frame': 'camera_link',
'input_imu_frame': 'camera_gyro_optical_frame',
'enable_imu_fusion': True,
'gyro_noise_density': 0.000244,
'gyro_random_walk': 0.000019393,
'accel_noise_density': 0.001862,
'accel_random_walk': 0.003,
'calibration_frequency': 200.0,
'img_jitter_threshold_ms': 22.00
}],
remappings=[('stereo_camera/left/image', 'camera/infra1/image_rect_raw'),
('stereo_camera/left/camera_info', 'camera/infra1/camera_info'),
('stereo_camera/right/image', 'camera/infra2/image_rect_raw'),
('stereo_camera/right/camera_info', 'camera/infra2/camera_info'),
('visual_slam/imu', 'camera/imu')]
)
visual_slam_launch_container = ComposableNodeContainer(
name='visual_slam_launch_container',
namespace='',
package='rclcpp_components',
executable='component_container',
composable_node_descriptions=[
visual_slam_node
]
)
image_resize_node_color = ComposableNode(
package='isaac_ros_image_proc',
plugin='nvidia::isaac_ros::image_proc::ResizeNode',
name='image_resize_right',
parameters=[{
'output_width': 640,
'output_height': 640,
'keep_aspect_ratio': True
}],
remappings=[
('camera_info', '/camera/color/camera_info'),
('image', '/camera/color/image_raw'),
('resize/camera_info', '/camera/color/camera_info_resize'),
('resize/image', '/image')]
)
resize_launch_container = ComposableNodeContainer(
name='resize_launch_container',
namespace='',
package='rclcpp_components',
executable='component_container',
composable_node_descriptions=[
image_resize_node_color
],
output='screen'
)
return launch.LaunchDescription([visual_slam_launch_container, realsense_camera_node, resize_launch_container])
Thank you.
Please take a look at these forum posts regarding this issue
I solved the issue,
I followed the procedures in this post
Greetings.
I have a Jetson Oin NX 16GB with carrier board J401 from seedstudio.
When I run
isaac_ros_yolov8
, I continuously get the following warning 'System throttled due to over-current.'I am using the
MAXN
power mode.Here is a log file generated by the Jetson Power GUI. yolo_over_current_issue_orin_nx16.csv
I also noticed that the cashed memory gets large when I run this package! Here is a screenshot from
jtop
Here is a small video that shows the output of
jtop
jtop1.webmHere are the commands I run with their terminal outputs.
command
realsense.launch.py
output
Command
Output
list of nodes
list of topics
I hope I can get some help on how to solve this as there would be more applications running alongside the yolov8.
Thanks.