From 578d512de43292df93bdd0f5c4548a4119abb094 Mon Sep 17 00:00:00 2001 From: JesusSilvaUtrera Date: Wed, 20 Mar 2024 08:51:40 +0100 Subject: [PATCH 1/3] Fixed wheel diameter in URDF --- andino_gz_classic/urdf/andino_gz_classic.xacro | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/andino_gz_classic/urdf/andino_gz_classic.xacro b/andino_gz_classic/urdf/andino_gz_classic.xacro index 22911df7..80598a23 100644 --- a/andino_gz_classic/urdf/andino_gz_classic.xacro +++ b/andino_gz_classic/urdf/andino_gz_classic.xacro @@ -67,7 +67,7 @@ 0.137 - 0.035 + 0.0662 20 From df32b9f0ca0cfa55a66f379fdecf259ab0ccd67f Mon Sep 17 00:00:00 2001 From: JesusSilvaUtrera Date: Wed, 20 Mar 2024 10:48:09 +0100 Subject: [PATCH 2/3] Added YAML file for default camera intrinsics --- andino_bringup/config/camera_intrinsics.yaml | 5 +++++ andino_bringup/launch/camera.launch.py | 20 +++++++++++++++----- 2 files changed, 20 insertions(+), 5 deletions(-) create mode 100644 andino_bringup/config/camera_intrinsics.yaml diff --git a/andino_bringup/config/camera_intrinsics.yaml b/andino_bringup/config/camera_intrinsics.yaml new file mode 100644 index 00000000..4ac53a06 --- /dev/null +++ b/andino_bringup/config/camera_intrinsics.yaml @@ -0,0 +1,5 @@ +v4l2_camera_node: + ros__parameters: + image_size: [640,480] + camera_frame_id: "camera_link" +# 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 \ No newline at end of file diff --git a/andino_bringup/launch/camera.launch.py b/andino_bringup/launch/camera.launch.py index 5d60f9f7..cdb9bea5 100644 --- a/andino_bringup/launch/camera.launch.py +++ b/andino_bringup/launch/camera.launch.py @@ -30,17 +30,27 @@ from launch import LaunchDescription from launch_ros.actions import Node +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration +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(): - return LaunchDescription([ + # Declare launch argument for the path to the camera intrinsics YAML file + camera_intrinsics_file = DeclareLaunchArgument( + 'camera_intrinsics_file', + default_value=join(pkg_andino_bringup, 'config', 'camera_intrinsics.yaml'), + description='Path to camera intrinsics YAML file' + ) + return LaunchDescription([ + camera_intrinsics_file, Node( package='v4l2_camera', executable='v4l2_camera_node', output='screen', - parameters=[{ - 'image_size': [640,480], - 'camera_frame_id': 'camera_link' - }] + parameters=[LaunchConfiguration('camera_intrinsics_file')], ) ]) From dfa13782c8b0b304c76708040fd31b5904989549 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jes=C3=BAs=20Silva?= <79662866+JesusSilvaUtrera@users.noreply.github.com> Date: Wed, 20 Mar 2024 15:13:08 +0100 Subject: [PATCH 3/3] Fixed wheel diameter in URDF (#93) (#230) Signed-off-by: JesusSilvaUtrera --- andino_gz_classic/urdf/andino_gz_classic.xacro | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/andino_gz_classic/urdf/andino_gz_classic.xacro b/andino_gz_classic/urdf/andino_gz_classic.xacro index 22911df7..80598a23 100644 --- a/andino_gz_classic/urdf/andino_gz_classic.xacro +++ b/andino_gz_classic/urdf/andino_gz_classic.xacro @@ -67,7 +67,7 @@ 0.137 - 0.035 + 0.0662 20