微信小程序和ros2进行通信
- 环境配置
- ubuntu下安装ros2
- ubuntu安装mqtt库
- windows安装微信开发者工具
- 主要功能模块介绍
- ROS2基础程序讲解
- 微信小程序基础程序讲解
- 编译及运行ros2程序
- 编译及运行微信小程序
- 主要事项
ROS2做为一款优秀的机器人操作系统软件,其搭载了丰富的机器人平台,是目前机器人领域应用最多的软件。微信做为一个大型社交软件,应用非常广泛,其中的小程序直接通过扫二维码进行加载,使用起来非常方便快捷。为了让手机端能够对机器人进行操作,于是通过微信小程序与ROS2通信的方式将两者联系在一起。
ROS2在ubuntu的电脑上运行,而微信则运行在手机端,可以通过一个中间设备透传两者之间的消息的方式实现,笔者目前采用mqtt通信的方式进行,中间设备是 免费公共 MQTT 服务器 ,作为本次测试的 MQTT 服务器地址,服务器接入信息如下:
- Broker: broker.emqx.io
- TCP Port: 1883
- SSL/TLS Port: 8883
更多详情请访问 EMQX Cloud 官网,或查看EMQX Cloud 文档 。
环境配置
ubuntu下安装ros2
直接使用鱼香ros进行安装,安装脚本命令:
wget http://fishros.com/install -O fishros && . fishros
ubuntu安装mqtt库
git clone https://github.com/eclipse/paho.mqtt.c.git
cd paho.mqtt.c
mkdir build
cd build
cmake ..
make
sudo make install
windows安装微信开发者工具
进入官网下载windows版本的安装程序,保证C盘有1G的空闲空间,否则会出现安装失败的情况。
主要功能模块介绍
ROS2基础程序讲解
mqtt_c.hpp
#ifndef MQTT_C_HPP_
#define MQTT_C_HPP_
#include <iostream>
#include "stdlib.h"
#include "string.h"
#include "unistd.h"
#include <functional>
#include "MQTTClient.h"
class Mqtt_C {
public:
//加载类的静态函数或全局函数做为mqtt的回调函数
Mqtt_C(char* address, char* client_id, char* user_name, char* password, char* topic, int qos, MQTTClient_messageArrived *callBack);
//加载类的非静态函数做为mqtt的回调函数
Mqtt_C(char* address, char* client_id, char* user_name, char* password, char* topic, int qos, std::function<void (void*, char*, int, MQTTClient_message*)> callBack);
~Mqtt_C();
// 发送mqtt消息
void publish(char *topic, char *payload);
private:
bool connect_flag_; //0表示连接失败,1表示成功
long TIMEOUT = 10000;
char* topic_;
MQTTClient client_;
int qos_;
//待绑定的回调函数
std::function<void (void*, char*, int, MQTTClient_message*)> callBackFun;
//接受mqtt的回调函数
static int on_message(void *context, char *topicName, int topicLen, MQTTClient_message *message);
};
typedef Mqtt_C* Mqtt_C_Ptr; //不能使用智能指针,否则会关闭mqtt连接
#endif
mqtt_c.cpp
#include "mqtt_c.hpp"
Mqtt_C::Mqtt_C(char* address, char* client_id, char* user_name, char* password, char* topic, int qos, MQTTClient_messageArrived *callBack)
: connect_flag_(0) {
int rc;
topic_ = topic;
qos_ = qos;
MQTTClient_create(&client_, address, client_id, 0, NULL);
MQTTClient_connectOptions conn_opts = MQTTClient_connectOptions_initializer;
conn_opts.username = user_name;
conn_opts.password = password;
//将全局函数或类的静态函数
MQTTClient_setCallbacks(client_, NULL, NULL, callBack, NULL);
if ((rc = MQTTClient_connect(client_, &conn_opts)) != MQTTCLIENT_SUCCESS) {
std::cout << "Failed to connect, return code " << rc << std::endl;
connect_flag_ = 0;
return;
} else {
std::cout << "Connected to MQTT Broker!" << std::endl;
connect_flag_ = 1;
}
// 开始订阅对应topic的消息
MQTTClient_subscribe(client_, topic, qos);
}
Mqtt_C::Mqtt_C(char* address, char* client_id, char* user_name, char* password, char* topic, int qos, std::function<void (void*, char*, int, MQTTClient_message*)> callBack)
: connect_flag_(0) {
int rc;
topic_ = topic;
qos_ = qos;
// 将需要回调的函数进行绑定
callBackFun = callBack;
MQTTClient_create(&client_, address, client_id, 0, NULL);
MQTTClient_connectOptions conn_opts = MQTTClient_connectOptions_initializer;
conn_opts.username = user_name;
conn_opts.password = password;
// 将类的this指针传入on_message函数中,以便静态函数调用类的非静态成员
MQTTClient_setCallbacks(client_, this, NULL, on_message, NULL);
if ((rc = MQTTClient_connect(client_, &conn_opts)) != MQTTCLIENT_SUCCESS) {
std::cout << "Failed to connect, return code " << rc << std::endl;
connect_flag_ = 0;
return;
} else {
std::cout << "Connected to MQTT Broker!" << std::endl;
connect_flag_ = 1;
}
// 开始订阅对应topic的消息
MQTTClient_subscribe(client_, topic, qos);
}
Mqtt_C::~Mqtt_C() {
if(connect_flag_ == 1) {
MQTTClient_disconnect(client_, TIMEOUT);
MQTTClient_destroy(&client_);
}
std::cout << "Close the mqtt connect" << std::endl;
}
void Mqtt_C::publish(char *topic, char *payload) {
if(connect_flag_ == 1) {
MQTTClient_message message = MQTTClient_message_initializer;
message.payload = payload;
message.payloadlen = strlen(payload);
message.qos = qos_;
message.retained = 0;
MQTTClient_deliveryToken token;
MQTTClient_publishMessage(client_, topic, &message, &token);
MQTTClient_waitForCompletion(client_, token, TIMEOUT);
std::cout << "Send " << payload << " to topic " << topic << std::endl;
}
else {
std::cout << "Failed to connect" << std::endl;
}
}
int Mqtt_C::on_message(void *context, char *topicName, int topicLen, MQTTClient_message *message) {
// 调用绑定的回调函数
Mqtt_C* ptr = (Mqtt_C*)context;
ptr->callBackFun(context, topicName, topicLen, message);
MQTTClient_freeMessage(&message);
MQTTClient_free(topicName);
return 1;
}
main.cpp
#include <chrono>
#include <functional>
#include <memory>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "MQTTClient.h"
#include "mqtt_c.hpp"
using namespace std::chrono_literals;
class MinimalPublisher : public rclcpp::Node {
public:
MinimalPublisher() : Node("minimal_publisher") {
// 初始化ros发布的消息
publisher_ = this->create_publisher<std_msgs::msg::String>("topic", 10);
// 初始化mqtt的消息及加载回调函数
mqtt_ = new Mqtt_C("tcp://broker.emqx.io:1883", "c-client", "test", "test", "/wechat_ros/mqtt", 0, std::bind(&MinimalPublisher::getMqttMessage,
this,
std::placeholders::_1,
std::placeholders::_2,
std::placeholders::_3,
std::placeholders::_4));
}
private:
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
Mqtt_C_Ptr mqtt_;
// 定义mqtt的回调函数
void getMqttMessage(void *context, char *topicName, int topicLen, MQTTClient_message *message) {
auto* payload = message->payload;
std::cout << "Received " << (char*)(payload) << " from " << topicName << " topic" << std::endl;
// 发布mqtt消息
mqtt_->publish("/wechat_ros_return/mqtt", "ros2 to wechat");
// 发布ros消息
auto ros_message = std_msgs::msg::String();
ros_message.data = (char*)(payload);
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", ros_message.data.c_str());
publisher_->publish(ros_message);
}
};
int main(int argc, char * argv[]) {
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalPublisher>());
rclcpp::shutdown();
return 0;
}
微信小程序基础程序讲解
微信小程序参考EMQ的demo,源程序
编译及运行ros2程序
mkdir ros2_ws
cd ros2_ws
mkdir src
cd src
git clone https://gitee.com/jdi-shen/wechat_to_ros2.git
cd ..
colcon build
export LD_LIBRARY_PATH=/usr/local/lib
source install/setup.bash
ros2 run ros2_end main
编译及运行微信小程序
在windows中下载源程序,运行微信开发者工具,加载源程序中的“wechat_robot”,勾选“不校验合法域名、web-view(业务域名)、TLS版本以及HTTPS证书”,如同1所示。
图1
直接使用微信开发者工具中的模拟器或点击“真机调试”生成二维码,用手机微信扫描二维码运行。点击“连接”、“订阅”,然后点击“发布”,会在ros2终端中收到消息,同时手机小程序也会收到消息。至此实现了ros2和微信小程序之间的简单通信过程。
主要事项
- 在运行ros程序时,需要加载环境变量“export LD_LIBRARY_PATH=/usr/local/lib”;
- 所有源程序在gitee仓库,https://gitee.com/jdi-shen/wechat_to_ros2.git;
- 运行ros2程序的ubuntu系统和手机都需要连上互联网;