Skip to content
Snippets Groups Projects
Commit ec89aa10 authored by Galambos Mihály's avatar Galambos Mihály
Browse files

Adding vision launch

parent d97e2c5d
No related branches found
No related tags found
No related merge requests found
/**:
ros__parameters:
# SETTINGS
base_frame_id: "base_link" # Define the frame_id all static transformations refers to.
odom_frame_id: "odom" # Define the origin coordinate system in ROS convention (X-Forward, Y-Left, Z-Up). Pose topic defines the pose relative to that system.
initial_reset: false # Allows resetting the device before using it. Recommended to be used for example, when a glitch prevented the device from being properly closed.
wait_for_device_timeout: -1.0 # Timeout for waiting for device to connect [seconds]
reconnect_timeout: 5.0 # Timeout between consecutive reconnection attempts [seconds]
enable_sync: false # ??
hollander/front_camera: # LINK https://dev.intelrealsense.com/docs/ros-wrapper#section-launch-parameters
ros__parameters:
# CAMERA IDENTITY
serial_no: "008222071571" # Attach to the device with the given serial number (serial_no) number.
camera_name: "front_camera"
# TF
publish_tf: true # A Boolean parameter, publish or not TF at all.
tf_prefix: "front_camera" # This parameter allows changing the frames' IDs prefix per camera.
tf_publish_rate: 0.0 # A double parameter, positive values mean dynamic transform publication with specified rate, all other values mean static transform publication.
publish_odom_tf: true # A Boolean parameter, publish if True TF from odom_frame to pose_frame.
# IMU
unite_imu_method: 2 # [0-None, 1-copy, 2-linear_interpolation]
linear_accel_cov: 0.01 # Set the variance given to the Imu readings.
angular_velocity_cov: 0.01
enable_gyro: true # Enable gyro stream
gyro_fps: 0 # Setting a value to 0, will choose the first format in the inner list. (i.e. consistent between runs but not defined).
enable_accel: true # Enable accel stream
accel_fps: 0 # Setting a value to 0, will choose the first format in the inner list. (i.e. consistent between runs but not defined).
# DEPTH
enable_depth: true # Enable depth stream
depth_width: 0 # Setting a value to 0, will choose the first format in the inner list. (i.e. consistent between runs but not defined).
depth_height: 0
depth_fps: 0
clip_distance: -2.0 # Remove from the depth image all values above a given value (meters).
align_depth: false # If set to true, will publish additional topics with all the images aligned to the depth image.
pointcloud.enable: true
#COLOR
enable_color: true # Enable color stream
color_width: 0 # Setting a value to 0, will choose the first format in the inner list. (i.e. consistent between runs but not defined).
color_height: 0
color_fps: 0
# INFRA
enable_infra: false # Enable infra1 stream
infra_width: 0 # Setting a value to 0, will choose the first format in the inner list. (i.e. consistent between runs but not defined).
infra_height: 0
infra_fps: 0
# POSE
enable_pose: true # Enable pose stream
pose_fps: 0 # Setting a value to 0, will choose the first format in the inner list. (i.e. consistent between runs but not defined)
hollander/back_camera: # LINK https://dev.intelrealsense.com/docs/ros-wrapper#section-launch-parameters
ros__parameters:
# CAMERA IDENTITY
serial_no: "008222071502" # Attach to the device with the given serial number (serial_no) number.
camera_name: "back_camera"
# SETTINGS
base_frame_id: "base_link" # Define the frame_id all static transformations refers to.
odom_frame_id: "odom" # Define the origin coordinate system in ROS convention (X-Forward, Y-Left, Z-Up). Pose topic defines the pose relative to that system.
initial_reset: false # Allows resetting the device before using it. Recommended to be used for example, when a glitch prevented the device from being properly closed.
wait_for_device_timeout: -1.0 # Timeout for waiting for device to connect [seconds]
reconnect_timeout: 5.0 # Timeout between consecutive reconnection attempts [seconds]
enable_sync: false # ??
# TF
publish_tf: true # A Boolean parameter, publish or not TF at all.
tf_prefix: "back_camera" # This parameter allows changing the frames' IDs prefix per camera.
tf_publish_rate: 0.0 # A double parameter, positive values mean dynamic transform publication with specified rate, all other values mean static transform publication.
publish_odom_tf: true # A Boolean parameter, publish if True TF from odom_frame to pose_frame.
# IMU
unite_imu_method: 2 # [0-None, 1-copy, 2-linear_interpolation]
linear_accel_cov: 0.01 # Set the variance given to the Imu readings.
angular_velocity_cov: 0.01
enable_gyro: true # Enable gyro stream
gyro_fps: 0 # Setting a value to 0, will choose the first format in the inner list. (i.e. consistent between runs but not defined).
enable_accel: true # Enable accel stream
accel_fps: 0 # Setting a value to 0, will choose the first format in the inner list. (i.e. consistent between runs but not defined).
# DEPTH
enable_depth: true # Enable depth stream
depth_width: 0 # Setting a value to 0, will choose the first format in the inner list. (i.e. consistent between runs but not defined).
depth_height: 0
depth_fps: 0
clip_distance: -2.0 # Remove from the depth image all values above a given value (meters).
align_depth: false # If set to true, will publish additional topics with all the images aligned to the depth image.
pointcloud.enable: true
#COLOR
enable_color: true # Enable color stream
color_width: 0 # Setting a value to 0, will choose the first format in the inner list. (i.e. consistent between runs but not defined).
color_height: 0
color_fps: 0
# INFRA
enable_infra: false # Enable infra1 stream
infra_width: 0 # Setting a value to 0, will choose the first format in the inner list. (i.e. consistent between runs but not defined).
infra_height: 0
infra_fps: 0
# POSE
enable_pose: true # Enable pose stream
pose_fps: 0 # Setting a value to 0, will choose the first format in the inner list. (i.e. consistent between runs but not defined)
......@@ -11,6 +11,7 @@ from launch import LaunchDescription
def generate_launch_description():
need_driver = DeclareLaunchArgument('need_driver', default_value='true', description='true|false')
need_teleop = DeclareLaunchArgument('need_teleop', default_value='true', description='true|false')
need_vision = DeclareLaunchArgument('need_vision', default_value='true', description='true|false')
driver = IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('hollander_bringup'), 'launch', 'driver.launch.py')),
......@@ -22,12 +23,19 @@ def generate_launch_description():
condition=IfCondition(LaunchConfiguration('need_teleop'))
)
vision = IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('hollander_bringup'), 'launch', 'vision.teleop.launch.py')),
condition=IfCondition(LaunchConfiguration('need_vision'))
)
return LaunchDescription([
# Conditions
need_driver,
need_teleop,
need_vision,
# Launch files
driver,
teleop,
vision,
])
......@@ -2,7 +2,6 @@ import os
from ament_index_python.packages import get_package_share_directory
from launch_ros.actions import Node
from launch.substitutions import LaunchConfiguration
from launch import LaunchDescription
......
import os
from ament_index_python.packages import get_package_share_directory
from launch.actions import DeclareLaunchArgument
from launch_ros.actions import Node
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch import LaunchDescription
def generate_launch_description():
# Get launch configuration
launch_dir = get_package_share_directory('hollander_bringup')
default_config_file = os.path.join(launch_dir, 'config', 'vision.config.yaml')
# Parameters
configurable_parameters = [
{'name': 'front_camera_name', 'default': 'front_camera', 'description': 'camera unique name'},
{'name': 'back_camera_name', 'default': 'back_camera', 'description': 'camera unique name'},
{'name': 'namespace', 'default': 'hollander', 'description': 'Namespace to avoide conflicts'},
{'name': 'config', 'default': default_config_file, 'description': 'Namespace to avoide conflicts'},
{'name': 'log_level', 'default': 'info', 'description': 'debug log level [DEBUG|INFO|WARN|ERROR|FATAL]'},
]
def declare_configurable_parameters(parameters):
return [DeclareLaunchArgument(param['name'], default_value=param['default'], description=param['description']) for param in parameters]
front_camera = Node(
package='realsense2_camera',
namespace=LaunchConfiguration("namespace"),
name=LaunchConfiguration("front_camera_name"),
executable='realsense2_camera_node',
parameters=[LaunchConfiguration("config")],
output='screen',
arguments=['--ros-args', '--log-level', LaunchConfiguration('log_level')],
emulate_tty=True,
)
back_camera = Node(
package='realsense2_camera',
namespace=LaunchConfiguration("namespace"),
name=LaunchConfiguration("back_camera_name"),
executable='realsense2_camera_node',
parameters=[LaunchConfiguration("config")],
output='screen',
arguments=['--ros-args', '--log-level', LaunchConfiguration('log_level')],
emulate_tty=True,
)
return LaunchDescription(
declare_configurable_parameters(configurable_parameters) +
[
front_camera,
back_camera
])
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment