diff --git a/.gitignore b/.gitignore index dcf4721..c6d59c4 100644 --- a/.gitignore +++ b/.gitignore @@ -1,3 +1,4 @@ *.bin *.ppm *.bag +*.vscode diff --git a/realsense_ros/config/d435.yaml b/realsense_ros/config/d435.yaml index 2fea070..2f5be5e 100644 --- a/realsense_ros/config/d435.yaml +++ b/realsense_ros/config/d435.yaml @@ -4,7 +4,7 @@ serial_no: 819312071869 # d435 base_frame_id: d435_link align_depth: false - enable_pointcloud: false + enable_pointcloud: true dense_pointcloud: true color0: enabled: true diff --git a/realsense_ros/config/rs_cartographer.lua b/realsense_ros/config/rs_cartographer.lua new file mode 100644 index 0000000..dcd849c --- /dev/null +++ b/realsense_ros/config/rs_cartographer.lua @@ -0,0 +1,69 @@ +-- Copyright 2016 The Cartographer Authors +-- +-- Licensed under the Apache License, Version 2.0 (the "License"); +-- you may not use this file except in compliance with the License. +-- You may obtain a copy of the License at +-- +-- http://www.apache.org/licenses/LICENSE-2.0 +-- +-- Unless required by applicable law or agreed to in writing, software +-- distributed under the License is distributed on an "AS IS" BASIS, +-- WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +-- See the License for the specific language governing permissions and +-- limitations under the License. + +-- /* Author: Darby Lim */ + +include "map_builder.lua" +include "trajectory_builder.lua" + +options = { + map_builder = MAP_BUILDER, + trajectory_builder = TRAJECTORY_BUILDER, + map_frame = "map", + tracking_frame = "camera_pose_optical_frame", + published_frame = "odom_frame", + odom_frame = "odom_frame", + provide_odom_frame = false, + publish_frame_projected_to_2d = true, + use_odometry = true, + use_nav_sat = false, + use_landmarks = false, + num_laser_scans = 1, + num_multi_echo_laser_scans = 0, + num_subdivisions_per_laser_scan = 1, + num_point_clouds = 0, + lookup_transform_timeout_sec = 0.2, + submap_publish_period_sec = 0.05, + pose_publish_period_sec = 5e-3, + trajectory_publish_period_sec = 30e-3, + rangefinder_sampling_ratio = 1., + odometry_sampling_ratio = 1., + fixed_frame_pose_sampling_ratio = 1., + imu_sampling_ratio = 1., + landmarks_sampling_ratio = 1., +} + +MAP_BUILDER.use_trajectory_builder_2d = true + +TRAJECTORY_BUILDER_2D.min_range = 0.12 +TRAJECTORY_BUILDER_2D.max_range = 3. +TRAJECTORY_BUILDER_2D.missing_data_ray_length = 4. +TRAJECTORY_BUILDER_2D.use_imu_data = false +TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = false +TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = math.rad(0.07) +TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 300 +TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 150 +TRAJECTORY_BUILDER_2D.submaps.grid_options_2d.resolution = 0.035 +TRAJECTORY_BUILDER_2D.submaps.num_range_data = 350 +POSE_GRAPH.constraint_builder.sampling_ratio = 0.9 + +POSE_GRAPH.optimization_problem.huber_scale = 1 +POSE_GRAPH.constraint_builder.min_score = 0.7 + +POSE_GRAPH.constraint_builder.global_localization_min_score = 0.8 +POSE_GRAPH.constraint_builder.loop_closure_translation_weight = 300 +POSE_GRAPH.constraint_builder.loop_closure_rotation_weight = 50 +POSE_GRAPH.optimize_every_n_nodes = 150 + +return options diff --git a/realsense_ros/config/rs_cartographer.rviz b/realsense_ros/config/rs_cartographer.rviz new file mode 100644 index 0000000..d005da6 --- /dev/null +++ b/realsense_ros/config/rs_cartographer.rviz @@ -0,0 +1,340 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /Image1 + - /Image2 + - /LaserScan1 + - /TF1 + - /Odometry1 + - /Odometry1/Shape1 + - /Map1 + - /PointCloud21 + Splitter Ratio: 0.5013054609298706 + Tree Height: 266 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: rviz_default_plugins/Image + Enabled: false + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 10 + Topic: /t265/fisheye1/image_raw + Unreliable: false + Value: false + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 10 + Topic: /d435/camera/color/image_raw + Unreliable: false + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/LaserScan + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /scan + Unreliable: true + Use Fixed Frame: true + Use rainbow: true + Value: false + - Class: rviz_default_plugins/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + camera_accel_optical_frame: + Value: true + camera_color_optical_frame: + Value: true + camera_depth_optical_frame: + Value: true + camera_fisheye1_optical_frame: + Value: true + camera_fisheye2_optical_frame: + Value: true + camera_gyro_optical_frame: + Value: true + camera_infra1_optical_frame: + Value: true + camera_infra2_optical_frame: + Value: true + camera_pose_optical_frame: + Value: true + d435_link: + Value: true + odom_frame: + Value: true + t265_link: + Value: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + odom_frame: + camera_pose_optical_frame: + t265_link: + camera_accel_optical_frame: + {} + camera_fisheye1_optical_frame: + {} + camera_fisheye2_optical_frame: + {} + camera_gyro_optical_frame: + {} + d435_link: + camera_color_optical_frame: + {} + camera_depth_optical_frame: + {} + camera_infra1_optical_frame: + {} + camera_infra2_optical_frame: + {} + Update Interval: 0 + Value: true + - Angle Tolerance: 0.10000000149011612 + Class: rviz_default_plugins/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Keep: 1 + Name: Odometry + Position Tolerance: 0.10000000149011612 + Shape: + Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Color: 238; 238; 236 + Head Length: 0.05000000074505806 + Head Radius: 0.019999999552965164 + Shaft Length: 0.4000000059604645 + Shaft Radius: 0.009999999776482582 + Value: Arrow + Topic: /odom + Unreliable: false + Value: true + - Alpha: 0.699999988079071 + Class: rviz_default_plugins/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /map + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: z + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 239; 41; 41 + Max Intensity: 0.03064223937690258 + Min Color: 239; 41; 41 + Min Intensity: 0.026489952579140663 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.05000000074505806 + Style: Flat Squares + Topic: /scan_matched_points2 + Unreliable: false + Use Fixed Frame: true + Use rainbow: false + Value: true + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 10 + Topic: /d435/camera/color/image_raw + Unreliable: false + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /d435/camera/pointcloud + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: odom_frame + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: /move_base_simple/goal + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 2.4680275917053223 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -1.210277795791626 + Y: -2.4129858016967773 + Z: 4.185188293457031 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.8847963213920593 + Target Frame: + Value: Orbit (rviz_default_plugins) + Yaw: 4.814521312713623 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 990 + Hide Left Dock: false + Hide Right Dock: true + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd00000004000000000000020600000384fc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000147000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006500000001a5000000d70000002800fffffffb0000000a0049006d006100670065000000010c0000012a0000002800fffffffb0000000a0049006d006100670065010000018a000002370000002800ffffff00000001000001000000028ffc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d0000028f000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000004dc0000038400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1768 + X: 45 + Y: 28 diff --git a/realsense_ros/include/realsense/rs_constants.hpp b/realsense_ros/include/realsense/rs_constants.hpp index 1443fff..038dea8 100644 --- a/realsense_ros/include/realsense/rs_constants.hpp +++ b/realsense_ros/include/realsense/rs_constants.hpp @@ -80,7 +80,7 @@ namespace realsense {RS2_STREAM_FISHEYE, CV_8UC1}}; const std::map MSG_ENCODING = {{RS2_STREAM_COLOR, sensor_msgs::image_encodings::RGB8}, - {RS2_STREAM_DEPTH, sensor_msgs::image_encodings::MONO16}, + {RS2_STREAM_DEPTH, sensor_msgs::image_encodings::TYPE_16UC1}, {RS2_STREAM_INFRARED, sensor_msgs::image_encodings::TYPE_8UC1}, {RS2_STREAM_FISHEYE, sensor_msgs::image_encodings::TYPE_8UC1}}; diff --git a/realsense_ros/launch/multi_cam.launch.py b/realsense_ros/launch/multi_cam.launch.py new file mode 100644 index 0000000..fe1c058 --- /dev/null +++ b/realsense_ros/launch/multi_cam.launch.py @@ -0,0 +1,54 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# /* Author: Gary Liu */ + +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import ThisLaunchFileDir + +def generate_launch_description(): + + rviz_config_dir = os.path.join(get_package_share_directory('realsense_ros'), 'config', 'rs_cartographer.rviz') + return LaunchDescription([ + + Node( + package='rviz2', + node_executable='rviz2', + node_name='rviz2', + arguments=['-d', rviz_config_dir], + parameters=[{'use_sim_time': 'false'}]), + Node( + package='realsense_node', + node_executable='realsense_camera_node', + node_namespace="/t265", + output='screen', + parameters=[get_package_share_directory('realsense_ros')+'/config/t265.yaml'], + remappings=[('/t265/camera/odom/sample', '/odom')], + ), + + Node( + package='realsense_node', + node_executable='realsense_camera_node', + node_namespace="/d435", + output='log', + parameters=[get_package_share_directory('realsense_ros')+'/config/d435.yaml'] + ), + ]) \ No newline at end of file diff --git a/realsense_ros/launch/rs_cartographer.launch.py b/realsense_ros/launch/rs_cartographer.launch.py new file mode 100644 index 0000000..9c02590 --- /dev/null +++ b/realsense_ros/launch/rs_cartographer.launch.py @@ -0,0 +1,100 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# /* Author: Gary Liu */ + +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import ThisLaunchFileDir + +def generate_launch_description(): + use_sim_time = LaunchConfiguration('use_sim_time', default='false') + realsense_prefix = get_package_share_directory('realsense_ros') + cartographer_config_dir = LaunchConfiguration('cartographer_config_dir', + default=os.path.join(realsense_prefix, 'config')) + configuration_basename = LaunchConfiguration('configuration_basename', default='rs_cartographer.lua') + + resolution = LaunchConfiguration('resolution', default='0.05') + publish_period_sec = LaunchConfiguration('publish_period_sec', default='1.0') + + rviz_config_dir = os.path.join(get_package_share_directory('realsense_ros'), 'config', 'rs_cartographer.rviz') + + return LaunchDescription([ + DeclareLaunchArgument( + 'cartographer_config_dir', + default_value=cartographer_config_dir, + description='Full path to config file to load'), + DeclareLaunchArgument( + 'configuration_basename', + default_value=configuration_basename, + description='Name of lua file for cartographer'), + DeclareLaunchArgument( + 'use_sim_time', + default_value='false', + description='Use simulation (Gazebo) clock if true'), + + Node( + package='tf2_ros', + node_executable='static_transform_publisher', + output='screen', + arguments=['0', '0', '0.03', '0', '0', '0', 't265_link', 'd435_link'] + ), + + Node( + ## Configure the TF of the robot to the origin of the map coordinates + package='tf2_ros', + node_executable='static_transform_publisher', + output='screen', + arguments=['0', '0', '0', '0', '0', '0', 'map', 'odom_frame'] + ), + + Node( + package='depthimage_to_laserscan', + node_executable='depthimage_to_laserscan_node', + node_name='scan', + output='screen', + remappings=[('depth','/d435/camera/depth/image_rect_raw'), + ('depth_camera_info', '/d435/camera/depth/camera_info')], + ), + + Node( + package='cartographer_ros', + node_executable='cartographer_node', + output='log', + parameters=[{'use_sim_time': use_sim_time}], + arguments=['-configuration_directory', cartographer_config_dir, '-configuration_basename', configuration_basename]), + + DeclareLaunchArgument( + 'resolution', + default_value=resolution, + description='Resolution of a grid cell in the published occupancy grid'), + + DeclareLaunchArgument( + 'publish_period_sec', + default_value=publish_period_sec, + description='OccupancyGrid publishing period'), + + Node( + package='cartographer_ros', + node_executable='occupancy_grid_node', + node_name='occupancy_grid_node', + parameters=[{'use_sim_time': use_sim_time}], + arguments=['-resolution', resolution, '-publish_period_sec', publish_period_sec]), + ]) \ No newline at end of file diff --git a/realsense_ros/src/rs_base.cpp b/realsense_ros/src/rs_base.cpp index afa7fd0..c675de3 100644 --- a/realsense_ros/src/rs_base.cpp +++ b/realsense_ros/src/rs_base.cpp @@ -91,7 +91,8 @@ void RealSenseBase::setupStream(const stream_index_pair & stream) if (node_.has_parameter(os.str())) node_.get_parameter(os.str(), res); else - res = node_.declare_parameter(os.str(), rclcpp::ParameterValue(DEFAULT_IMAGE_RESOLUTION)).get(); os.str(""); + res = node_.declare_parameter(os.str(), rclcpp::ParameterValue(DEFAULT_IMAGE_RESOLUTION)).get(); + os.str(""); os << STREAM_NAME.at(stream.first) << stream.second << ".fps"; if (node_.has_parameter(os.str())) node_.get_parameter(os.str(), fps);