投放装置控制原理:
飞机中心分电板上搭载一块 ATmega328P 芯片(后称下位机)与 CH340 USB转串口芯片。其中 ATmega328P 芯片的5、6、9、10、3号引脚分别连接1到5号PWM舵机控制口的信号线,串口芯片与分电板内置USBHUB相连,作为USB从设备。
使用飞机中心分电板中引出的USB-A接头连接上位机(即机载电脑),此时上位机可通过串口(在上位机中/dev/ttyUSB0)与下位机通信。

上位机与下位机通过rosserial库实现使用ros话题互相通信。
投放装置驱动launch文件解析:
<?xml version="1.0"?><launch> <!-- Servo angle parameters --> <arg name="back_right_open_angle" default="180"/> <arg name="back_right_close_angle" default="30"/> <arg name="back_left_open_angle" default="0"/> <arg name="back_left_close_angle" default="149"/> <arg name="front_right_open_angle" default="0"/> <arg name="front_right_close_angle" default="149"/> <arg name="front_left_open_angle" default="180"/> <arg name="front_left_close_angle" default="30"/> <!-- Serial connection to Arduino --> <node pkg="rosserial_python" type="serial_node.py" name="serial_node" required="true"> <param name="port" value="/dev/ttyUSB0"/> <param name="baud" value="57600"/> </node> <node pkg="tutorial_catapult" type="catapult_driver" name="catapult_driver" output="screen"> <param name="back_right_open_angle" value="$(arg back_right_open_angle)"/> <param name="back_right_close_angle" value="$(arg back_right_close_angle)"/> <param name="back_left_open_angle" value="$(arg back_left_open_angle)"/> <param name="back_left_close_angle" value="$(arg back_left_close_angle)"/> <param name="front_right_open_angle" value="$(arg front_right_open_angle)"/> <param name="front_right_close_angle" value="$(arg front_right_close_angle)"/> <param name="front_left_open_angle" value="$(arg front_left_open_angle)"/> <param name="front_left_close_angle" value="$(arg front_left_close_angle)"/> </node></launch>
参数解读:
- back_right_open_angle:右后仓门开启角度,默认为180度
- back_right_close_angle:右后仓门关闭角度,默认为30度
- back_left_open_angle:左后仓门开启角度,默认为0度
- back_left_close_angle:左后仓门关闭角度,默认为149度
- front_right_open_angle:右前仓门开启角度,默认为0度
- front_right_close_angle:右前仓门关闭角度,默认为149度
- front_left_open_angle:左前仓门开启角度,默认为180度
- front_left_close_angle:左前仓门关闭角度,默认为30度
节点解读: 在启动serial_node节点后,该节点发布控制仓门角度的节点;启动catapult_driver节点后,节点将仓门角度二次包装,发布控制仓门开关的节点,将角度控制细节隐藏。
下位机固件烧录方法:
- 在电脑中(后称烧录机)下载
Arduino IDE(Windows、Linux、macOS均支持,但飞机上位机无法安装)并安装 - 安装
rosserial 0.7.9库

- 将上位机系统中
/home/jetson/catkin_ws/src/tutorials/tutorial_catapult/catapult_firmware目录拷贝到烧录机中,使用Arduino IDE打开其中catapult_firmware.ino文件 - 将飞机中心分电板中引出的USB-A接口插入烧录机

- 在左上角选择对应串口,如不确定是哪个,可先点开下拉框,并插拔USB-A接头,查看哪个选项为新出现的接口(如果是Windows,可能会出现2个COM口,选择编号大的那个)

- 选择单片机型号为
Arduino Uno

- 点击上传按钮,上传程序到下位机

- 右下角出现上传完成的提示框则烧录完成
