带有可旋转摄像头的移动小车(urdf+rviz)
成果图
step1:新建工作空间
mkdir -p catkin_ws/src
cd catkin_ws
catkin_make
step2:建立工作包
右键src,选择 Create Catkin Package
输入包名之后,点击回车
依次写入配置:urdf xacro
step3: 创建要用的文件夹
在urdf01_rviz文件夹下依次创建config、launch、meshes、urdf文件夹
在urdf文件夹下再创建一个urdf文件夹(保证结构的可读性)
step4:下载meshes文件夹下需要的文件
终端输入:
git clone https://github.com/zx595306686/sim_demo.git
得到以下文件
将前两个文件复制到创建的meshes文件夹下
step5:src/urdf01_rviz/urdf/urdf/camera_car_footprint.urdf
<robot name="mycar">
<link name="base_footprint">
<visual>
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</visual>
</link>
<link name="base_link">
<visual>
<geometry>
<mesh filename="package://urdf01_rviz/meshes/autolabor_mini.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="1.57 0 1.57" />
<material name="base_color">
<color rgba="1 0.5 0 1" />
</material>
</visual>
</link>
<link name="camera">
<visual>
<geometry>
<box size="0.02 0.05 0.05" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="camera_color">
<color rgba="1 0.4 0.2 1" />
</material>
</visual>
</link>
<joint name="base_link2base_footprint" type="fixed">
<parent link="base_footprint"/>
<child link="base_link" />
<origin xyz="0 0 0.05" rpy="0 0 0" />
</joint>
<joint name="camera2baselink" type="continuous">
<parent link="base_link"/>
<child link="camera" />
<origin xyz="0.11 0 0.115" rpy="0 0 0" />
<axis xyz="0 0 1" />
</joint>
</robot>
step6:src/urdf01_rviz/launch/camera_car_footprint.launch
<launch>
<!-- 在参数服务器载入 urdf 文件 -->
<!-- 设置参数 -->
<param name="robot_description" textfile="$(find urdf01_rviz)/urdf/urdf/camera_car_footprint.urdf" />
<!-- 启动 rviz -->
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find urdf01_rviz)/config/show_mycar.rviz" />
<!-- 添加关节状态发布节点(出现转速过快现象进行注释) -->
<!-- <node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" /> -->
<!-- 添加机器人状态发布节点 -->
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" />
<!-- 可选:用于控制关节运动的节点 -->
<node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui" />
</launch>
step7:在终端启动launch文件
cd catkin_ws
source ./devel/setup.bash
roslaunch urdf01_rviz camera_car_footprint.launch
rviz启动后,需要先add模型
设置joint参考的parent
step8:保存模型
保存模型至创建的config文件夹下
可取名为show_mycar.rviz
常见问题汇总
1、没有安装rviz
如果rviz没有安装,请调用如下命令自行安装:
sudo apt install ros-[ROS_DISTRO]-rviz
2、没有安装gazebo
1.添加源:
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main"
>
/etc/apt/sources.list.d/gazebo-stable.list'
wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
2.安装:
sudo apt update
sudo apt install gazebo11
sudo apt install libgazebo11-dev
3、命令行输出UnicodeEncodeError错误提示
UnicodeEncodeError: 'ascii' codec can't encode characters in position 463-464: ordinal not in range(128)
[joint_state_publisher-3] process has died [pid 4443, exit code 1, cmd /opt/ros/melodic/lib/joint_state_publisher/joint_state_publisher __name:=joint_state_publisher __log:=/home/rosmelodic/.ros/log/b38967c0-0acb-11eb-aee3-0800278ee10c/joint_state_publisher-3.log].
log file: /home/rosmelodic/.ros/log/b38967c0-0acb-11eb-aee3-0800278ee10c/joint_state_publisher-3*.log
rviz中提示坐标变换异常,导致机器人部件显示结构异常
原因:编码问题导致的
解决:去除URDF中的中文注释
4、命令行输出joint_state_publisher_gui错误提示
[ERROR] [1584370263.037038]: Could not find the GUI, install the 'joint_state_publisher_gui' package
终端执行安装指令:
sudo apt install ros-noetic-joint-state-publisher-gui
5、无法安全地用该源进行更新,所以默认禁用该源 E: 无法定位软件包
我们安装软件的时候经常会出现无法安全地用该源进行更新,所以默认禁用该源 以及 E: 无法定位软件包
依次在终端执行以下指令:
sudo apt install ros-noetic-gmapping
sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
sudo sh -c '. /etc/lsb-release && echo "deb http://mirrors.tuna.tsinghua.edu.cn/ros/ubuntu/ `lsb_release -cs` main" > /etc/apt/sources.list.d/ros-latest.list'
sudo sh -c '. /etc/lsb-release && echo "deb http://mirrors.ustc.edu.cn/ros/ubuntu/ `lsb_release -cs` main" > /etc/apt/sources.list.d/ros-latest.list'
sudo apt update
sudo apt-get install ros-melodic-joint-state-publisher-gui