|
| 1 | + |
| 2 | +/** |
| 3 | + * このプログラムとechoreply_stringを使う |
| 4 | + * 10回くらい送信して返ってくるかチェックする |
| 5 | + */ |
| 6 | + |
| 7 | +#include "mros2.h" |
| 8 | +#include "std_msgs/msg/string.hpp" |
| 9 | + |
| 10 | +#include "cmsis_os.h" |
| 11 | +#include "netif.h" |
| 12 | +#include "netif_posix_add.h" |
| 13 | + |
| 14 | +#include <stdio.h> |
| 15 | +#include <string.h> |
| 16 | +#include <pthread.h> |
| 17 | + |
| 18 | +bool result = true; |
| 19 | +auto TestMessagePreFix = "TestMessage"; |
| 20 | +std::string expect = ""; |
| 21 | +int sub_counter = 0; |
| 22 | +pthread_mutex_t mutex_expect_sting; |
| 23 | + |
| 24 | +void userCallback(std_msgs::msg::String *msg) |
| 25 | +{ |
| 26 | + pthread_mutex_lock(&mutex_expect_sting); |
| 27 | + sub_counter++; |
| 28 | + printf("*test count : %d\r\n", sub_counter); |
| 29 | + auto actual = msg->data; |
| 30 | + // FIXME 受信データに改行や不要な文字が含まれている模様 |
| 31 | + actual.erase(std::remove(actual.begin(), actual.end(), '\n'), actual.end()); |
| 32 | + actual.erase(std::remove(actual.begin(), actual.end(), '\r'), actual.end()); |
| 33 | + |
| 34 | + printf("expect : '%s',\r\nactural: '%s'\r\n", expect.c_str(), actual.c_str()); |
| 35 | + printf("expect length: %lu, actual length: %lu\r\n", expect.size(), actual.size()); |
| 36 | + if (strcmp(expect.c_str(), actual.c_str()) == 0) |
| 37 | + { |
| 38 | + printf("****SUCCEED****'\r\n"); |
| 39 | + result = result & true; |
| 40 | + } |
| 41 | + else |
| 42 | + { |
| 43 | + printf("FAIL different data responsed.\r\n"); |
| 44 | + result = result & false; |
| 45 | + } |
| 46 | + pthread_mutex_unlock(&mutex_expect_sting); |
| 47 | + printf("\r\n"); |
| 48 | + |
| 49 | + if (sub_counter > 10) |
| 50 | + { |
| 51 | + if (result) |
| 52 | + { |
| 53 | + printf("All tests succeed.\r\n"); |
| 54 | + std::exit(0); |
| 55 | + } |
| 56 | + printf("Some tests faild.\r\n"); |
| 57 | + std::exit(-1); |
| 58 | + } |
| 59 | +} |
| 60 | + |
| 61 | +int main(int argc, char *argv[]) |
| 62 | +{ |
| 63 | + netif_posix_add(NETIF_IPADDR, NETIF_NETMASK); |
| 64 | + |
| 65 | + osKernelStart(); |
| 66 | + |
| 67 | + printf("mros2-posix start!\r\n"); |
| 68 | + printf("app name: echoback_string\r\n"); |
| 69 | + mros2::init(0, NULL); |
| 70 | + MROS2_DEBUG("mROS 2 initialization is completed\r\n"); |
| 71 | + |
| 72 | + mros2::Node node = mros2::Node::create_node("mros2_test_node"); |
| 73 | + mros2::Publisher pub = node.create_publisher<std_msgs::msg::String>("to_linux", 10); |
| 74 | + auto msg = std_msgs::msg::String(); |
| 75 | + msg.data = "initial"; |
| 76 | + pub.publish(msg); |
| 77 | + osDelay(1000); |
| 78 | + mros2::Subscriber sub = node.create_subscription<std_msgs::msg::String>("to_stm", 10, userCallback); |
| 79 | + |
| 80 | + MROS2_INFO("ready to pub/sub message\r\n"); |
| 81 | + auto count = 0; |
| 82 | + sub_counter = 0; |
| 83 | + while (true) |
| 84 | + { |
| 85 | + auto msg = std_msgs::msg::String(); |
| 86 | + pthread_mutex_lock(&mutex_expect_sting); |
| 87 | + expect = TestMessagePreFix + std::to_string(count++); |
| 88 | + msg.data = expect; |
| 89 | + printf("publishing msg: '%s'\r\n", msg.data.c_str()); |
| 90 | + pub.publish(msg); |
| 91 | + pthread_mutex_unlock(&mutex_expect_sting); |
| 92 | + |
| 93 | + osDelay(1000); |
| 94 | + } |
| 95 | + |
| 96 | + mros2::spin(); |
| 97 | + return 0; |
| 98 | +} |
0 commit comments