大致学习了前面的 micro-ROS 之后,我们就可以开始动手实践了。那么我们现在就使用 micro-ROS 来让我们的小车动起来。其作用就是让我们的小车的控制器——ESP32,能够接入我们的 ROS 机器人系统,方便我们的编程和使用。
移动机器人
硬件设备
使用的移动小车,需要两个电机和一个驱动模块,驱动模块使用的是 L298N,用 PWM 来控制电机转速和方向。
配置文件
那么还是一样,我们需要在 VS Code 中的 PlatformIO 新建工程,这个在第一篇博客中就有说明。之后配置我们的 platformio.ini
配置文件,具体配置如下:
[env:featheresp32] ; 这是一个环境配置标签,指定了代码将运行的硬件平台和框架
platform = espressif32 ; 指定了使用的平台为Espressif 32
board = featheresp32 ; 指定使用的硬件板为Feather ESP32
framework = arduino ; 指定使用的框架为Arduino
board_microros_transport = wifi ; 指定使用的Micro-ROS传输方式为Wi-Fi
lib_deps = ; 列出所有依赖库的URL,这些库将被下载和安装
https://github.com/fishros/Esp32McpwmMotor.git
https://gitee.com/ohhuo/micro_ros_platformio.git
之后我们需要编写我们的代码,rclc 初始化 Node 和添加一个 Subscriber 的操作可以在上一篇博客中找到。代码使用 Esp32McpwmMotor
库初始化电机,设置 micro-ROS 通信参数以连接到 ROS2 agent,并初始化一个 ROS2 Node 和一个 Subscriber,以订阅 /cmd_vel
主题上的 Twist 类型消息。
消息格式
这是 geometry_msgs/msg/Twist
的定义,含有两个三维向量,分别表示线速度和角速度。
# This expresses velocity in free space broken into its linear and angular parts.
Vector3 linear
float64 x
float64 y
float64 z
Vector3 angular
float64 x
float64 y
float64 z
代码编写
当接收到新的 Twist 消息时,调用 twist_callback()
函数提取线性和角速度,并相应地控制电机。如果两个速度都为零,则电机停止。否则,根据方向设置电机速度。在正向方向上,速度设置为 70,在反向方向上为 -70。
loop()
函数重复调用 rclc_executor_spin_some()
来处理来自 ROS2 网络的传入数据。
#include <Arduino.h>
#include <Esp32McpwmMotor.h>
#include <Arduino.h>
#include <micro_ros_platformio.h>
#include <WiFi.h>
#include <rcl/rcl.h>
#include <rclc/rclc.h>
#include <rclc/executor.h>
#include <geometry_msgs/msg/twist.h>
// 定义 ROS2 执行器和支持结构
rclc_executor_t executor;
rclc_support_t support;
// 定义 ROS2 内存分配器
rcl_allocator_t allocator;
// 定义 ROS2 节点和订阅者
rcl_node_t node;
rcl_subscription_t subscriber;
// 定义接收到的消息结构体
geometry_msgs__msg__Twist sub_msg;
// 定义控制两个电机的对象
Esp32McpwmMotor motor;
// 回调函数,当接收到新的 Twist 消息时会被调用
void twist_callback(const void *msg_in)
{
// 将接收到的消息指针转化为 geometry_msgs__msg__Twist 类型
const geometry_msgs__msg__Twist *twist_msg = (const geometry_msgs__msg__Twist *)msg_in;
// 从 Twist 消息中获取线速度和角速度
float linear_x = twist_msg->linear.x;
float angular_z = twist_msg->angular.z;
// 打印接收到的速度信息
Serial.printf("recv spped(%f,%f)\n", linear_x, angular_z);
// 如果速度为零,则停止两个电机
if (linear_x == 0 && angular_z == 0)
{
motor.updateMotorSpeed(0, 0);
motor.updateMotorSpeed(1, 0);
return;
}
// 根据线速度和角速度控制两个电机的转速
if (linear_x > 0)
{
motor.updateMotorSpeed(0, 70);
motor.updateMotorSpeed(1, 70);
}
if (linear_x < 0)
{
motor.updateMotorSpeed(0, -70);
motor.updateMotorSpeed(1, -70);
}
if (angular_z > 0)
{
motor.updateMotorSpeed(0, -70);
motor.updateMotorSpeed(1, 70);
}
if (angular_z < 0)
{
motor.updateMotorSpeed(0, 70);
motor.updateMotorSpeed(1, -70);
}
}
void setup()
{
// 初始化串口
Serial.begin(115200);
// 初始化两个电机的引脚
motor.attachMotor(0, 22, 23);
motor.attachMotor(1, 12, 13);
// 设置 micro-ROS 通信参数,连接到指定的 ROS2 代理
IPAddress agent_ip;
agent_ip.fromString("192.168.1.110");
set_microros_wifi_transports("SSID", "PASSWD", agent_ip, PORT);
delay(2000);
// 初始化 ROS2 执行器和支持结构
allocator = rcl_get_default_allocator();
rclc_support_init(&support, 0, NULL, &allocator);
// 初始化 ROS2 节点
rclc_node_init_default(&node, "esp32_car", "", &support);
// 初始化订阅者
rclc_subscription_init_default(
&subscriber,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(geometry_msgs, msg, Twist),
"/cmd_vel");
rclc_executor_init(&executor, &support.context, 1, &allocator);
// 设置订阅的回调函数
rclc_executor_add_subscription(&executor, &subscriber, &sub_msg, &twist_callback, ON_NEW_DATA);
}
void loop()
{
rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100)); // 循环处理数据
}
这样,我们就搭建了一个简单的可遥控的移动小车,要想让小车运动起来,还需要向 cmd_vel
话题中传入我们的数据,让小车接受并处理后运动起来。
旭日 X3 派
我们将旭日 X3 派作为项目中物联网网关,旭日 X3 派官方的镜像中包含了 tros 系统,作为数据的中转,将多个设备如 PC、我们的移动小车连接起来。在旭日 X3 派上我们使用 rosbridge
作为消息中间件,讲 JSon 格式的数据与 ROS 消息格式进行相互转换。
安装 Rosbridge
可以使用 apt
sudo apt install ros-<rosdistro>-rosbridge-suite
之后启动 rosbridge-server,注意启动的地址默认为 ws://localhost:9090
,如果需要修改,可以更改 launch 文件。
然后我们开始搭建我们的 web 应用,讲我们 PC 端的数据发送至我们的物联网网关,再由其处理转发后发送至 cmd_vel
话题。
完整的 html 文件如下:
<!DOCTYPE html>
<html>
<head>
<meta charset="utf-8" />
<!-- <script type="text/javascript" src="http://static.robotwebtools.org/EventEmitter2/current/eventemitter2.min.js"></script> -->
<script src="../build/roslib.js"></script>
<style type="text/css">
#box1{
width: 44px;
height:44px;
position: absolute;
background: lightskyblue;
}
</style>
<script>
// Connecting to ROS
var ros = new ROSLIB.Ros({
url: 'ws://localhost:12346'
});
var isconected=false;
//判断是否连接成功并输出相应的提示消息到web控制台
ros.on('connection', function() {
isconected=true;
console.log('Connected to websocket server.');
subscribe();
});
ros.on('error', function(error) {
isconected=false;
console.log('Error connecting to websocket server: ', error);
});
ros.on('close', function() {
isconected=false;
console.log('Connection to websocket server closed.');
unsubscribe();
});
// Publishing a Topic
var cmdVel = new ROSLIB.Topic({
ros : ros,
name : 'turtle1/cmd_vel',
messageType : 'geometry_msgs/Twist'
});
var twist = new ROSLIB.Message({
linear : {
x : 0.0,
y : 0.0,
z : 0.0
},
angular : {
x : 0.0,
y : 0.0,
z : 0.0
}
});//创建一个message
function control_move(direction){
twist.linear.x = 0.0;
twist.linear.y = 0;
twist.linear.z = 0;
twist.angular.x = 0;
twist.angular.y = 0;
twist.angular.z = 0.0;
switch(direction){
case 'up':
twist.linear.x = 2.0;
break;
case 'down':
twist.linear.x = -2.0;
break;
case 'left':
twist.angular.z = 2.0;
break;
case 'right':
twist.angular.z = -2.0;
break;
}
cmdVel.publish(twist);
}
var timer=null;
function buttonmove(){
var oUp=document.getElementById('up');
var oDown=document.getElementById('down');
var oLeft=document.getElementById('left');
var oRight=document.getElementById('right');
oUp.onmousedown=function ()
{
Move('up');
}
oDown.onmousedown=function ()
{
Move('down');
}
oLeft.onmousedown=function ()
{
Move('left');
}
oRight.onmousedown=function ()
{
Move('right');
}
oUp.onmouseup=oDown.onmouseup=oLeft.onmouseup=oRight.onmouseup=function ()
{
MouseUp ();
}
}
function keymove (event) {
event = event || window.event;
console.log(event.keyCode);
switch (event.keyCode){
case 65:
Move('left');
break;
case 87:
Move('up');
break;
case 68:
Move('right');
break;
case 83:
Move('down');
break;
default:
break;
}
}
var MoveTime=20;
function Move (f){
clearInterval(timer);
timer=setInterval(function (){
control_move(f)
},MoveTime);
}
function MouseUp ()
{
clearInterval(timer);
}
function KeyUp(event){
MouseUp();
}
window.onload=function ()
{
buttonmove();
document.onkeyup=KeyUp;
document.onkeydown=keymove;
Movebox();
}
// Subscribing to a Topic
var listener = new ROSLIB.Topic({
ros : ros,
name : '/robot/pose',
messageType : 'robot/Pose'
});
var turtle_x=0.0;
var turtle_y=0.0;
function subscribe()//在连接成功后,控制div的位置,
{
listener.subscribe(function(message) {
turtle_x=message.x;
turtle_y=message.y;
document.getElementById("output").innerHTML = ('Received message on ' + listener.name +' x: ' + message.x+" ,y: "+message.y);
});
}
function unsubscribe()//在断开连接后,取消订阅
{
listener.unsubscribe();
}
function Movebox ()
{
var obox=document.getElementById("box1");
var timer=null;
clearInterval(timer);
timer=setInterval(function (){
if(!isconected)
{
obox.style.left = '0px';
obox.style.top = '0px';
} else {
obox.style.left =Math.round(60*turtle_x)-330+"px";
console.log(obox.style.left)
obox.style.top =330-Math.round(60*turtle_y)+"px";
console.log(obox.style.top)
}
},20);
}
</script>
</head>
<body>
<h1>移动机器人控制器 </h1>
<p>需要在micro-ROS中订阅cmd_vel话题</p>
<p>控制按键</p>
<input type="button" value="前行" id="up">
<input type="button" value="后退" id="down">
<input type="button" value="左转" id="left">
<input type="button" value="右转" id="right">
<p>机器人位置地图</p>
<p id = "output"></p>
<div id="mbox" style="width:704px;height:704px;border:1px solid red;position: relative;">
<div id="box1" style="margin-left:330px;margin-top:330px;position:absolute;" ></div>
</div>
</body>
</html>
web 应用主要做了以下三件事:
- 连接到我们旭日 X3 派的 ROS 网络
- 通过向
cmd_vel
话题发送 Twist 类型消息来控制机器人移动 - 订阅机器人的位置话题
robot/Pos
之后我们可以在浏览器里打开页面,位置地图用来显示 robot/Pos
话题的数据,也就是机器人的位置信息。可以点击按钮控制机器人的运动,也可以使用键盘 WASD 来控制移动。
Dokcer 镜像
将我们所做的 Docker 镜像,方便我们快速搭建我们的应用。Dockerfile 文件的编写就不过多阐述了,可以上网络上搜索相关的教程。我的 Dockerfile 文件如下,映射了我本地的文件夹,如果你需要使用 Docker 镜像可以修改一下相关的部分。
FROM --platform=arm64 ros:foxy
USER root
COPY sources.list.tsinghua /etc/apt/sources.list.tsinghua
RUN mv /etc/apt/sources.list /etc/apt/sources.list.bak \
&& mv /etc/apt/sources.list.tsinghua /etc/apt/sources.list \
&& apt update \
&& apt install -y vim xfce4 tigervnc-standalone-server fonts-wqy-zenhei net-tools \
&& apt install -y ros-foxy-rosbridge-suite \
&& source /opt/ros/foxy/setup.bash \
&& ros2 run rosbridge_server rosbridge_websocket
COPY index.html /index.html
ENV LANG=zh.CN.UTF-8
EXPOSE 5901 12345/udp 12346
VOLUME [ "/Users/han/ros2_ws" ]
评论(0)
您还未登录,请登录后发表或查看评论