目录
报错:关节设置为 revolute 缺少 limit 属性
- revolute 表示是有限制的旋转,需要设置limit属性进行约束
- continuous 表示无限制的旋转
- fixed 表示固定
[robot state publisher-3] Error:Joint [left front orient joint] is of type REVOLUTE but it does not specify limits
解决方法
找到描述车子的xacro文件进行修改,添加 limit 属性设置即可
轮子转向左右相反
轮子在控制过程中按左会显示向右转弯
解决方法
找到描述车子的xacro文件进行修改,修改车轮旋转轴的方向即可,原本是0 0 -1
,需要修改成0 0 1
rviz2只显示一次雷达数据,刷新后消失
就在启动的 gazebo 仿真的时候,雷达数据会显示,点击 rviz2 左下角的 reset 后雷达数据消失,这个会影响我进行cartgrapher建图
解决方法
找到描述雷达的xacro文件进行修改,我这里采样的雷达是3D雷达
原因: 缺少声明 <frame_name>
修改2D雷达为3D雷达
参考链接:gazebo_sensor
2d 雷达
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="laser">
<xacro:macro name="rplidar" params="prefix:=laser">
<!-- Create laser reference frame -->
<link name="${prefix}_link">
<inertial>
<mass value="0.1" />
<origin xyz="0 0 0" />
<inertia ixx="0.01" ixy="0.0" ixz="0.0"
iyy="0.01" iyz="0.0"
izz="0.01" />
</inertial>
<visual>
<origin xyz=" 0 0 0 " rpy="0 0 0" />
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
<geometry>
<cylinder length="0.06" radius="0.05"/>
</geometry>
</collision>
</link>
<gazebo reference="${prefix}_link">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="${prefix}_link">
<sensor type="ray" name="rplidar">
<!-- <visualize>true</visualize> -->
<update_rate>20</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1</resolution>
<min_angle>-3</min_angle>
<max_angle>3</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</min>
<max>30.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_rplidar" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace>/</namespace>
<remapping>~/out:=scan</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>
3D 雷达
- 修改 sensor 的类型
ray
>>gpu_lidar
- 在
<scan>
下增加<vertical>
属性设置,意思是垂直方向的射线 - 注意这个
min_angle
角度范围采用的是弧度制 - 注意这里的
<horizontal>
和<vertical>
属性的<sample>
和<resolution>
设置- samples:是每个完整激光扫描周期生成的模拟激光雷达射线的数量(样本数量)。
- resolution:该数字乘以样本以确定数据点的数量范围。(这个数字越大点越密集)
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="laser">
<xacro:macro name="rplidar" params="prefix:=laser">
<!-- Create laser reference frame -->
<link name="${prefix}_link">
<inertial>
<mass value="0.1" />
<origin xyz="0 0 0" />
<inertia ixx="0.01" ixy="0.0" ixz="0.0"
iyy="0.01" iyz="0.0"
izz="0.01" />
</inertial>
<visual>
<origin xyz=" 0 0 0 " rpy="0 0 0" />
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
<geometry>
<cylinder length="0.06" radius="0.05"/>
</geometry>
</collision>
</link>
<gazebo reference="${prefix}_link">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="${prefix}_link">
<sensor type="gpu_lidar" name="rplidar">
<visualize>false</visualize>
<always_on>true</always_on>
<update_rate>10</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<!-- 水平方向上360个样本,分辨率表示一个样本处的细分 -->
<resolution>1</resolution>
<min_angle>0.0</min_angle>
<max_angle>6.28</max_angle>
</horizontal>
<vertical>
<samples>16</samples>
<resolution>1</resolution>
<min_angle>-0.17</min_angle>
<max_angle>0.17</max_angle>
</vertical>
</scan>
<range>
<min>0.30</min>
<max>200.0</max>
<resolution>0.03</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_rplidar" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace>/</namespace>
<remapping>~/out:=scan</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>laser_link</frame_name>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>