Skip to content

Commit

Permalink
Changed the 'camera_info_url' to be relative path
Browse files Browse the repository at this point in the history
Signed-off-by: JesusSilvaUtrera <[email protected]>
  • Loading branch information
JesusSilvaUtrera committed Jun 10, 2024
1 parent f738c1f commit 061658b
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 15 deletions.
6 changes: 0 additions & 6 deletions andino_bringup/config/camera_params.yaml

This file was deleted.

6 changes: 4 additions & 2 deletions andino_bringup/config/raspicam.yaml
Original file line number Diff line number Diff line change
@@ -1,7 +1,9 @@
# Calibration tutorial (from Nav2 docs): https://docs.nav2.org/tutorials/docs/camera_calibration.html
# Other info for this Raspberry Pi Camera Module V2 can be found here: https://elinux.org/Rpi_Camera_Module#Technical_Parameters_.28v.2_board.29

image_width: 640
image_height: 480
# camera_name: narrow_stereo
camera_name: hd_webcam:_hd_webcam
camera_name: narrow_stereo
camera_matrix:
rows: 3
cols: 3
Expand Down
18 changes: 11 additions & 7 deletions andino_bringup/launch/camera.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,27 +31,31 @@
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution, TextSubstitution
from ament_index_python.packages import get_package_share_directory
from os.path import join

pkg_andino_bringup = get_package_share_directory('andino_bringup')

def generate_launch_description():
# Declare launch argument for the path to the camera params YAML file
camera_params_file = DeclareLaunchArgument(
'camera_params_file',
default_value=join(pkg_andino_bringup, 'config', 'camera_params.yaml'),
# Declare launch argument for the path to the camera params YAML file (the 'file://' part is mandatory, you can't skip it)
intrinsic_params_file = DeclareLaunchArgument(
'intrinsic_params_file',
default_value='file://' + join(pkg_andino_bringup, 'config', 'raspicam.yaml'),
description='Path to camera intrinsics YAML file'
)

return LaunchDescription([
camera_params_file,
intrinsic_params_file,
Node(
package='v4l2_camera',
executable='v4l2_camera_node',
name='v4l2_camera_node',
output='screen',
parameters=[LaunchConfiguration('camera_params_file')],
parameters=[{
'image_size': [640, 480],
'camera_frame_id': 'camera_link',
'camera_info_url': LaunchConfiguration('intrinsic_params_file'),
}],
)
])

0 comments on commit 061658b

Please sign in to comment.