紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
ros2,cartographer建图,rviz2不能显示submaps
-
ros2,cartographer建图时,rviz2中submaps组件无法显示?
-
-
@阿甘 平时没怎么注意submap,今天晚点我抽时间瞅瞅,图能正常建出来吗?carto配置参数怎么配的
-
@小鱼 感谢回复 可以正常建图
配置参数:include "map_builder.lua" include "trajectory_builder.lua" options = { map_builder = MAP_BUILDER, trajectory_builder = TRAJECTORY_BUILDER, map_frame = "map", tracking_frame = "base_link", --imu_link published_frame = "base_link", --base_link odom_frame = "odom", provide_odom_frame = true, publish_frame_projected_to_2d = false, use_pose_extrapolator = true, use_odometry = false, use_nav_sat = false, use_landmarks = true, num_laser_scans = 1, num_multi_echo_laser_scans = 0, num_subdivisions_per_laser_scan = 1,--10 num_point_clouds = 0, lookup_transform_timeout_sec = 0.2, submap_publish_period_sec = 0.3, 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 MAP_BUILDER.num_background_threads=6 --7 TRAJECTORY_BUILDER_2D.min_range = 0.1 TRAJECTORY_BUILDER_2D.max_range = 15 TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 1 TRAJECTORY_BUILDER_2D.use_imu_data = false TRAJECTORY_BUILDER_2D.motion_filter.max_distance_meters=0.08 TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians=math.rad(6.) TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching =true TRAJECTORY_BUILDER_2D.ceres_scan_matcher.occupied_space_weight = 1. TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 1. TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 1. TRAJECTORY_BUILDER_2D.submaps.num_range_data=100 TRAJECTORY_BUILDER_2D.submaps.grid_options_2d.resolution = 0.05 return options
-
@小鱼 launch文件
import os from launch import LaunchDescription from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node from launch_ros.substitutions import FindPackageShare from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription def generate_launch_description(): # 定位到功能包的地址 pkg_share = FindPackageShare(package='fishbot_cartographer').find('fishbot_cartographer') #=====================运行节点需要的配置======================================================================= # 是否使用仿真时间,我们用gazebo,这里设置成true use_sim_time = LaunchConfiguration('use_sim_time', default='false') # 地图的分辨率 resolution = LaunchConfiguration('resolution', default='0.05') # 地图的发布周期 publish_period_sec = LaunchConfiguration('publish_period_sec', default='1.0') # 配置文件夹路径 configuration_directory = LaunchConfiguration('configuration_directory',default= os.path.join(pkg_share, 'config') ) # 配置文件 configuration_basename = LaunchConfiguration('configuration_basename', default='cartographer_slam.lua') urdf_dir = os.path.join(pkg_share, 'urdf') urdf_file = os.path.join(urdf_dir, 'jzdbot_base.urdf') with open(urdf_file, 'r') as infp: robot_desc = infp.read() #=====================声明三个节点,cartographer/occupancy_grid_node/rviz_node================================= robot_state_publisher_node = Node( package = 'robot_state_publisher', executable = 'robot_state_publisher', parameters=[ {'robot_description': robot_desc}, {'use_sim_time': use_sim_time}], output = 'screen' ) cartographer_node = Node( package='cartographer_ros', executable='cartographer_node', name='cartographer_node', output='screen', parameters=[{'use_sim_time': use_sim_time}], arguments=['-configuration_directory', configuration_directory, '-configuration_basename', configuration_basename]) occupancy_grid_node = Node( package='cartographer_ros', executable='cartographer_occupancy_grid_node', name='cartographer_occupancy_grid_node', output='screen', parameters=[{'use_sim_time': use_sim_time}], arguments=['-resolution', resolution, '-publish_period_sec', publish_period_sec]) rviz_node = Node( package='rviz2', executable='rviz2', name='rviz2', # arguments=['-d', rviz_config_dir], parameters=[{'use_sim_time': use_sim_time}], output='screen') #===============================================定义启动文件======================================================== ld = LaunchDescription() ld.add_action(robot_state_publisher_node) ld.add_action(cartographer_node) ld.add_action(occupancy_grid_node) ld.add_action(rviz_node) return ld