
mros2 on MBed example reported at ROS Japan UG #44 LT. [Event] https://rosjp.connpass.com/event/222141/ [Slide] https://www.slideshare.net/smorita1/mros2-on-mbed
Please refer to the getting started.
https://github.com/mROS-base/mros2-mbed
Diff: main.cpp
- Branch:
- test_v0.3.2
- Revision:
- 4:2030aed3c888
- Parent:
- 1:c01b621ed377
--- a/main.cpp Sun Mar 13 21:27:29 2022 +0900 +++ b/main.cpp Sun Mar 13 21:41:01 2022 +0900 @@ -1,4 +1,4 @@ -/* mros2 on Mbed Example +/* mros2 example * Copyright (c) 2021 smorita_emb * * Licensed under the Apache License, Version 2.0 (the "License"); @@ -15,11 +15,15 @@ */ #include "mbed.h" -#include "mbed-trace/mbed_trace.h" #include "mros2.h" #include "std_msgs/msg/string.hpp" #include "EthernetInterface.h" +#define IP_ADDRESS ("192.168.11.2") /* IP address */ +#define SUBNET_MASK ("255.255.255.0") /* Subnet mask */ +#define DEFAULT_GATEWAY ("192.168.11.1") /* Default gateway */ + + mros2::Subscriber sub; mros2::Publisher pub; @@ -30,30 +34,23 @@ pub.publish(*msg); } -DigitalOut led1(LED1); -#define IP_ADDRESS ("192.168.11.2") /* IP address - if you want to change this, you also have to - modify the file below(IP_ADDRESS). - [embeddedRTPS/include/rtps/config.h] */ -#define SUBNET_MASK ("255.255.255.0") /* Subnet mask */ -#define DEFAULT_GATEWAY ("192.168.11.1") /* Default gateway */ int main() { - EthernetInterface network; - network.set_dhcp(false); - network.set_network(IP_ADDRESS, SUBNET_MASK, DEFAULT_GATEWAY); - nsapi_size_or_error_t result = network.connect(); + EthernetInterface network; + network.set_dhcp(false); + network.set_network(IP_ADDRESS, SUBNET_MASK, DEFAULT_GATEWAY); + nsapi_size_or_error_t result = network.connect(); - printf("mbed mros2 start!\r\n"); - mros2::init(0, NULL); - printf("mROS 2 initialization is completed\r\n"); + printf("mbed mros2 start!\r\n"); + printf("app name: echoreply_string\r\n"); + mros2::init(0, NULL); + MROS2_DEBUG("mROS 2 initialization is completed\r\n"); - mros2::Node node = mros2::Node::create_node("mros2_node"); - pub = node.create_publisher<std_msgs::msg::String>("to_linux", 10); - sub = node.create_subscription("to_stm", 10, userCallback); - std_msgs::msg::String msg; + mros2::Node node = mros2::Node::create_node("mros2_node"); + pub = node.create_publisher<std_msgs::msg::String>("to_linux", 10); + sub = node.create_subscription<std_msgs::msg::String>("to_stm", 10, userCallback); - printf("ready to pub/sub message\r\n"); - mros2::spin(); + MROS2_INFO("ready to pub/sub message\r\n"); - return 0; -} + mros2::spin(); + return 0; +} \ No newline at end of file