本教程为https://blog.csdn.net/2301_81924597/article/details/141757091?spm=1001.2014.3001.5501的进一步拓展
ROS 2 与 Arduino 通信指南
准备工作
- 确保已安装 ROS 2(本指南基于 ROS 2 Humble)
- 确保已安装 Arduino IDE 并能正常使用
- 安装必要的 ROS 2 包:
sudo apt install ros-humble-serial-driver
Arduino 端设置
- 打开 Arduino IDE,创建新项目
- 将以下代码复制到 Arduino IDE 中:
#include <Arduino.h>
void printMenu() {
Serial.println("\n--- Arduino Menu ---");
Serial.println("1. Say Hello");
Serial.println("2. Get Arduino Uptime");
Serial.println("3. Blink LED");
Serial.println("Enter your choice:");
}
void setup() {
Serial.begin(9600);
while (!Serial) {
; // Wait for serial port to connect (needed for native USB port only)
}
delay(1000); // 添加一个短暂的延迟
Serial.println("Arduino ready for communication!");
pinMode(LED_BUILTIN, OUTPUT);
printMenu();
}
void loop() {
if (Serial.available() > 0) {
char choice = Serial.read();
// Clear the serial buffer
while(Serial.available() > 0) {
Serial.read();
}
switch(choice) {
case '1':
Serial.println("Hello from Arduino!");
break;
case '2':
Serial.print("Arduino uptime: ");
Serial.print(millis() / 1000);
Serial.println(" seconds");
break;
case '3':
Serial.println("Blinking LED 3 times...");
for(int i = 0; i < 3; i++) {
digitalWrite(LED_BUILTIN, HIGH);
delay(500);
digitalWrite(LED_BUILTIN, LOW);
delay(500);
}
Serial.println("Blinking complete!");
break;
default:
Serial.println("Invalid choice. Please try again.");
}
printMenu();
}
}
- 将代码上传到 Arduino
ROS 2 端设置
-
创建一个新的 ROS 2 包(如果还没有):
mkdir ros2_ws/src/arduino_communication cd ros2_ws/src/arduino_communication ros2 pkg create --build-type ament_cmake arduino_communication
-
在
arduino_communication
包中创建src/arduino_serial_node.cpp
文件,并添加以下代码:
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>
#include <serial_driver/serial_driver.hpp>
#include <vector>
#include <string>
using drivers::serial_driver::SerialDriver;
using drivers::serial_driver::SerialPortConfig;
using drivers::common::IoContext;
class ArduinoSerialNode : public rclcpp::Node {
public:
ArduinoSerialNode()
: Node("arduino_serial_node")
{
// 创建 IoContext
io_context_ = std::make_shared<IoContext>(1);
// 创建 SerialPortConfig
auto device_config = std::make_shared<SerialPortConfig>(
9600,
drivers::serial_driver::FlowControl::NONE,
drivers::serial_driver::Parity::NONE,
drivers::serial_driver::StopBits::ONE
);
// 创建 SerialDriver
serial_driver_ = std::make_unique<SerialDriver>(*io_context_);
// 打开串口
try {
serial_driver_->init_port("/dev/ttyACM0", *device_config);
serial_driver_->port()->open();
RCLCPP_INFO(this->get_logger(), "Serial port opened successfully");
} catch (const std::exception &ex) {
RCLCPP_ERROR(this->get_logger(), "Error opening serial port: %s", ex.what());
return;
}
// 创建定时器和发布者
timer_ = this->create_wall_timer(
std::chrono::milliseconds(100),
std::bind(&ArduinoSerialNode::timer_callback, this));
publisher_ = this->create_publisher<std_msgs::msg::String>("arduino_data", 10);
}
private:
void timer_callback() {
std::vector<uint8_t> buffer(256);
size_t bytes_read = 0;
try {
bytes_read = serial_driver_->port()->receive(buffer);
} catch (const std::exception &ex) {
RCLCPP_ERROR(this->get_logger(), "Error reading from serial port: %s", ex.what());
return;
}
if (bytes_read > 0) {
std::string data(buffer.begin(), buffer.begin() + bytes_read);
process_and_publish_data(data);
}
}
void process_and_publish_data(const std::string& data) {
static std::string buffer;
buffer += data;
size_t pos;
while ((pos = buffer.find('\n')) != std::string::npos) {
std::string line = buffer.substr(0, pos);
buffer.erase(0, pos + 1);
if (line.find("Arduino ready for communication!") != std::string::npos ||
line.find("Hello from Arduino!") != std::string::npos ||
line.find("Arduino uptime:") != std::string::npos ||
line.find("Blinking LED") != std::string::npos ||
line.find("Blinking complete!") != std::string::npos ||
line.find("Invalid choice") != std::string::npos) {
auto message = std_msgs::msg::String();
message.data = line;
publisher_->publish(message);
RCLCPP_INFO(this->get_logger(), "Published data: %s", line.c_str());
}
}
}
std::shared_ptr<IoContext> io_context_;
std::unique_ptr<SerialDriver> serial_driver_;
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
};
int main(int argc, char *argv[]) {
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<ArduinoSerialNode>());
rclcpp::shutdown();
return 0;
}
- 修改
CMakeLists.txt
文件,添加以下内容:
cmake_minimum_required(VERSION 3.5)
project(arduino_communication)
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(serial_driver REQUIRED)
add_executable(arduino_serial_node src/arduino_serial_node.cpp)
ament_target_dependencies(arduino_serial_node rclcpp std_msgs serial_driver)
install(TARGETS
arduino_serial_node
DESTINATION lib/${PROJECT_NAME})
ament_package()
- 修改
package.xml
文件,添加以下依赖项:
<package format="3">
<name>arduino_communication</name>
<version>0.0.0</version>
<description>ROS 2 package for communicating with Arduino</description>
<maintainer email="you@example.com">Your Name</maintainer>
<license>Apache-2.0</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>rclcpp</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>serial_driver</build_depend>
<exec_depend>rclcpp</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>serial_driver</exec_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>
- 构建并安装包:
cd ~/文档/PlatformIO/Projects/arduino_ros2_communicate/ros2_ws
colcon build --symlink-install
source install/setup.bash
- 运行节点:
在运行节点之前,需要 source
ROS 2 和工作空间的环境设置:
source /opt/ros/humble/setup.bash
source ~/文档/PlatformIO/Projects/arduino_ros2_communicate/ros2_ws/install/setup.bash
ros2 run arduino_communication arduino_serial_node
- 在另一个终端中,查看从 Arduino 发布的数据:
source /opt/ros/humble/setup.bash
source ~/文档/PlatformIO/Projects/arduino_ros2_communicate/ros2_ws/install/setup.bash
ros2 topic echo /arduino_data
运行成功的话,可以看到 Arduino 发送的数据。
故障排除
重新编译和运行
-
导航到工作空间目录:
cd ~/文档/PlatformIO/Projects/arduino_ros2_communicate/ros2_ws
-
清理之前的构建并重新编译包:
colcon build --symlink-install --cmake-clean-cache
-
如果上述命令失败,尝试只构建 arduino_communication 包:
colcon build --symlink-install --packages-select arduino_communication
-
重新加载环境:
source /opt/ros/humble/setup.bash source ~/文档/PlatformIO/Projects/arduino_ros2_communicate/ros2_ws/install/setup.bash
-
运行节点:
ros2 run arduino_communication arduino_serial_node
通过以上步骤,你应该能够成功实现 ROS 2 与 Arduino 的通信。如果仍然遇到问题,请检查代码中的错误并确保所有依赖都已正确安装。