目录总览

小车yolo机械臂(一)ros下gazebo搭建小车(可键盘控制)安装摄像头仿真 加载yolo检测识别标记物体

小车yolo机械臂(二)机械臂仿真 ros下从xacro模型文件搭建Moveit!+Gazebo仿真系统

小车yolo机械臂(三)ROS消息订阅监听 rospy.Subscriber 订阅监听yolo python实现订阅/darknet_ros/bounding_boxes topic

小车yolo机械臂(四)python ros 和darknet_ros 使用launch文件启动脚本

小车yolo机械臂(五)让小车在命令下运动起来 rostopic pub /cmd_vel geometry_msgs/Twist

小车yolo机械臂(六)ros gazebo 小车摄像头根据darknet_ros中yolo目标检测的信息进行自主运动

小车yolo机械臂(七)小车与机械臂融合,并控制机械臂运动 gazebo control

小车yolo机械臂(八)ros小车和机械臂gazebo仿真,机械臂根据darknet_ros中yolo检测结果来自动运动 python实现

项目下载

这一篇内容是将小车与机械臂组合在一起,涉及到很多文件的修改,我把最终的文件代码上传到了github中,是这篇文章所用到的,下载即可用。

github项目

创建小车机械臂模型

小车机械臂模型在arm_car_description文件中

我们查看arm_car_description的结构
这次采用一个命令:

tree arm_car_description

结果如下:

├── CMakeLists.txt
├── launch
│   └── view_arm_car.launch
├── package.xml
├── urdf
│   ├── arm.xacro
│   ├── camera.xacro
│   ├── car_arm.urdf.xacro
│   └── car.urdf.xacro
└── urdf.rviz

tree是Ubuntu查看目录树形结构,如果没安装,使用命令:

 sudo apt install tree

运行view_arm_car.launch文件

roslaunch marm_description fake_arm.launch

在这里插入图片描述
可以看到搭建的模型张这个样子,好丑,我都受不了了,只能以后修改了美化了,先把功能实现。

我们来把模型背后的文件,关键地方说一说。

arm_car_description/urdf/arm.xacro
这个模型我是根据之前的6轴机械臂改写的,只剩下3轴了,抓取的部分也去掉了。

    <!-- /  ARM_PLATE    // -->

        <link name="arm_plate">
	    <box_inertial_matrix m="0.1" w="${base_link_width}" h="${base_link_hight}" d="${base_link_length}" />

            <visual>
                <origin xyz=" 0 0 0 " rpy="0 0 0" />
                <geometry>
		    <box size="${base_link_length} ${base_link_width} ${base_link_hight}" />
                </geometry>
                <material name="yellow"/>
            </visual>

            <collision>
                <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
                <geometry>
		    <box size="${base_link_length} ${base_link_width} ${base_link_hight}" />
		    <!--<box_inertial_matrix m="0.1" w="${base_link_width}" h="${base_link_hight}" d="${base_link_length}" />-->
                </geometry>
            </collision>
        </link>

        <joint name="arm_plate" type="prismatic">
            <origin xyz="0.1 0 0.1" rpy="0 0 0" />
            <parent link="arm_standoff_link"/>
            <child link="arm_plate" />
	    <limit effort="1000.0" lower="-0.08" upper="0.12" velocity="0.5"/>
	    <axis xyz="0 0 1" />
	    <dynamics damping="0.7" />
        </joint>

这一部分是我新加的,一个平板,可以上下滑动,我的想法是,用机械臂推动这个平板上下滑动。

在这里插入图片描述

就是最上面那个黑色的(可上下滑动),为什么是黑色,我现在还不明白,可能和机械臂无关的,都是黑色的。

在arm_car_description/urdf/car_arm.urdf.xacro文件中,导入arm.xacro文件

xacro:include filename="$(find car_arm)/urdf/arm.xacro" />

最后即为:

<?xml version="1.0"?>

<robot name="mrobot" xmlns:xacro="http://www.ros.org/wiki/xacro">

	<!--car-->
	<xacro:include filename="$(find car_arm)/urdf/car.urdf.xacro" />
	<xacro:include filename="$(find car_arm)/urdf/camera.xacro" />
	<xacro:include filename="$(find car_arm)/urdf/arm.xacro" />

	<xacro:property name="camera_offset_x" value="0.08" />
	<xacro:property name="camera_offset_y" value="0" />
	<xacro:property name="camera_offset_z" value="0.02" />

	<!-- Body of mrobot, with plates, standoffs -->
	<mrobot_body/>

	<!-- Attach the camera -->
	<joint name="camera_joint" type="fixed">
		<origin xyz="${camera_offset_x} ${camera_offset_y} ${camera_offset_z}" rpy="0 0 0" />
		<parent link="plate_1_link"/>
		<child link="camera_link"/>
	</joint>


	<xacro:usb_camera prefix="camera"/>

</robot>

在arm_car_description/launch/ view_arm_car.launch这个文件中
是启动rviz显示小车机械臂模型:

<launch>
    <arg name="model" />
    <!-- 加载机器人模型参数 -->
    <param name="robot_description" command="$(find xacro)/xacro --inorder $(find arm_car_description)/urdf/car_arm.urdf.xacro" />

    <!-- 设置GUI参数,显示关节控制插件 -->
    <param name="use_gui" value="true"/>

    <!-- 运行joint_state_publisher节点,发布机器人的关节状态  -->
    <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
    
    <!-- 运行robot_state_publisher节点,发布tf  -->
    <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />

    <!-- 运行rviz可视化界面 -->
    <node name="rviz" pkg="rviz" type="rviz" args="-d $(find arm_car_description)/urdf.rviz" required="true" />
</launch>

gazebo中小车机械臂仿真

创建配置文件

接下来,我们创建下一个文件arm_car_gazebo
看看结构:

 tree arm_car_gazebo
arm_car_gazebo
├── CMakeLists.txt
├── config
│   └── arm_car_gazebo_control.yaml
├── launch
│   ├── arm_car_gazebo_control.launch
│   ├── arm_car_gazebo_controller.launch
│   └── arm_car_world.launch
└── package.xml

首先需要配置controller插件。Gazebo中需要用到的控制器就是
ros_control提供的joint_position_controller,配置文件
arm_car_gazebo/config/arm_car_gazebo_control.yaml的内容如下

arm:
  # Publish all joint states -----------------------------------
  joint_state_controller:
    type: joint_state_controller/JointStateController
    publish_rate: 50  
  
  # Position Controllers ---------------------------------------
  joint1_position_controller:
    type: position_controllers/JointPositionController
    joint: joint1
    pid: {p: 100.0, i: 0.01, d: 10.0}
  joint2_position_controller:
    type: position_controllers/JointPositionController
    joint: joint2
    pid: {p: 100.0, i: 0.01, d: 10.0}
  joint3_position_controller:
    type: position_controllers/JointPositionController
    joint: joint3
    pid: {p: 100.0, i: 0.01, d: 10.0}
 

这个配置文件定义了每个关节的位置控制器.
JointPositionController,并且需要将控制器绑定到具体的joint上,还设置
了每个关节控制的PID参数。另外还配置了一个joint_state_controller,用
来发布机器人每个关节的状态,类似于joint_state_publisher节点。

创建launch文件

再编写一个launch文件

arm_car_gazebo/launch/arm_car_gazebo_controller.launch,加载设置好的所有控
制器,代码如下:

<launch>

    <!-- 将关节控制器的配置参数加载到参数服务器中 -->
    <rosparam file="$(find arm_car_gazebo)/config/arm_car_gazebo_control.yaml" command="load"/>

    <!-- 加载controllers -->
    <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
          output="screen" ns="/arm" args="joint_state_controller
                                          joint1_position_controller
                                          joint2_position_controller
                                          joint3_position_controller"/>

    <!-- 运行robot_state_publisher节点,发布tf  -->
    <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
          respawn="false" output="screen">
        <remap from="/joint_states" to="/arm/joint_states" />
    </node>

</launch>

launch文件首先将配置文件中的所有参数加载到ROS参数服务器
上,然后使用controller_spawner一次性加载所有控制器,最后还要通过
robot_state_publisher节点发布机器人的状态。

再创建一个顶层launch文件
arm_car_gazebo/launch/arm_car_gazebo_control.launch,包含上面的arm_car_gazebo_controller.launch,并启动Gazebo仿真环境,代码如下:

<launch>

    <!-- 启动Gazebo  -->
    <include file="$(find arm_car_gazebo)/launch/arm_car_world.launch" />   

    <!-- 启动Gazebo controllers -->
    <include file="$(find arm_car_gazebo)/launch/arm_car_gazebo_controller.launch" />   

</launch>

其中arm_car_gazebo/launch/arm_car_world.launch就是把我们所写的小车机械臂模型导入,代码如下:

<launch>

  <!-- these are the arguments you can pass this launch file, for example paused:=true -->
  <arg name="paused" default="false"/>
  <arg name="use_sim_time" default="true"/>
  <arg name="gui" default="true"/>
  <arg name="headless" default="false"/>
  <arg name="debug" default="false"/>

  <!-- We resume the logic in empty_world.launch -->
  <include file="$(find gazebo_ros)/launch/empty_world.launch">
    <arg name="debug" value="$(arg debug)" />
    <arg name="gui" value="$(arg gui)" />
    <arg name="paused" value="$(arg paused)"/>
    <arg name="use_sim_time" value="$(arg use_sim_time)"/>
    <arg name="headless" value="$(arg headless)"/>
  </include>

  <!-- Load the URDF into the ROS Parameter Server -->
  <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find arm_car_description)/urdf/car_arm.urdf.xacro'" /> 


  <!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
  <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
	args="-urdf -model arm -param robot_description"/> 


</launch>

开始仿真

现在就可以使用如下命令启动小车机械臂仿真环境了:

roslaunch arm_car_gazebo arm_car_gazebo_control.launch

稍作等候,就可以看到
在这里插入图片描述
很丑对吧。

机械臂动起来

让机械臂运动起来,当然是发送控制运动的话题消息。使用rostopic list命令查看当前系统中的话题列表,应该可以看到如图所示的控制器订阅的控制命令话题。

rostopic list

在这里插入图片描述
其中:

/arm/joint1_position_controller/command
/arm/joint2_position_controller/command
/arm/joint3_position_controller/command
/arm/joint_states

这四个就是关于机械臂运动的话题topic
我们打印出其中一个的详细信息

rostopic info /arm/joint1_position_controller/command
Type: std_msgs/Float64

Publishers: None

Subscribers: 
 * /gazebo (http://winston-ThinkPad-T450:42105/)

可以看到话题:/arm/joint1_position_controller/command的类型是std_msgs/Float64

这些话题消息的类型都比较简单,只包含一个64位浮点数的位置指
令,所以需要让哪个轴转动,就发布相应哪个轴的消息。例如要让机器
人的joint2运动到弧度为1的位置,只需要发布以下话题消息:

 rostopic pub /arm/joint1_position_controller/command std_msgs/Float64 1.0

消息发布后,gazebo中的机械臂应该立刻就会开始运动,joint2会移
动到如图所示弧度为1的位置。
在这里插入图片描述
在这里插入图片描述

运行结果如上图,前后动作对比。
我们也可以试试操控/arm/joint2_position_controller/command
输入指令:

rostopic pub /arm/joint2_position_controller/command std_msgs/Float64 1.0

在这里插入图片描述
看上图,第二根机械臂动,但是它并没有像我所想象的那样,把最上面的平板推动,不是推动,而是穿过。这个问题后续解决。