硬件
- STM32F103c8t6
- OLED(I2C)
- USB2TTL
- Stlink
接線
OLED(GPIO模擬I2C)
硬件 | 引腳 |
---|---|
OLEDSCL | PA4 |
OLEDSDA | PA5 |
USART1
硬件 | 引腳 | 作用 |
---|---|---|
RX | PA9 | USART1_TX |
TX | PA10 | USART1_RX |
LED
硬件 | 引腳 |
---|---|
LED0 | PC13 |
LED1 | PC15 |
軟件
- STM32CubeMX
- Clion
STM32CubeMX配置
- SYS->Debug->Serial Wire
- RCC->HSE->Crystal/Ceramic Resonator
- PC15->OutPut ,Label為LED0
- PC13->OutPut ,Label為LED1
- TIM1->Clock Source->Internal Clock
- 時(shí)鐘樹,時(shí)鐘設(shè)置為72M
- USART1->Asynchronous Baud Rate: 115200
設(shè)置DMA
開啟串口中斷
rosserial
rosserial是ROS中的一個(gè)重要模塊,它實(shí)現(xiàn)了ROS通信協(xié)議與各類嵌入式硬件平臺之間的橋接,大大簡化了ROS在底層硬件上的移植和應(yīng)用。rosserial通過消息序列化和常用串行通信接口,實(shí)現(xiàn)了ROS主機(jī)和嵌入式客戶端之間的消息交互,為各種嵌入式平臺提供了C++和Python的ROS客戶端庫,使得在這些硬件上也能方便地使用ROS的通信架構(gòu)來進(jìn)行節(jié)點(diǎn)管理、話題通信和服務(wù)調(diào)用。rosserial還支持動態(tài)主題和服務(wù),以較小的代碼占用實(shí)現(xiàn)ROS功能,具有很強(qiáng)的可移植性。因此,rosserial是ROS物聯(lián)網(wǎng)和機(jī)器人應(yīng)用不可或缺的重要組件,極大地便利了ROS在各類嵌入式系統(tǒng)和小型機(jī)器人產(chǎn)品上的移植應(yīng)用和開發(fā)。
rosserial_WIKI
rosserial_stm32 Github地址
本文資源包stm32f103c8t6_rosserial, CSDN資源下載
移植
下載上述資源stm32f103c8t6_rosserial
git clone https://github.com/GHigher12/STM32f103c8t6_rosserial.git
or 直接在CSDN下載
將RosLibs文件夾添加到stm32工作文件里
還有Core文件夾中的mainpp.h , round.h, mainpp.cpp
此時(shí)如果用Clion作為開發(fā)環(huán)境還需要修改CMakeList.txt
包含文件的路徑
main.c
使用
//...
#include "mainpp.h"
//...
int main(void)
{
//...
setup();
while (1)
{
loop();
}
/* USER CODE END 3 */
}
上位機(jī)訂閱-下位機(jī)發(fā)布
上位機(jī)訂閱
python訂閱 demo01_sub_py.py
#! /usr/bin/env python
import rospy
from std_msgs.msg import String
if __name__ == "__main__":
rospy.init_node("ros_pc_pub")
pub = rospy.Publisher("pc_to_stm32",String,queue_size=10)
msg = String()
msg_front = "ros_2_stm32->"
count = 0
rate = rospy.Rate(1)
while not rospy.is_shutdown():
msg.data = msg_front + str(count)
pub.publish(msg)
rate.sleep()
rospy.loginfo("發(fā)布的數(shù)據(jù)為:%s",msg.data)
count += 1
c++訂閱 demo01_sub_c.cpp
#include "ros/ros.h"
#include "std_msgs/String.h"
#include <sstream>
void doMsg(const std_msgs::String::ConstPtr &msg)
{
ROS_INFO("訂閱的數(shù)據(jù)為: %s", msg->data.c_str());
}
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
ros::init(argc, argv, "ros_pc_sub");
ros::NodeHandle nh;
ros::Subscriber sub = nh.subscribe("stm32_to_pc", 10, doMsg);
ros::spin();
return 0;
}
安裝rosserial_python
sudo apt-get install ros-noetic-rosserial-python
下位機(jī)發(fā)布
mainpp.cpp
#include <mainpp.h>
#include <ros.h>
#include <std_msgs/String.h>
#include "main.h"
ros::NodeHandle nh;
std_msgs::String stm32_to_pc_word;
ros::Publisher stm32_to_pc("stm32_to_pc", &stm32_to_pc_word);
void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart){
nh.getHardware()->flush();
}
void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart){
nh.getHardware()->reset_rbuf();
}
char hello[13] = "hello ros!";
u8 cnt = 0;
void setup(void)
{
nh.initNode();
nh.advertise(stm32_to_pc);
}
void loop(void)
{
cnt+=1;
sprintf(oledBuf,"stm32_2_ros->%d",cnt);
OLED_ShowString(0,24,(u8*)oledBuf,16);
OLED_Refresh();
stm32_to_pc_word.data = oledBuf;
HAL_GPIO_TogglePin(LED0_GPIO_Port, LED0_Pin);
HAL_GPIO_TogglePin(LED1_GPIO_Port, LED1_Pin);
HAL_Delay(1000);
stm32_to_pc.publish(&stm32_to_pc_word);
nh.spinOnce();
}
編譯將程序燒錄到stm32中
通信
將usb2ttl連接好usart1,連接電腦
執(zhí)行下列命令
lsusb
ls /dev/ttyUSB*
sudo chmod 777 /dev/ttyUSB0
啟動rosserial_python節(jié)點(diǎn)
roscore
rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0 _baud:=115200
出現(xiàn)以下內(nèi)容則表示運(yùn)行正常
[INFO] [1690446448.903399]: ROS Serial Python Node
[INFO] [1690446448.908570]: Connecting to /dev/ttyUSB0 at 115200 baud
[INFO] [1690446451.013146]: Requesting topics...
[INFO] [1690446451.772474]: Note: publish buffer size is 512 bytes
[INFO] [1690446451.774498]: Setup publisher on stm32_to_pc [std_msgs/String]
可使用rostopic echo /stm32_to_pc
查看話題
不過這里會出現(xiàn)[ERROR] [1690446652.290474]: Lost sync with device, restarting...
報(bào)錯,導(dǎo)致收發(fā)頻率不一致,博主現(xiàn)在還沒解決,如有讀者有解決辦法,可在評論留言。
python訂閱
cd ~/catkin_ws
source ./devel/setup.bash
rosrun hello_vscode demo01_sub_py.py
c++訂閱
cd ~/catkin_ws
source ./devel/setup.bash
rosrun hello_vscode demo01_sub_c
下位機(jī)顯示
查看rqt_graph
文章來源:http://www.zghlxwxcb.cn/news/detail-708696.html
上位機(jī)發(fā)布-下位機(jī)訂閱
上位機(jī)發(fā)布
python發(fā)布 demo01_pub_py.py
#! /usr/bin/env python
import rospy
from std_msgs.msg import String
if __name__ == "__main__":
rospy.init_node("ros_pc_pub")
pub = rospy.Publisher("pc_to_stm32",String,queue_size=10)
msg = String()
msg_front = "ros_2_stm32->"
count = 0
rate = rospy.Rate(1)
while not rospy.is_shutdown():
msg.data = msg_front + str(count)
pub.publish(msg)
rate.sleep()
rospy.loginfo("發(fā)布的數(shù)據(jù)為:%s",msg.data)
count += 1
c++發(fā)布 demo01_pub_c.cpp
#include "ros/ros.h"
#include "std_msgs/String.h"
#include <sstream>
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
ros::init(argc, argv, "ros_pc_pub");
ros::NodeHandle nh;
ros::Publisher pub = nh.advertise<std_msgs::String>("pc_to_stm32", 10);
std_msgs::String msg;
ros::Rate rate(1);
int count = 0;
ros::Duration(3).sleep();
while (ros::ok)
{
count++;
std::stringstream ss;
ss << "ros_2_stm32->" << count;
msg.data = ss.str();
pub.publish(msg);
ROS_INFO("發(fā)布的數(shù)據(jù)為: %s", ss.str().c_str());
rate.sleep();
ros::spinOnce(); //處理回調(diào)函數(shù)
}
return 0;
}
下位機(jī)訂閱
mainpp.cpp
#include <mainpp.h>
#include <ros.h>
#include <std_msgs/String.h>
#include "main.h"
void command_callback( const std_msgs::String& rxbuff);
ros::NodeHandle nh;
std_msgs::String stm32_to_pc_word;
ros::Subscriber<std_msgs::String> cmd_sub("pc_to_stm32", command_callback);
void command_callback(const std_msgs::String &rxbuff)
{
char oled_rxbuff[128];
stm32_to_pc_word = rxbuff;
snprintf(oled_rxbuff, sizeof(oled_rxbuff), "%s", rxbuff.data);
OLED_ShowString(0,24, (u8*)oled_rxbuff,16);
OLED_Refresh();
}
void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart){
nh.getHardware()->flush();
}
void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart){
nh.getHardware()->reset_rbuf();
}
void setup(void)
{
nh.initNode();
nh.subscribe(cmd_sub);
}
void loop(void)
{
HAL_GPIO_TogglePin(LED0_GPIO_Port, LED0_Pin);
HAL_GPIO_TogglePin(LED1_GPIO_Port, LED1_Pin);
HAL_Delay(1000);
nh.spinOnce();
}
通信
python發(fā)布
rosrun hello_vscode demo01_pub_py.py
c++發(fā)布
rosrun hello_vscode demo01_pub_c
下位機(jī)顯示
查看rqt_graph
文章來源地址http://www.zghlxwxcb.cn/news/detail-708696.html
到了這里,關(guān)于ROS與STM32通信(一)-rosserial的文章就介紹完了。如果您還想了解更多內(nèi)容,請?jiān)谟疑辖撬阉鱐OY模板網(wǎng)以前的文章或繼續(xù)瀏覽下面的相關(guān)文章,希望大家以后多多支持TOY模板網(wǎng)!