你好,我是愛吃魚香ROS的小魚。本節將學習在開發板上實現話題的發布,最終實現通過話題發布當前開發板的電池電量信息,關于電量信息的測量,請參考:4.電池電壓測量-學會使用ADC。
硬件開發平臺
為方便學習,本教程配套的硬件是小魚自制的MicroROS學習板,同時該板可以作為下一章節搭建實體移動機器人的主控板以及后續制作機械臂的驅動板使用。
板載資源圖如下:
該主控板可以在小魚的店鋪直接購買,性價比接地氣,點擊左下角閱讀原文直達魚香小鋪。
一、新建工程添加依賴
新建example12_microros_topic_pub
工程
修改platformio.ini
添加依賴
; PlatformIO Project Configuration File
;
; Build options: build flags, source filter
; Upload options: custom upload port, speed and extra flags
; Library options: dependencies, extra library storages
; Advanced options: extra scripting
;
; Please visit documentation for the other options and examples
; https://docs.platformio.org/page/projectconf.html
[env:featheresp32]
platform = espressif32
board = featheresp32
framework = arduino
lib_deps =
https://gitee.com/ohhuo/micro_ros_platformio.git
二、編寫代碼-實現訂閱
編輯main.cpp,代碼如下,注釋小魚已經添加到代碼中來了
#include < Arduino.h >
#include < micro_ros_platformio.h >
#include < rcl/rcl.h >
#include < rclc/rclc.h >
#include < rclc/executor.h >
// 添加頭文件
#include < std_msgs/msg/float32.h >
rclc_executor_t executor;
rclc_support_t support;
rcl_allocator_t allocator;
rcl_node_t node;
rcl_timer_t timer;
// 聲明話題發布者
rcl_publisher_t publisher;
// 聲明消息文件
std_msgs__msg__Float32 pub_msg;
// 定義定時器接收回調函數
void timer_callback(rcl_timer_t *timer, int64_t last_call_time)
{
RCLC_UNUSED(last_call_time);
if (timer != NULL)
{
rcl_publish(&publisher, &pub_msg, NULL);
}
}
void setup()
{
Serial.begin(115200);
// 設置通過串口進行MicroROS通信
set_microros_serial_transports(Serial);
// 延時時一段時間,等待設置完成
delay(2000);
// 初始化內存分配器
allocator = rcl_get_default_allocator();
// 創建初始化選項
rclc_support_init(&support, 0, NULL, &allocator);
// 創建節點 topic_sub_test
rclc_node_init_default(&node, "topic_pub_test", "", &support);
// 訂閱者初始化
rclc_publisher_init_default(
&publisher,
&node,
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float32),
"battery_voltage");
// 創建定時器,200ms發一次
const unsigned int timer_timeout = 200;
rclc_timer_init_default(
&timer,
&support,
RCL_MS_TO_NS(timer_timeout),
timer_callback);
// 創建執行器
rclc_executor_init(&executor, &support.context, 1, &allocator);
// 給執行器添加定時器
rclc_executor_add_timer(&executor, &timer);
// 初始化ADC
pinMode(34, INPUT);
analogSetAttenuation(ADC_11db);
}
void loop()
{
delay(100);
// 循環處理數據
rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));
// 通過ADC獲取電壓值
int analogValue = analogRead(34); // 讀取原始值0-4096
int analogVolts = analogReadMilliVolts(34); // 讀取模擬電壓,單位毫伏
float realVolts = 5.02 * ((float)analogVolts * 1e-3); // 計算實際電壓值
pub_msg.data = realVolts;
}
三、代碼注解
相比之前的節點代碼這里主要多了這幾行
?#include
包含flaot32類型頭文件
?rcl_publisher_t publisher; 定義發布者
?std_msgs__msg__Float32 pub_msg; 定義發布消息,也需要提前定義
?void timer_callback(rcl_timer_t *timer, int64_t last_call_time)
定義定時器回調函數,當我們需要以某個頻率做什么的時候定時器可以派上用場
?rclc_publisher_init_default
初始化發布者
?rclc_timer_init_default 初始化定時器
?rclc_executor_add_timer 給執行器添加一個定時器回調
四、下載測試
4.1 編譯下載
連接開發板,編譯下載。
4.2 啟動Agent服務
接著打開終端啟動agent
sudo docker run -it --rm -v /dev:/dev -v /dev/shm:/dev/shm --privileged --net=host microros/micro-ros-agent:$ROS_DISTRO serial --dev /dev/ttyUSB0 -v
點擊下RST按鈕,重啟開發板,正常可以看到下圖內容
4.3 測試是否連通
ros2 node list
ros2 topic list
4.4 查看話題數據
ros2 topic echo /battery_voltage
這里小魚連接了小車的電池,VM電壓代表電池電壓,符合正常電壓值范圍。
同時可以使用下面指令測量話題頻率
fishros@fishros-MS-7D42:~/example12_microros_topic_pub$ ros2 topic hz /battery_voltage
average rate: 4.828
min: 0.207s max: 0.208s std dev: 0.00021s window: 6
average rate: 5.034
min: 0.106s max: 0.208s std dev: 0.02793s window: 12
average rate: 4.973
min: 0.106s max: 0.208s std dev: 0.02378s window: 17
average rate: 4.941
min: 0.106s max: 0.208s std dev: 0.02104s window: 22
average rate: 5.005
min: 0.106s max: 0.208s std dev: 0.02594s window: 28
average rate: 4.977
min: 0.106s max: 0.208s std dev: 0.02404s window: 33
average rate: 4.958
min: 0.106s max: 0.208s std dev: 0.02249s window: 38
average rate: 4.997
min: 0.106s max: 0.208s std dev: 0.02541s window: 44
五、總結
本節我們通過電量信息發布例程,學習了如何在開發板上實現話題發布流程。下一節我們開始嘗試在開發板上建立服務端,嘗試服務通信。
-
Micro
+關注
關注
2文章
262瀏覽量
34833 -
adc
+關注
關注
98文章
6495瀏覽量
544467 -
開發板
+關注
關注
25文章
5032瀏覽量
97375 -
代碼
+關注
關注
30文章
4779瀏覽量
68525 -
ROS
+關注
關注
1文章
278瀏覽量
17001
發布評論請先 登錄
相關推薦
評論