紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
cartographer建图失败,报警告:
-
系统配置
vm 安装 Ubuntu 20.04.6 LTS Distributor ID: Ubuntu Description: Ubuntu 20.04.6 LTS Release: 20.04 Codename: focal
ros2版本
小鱼的一键安装 galactic 同时还安装了,ros的noetic
情景回放:
根据CSDN小鱼的教程,
Gazebo仿真环境的搭建及运行
以下是俺自己调整过的文件夹树、配置文件、运行结果
文件夹树
├── lyprc_description │ ├── launch │ │ ├── display_rviz2.launch.py │ │ └── gazebo.launch.py │ ├── lyprc01.rviz │ ├── lyprc_description │ │ └── __init__.py │ ├── package.xml │ ├── resource │ │ └── lyprc_description │ ├── setup.cfg │ ├── setup.py │ ├── test │ │ ├── test_copyright.py │ │ ├── test_flake8.py │ │ └── test_pep257.py │ ├── urdf │ │ ├── lyprc_base.urdf │ │ └── lyprc_gazebo.urdf │ └── world │ └── myhouse01.world
gazebo.launch.py文件
import os from launch import LaunchDescription from launch.actions import ExecuteProcess from launch_ros.actions import Node from launch_ros.substitutions import FindPackageShare def generate_launch_description(): robot_name_in_model = 'lyprcbot' package_name = 'lyprc_description' urdf_name = "lyprc_gazebo.urdf" world_name = "myhouse01.world" ld = LaunchDescription() pkg_share = FindPackageShare(package=package_name).find(package_name) urdf_model_path = os.path.join(pkg_share, f'urdf/{urdf_name}') gazebo_world_path = os.path.join(pkg_share, f'world/{world_name}') # Start Gazebo server start_gazebo_cmd = ExecuteProcess( cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so', gazebo_world_path], output='screen') # start_gazebo_cmd = ExecuteProcess( # cmd=['gazebo', '--verbose','-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], # output='screen') # Launch the robot spawn_entity_cmd = Node( package='gazebo_ros', executable='spawn_entity.py', arguments=['-entity', robot_name_in_model, '-file', urdf_model_path ], output='screen', ) # Start Robot State publisher start_robot_state_publisher_cmd = Node( package='robot_state_publisher', executable='robot_state_publisher', arguments=[urdf_model_path], ) # Launch RViz start_rviz_cmd = Node( package='rviz2', executable='rviz2', name='rviz2', output='screen', arguments=['-d', "/home/lyprc/LOVE/ROStest/ROSLAM_ws/src/lyprc_description/lyprc01.rviz"], ) ld.add_action(start_gazebo_cmd) ld.add_action(spawn_entity_cmd) ld.add_action(start_robot_state_publisher_cmd) ld.add_action(start_rviz_cmd) return ld
lyprc_gazebo.urdf文件
<?xml version="1.0"?> <robot name="lyprc"> <!-- Robot Footprint --> <link name="base_footprint"/> <joint name="base_joint" type="fixed"> <parent link="base_footprint"/> <child link="base_link"/> <origin xyz="0.0 0.0 0.076" rpy="0 0 0"/> </joint> <!-- base link --> <link name="base_link"> <visual> <origin xyz="0 0 0.0" rpy="0 0 0"/> <geometry> <cylinder length="0.12" radius="0.10"/> </geometry> <material name="blue"> <color rgba="0.1 0.1 1.0 0.5" /> </material> </visual> <collision> <origin xyz="0 0 0.0" rpy="0 0 0"/> <geometry> <cylinder length="0.12" radius="0.10"/> </geometry> <material name="blue"> <color rgba="0.1 0.1 1.0 0.5" /> </material> </collision> <inertial> <mass value="0.2"/> <inertia ixx="0.0122666" ixy="0" ixz="0" iyy="0.0122666" iyz="0" izz="0.02"/> </inertial> </link> <!-- laser link --> <link name="laser_link"> <visual> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <cylinder length="0.02" radius="0.02"/> </geometry> <material name="black"> <color rgba="0.0 0.0 0.0 0.5" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <cylinder length="0.02" radius="0.02"/> </geometry> <material name="black"> <color rgba="0.0 0.0 0.0 0.5" /> </material> </collision> <inertial> <mass value="0.1"/> <inertia ixx="0.000190416666667" ixy="0" ixz="0" iyy="0.0001904" iyz="0" izz="0.00036"/> </inertial> </link> <!-- laser joint --> <joint name="laser_joint" type="fixed"> <parent link="base_link" /> <child link="laser_link" /> <origin xyz="0 0 0.075" /> </joint> <link name="imu_link"> <visual> <origin xyz="0 0 0.0" rpy="0 0 0"/> <geometry> <box size="0.02 0.02 0.02"/> </geometry> </visual> <collision> <origin xyz="0 0 0.0" rpy="0 0 0"/> <geometry> <box size="0.02 0.02 0.02"/> </geometry> </collision> <inertial> <mass value="0.1"/> <inertia ixx="0.000190416666667" ixy="0" ixz="0" iyy="0.0001904" iyz="0" izz="0.00036"/> </inertial> </link> <!-- imu joint --> <joint name="imu_joint" type="fixed"> <parent link="base_link" /> <child link="imu_link" /> <origin xyz="0 0 0.02" /> </joint> <link name="left_wheel_link"> <visual> <origin xyz="0 0 0" rpy="1.57079 0 0"/> <geometry> <cylinder length="0.04" radius="0.032"/> </geometry> <material name="black"> <color rgba="0.0 0.0 0.0 0.5" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="1.57079 0 0"/> <geometry> <cylinder length="0.04" radius="0.032"/> </geometry> <material name="black"> <color rgba="0.0 0.0 0.0 0.5" /> </material> </collision> <inertial> <mass value="0.2"/> <inertia ixx="0.000190416666667" ixy="0" ixz="0" iyy="0.0001904" iyz="0" izz="0.00036"/> </inertial> </link> <link name="right_wheel_link"> <visual> <origin xyz="0 0 0" rpy="1.57079 0 0"/> <geometry> <cylinder length="0.04" radius="0.032"/> </geometry> <material name="black"> <color rgba="0.0 0.0 0.0 0.5" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="1.57079 0 0"/> <geometry> <cylinder length="0.04" radius="0.032"/> </geometry> <material name="black"> <color rgba="0.0 0.0 0.0 0.5" /> </material> </collision> <inertial> <mass value="0.2"/> <inertia ixx="0.000190416666667" ixy="0" ixz="0" iyy="0.0001904" iyz="0" izz="0.00036"/> </inertial> </link> <joint name="left_wheel_joint" type="continuous"> <parent link="base_link" /> <child link="left_wheel_link" /> <origin xyz="-0.02 0.10 -0.06" /> <axis xyz="0 1 0" /> </joint> <joint name="right_wheel_joint" type="continuous"> <parent link="base_link" /> <child link="right_wheel_link" /> <origin xyz="-0.02 -0.10 -0.06" /> <axis xyz="0 1 0" /> </joint> <link name="caster_link"> <visual> <origin xyz="0 0 0" rpy="1.57079 0 0"/> <geometry> <sphere radius="0.016"/> </geometry> <material name="black"> <color rgba="0.0 0.0 0.0 0.5" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="1.57079 0 0"/> <geometry> <sphere radius="0.016"/> </geometry> <material name="black"> <color rgba="0.0 0.0 0.0 0.5" /> </material> </collision> <inertial> <mass value="0.02"/> <inertia ixx="0.000190416666667" ixy="0" ixz="0" iyy="0.0001904" iyz="0" izz="0.00036"/> </inertial> </link> <joint name="caster_joint" type="fixed"> <parent link="base_link" /> <child link="caster_link" /> <origin xyz="0.06 0.0 -0.076" /> <axis xyz="0 1 0" /> </joint> <gazebo reference="caster_link"> <material>Gazebo/Black</material> </gazebo> <gazebo reference="caster_link"> <mu1 value="0.0"/> <mu2 value="0.0"/> <kp value="1000000.0" /> <kd value="10.0" /> <!-- <fdir1 value="0 0 1"/> --> </gazebo> <gazebo> <plugin name='diff_drive' filename='libgazebo_ros_diff_drive.so'> <ros> <namespace>/</namespace> <remapping>cmd_vel:=cmd_vel</remapping> <remapping>odom:=odom</remapping> </ros> <update_rate>30</update_rate> <!-- wheels --> <left_joint>left_wheel_joint</left_joint> <right_joint>right_wheel_joint</right_joint> <!-- kinematics --> <wheel_separation>0.2</wheel_separation> <wheel_diameter>0.065</wheel_diameter> <!-- limits --> <max_wheel_torque>20</max_wheel_torque> <max_wheel_acceleration>1.0</max_wheel_acceleration> <!-- output --> <publish_odom>true</publish_odom> <publish_odom_tf>true</publish_odom_tf> <publish_wheel_tf>false</publish_wheel_tf> <odometry_frame>odom</odometry_frame> <robot_base_frame>base_footprint</robot_base_frame> </plugin> <plugin name="lyprc_joint_state" filename="libgazebo_ros_joint_state_publisher.so"> <ros> <remapping>~/out:=joint_states</remapping> </ros> <update_rate>30</update_rate> <joint_name>right_wheel_joint</joint_name> <joint_name>left_wheel_joint</joint_name> </plugin> </gazebo> <gazebo reference="laser_link"> <material>Gazebo/Black</material> </gazebo> <gazebo reference="imu_link"> <sensor name="imu_sensor" type="imu"> <plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin"> <ros> <namespace>/</namespace> <remapping>~/out:=imu</remapping> </ros> <initial_orientation_as_reference>false</initial_orientation_as_reference> </plugin> <always_on>true</always_on> <update_rate>100</update_rate> <visualize>true</visualize> <imu> <angular_velocity> <x> <noise type="gaussian"> <mean>0.0</mean> <stddev>2e-4</stddev> <bias_mean>0.0000075</bias_mean> <bias_stddev>0.0000008</bias_stddev> </noise> </x> <y> <noise type="gaussian"> <mean>0.0</mean> <stddev>2e-4</stddev> <bias_mean>0.0000075</bias_mean> <bias_stddev>0.0000008</bias_stddev> </noise> </y> <z> <noise type="gaussian"> <mean>0.0</mean> <stddev>2e-4</stddev> <bias_mean>0.0000075</bias_mean> <bias_stddev>0.0000008</bias_stddev> </noise> </z> </angular_velocity> <linear_acceleration> <x> <noise type="gaussian"> <mean>0.0</mean> <stddev>1.7e-2</stddev> <bias_mean>0.1</bias_mean> <bias_stddev>0.001</bias_stddev> </noise> </x> <y> <noise type="gaussian"> <mean>0.0</mean> <stddev>1.7e-2</stddev> <bias_mean>0.1</bias_mean> <bias_stddev>0.001</bias_stddev> </noise> </y> <z> <noise type="gaussian"> <mean>0.0</mean> <stddev>1.7e-2</stddev> <bias_mean>0.1</bias_mean> <bias_stddev>0.001</bias_stddev> </noise> </z> </linear_acceleration> </imu> </sensor> </gazebo> <gazebo reference="laser_link"> <sensor name="laser_sensor" type="ray"> <always_on>true</always_on> <visualize>true</visualize> <update_rate>5</update_rate> <pose>0 0 0.075 0 0 0</pose> <ray> <scan> <horizontal> <samples>360</samples> <resolution>1.000000</resolution> <min_angle>0.000000</min_angle> <max_angle>6.280000</max_angle> </horizontal> </scan> <range> <min>0.120000</min> <max>3.5</max> <resolution>0.015000</resolution> </range> <noise> <type>gaussian</type> <mean>0.0</mean> <stddev>0.01</stddev> </noise> </ray> <plugin name="laserscan" filename="libgazebo_ros_ray_sensor.so"> <ros> <!-- <namespace>/tb3</namespace> --> <remapping>~/out:=scan</remapping> </ros> <output_type>sensor_msgs/LaserScan</output_type> <frame_name>laser_link</frame_name> </plugin> </sensor> </gazebo> </robot>
gazebo仿真运行效果
运行指令
ros:galactic(1) noetic(2) ? 1 lyprc@lyprc-vm-ubuntu2004:~/LOVE/ROStest/ROSLAM_ws$ colcon build Starting >>> absl Starting >>> lyprc_cartographer Starting >>> lyprc_description Finished <<< lyprc_cartographer [0.58s] Finished <<< absl [0.78s] Finished <<< lyprc_description [1.62s] Summary: 3 packages finished [2.61s] lyprc@lyprc-vm-ubuntu2004:~/LOVE/ROStest/ROSLAM_ws$ source install/setup.bash lyprc@lyprc-vm-ubuntu2004:~/LOVE/ROStest/ROSLAM_ws$ ros2 launch lyprc_description gazebo.launch.py [INFO] [launch]: All log files can be found below /home/lyprc/.ros/log/2024-04-03-15-01-11-164272-lyprc-vm-ubuntu2004-2655 [INFO] [launch]: Default logging verbosity is set to INFO [INFO] [gazebo-1]: process started with pid [2657] [INFO] [spawn_entity.py-2]: process started with pid [2659] [INFO] [robot_state_publisher-3]: process started with pid [2661] [INFO] [rviz2-4]: process started with pid [2663] [robot_state_publisher-3] [WARN] [1712127671.602336654] [robot_state_publisher]: No robot_description parameter, but command-line argument available. Assuming argument is name of URDF file. This backwards compatibility fallback will be removed in the future. [robot_state_publisher-3] Link base_link had 5 children [robot_state_publisher-3] Link caster_link had 0 children [robot_state_publisher-3] Link imu_link had 0 children [robot_state_publisher-3] Link laser_link had 0 children [robot_state_publisher-3] Link left_wheel_link had 0 children [robot_state_publisher-3] Link right_wheel_link had 0 children [robot_state_publisher-3] [INFO] [1712127671.673373107] [robot_state_publisher]: got segment base_footprint [robot_state_publisher-3] [INFO] [1712127671.673469172] [robot_state_publisher]: got segment base_link [robot_state_publisher-3] [INFO] [1712127671.673530713] [robot_state_publisher]: got segment caster_link [robot_state_publisher-3] [INFO] [1712127671.673591054] [robot_state_publisher]: got segment imu_link [robot_state_publisher-3] [INFO] [1712127671.673651094] [robot_state_publisher]: got segment laser_link [robot_state_publisher-3] [INFO] [1712127671.673711435] [robot_state_publisher]: got segment left_wheel_link [robot_state_publisher-3] [INFO] [1712127671.673771074] [robot_state_publisher]: got segment right_wheel_link [spawn_entity.py-2] [INFO] [1712127672.371026930] [spawn_entity]: Spawn Entity started [spawn_entity.py-2] [INFO] [1712127672.371484217] [spawn_entity]: Loading entity XML from file /home/lyprc/LOVE/ROStest/ROSLAM_ws/install/lyprc_description/share/lyprc_description/urdf/lyprc_gazebo.urdf [spawn_entity.py-2] [INFO] [1712127672.377082939] [spawn_entity]: Waiting for service /spawn_entity, timeout = 5 [spawn_entity.py-2] [INFO] [1712127672.377476486] [spawn_entity]: Waiting for service /spawn_entity [rviz2-4] [INFO] [1712127672.959204836] [rviz2]: Stereo is NOT SUPPORTED [rviz2-4] [INFO] [1712127672.960361664] [rviz2]: OpenGl version: 3.3 (GLSL 3.3) [rviz2-4] [INFO] [1712127673.082845510] [rviz2]: Stereo is NOT SUPPORTED [gazebo-1] Gazebo multi-robot simulator, version 11.11.0 [gazebo-1] Copyright (C) 2012 Open Source Robotics Foundation. [gazebo-1] Released under the Apache 2 License. [gazebo-1] http://gazebosim.org [gazebo-1] [gazebo-1] Gazebo multi-robot simulator, version 11.11.0 [gazebo-1] Copyright (C) 2012 Open Source Robotics Foundation. [gazebo-1] Released under the Apache 2 License. [gazebo-1] http://gazebosim.org [gazebo-1] [rviz2-4] Warning: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist [rviz2-4] at line 156 in /tmp/binarydeb/ros-galactic-tf2-0.17.5/src/buffer_core.cpp [rviz2-4] Warning: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist [rviz2-4] at line 156 in /tmp/binarydeb/ros-galactic-tf2-0.17.5/src/buffer_core.cpp 。。。。。。。好多([rviz2-4] at line 156...) 大哥看这里 [spawn_entity.py-2] [INFO] [1712127675.267688990] [spawn_entity]: Spawn status: Entity pushed to spawn queue, but spawn service timed outwaiting for entity to appear in simulation under the name [lyprcbot] [spawn_entity.py-2] [ERROR] [1712127675.268074590] [spawn_entity]: Spawn service failed. Exiting. [rviz2-4] Warning: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist [rviz2-4] at line 156 in /tmp/binarydeb/ros-galactic-tf2-0.17.5/src/buffer_core.cpp 。。。。。。。好多([rviz2-4] at line 156...) [ERROR] [spawn_entity.py-2]: process has died [pid 2659, exit code 1, cmd '/opt/ros/galactic/lib/gazebo_ros/spawn_entity.py -entity lyprcbot -file /home/lyprc/LOVE/ROStest/ROSLAM_ws/install/lyprc_description/share/lyprc_description/urdf/lyprc_gazebo.urdf --ros-args']. [gazebo-1] [INFO] [1712127675.927765017] [diff_drive]: Wheel pair 1 separation set to [0.200000m] [gazebo-1] [INFO] [1712127675.930377570] [diff_drive]: Wheel pair 1 diameter set to [0.065000m] [gazebo-1] [INFO] [1712127675.933248258] [diff_drive]: Subscribed to [/cmd_vel] [gazebo-1] [INFO] [1712127675.938882877] [diff_drive]: Advertise odometry on [/odom] [gazebo-1] [INFO] [1712127675.943610027] [diff_drive]: Publishing odom transforms between [odom] and [base_footprint] 。。。。。。。好多([rviz2-4] at line 156...) [gazebo-1] [INFO] [1712127675.977996645] [lyprc_joint_state]: Going to publish joint [right_wheel_joint] [gazebo-1] [INFO] [1712127675.978190445] [lyprc_joint_state]: Going to publish joint [left_wheel_joint] 。。。。。。。好多([rviz2-4] at line 156...) [gazebo-1] [Msg] Waiting for master. [gazebo-1] [Msg] Connected to gazebo master @ http://127.0.0.1:11345 [gazebo-1] [Msg] Publicized address: 192.168.164.130 [gazebo-1] context mismatch in svga_surface_destroy [gazebo-1] context mismatch in svga_surface_destroy [rviz2-4] [INFO] [1712127686.796322989] [rviz2]: Message Filter dropping message: frame 'laser_link' at time 255.566 for reason 'the timestamp on the message is earlier than all the data in the transform cache' [gazebo-1] [gazebo-1] libcurl: (35) OpenSSL SSL_connect: 连接被对方重设 in connection to fuel.ignitionrobotics.org:443 [gazebo-1] [gazebo-1] libcurl: (7) Failed to connect to fuel.gazebosim.org port 443: 拒绝连接
gazebo效果
rviz 效果
tf树图
订阅图
gazebo仿真的主要警告
[rviz2-4] Warning: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist [rviz2-4] at line 156 in /tmp/binarydeb/ros-galactic-tf2-0.17.5/src/buffer_core.cpp
安装配置运行Cartographer
安装是采取小鱼的一键安装
文件夹树
├── lyprc_cartographer │ ├── CMakeLists.txt │ ├── config │ │ └── lyprc_2d.lua │ ├── include │ │ └── lyprc_cartographer │ ├── launch │ │ └── cartographer.launch.py │ ├── package.xml │ ├── rviz │ └── src
配置文件
cartographer.launch.py
import os from launch import LaunchDescription from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node from launch_ros.substitutions import FindPackageShare def generate_launch_description(): # 定位到功能包的地址 pkg_share = FindPackageShare(package='lyprc_cartographer').find('lyprc_cartographer') #=====================运行节点需要的配置======================================================================= # 是否使用仿真时间,我们用gazebo,这里设置成true use_sim_time = LaunchConfiguration('use_sim_time', default='true') # 地图的分辨率 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='lyprc_2d.lua') rviz_config_dir = os.path.join(pkg_share, 'config')+"/cartographer.rviz" print(f"rviz config in {rviz_config_dir}") #=====================声明三个节点,cartographer/occupancy_grid_node/rviz_node================================= 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], # remappings = [('scan','/laser')], ) cartographer_occupancy_grid_node = Node( package='cartographer_ros', executable='occupancy_grid_node', name='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(cartographer_node) ld.add_action(cartographer_occupancy_grid_node) ld.add_action(rviz_node) return ld
lyprc_2d.lua
include "map_builder.lua" include "trajectory_builder.lua" options = { map_builder = MAP_BUILDER, trajectory_builder = TRAJECTORY_BUILDER, map_frame = "map", tracking_frame = "base_link", -- base_link改为odom,发布map到odom之间的位姿态 published_frame = "odom", odom_frame = "odom", -- true改为false,不用提供里程计数据 provide_odom_frame = false, -- false改为true,仅发布2D位资 publish_frame_projected_to_2d = true, -- false改为true,使用里程计数据 use_odometry = true, use_nav_sat = false, use_landmarks = false, -- 0改为1,使用一个雷达 num_laser_scans = 1, -- 1改为0,不使用多波雷达 num_multi_echo_laser_scans = 0, -- 10改为1,1/1=1等于不分割 num_subdivisions_per_laser_scan = 1, 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., } -- false改为true,启动2D SLAM MAP_BUILDER.use_trajectory_builder_2d = true -- 0改成0.10,比机器人半径小的都忽略 TRAJECTORY_BUILDER_2D.min_range = 0.10 -- 30改成3.5,限制在雷达最大扫描范围内,越小一般越精确些 TRAJECTORY_BUILDER_2D.max_range = 3.5 -- 5改成3,传感器数据超出有效范围最大值 TRAJECTORY_BUILDER_2D.missing_data_ray_length = 3. -- true改成false,不使用IMU数据,大家可以开启,然后对比下效果 TRAJECTORY_BUILDER_2D.use_imu_data = false -- false改成true,使用实时回环检测来进行前端的扫描匹配 TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true -- 1.0改成0.1,提高对运动的敏感度 TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = math.rad(0.1) -- 0.55改成0.65,Fast csm的最低分数,高于此分数才进行优化。 POSE_GRAPH.constraint_builder.min_score = 0.65 --0.6改成0.7,全局定位最小分数,低于此分数则认为目前全局定位不准确 POSE_GRAPH.constraint_builder.global_localization_min_score = 0.7 -- 设置0可关闭全局SLAM -- POSE_GRAPH.optimize_every_n_nodes = 0 return options
运行指令及效果
lyprc@lyprc-vm-ubuntu2004:~/LOVE/ROStest/ROSLAM_ws$ colcon build Starting >>> absl Starting >>> lyprc_cartographer Starting >>> lyprc_description Finished <<< lyprc_cartographer [0.78s] Finished <<< absl [1.05s] Finished <<< lyprc_description [1.54s] Summary: 3 packages finished [2.09s] lyprc@lyprc-vm-ubuntu2004:~/LOVE/ROStest/ROSLAM_ws$ source install/setup.bash lyprc@lyprc-vm-ubuntu2004:~/LOVE/ROStest/ROSLAM_ws$ ros2 launch lyprc_cartographer cartographer.launch.py [INFO] [launch]: All log files can be found below /home/lyprc/.ros/log/2024-04-03-15-57-20-722215-lyprc-vm-ubuntu2004-15614 [INFO] [launch]: Default logging verbosity is set to INFO rviz config in /home/lyprc/LOVE/ROStest/ROSLAM_ws/install/lyprc_cartographer/share/lyprc_cartographer/config/cartographer.rviz [INFO] [cartographer_node-1]: process started with pid [15622] [INFO] [occupancy_grid_node-2]: process started with pid [15624] [INFO] [rviz2-3]: process started with pid [15626] [cartographer_node-1] [INFO] [1712131041.004654099] [cartographer_ros]: I0403 15:57:21.000000 15622 configuration_file_resolver.cc:41] Found '/home/lyprc/LOVE/ROStest/ROSLAM_ws/install/lyprc_cartographer/share/lyprc_cartographer/config/lyprc_2d.lua' for 'lyprc_2d.lua'. [cartographer_node-1] [INFO] [1712131041.005447761] [cartographer_ros]: I0403 15:57:21.000000 15622 configuration_file_resolver.cc:41] Found '/opt/ros/galactic/share/cartographer/configuration_files/map_builder.lua' for 'map_builder.lua'. [cartographer_node-1] [INFO] [1712131041.005544856] [cartographer_ros]: I0403 15:57:21.000000 15622 configuration_file_resolver.cc:41] Found '/opt/ros/galactic/share/cartographer/configuration_files/map_builder.lua' for 'map_builder.lua'. [cartographer_node-1] [INFO] [1712131041.005660751] [cartographer_ros]: I0403 15:57:21.000000 15622 configuration_file_resolver.cc:41] Found '/opt/ros/galactic/share/cartographer/configuration_files/pose_graph.lua' for 'pose_graph.lua'. [cartographer_node-1] [INFO] [1712131041.005730147] [cartographer_ros]: I0403 15:57:21.000000 15622 configuration_file_resolver.cc:41] Found '/opt/ros/galactic/share/cartographer/configuration_files/pose_graph.lua' for 'pose_graph.lua'. [cartographer_node-1] [INFO] [1712131041.006216924] [cartographer_ros]: I0403 15:57:21.000000 15622 configuration_file_resolver.cc:41] Found '/opt/ros/galactic/share/cartographer/configuration_files/trajectory_builder.lua' for 'trajectory_builder.lua'. [cartographer_node-1] [INFO] [1712131041.006685002] [cartographer_ros]: I0403 15:57:21.000000 15622 configuration_file_resolver.cc:41] Found '/opt/ros/galactic/share/cartographer/configuration_files/trajectory_builder.lua' for 'trajectory_builder.lua'. [cartographer_node-1] [INFO] [1712131041.007238775] [cartographer_ros]: I0403 15:57:21.000000 15622 configuration_file_resolver.cc:41] Found '/opt/ros/galactic/share/cartographer/configuration_files/trajectory_builder_2d.lua' for 'trajectory_builder_2d.lua'. [cartographer_node-1] [INFO] [1712131041.007327371] [cartographer_ros]: I0403 15:57:21.000000 15622 configuration_file_resolver.cc:41] Found '/opt/ros/galactic/share/cartographer/configuration_files/trajectory_builder_2d.lua' for 'trajectory_builder_2d.lua'. [cartographer_node-1] [INFO] [1712131041.007480964] [cartographer_ros]: I0403 15:57:21.000000 15622 configuration_file_resolver.cc:41] Found '/opt/ros/galactic/share/cartographer/configuration_files/trajectory_builder_3d.lua' for 'trajectory_builder_3d.lua'. [cartographer_node-1] [INFO] [1712131041.007553060] [cartographer_ros]: I0403 15:57:21.000000 15622 configuration_file_resolver.cc:41] Found '/opt/ros/galactic/share/cartographer/configuration_files/trajectory_builder_3d.lua' for 'trajectory_builder_3d.lua'. [cartographer_node-1] [INFO] [1712131041.148905592] [cartographer_ros]: I0403 15:57:21.000000 15622 submap_2d.cc:187] Added submap 1 [cartographer_node-1] [INFO] [1712131041.149095083] [cartographer_ros]: I0403 15:57:21.000000 15622 map_builder_bridge.cc:132] Added trajectory with ID '0'. [cartographer_node-1] Warning: Invalid frame ID "base_link" passed to canTransform argument target_frame - frame does not exist [cartographer_node-1] at line 156 in /tmp/binarydeb/ros-galactic-tf2-0.17.5/src/buffer_core.cpp [cartographer_node-1] [INFO] [1712131041.208839523] [cartographer_ros]: I0403 15:57:21.000000 15622 ordered_multi_queue.cc:172] All sensor data for trajectory 0 is available starting at '621355988732800000'. [cartographer_node-1] [INFO] [1712131041.209073512] [cartographer_ros]: I0403 15:57:21.000000 15622 local_trajectory_builder_2d.cc:295] Extrapolator not yet initialized. [cartographer_node-1] [WARN] [1712131041.211820980] [cartographer_ros]: W0403 15:57:21.000000 15622 pose_extrapolator.cc:168] Queue too short for velocity estimation. Queue duration: 0 ms [occupancy_grid_node-2] [WARN] [1712131042.003545074] [occupancy_grid_node]: submap_slices and last_frame_id is empty [rviz2-3] [INFO] [1712131042.605491716] [rviz2]: Stereo is NOT SUPPORTED [rviz2-3] [INFO] [1712131042.605837599] [rviz2]: OpenGl version: 3.3 (GLSL 3.3) [rviz2-3] [INFO] [1712131042.720081141] [rviz2]: Stereo is NOT SUPPORTED [occupancy_grid_node-2] [WARN] [1712131043.003230614] [occupancy_grid_node]: submap_slices and last_frame_id is empty [occupancy_grid_node-2] [WARN] [1712131044.003080849] [occupancy_grid_node]: submap_slices and last_frame_id is empty
rviz和tf树及订阅关系图
错误表现 :运行slam后的rviz里的map显示Frame [map] does not exist
框架[map]不存在
球球各位好心人麻烦给小弟看看吧,小弟已经被折磨死了
-
cartographer警告:[occupancy_grid_node-2] [WARN] [1712131755.556136200] [occupancy_grid_node]: submap_slices and last_frame_id is empty
-
激光雷达数据和odom数据
ros2 topic echo /scan --- header: stamp: sec: 2746 nanosec: 236000000 frame_id: laser_link angle_min: 0.0 angle_max: 6.28000020980835 angle_increment: 0.01749303564429283 time_increment: 0.0 scan_time: 0.0 range_min: 0.11999999731779099 range_max: 3.5 ranges: - 0.1357576549053192 - 0.13274267315864563 - 0.13491924107074738 - 0.12728963792324066 - 0.14018651843070984 - 0.12947429716587067 - 0.12550762295722961 - 0.13136516511440277 - 0.13024954497814178 - 0.11999999731779099 - 0.1615028977394104 - 0.12435409426689148 - 0.1320551633834839 - 0.1409989297389984 - 0.13507522642612457 - 0.12268535047769547 - 0.1404579132795334 - 0.13761071860790253 - 0.1503773033618927 - 0.12420032173395157 - 0.13359826803207397 - 0.11999999731779099 - 0.13831619918346405 - 0.1477203220129013 - 0.1642967164516449 - 0.12940004467964172 - 0.13067279756069183 - 0.14587172865867615 - 0.1440461277961731 - 0.13927079737186432 - 0.14637331664562225 - 0.1444903016090393 - 0.15897628664970398 - 0.13588352501392365 - 0.1636868715286255 - 0.155186265707016 - 0.14988493919372559 - 0.15125592052936554 - 0.1648588478565216 - 0.17682687938213348 - 0.18185685575008392 - 0.16568540036678314 - 0.159017413854599 - 0.174812912940979 - 0.16447405517101288 - 0.1809515804052353 - 0.18421538174152374 - 0.1739244908094406 - 0.18986830115318298 - 0.18216152489185333 - 0.21208709478378296 - 0.21196608245372772 - 0.20567473769187927 - 0.19463729858398438 - 0.23318085074424744 - 0.23568953573703766 - 0.2256600558757782 - 0.22568027675151825 - 0.2326006144285202 - 0.26731249690055847 - 0.24962016940116882 - 0.2763374149799347 - 0.273208349943161 - 0.2861330211162567 - 0.3047672212123871 - 0.30232295393943787 - 0.30729132890701294 - 0.31756049394607544 - 0.34554943442344666 - 0.34511616826057434 - 0.37451374530792236 - 0.37072256207466125 - 0.4023578464984894 - 0.4413558840751648 - 0.43559730052948 - 0.4920308589935303 - 0.5098116993904114 - 0.5451174378395081 - 0.5837374925613403 - 0.6548380255699158 - 0.6910128593444824 - 0.7842224836349487 - 0.8446397185325623 - 0.9695355296134949 - 1.1217998266220093 - 1.319140911102295 - 1.580551266670227 - 2.0140998363494873 - 2.7679007053375244 - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - .inf - '...' intensities: - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - '...' ---
ros2 topic echo /odom --- header: stamp: sec: 2868 nanosec: 167000000 frame_id: odom child_frame_id: base_footprint pose: pose: position: x: 0.0009427214987770558 y: -0.0003296974495629194 z: 0.015999687516554978 orientation: x: 3.9623270712921966e-07 y: 7.119830491485281e-06 z: -0.008208864600624864 w: 0.99996630667794 covariance: - 1.0e-05 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 1.0e-05 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 1000000000000.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 1000000000000.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 1000000000000.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.001 twist: twist: linear: x: -6.883061792922824e-07 y: -1.2410642423866674e-07 z: 0.0 angular: x: 0.0 y: 0.0 z: -6.180685727256352e-06 covariance: - 1.0e-05 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 1.0e-05 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 1000000000000.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 1000000000000.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 1000000000000.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.001 ---
-
-
-
@319276657 兄弟解决了吗,我现在也报[occupancy_grid_node]: submap_slices and last_frame_id is empty,方便讲一下你是怎么解决的吗?感谢