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

    启动gazebo仿真环境后,rviz2中model的左右车轮link报错

    已定时 已固定 已锁定 已移动 未解决
    综合问题
    gazebo rviz2 ros2
    3
    9
    610
    正在加载更多帖子
    • 从旧到新
    • 从新到旧
    • 最多赞同
    回复
    • 在新帖中回复
    登录后回复
    此主题已被删除。只有拥有主题管理权限的用户可以查看。
    • 9273485819
      x
      最后由 编辑

      w341-tyadn2-vn1c75f.png
      @小鱼

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

        @927348581 给一下你的所有配置


        @小鱼 在 提问前必看!一定要看!必须看一下! 中说:

        问题一定要描述清楚,终端打印一定复制粘贴,方便回答者检索和引用(你可以在linux系统上打开浏览器进社区)
        基本的Markdown语法一定要学习下,有的小伙伴图片代码一团糟
        提问时一定要提供尽可能多的信息(系统版本,ROS版本,前后操作,终端日志),包括你的目的,比如你其实想装装某个库遇到问题,不要只说这个问题,因为可能有更好的替代方案
        先搜索再提问,很多问题其实都有解决方案,确保你自己对自己的问题有一定了解再提问
        尽量一句话说完,不要把社区当微信聊天一样用,每一个回复都尽量提供更多的的信息。

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

        9273485819 2 条回复 最后回复 回复 引用 0
        • 9273485819
          x @小鱼
          最后由 编辑

          @小鱼
          这是urdf文件
          <?xml version="1.0"?>
          <robot name="fishbot">

          <!-- 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="yellow">
                      <color rgba="0.8 0.6 0.2 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="yellow">
                      <color rgba="0.8 0.6 0.2 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>
          
          <!-- 雷达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>
          
          <!-- 雷达与地盘的关节 -->
          <joint name="laser_joint" type="fixed">
              <parent link="base_link" />
              <child link="laser_link" />
              <origin xyz="0 0 0.075" />
          </joint>
          <!-- 传感器link -->
          <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 -->
          <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">
              <!-- mu 摩擦力 -->
              <mu1 value="0.0" />
              <mu2 value="0.0" />
              <!-- kp kd 刚性系数 -->
              <kp value="1000000.0" />
              <kd value="10.0" />
              <!-- <fdir1 value="0 0 1"/> -->
          </gazebo>
          
          
          <gazebo>
              <!-- plugin -插件 -->
              <plugin name='diff_drive' filename='libgazebo_ros_diff_drive.so'>
                  <!-- ros相关配置 -->
                  <ros>
                      <namespace>/</namespace>
                      <!-- 话题重映射 -->
                      <remapping>cmd_vel:=cmd_vel</remapping>
                      <remapping>odom:=odom</remapping>
                  </ros>
                  <!-- 数据更新速率 -->
                  <update_rate>30</update_rate>
                  <!-- 车轮关节名称 -->
                  <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>
                  <!-- 是否发布里程计的tf开关 -->
                  <publish_odom_tf>true</publish_odom_tf>
                  <!-- 是否发布车轮的tf数据开关 -->
                  <publish_wheel_tf>false</publish_wheel_tf>
                  <!-- 里程计的framed ID,最终体现在话题和TF上 -->
                  <odometry_frame>odom</odometry_frame>
                  <odometry_topic>odom</odometry_topic>
                  <!-- 机器人的基础frame的ID -->
                  <robot_base_frame>base_footprint</robot_base_frame>
              </plugin>
          
              <plugin name="fishbot_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中的传感器连接到连杆link中 -->
          <gazebo reference="imu_link">
              <!-- sensor 传感器 -->
              <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>
                  <!-- 雷达的joint中位置的设置值 位姿信息-->
                  <pose>0 0 0.075 0 0 0</pose>
                  <ray>
                      <!-- 扫描属性 -->
                      <scan>
                          <!-- 水平位置 -->
                          <horizontal>
                              <!-- 采样数量 雷达旋转一周发射360道射线 -->
                              <samples>360</samples>
                              <resolution>1</resolution>
                              <!-- 雷达采样范围 一圈6.28个弧度-->
                              <min_angle>0.000000</min_angle>
                              <max_angle>6.280000</max_angle>
                          </horizontal>
                      </scan>
                      <!-- 雷达扫描范围 -->
                      <range> <!-- 0.12m ~ 0.35m  应该是半径-->
                          <min>0.120000</min>
                          <max>10</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>

          这是launch文件

          import os
          from launch import LaunchDescription
          from launch.actions import ExecuteProcess
          from launch_ros.actions import Node
          from launch_ros.substitutions import FindPackageShare
          from ament_index_python.packages import get_package_share_directory

          def generate_launch_description():
          robot_name_in_model = 'fishbot'

          ld = LaunchDescription()
          
          urdf_model_path = os.path.join(get_package_share_directory("gazebo_exercise"),"urdf","urdf","demo02_gazebo.launch.urdf")   
          #加载gazebo的world文件 -- 在终端启动gazebo后面直接加上world的路径
          gazebo_world_path = os.path.join(get_package_share_directory("gazebo_exercise"),"world","box_house.world") 
          
          # 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')
              
          # 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='both')
          
          # 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',
              executable='joint_state_publisher',
              name='joint_state_publisher',
              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
          

          gazebo仿真环境小车没有问题,但是rviz2中出现车轮报错问题

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

            @小鱼 1692674679163.png 1692674696105.png

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

              @927348581 在 启动gazebo仿真环境后,rviz2中model的左右车轮link报错 中说:

                  <!-- 是否发布车轮的tf数据开关 -->
                  <publish_wheel_tf>false</publish_wheel_tf>
              

              这里改成true

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

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

                @小鱼 改了之后没有效果,还是一样报错

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

                  @927348581 重新编译,然后看看tf

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

                  S 1 条回复 最后回复 回复 引用 0
                  • S
                    sxjklgl
                    最后由 编辑

                    此回复已被删除!
                    1 条回复 最后回复 回复 引用 0
                    • S
                      sxjklgl @小鱼
                      最后由 编辑

                      @小鱼 我也有同样的问题,按照历史记录的提示修改,也是同样的报错,请再给出些修改思路,谢谢

                      1 条回复 最后回复 回复 引用 0
                      • 第一个帖子
                        最后一个帖子
                      皖ICP备16016415号-7
                      Powered by NodeBB | 鱼香ROS