无人艇开发从入门到入土(1)——动力系统开发

本章将讲解无人艇动力系统的开发,目的是实现无人艇的双模控制,即使其具有自主控制功能和RC遥控控制功能。我将按硬件介绍、arduino代码实现、硬件组装以及开发过程中遇到的问题展开。

1、硬件介绍

ddbc89c6889b3991786a65fc8f9c68c1

5200mah动力电池

电池两根红黑粗线为电池供电口,接口型号是XT60,电池细线为充电口,工作时电池充电口也可以回传电压。

37d9dabf96a305cafadac7f66881ab96

arduino mega2560

下位机我采用arduino mega2560,arduino相比于stm32开发更加简单高效,且拥有庞大的功能库,对于短时间内无人艇开发来说,mega2560是不二之选。

cd59c2404e9e7d9e8043b0b2d8a5dec6

一对t60无刷电机和电调

电调左边两根粗线是供电线,红色接正极黑色接负极,左边引出的并排三根细线为信号线,其中黑线为接地线(通常接arduino的GND端口),红线为5v供电线(通常不接),白线/黄线为PWM信号线(通常接arduino的PWM输出端口)。

cda8a29254db3510c462b52d34348a15

RC遥控器
为实现手动远程控制功能,采用hotrc的HT-10A遥控器,遥控距离约为300m。

2、arduino代码实现

(1)自主控制功能

为了实现电脑ROS端发布话题控制下位机arduino,需要用到rosserial功能包,rosserial功能包安装方法如下:

1.打开终端,输入sudo apt install ros-noetic-rosserial-arduino ros-noetic-rosserial,安装rosserial功能包。
2.输入rospack find rosserial_arduino检查系统能否定位到rosserial功能包,如果返回了类似/opt/ros/noetic/share/rosserial_arduino的路径,说明rosserial功能包已经安装就绪。
3.输入指令cd /home/rosnoetic/Arduino/libraries进入arduino库目录,利用rm -rf ros_lib指令删除旧的ros_lib文件夹,再输入rosrun rosserial_arduino make_libraries.py .指令,运行生成脚本。

rosserial功能包安装好后,现在要实现下位机arduino与上位机电脑端ROS之间实现交互功能,以下代码为ROS、arduino之间交互测试代码:
arduino端订阅/test_arduino话题,并将订阅信息打包为/chatter话题再发送回电脑端ROS
arduino端代码:

#include <ros.h>
#include <std_msgs/String.h>

ros::NodeHandle nh;//设置节点管家nh
std_msgs::String str_msg;//定义String类对象 str_msg
ros::Publisher chatter("chatter",&str_msg);//设置发布者chatter,发布话题为/chatter

void StringCallBack(const std_msgs::String& msg){//定义回调函数StringCallBack
  str_msg.data = msg.data;
  chatter.publish(&str_msg);
}
ros::Subscriber<std_msgs::String> sub("/test_arduino",&StringCallBack);//设置订阅者sub

void setup() {
  nh.initNode();//节点初始化
  nh.advertise(chatter);//管家nh分配给chatter发布功能
  nh.subscribe(sub);//管家nh分配给sub订阅功能
}

void loop() {
  nh.spinOnce();//运行回调函数
}

电脑ROS端以20hz的频率发布/test_arduino话题,话题内容为"hello arduino!"
电脑ROS端代码:

import rospy
from std_msgs.msg import String

if __name__ == "__main__":
    rospy.init_node("test_arduino")
    pub_str = rospy.Publisher("/test_arduino",String,queue_size = 10)
    rate = rospy.Rate(20)
    while not rospy.is_shutdown():
        msg = String()
        msg.data = "hello arduino!"
        pub_str.publish(msg)
        rate.sleep()

在调试前先要知道linux系统是否识别到了USB接口,输入ls /dev/ttyUSB*,如果有返回USB接口号,说明linux已经识别到了USB接口,如果没有识别到,需要通过指令sudo usermod -aG dialout $USER,将当前用户添加到dialout组来获得USB访问权限。
将代码烧录给arduino并运行ROS端代码发布话题后,打开终端,输入rosrun rosserial_python serial_node.py,运行rosserial功能包,此时调用rostopic list指令,返回如下结果:
image
可以看见ros发布的话题/test_arduino和arduino发布的话题/chatter
输入rostopic echo /chatter,结果如下:
image
可见arduino订阅了/test_arduino并发布了/chatter话题

(2)RC遥控功能

以下代码添加了手动控制模式,并定义了21端口为模式切换端口,通过手柄拨杆即可实现在自主模式和手动模式下的切换:

#include <ros.h>
#include <geometry_msgs/Twist.h>
#include <Servo.h>

ros::NodeHandle nh;

// 电机对象
Servo leftESC;
Servo rightESC;

// 引脚定义
const int leftEscPin = 9;
const int rightEscPin = 10;
const int ch1Pin = 2;  // 转向
const int ch2Pin = 3;  // 油门
const int ch3Pin = 21; // 模式切换

// 常量定义
const int NEUTRAL = 1500;
const int MIN_PWM = 1200;
const int MAX_PWM = 1800;

// ==========================================
// 中断相关变量 (必须使用 volatile)
// ==========================================
volatile unsigned long ch1_start = 0;
volatile int ch1_val = NEUTRAL;

volatile unsigned long ch2_start = 0;
volatile int ch2_val = NEUTRAL;

volatile unsigned long ch3_start = 0;
volatile int ch3_val = 1000; // 默认 ROS 模式

// ROS 变量
float ros_x = 0;
float ros_z = 0;

// ROS 回调
void roverCallBack(const geometry_msgs::Twist& cmd_msg) {
  ros_x = cmd_msg.linear.x;
  ros_z = cmd_msg.angular.z;
}

ros::Subscriber<geometry_msgs::Twist> sub("cmd_vel", &roverCallBack);

// ==========================================
// 中断服务程序 (ISR)
// ==========================================
void ch1_isp() {
  if (digitalRead(ch1Pin) == HIGH) ch1_start = micros();
  else ch1_val = micros() - ch1_start;
}

void ch2_isp() {
  if (digitalRead(ch2Pin) == HIGH) ch2_start = micros();
  else ch2_val = micros() - ch2_start;
}

void ch3_isp() {
  if (digitalRead(ch3Pin) == HIGH) ch3_start = micros();
  else ch3_val = micros() - ch3_start;
}

void setup() {
  nh.getHardware()->setBaud(57600);
  nh.initNode();
  nh.subscribe(sub);

  leftESC.attach(leftEscPin);
  rightESC.attach(rightEscPin);

  // 配置中断:CHANGE 模式下电平变化即触发
  pinMode(ch1Pin, INPUT_PULLUP);
  pinMode(ch2Pin, INPUT_PULLUP);
  pinMode(ch3Pin, INPUT_PULLUP);
  
  attachInterrupt(digitalPinToInterrupt(ch1Pin), ch1_isp, CHANGE);
  attachInterrupt(digitalPinToInterrupt(ch2Pin), ch2_isp, CHANGE);
  attachInterrupt(digitalPinToInterrupt(ch3Pin), ch3_isp, CHANGE);

  // 解锁电调
  leftESC.writeMicroseconds(NEUTRAL);
  rightESC.writeMicroseconds(NEUTRAL);
  delay(4000);
}

void loop() {
  int finalLeftPWM, finalRightPWM;

  // 根据 CH3 脉宽判断模式
  if (ch3_val > 1500) {
    // ------------------------------------------
    // RC 模式逻辑
    // ------------------------------------------
    int throttleOffset = ch2_val - NEUTRAL;
    int steerOffset    = ch1_val - NEUTRAL;

    finalLeftPWM  = NEUTRAL + throttleOffset - steerOffset;
    finalRightPWM = NEUTRAL + throttleOffset + steerOffset;
  } 
  else {
    // ------------------------------------------
    // ROS 模式逻辑
    // ------------------------------------------
    nh.spinOnce();
    
    float leftRaw  = (ros_x * 400.0) - (ros_z * 100.0);
    float rightRaw = (ros_x * 400.0) + (ros_z * 100.0);
    
    finalLeftPWM  = NEUTRAL + (int)leftRaw;
    finalRightPWM = NEUTRAL + (int)rightRaw;
  }

  // 统一限速 1200-1800 并输出
  finalLeftPWM  = constrain(finalLeftPWM, MIN_PWM, MAX_PWM);
  finalRightPWM = constrain(finalRightPWM, MIN_PWM, MAX_PWM);

  leftESC.writeMicroseconds(finalLeftPWM);
  rightESC.writeMicroseconds(finalRightPWM);

  delay(10); // 适当延迟防止频率过高
}

3、硬件组装

在接线前需要了解arduino板各个接口功能,arduino mega2560板接口示意图如下:
1c4b47acb6cf972bd3721e4d6e3c1d7d
根据第二章展示的代码,两个电调的信号线分别接9、10端口,黑色接地线接到arduino的GND端。

RC遥控接收器如图所示:
e3d1d07c56cad55c3d8f716ed7167971

根据第二章给出的手动模式代码,转向控制从RC遥控接收器的4端口引出,并接入到arduino具有中断功能的2端口;同样油门控制从RC遥控接收器的3端口引出,并接入到arduino具有中断功能的3端口;模式切换控制从RC遥控接收器的7端口引出,并接入到arduino的21端口,RC接收器的供电由arduino的5v供电口供电;电压回传线从RC接收器引出接到动力电池的充电口。

完整的接线图如下:
4b483e3267ef8ad3e79dc7189862eb92

823b90fe8fa46f4d3cd80023a134bf88


4、开发过程中遇到的问题

(1)ROS和arduino通信之前需要关闭arduino IDE的串口监视器:

在进行调试的时候,rosserial和串口监视器不能同时开启,否则串口监视器会占用串口,导致报错:[ERROR] [1768632441.316437]: Error opening serial: [Errno 16] could not open port /dev/ttyUSB0: [Errno 16] Device or resource busy: '/dev/ttyUSB0'

(2)电调在第一次使用时要进行油门校准,否则对应输出的转速会不准确

(3)不要在arduino IDE的库管理器中直接下载rosserial功能包,要通过ROS终端生成

posted @ 2026-01-19 17:24  LanBing_He  阅读(13)  评论(1)    收藏  举报