Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Jesus/#169 camera info yaml #231

Merged
merged 16 commits into from
Jun 17, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
29 changes: 29 additions & 0 deletions andino_bringup/config/raspicam.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
# 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
JesusSilvaUtrera marked this conversation as resolved.
Show resolved Hide resolved
image_height: 480
camera_name: narrow_stereo
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

nit: not sure where this name is being used however it catches my attention it says stereo when it is actually mono

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yeah, but the name is fixed by the hardware (happens the same when I used my webcam) so there is anything we can do about that. If I change the name on the YAML it won't use that file because it doesn't have the right name.

camera_matrix:
rows: 3
cols: 3
data: [502.10979, 0. , 315.89371,
0. , 499.35622, 233.15895,
0. , 0. , 1. ]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [0.150091, -0.263342, 0.002136, -0.004508, 0.000000]
rectification_matrix:
rows: 3
cols: 3
data: [1., 0., 0.,
0., 1., 0.,
0., 0., 1.]
projection_matrix:
rows: 3
cols: 4
data: [510.31363, 0. , 312.43595, 0. ,
0. , 510.29425, 233.43648, 0. ,
0. , 0. , 1. , 0. ]
25 changes: 20 additions & 5 deletions andino_bringup/launch/camera.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,17 +30,32 @@

from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import DeclareLaunchArgument
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():
return LaunchDescription([
# 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([
intrinsic_params_file,
Node(
package='v4l2_camera',
executable='v4l2_camera_node',
name='v4l2_camera_node',
output='screen',
parameters=[{
'image_size': [640,480],
'camera_frame_id': 'camera_link'
}]
)
'image_size': [640, 480],
'camera_frame_id': 'camera_link',
'camera_info_url': LaunchConfiguration('intrinsic_params_file'),
}],
)
])
2 changes: 1 addition & 1 deletion andino_firmware/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ Via `serial` connection (57600 baud) it is possible to interact with the microco

- Get encoder values: `'e'`
- Set open-loop speed for the motors[pwm] `'o <left> <right>'`
- Example to move forward full speed: `'o 255 255'`
- Example to move forward full speed: `'o 255 255'`
- Range `[-255 -> 255]`
- Set closed-loop speed for the motors[ticks/sec] `'m <left> <right>'`
- Important!: See the `Test it!` section.
Expand Down
27 changes: 27 additions & 0 deletions andino_hardware/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -151,6 +151,33 @@ Check camera status:
vcgencmd get_camera
```

If the output of the previous command is `supported=1 detected=1', everything is fine. If not, your camera won't work correctly, you need to perform some configuration first.
JesusSilvaUtrera marked this conversation as resolved.
Show resolved Hide resolved

Modify the `config.txt` file for the boot:

```sh
sudo nano /boot/firmware/config.txt
```

And add these lines:

```
# Autoload overlays for any recognized cameras or displays that are attached
# to the CSI/DSI ports. Please note this is for libcamera support, *not* for
# the legacy camera stack
start_x=1
gpu_mem=128
```

Save and close the file. Then we need to enable the camera support for the raspberry:

```sh
sudo raspi-config
```

Go to `Interface Options`, select `camera` and enable it.

Finally, you just need to reboot and the camera should be working fine.

#### RPLidar installation

Expand Down
Loading