鱼香ROS社区
    • 版块
    • 最新
    • 未解决
    • 已解决
    • 群组
    • 注册
    • 登录
    紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
    提问前必看的发帖注意事项: 社区问答规则(小鱼个人)更新 | 高质量帖子发布指南

    rviz2中不显示代价地图

    已定时 已固定 已锁定 已移动
    ROS 2相关问题
    rviz2 nav2 代价地图
    2
    5
    1.6k
    正在加载更多帖子
    • 从旧到新
    • 从新到旧
    • 最多赞同
    回复
    • 在新帖中回复
    登录后回复
    此主题已被删除。只有拥有主题管理权限的用户可以查看。
    • slxS
      slx
      最后由 slx 编辑

      ros2 galactic仿真导航时,rviz中不显示代价地图

      • ROS版本:ROS2 galactic
      • 导航包:nav2
        按照动手学ros2第11章第三节 (使用FishBot进行自主导航) 配置好后,rviz中能显示地图,也能导航,但是通过 “by/topic” 方式添加代价地图话题,提示 Warning "No map received",不能显示代价地图, 这是为什么啊?

      这是launch文件

      
      import os
      from ament_index_python.packages import get_package_share_directory
      from launch import LaunchDescription
      from launch.actions import IncludeLaunchDescription
      from launch.launch_description_sources import PythonLaunchDescriptionSource
      from launch.substitutions import LaunchConfiguration
      from launch_ros.actions import Node
      
      
      def generate_launch_description():
          #=============================1.定位到包的地址=============================================================
          fishbot_navigation2_dir = get_package_share_directory('robot_navigation2')
          nav2_bringup_dir = get_package_share_directory('nav2_bringup')
          
          
          #=============================2.声明参数,获取配置文件路径===================================================
          # use_sim_time 这里要设置成true,因为gazebo是仿真环境,其时间是通过/clock话题获取,而不是系统时间
          use_sim_time = LaunchConfiguration('use_sim_time', default='true') 
          map_yaml_path = LaunchConfiguration('map',default=os.path.join(fishbot_navigation2_dir,'maps','fishbot_map.yaml'))
          nav2_param_path = LaunchConfiguration('params_file',default=os.path.join(fishbot_navigation2_dir,'param','robot_nav2_params.yaml'))
          rviz_config_dir = os.path.join(nav2_bringup_dir,'rviz','nav2_default_view.rviz')
      
          #=============================3.声明启动launch文件,传入:地图路径、是否使用仿真时间以及nav2参数文件==============
          nav2_bringup_launch = IncludeLaunchDescription(
                  PythonLaunchDescriptionSource([nav2_bringup_dir,'/launch','/bringup_launch.py']),
                  launch_arguments={
                      'map': map_yaml_path,
                      'use_sim_time': use_sim_time,
                      'params_file': nav2_param_path}.items(),
              )
          rviz_node =  Node(
                  package='rviz2',
                  executable='rviz2',
                  name='rviz2',
                  arguments=['-d', rviz_config_dir],
                  parameters=[{'use_sim_time': use_sim_time}],
                  output='screen')
          
          return LaunchDescription([nav2_bringup_launch,rviz_node])
      
      

      20220805160127.png

      小鱼小 1 条回复 最后回复 回复 引用 0
      • 小鱼小
        小鱼 技术大佬 @slx
        最后由 编辑

        @slx 这个问题大概出在了数据来源端,仿真来说就是gazebo这一块,所以需要你贴下启动gazebo的launch文件,另外你的代码是直接下载的fishbot源码还是从教程中复制粘贴下来的?

        新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

        slxS 1 条回复 最后回复 回复 引用 0
        • slxS
          slx @小鱼
          最后由 slx 编辑

          @小鱼
          代码是复制粘贴的,我自己也做了改动

          这是gazebo的启动launch

          
          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 = 'my_robot'
              package_name = 'robot_urdf'
              urdf_name = "my_robot.urdf"
              rviz_name = "my.rviz"
              world_name = "fishbot.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}')
              default_rviz_config_path = os.path.join(pkg_share, f'rviz/{rviz_name}')
          
              # Start Gazebo server
              start_gazebo_cmd = ExecuteProcess(
                  cmd=['gazebo', '--verbose', '-s', 'libgazebo_ros_factory.so', gazebo_world_path],
                  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]
              )
              # joint_state_publisher_node = Node(
              #     package='joint_state_publisher_gui',
              #     executable='joint_state_publisher_gui',
              #     name='joint_state_publisher_gui',
              #     arguments=[urdf_model_path]
              # )
          
              # Launch RViz
              start_rviz_cmd = Node(
                  package='rviz2',
                  executable='rviz2',
                  name='rviz2',
                  output='screen',
                  arguments=['-d', default_rviz_config_path]
                  )
          
              ld.add_action(start_gazebo_cmd)
              ld.add_action(spawn_entity_cmd)
              ld.add_action(start_robot_state_publisher_cmd)
              # ld.add_action(joint_state_publisher_node)
              # ld.add_action(start_rviz_cmd)
          
          
              return ld
          
          小鱼小 1 条回复 最后回复 回复 引用 0
          • 小鱼小
            小鱼 技术大佬 @slx
            最后由 编辑

            @slx 在 rviz2中不显示代价地图 中说:

            cmd=['gazebo', '--verbose', '-s', 'libgazebo_ros_factory.so', gazebo_world_path],

            问题出在了这里,少加载了一个库,修改一下即可

            原始启动gazebo代码

              # Start Gazebo server
                start_gazebo_cmd = ExecuteProcess(
                    cmd=['gazebo', '--verbose', '-s', 'libgazebo_ros_factory.so', gazebo_world_path],
                    output='screen')
            

            修改后的启动gazebo代码

                # 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')
            

            新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

            1 条回复 最后回复 回复 引用 0
            • slxS
              slx
              最后由 编辑

              可以了可以了 感谢

              1 条回复 最后回复 回复 引用 0
              • 小鱼小 小鱼 从 中的 动手学ROS2 移动了该主题
              • 第一个帖子
                最后一个帖子
              皖ICP备16016415号-7
              Powered by NodeBB | 鱼香ROS