Renesas Community
Renesas Community
  • User
    Join or sign in
  • Site
  • Search Community
  • User
  • Renesas Engineering Community
  • FAQ
  • HELP
  • More
  • Cancel
がじぇっとるねさすコミュニティ
がじぇっとるねさすコミュニティ
GR-ROSE GR-RoseとROS2でサービス通信を行う方法について
  • Forums
  • Files
  • がじぇっとるねさす ゆーざー会 - Wiki
  • Tags
  • More
  • Cancel
  • New

 

 GR-SAKURA

 GR-KURUMI

 GR-COTTON

 GR-CITRUS

 GR-PEACH

 GR-KAEDE

 GR-ADZUKI

 GR-LYCHEE

 GR-ROSE

 GR-MANGO(*)

 SNShield

 Web Compiler

 IDE for GR

 TOPPERS関連

 女子美コラボ

 その他

 ※プロデューサミーティング中

 作り方使い方資料

 イベント関連

 作品記事

 体験記事

 その他

 

 ライブラリ

 ツール

 その他・過去ファイル

  • State Not Answered
  • Replies 2 replies
  • Subscribers 441 subscribers
  • Views 675 views
  • Users 0 members are here
Options
  • Share
  • More
  • Cancel
Related Tags
  • 3D
  • analog
  • B3M
  • DDS-XRCE
  • endif
  • esp8266
  • FIT
  • GR-ROSE
  • ICS
  • include
  • MG996R
  • MIC3
  • microSD
  • MPL3115A2
  • OLED
  • pin
  • PMOD
  • ROS
  • ROS2
  • rosserial
  • RS-485
  • RX65N
  • SDHI
  • serial
  • SmartConfigurator
Related

GR-RoseとROS2でサービス通信を行う方法について

Habanero
Habanero over 1 year ago

はじめまして。

Micro-XRCE-DDS-Agentを用いてROS2とGR-ROSEを接続し、サービス通信を行う方法がわかりません。

目標としているのは、ROS2側をクライアントとして、Twist型メッセージ(あるいは独自メッセージ)をGR-ROSEに送信し、GR-ROSEをサーバーとして、受け取った値に対応したレスポンスを返すといったサービスです。

最初にROS2から実数型、整数型、それぞれ2種類のメッセージをGR-ROSEに送信し、GR-ROSEからそれぞれの値に+10して返すといったテストプログラムを作りたかったのですが、GR-ROSEとROS2間でサービス通信を行う方法がわからず困っています。

サービス通信を行う手法を教えていただけないでしょうか。

あるいはサンプルプログラムがあれば大変ありがたいです。

開発環境

OS: Ubuntu 18.04.5 LTS

ROS2: Dashing Diademata

Micro-XRCE-DDS-Agent: v1.1.0

IDE for GR

  • Reply
  • Cancel
  • Cancel
Parents
  • Okamiya Yuuki
    0 Okamiya Yuuki over 1 year ago

    がじぇるね岡宮です。

    すみません、かなり前に作っていたサンプルを貼り付けたいと思います。Pub/Subを組み合わせたものが見つからずお役に立てないかもしれません。

    rose_ros2_jointstate_pub.txt
    // Copyright 2018 eSOL Co.,Ltd.
    // Copyright 2018 Proyectos y Sistemas de Mantenimiento SL (eProsima).
    //
    // Licensed under the Apache License, Version 2.0 (the "License");
    // you may not use this file except in compliance with the License.
    // You may obtain a copy of the License at
    //
    //     http://www.apache.org/licenses/LICENSE-2.0
    //
    // Unless required by applicable law or agreed to in writing, software
    // distributed under the License is distributed on an "AS IS" BASIS,
    // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
    // See the License for the specific language governing permissions and
    // limitations under the License.
    
    #include <Arduino.h>
    #include <WiFiEsp.h>
    #include <Ethernet.h>
    #include <stdio.h>
    #include <string.h>
    #include <stdlib.h>
    #include <limits.h>
    
    #include "ros2_msg/Ros2String.h"
    
    #include <uxr/client/client.h>
    #include <ucdr/microcdr.h>
    
    extern "C" {
    #include <FreeRTOS.h>
    #include <task.h>
    }
    #include <JointState.h>
    // Micro-XRCE-DDS-Client key identifier of the client.
    // If multiple clients connect to the same agent, each client must have a different key.
    #define CLIENT_KEY      0xAAAABBC4
    
    #define BUFFER_SIZE     UXR_CONFIG_UDP_TRANSPORT_MTU
    
    char ssid[] = "elecom2g01-45ea1e";                 // your network SSID (name)
    char pass[] = "renerene";             // your network password
    int status = WL_IDLE_STATUS;          // the Wifi radio's status
    byte mac[] = { 0x74, 0x90, 0x50, 0x00, 0x79, 0x03 };
    IPAddress ip(192, 168, 2, 52);
    
    uxrSession session;
    uxrUDPTransport transport;
    uxrUDPPlatform udp_platform;
    uxrObjectId datawriter_id;
    uxrStreamId output_stream;
    uxrStreamId input_stream;
    uint32_t count = 0;
    static char agent_ip[32] = {0};
    
    uint8_t output_best_effort_stream_buffer[BUFFER_SIZE];
    uint8_t input_best_effort_stream_buffer[BUFFER_SIZE];
    
    static bool use_ethernet = false;
    
    void on_agent_found(const uxrAgentAddress* address, void* args);
    static void prvUXRManagerTask(void * pvParameters);
    
    void setup() {
        // Initialize the LED pin
        pinMode(PIN_LED1, OUTPUT);
    
        if(!use_ethernet)
        {
            // initialize serial for debugging
            Serial.begin(115200);
            // initialize serial for ESP module
            Serial6.begin(115200);
            // initialize ESP module
            WiFi.init(&Serial6);
        }
        else
        {
            // Serial output to USB
            Serial.begin(9600);
        }
    
        if(!use_ethernet)
        {
            // check for the presence of the shield
            if (WiFi.status() == WL_NO_SHIELD) {
                Serial.println("WiFi shield not present");
                // don't continue
                while (true);
            }
            // attempt to connect to WiFi network
            while ( status != WL_CONNECTED) {
                Serial.print("Attempting to connect to WPA SSID: ");
                Serial.println(ssid);
                // Connect to WPA/WPA2 network
                status = WiFi.begin(ssid, pass);
            }
        }
        else
        {
            // Setting IP
            Ethernet.begin(mac, ip);
        }
    
        // Wait for network configuration
        vTaskDelay(5000);
    
        // Discovery Agent
        Serial.println("Discovery Agent...");
        uxrAgentAddress chosen;
        chosen.ip = agent_ip;
    
        // Choose Ethernet or WiFi
        uxr_discovery_choose_ethernet(use_ethernet);
    
        // Try forever until Agent is found
        uxr_discovery_agents_default(INT_MAX, 1000, on_agent_found, &chosen);
    
        Serial.print("Chosen agent => ip: ");
        Serial.print(chosen.ip);
        Serial.print(", port: ");
        Serial.println(chosen.port);
    
        // Transport
        udp_platform.use_ethernet = use_ethernet;
        if (!uxr_init_udp_transport(&transport, &udp_platform, chosen.ip, chosen.port))
        {
            Serial.println("Error at create transport.");
            return;
        }
    
        // Session
        uxr_init_session(&session, &transport.comm, CLIENT_KEY);
        if (!uxr_create_session(&session))
        {
            Serial.println("Error at create session.");
            return;
        }
    
        // Streams
        output_stream = uxr_create_output_best_effort_stream(&session, output_best_effort_stream_buffer, BUFFER_SIZE);
        input_stream = uxr_create_input_best_effort_stream(&session);
    
        // Create entities
        uxrObjectId participant_id = uxr_object_id(0x01, UXR_PARTICIPANT_ID);
        const char* participant_xml = "<dds>"
                                          "<participant>"
                                              "<rtps>"
                                                  "<name>default_xrce_participant</name>"
                                              "</rtps>"
                                          "</participant>"
                                      "</dds>";
        uint16_t participant_req = uxr_buffer_create_participant_xml(&session, output_stream, participant_id, 0, participant_xml, UXR_REPLACE);
    
        // In order to avoid buffer overflow, uxr_flash_output_streams() has to be
        // called everytime entities message is created.
        (void) uxr_flash_output_streams(&session);
    
        uxrObjectId topic_id = uxr_object_id(0x01, UXR_TOPIC_ID);
        const char* topic_xml = "<dds>"
                                    "<topic>"
                                        "<name>rt/joint_states</name>"
                                        "<dataType>sensor_msgs::msg::dds_::JointState_</dataType>"
                                    "</topic>"
                                "</dds>";
        uint16_t topic_req = uxr_buffer_create_topic_xml(&session, output_stream, topic_id, participant_id, topic_xml, UXR_REPLACE);
    
        // In order to avoid buffer overflow, uxr_flash_output_streams() has to be
        // called everytime entities message is created.
        (void) uxr_flash_output_streams(&session);
    
        uxrObjectId publisher_id = uxr_object_id(0x01, UXR_PUBLISHER_ID);
        const char* publisher_xml = "";
        uint16_t publisher_req = uxr_buffer_create_publisher_xml(&session, output_stream, publisher_id, participant_id, publisher_xml, UXR_REPLACE);
    
        // In order to avoid buffer overflow, uxr_flash_output_streams() has to be
        // called everytime entities message is created.
        (void) uxr_flash_output_streams(&session);
    
        datawriter_id = uxr_object_id(0x01, UXR_DATAWRITER_ID);
        const char* datawriter_xml = "<dds>"
                                         "<data_writer>"
                                             "<topic>"
                                                 "<kind>NO_KEY</kind>"
                                                 "<name>rt/joint_states</name>"
                                                 "<dataType>sensor_msgs::msg::dds_::JointState_</dataType>"
                                             "</topic>"
                                         "</data_writer>"
                                     "</dds>";
        uint16_t datawriter_req = uxr_buffer_create_datawriter_xml(&session, output_stream, datawriter_id, publisher_id, datawriter_xml, UXR_REPLACE);
    
        // In order to avoid buffer overflow, uxr_flash_output_streams() has to be
        // called everytime entities message is created.
        (void) uxr_flash_output_streams(&session);
    
        xTaskCreate(prvUXRManagerTask, "TalkerDemo", configMINIMAL_STACK_SIZE * 5, NULL, 2, NULL);
    }
    
    void loop() {
        // Do nothing
        vTaskDelay(10000);
    }
    
    void on_agent_found(const uxrAgentAddress* address, void* args) {
        uxrAgentAddress* agent = (uxrAgentAddress*)args;
    
        Serial.print("Found agent => ip: ");
        Serial.print(address->ip);
        Serial.print(", port: ");
        Serial.println(address->port);
    
        memcpy((void*)(agent->ip), address->ip, 32);
        agent->port = address->port;
    }
    
    static void prvUXRManagerTask(void * pvParameters) {
        // Cannot confirm whether client is connected to agent or not.
        while (1)
        {
            // Topic serialization
        	JointState topic;
            sprintf(topic.header.frame_id , "%lu", count++);
            topic.header.stamp.nanosec = millis() * 1000000;
            topic.header.stamp.sec = millis() / 1000;
            topic.name_size = 3;
            sprintf((char*)topic.name[0], "Joint_Roll");
            sprintf((char*)topic.name[1], "Joint_Pitch");
            sprintf((char*)topic.name[2], "Joint_Yaw");
            topic.position_size = 3;
            topic.position[0] = 0.1;
            topic.position[1] = 0.2;
            topic.position[2] = 0.3;
            topic.velocity_size = 3;
            topic.velocity[0] = 0;
            topic.velocity[1] = 0;
            topic.velocity[2] = 0;
            topic.effort_size = 3;
            topic.effort[0] = 0;
            topic.effort[1] = 0;
            topic.effort[2] = 0;
    
            ucdrBuffer mb;
            uint32_t topic_size = JointState_size_of_topic(&topic, 0);
            uxr_prepare_output_stream(&session, output_stream, datawriter_id, &mb, topic_size);
            bool flag = JointState_serialize_topic(&mb, &topic);
    
            /* Set timeout period to 0s. */
            (void) uxr_run_session_time(&session, 0);
            Serial.print("Sent topic:");
            Serial.print(topic_size);
            Serial.print("\t");
            Serial.println(flag);
    
            // Toggle the heartbeat LED
            digitalWrite(PIN_LED1, !digitalRead(PIN_LED1));
    
            /* Set timeout period to 1s. */
            vTaskDelay(200);
        }
    
        // Delete resources
        (void) uxr_delete_session(&session);
        (void) uxr_close_udp_transport(&transport);
    
        // Delete this task
        vTaskDelete(NULL);
    }
    

    rose_ros2_jointstate_sub.txt
    // Copyright 2018 eSOL Co.,Ltd.
    // Copyright 2018 Proyectos y Sistemas de Mantenimiento SL (eProsima).
    //
    // Licensed under the Apache License, Version 2.0 (the "License");
    // you may not use this file except in compliance with the License.
    // You may obtain a copy of the License at
    //
    //     http://www.apache.org/licenses/LICENSE-2.0
    //
    // Unless required by applicable law or agreed to in writing, software
    // distributed under the License is distributed on an "AS IS" BASIS,
    // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
    // See the License for the specific language governing permissions and
    // limitations under the License.
    
    #include <Arduino.h>
    #include <WiFiEsp.h>
    #include <Ethernet.h>
    #include <stdio.h>
    #include <string.h>
    #include <stdlib.h>
    #include <limits.h>
    
    #include "ros2_msg/Ros2String.h"
    
    #include <uxr/client/client.h>
    #include <ucdr/microcdr.h>
    
    extern "C" {
    #include <FreeRTOS.h>
    #include <task.h>
    }
    #include <JointState.h>
    
    // Micro-XRCE-DDS-Client key identifier of the client.
    // If multiple clients connect to the same agent, each client must have a different key.
    #define CLIENT_KEY      0xCCCCDDD1
    
    #define BUFFER_SIZE     UXR_CONFIG_UDP_TRANSPORT_MTU
    
    char ssid[] = "elecom2g01-45ea1e";                 // your network SSID (name)
    char pass[] = "renerene";             // your network password
    int status = WL_IDLE_STATUS;          // the Wifi radio's status
    byte mac[] = { 0x74, 0x90, 0x50, 0x00, 0x79, 0x03 };
    IPAddress ip(192, 168, 2, 52);
    
    uxrSession session;
    uxrUDPTransport transport;
    uxrUDPPlatform udp_platform;
    uxrStreamId output_stream;
    uxrStreamId input_stream;
    static char agent_ip[32] = {0};
    
    uint8_t output_best_effort_stream_buffer[BUFFER_SIZE];
    uint8_t input_best_effort_stream_buffer[BUFFER_SIZE];
    
    static bool use_ethernet = false;
    
    void on_topic(uxrSession* session, uxrObjectId object_id, uint16_t request_id, uxrStreamId stream_id, struct ucdrBuffer* mb, void* args);
    void on_agent_found(const uxrAgentAddress* address, void* args);
    static void prvUXRManagerTask(void * pvParameters);
    
    void setup() {
        // Initialize the LED pin
        pinMode(PIN_LED1, OUTPUT);
    
        if(!use_ethernet)
        {
            // initialize serial for debugging
            Serial.begin(115200);
            // initialize serial for ESP module
            Serial6.begin(115200);
            // initialize ESP module
            WiFi.init(&Serial6);
        }
        else
        {
            // Serial output to USB
            Serial.begin(9600);
        }
    
        if(!use_ethernet)
        {
            // check for the presence of the shield
            if (WiFi.status() == WL_NO_SHIELD) {
                Serial.println("WiFi shield not present");
                // don't continue
                while (true);
            }
            // attempt to connect to WiFi network
            while ( status != WL_CONNECTED) {
                Serial.print("Attempting to connect to WPA SSID: ");
                Serial.println(ssid);
                // Connect to WPA/WPA2 network
                status = WiFi.begin(ssid, pass);
            }
        }
        else
        {
            // Setting IP
            Ethernet.begin(mac, ip);
        }
    
        // Wait for network configuration
        vTaskDelay(5000);
    
        // Discovery Agent
        Serial.println("Discovery Agent...");
        uxrAgentAddress chosen;
        chosen.ip = agent_ip;
    
        // Choose Ethernet or WiFi
        uxr_discovery_choose_ethernet(use_ethernet);
    
        // Try forever until Agent is found
        uxr_discovery_agents_default(INT_MAX, 1000, on_agent_found, &chosen);
    
        Serial.print("Chosen agent => ip: ");
        Serial.print(chosen.ip);
        Serial.print(", port: ");
        Serial.println(chosen.port);
    
        // Transport
        udp_platform.use_ethernet = use_ethernet;
        if (!uxr_init_udp_transport(&transport, &udp_platform, chosen.ip, chosen.port))
        {
            Serial.println("Error at create transport.");
            return;
        }
    
        // Session
        uxr_init_session(&session, &transport.comm, CLIENT_KEY);
        uxr_set_topic_callback(&session, on_topic, NULL);
        if (!uxr_create_session(&session))
        {
            Serial.println("Error at create session.");
            return;
        }
    
        // Streams
        output_stream = uxr_create_output_best_effort_stream(&session, output_best_effort_stream_buffer, BUFFER_SIZE);
        input_stream = uxr_create_input_best_effort_stream(&session);
    
        // Create entities
        uxrObjectId participant_id = uxr_object_id(0x01, UXR_PARTICIPANT_ID);
        const char* participant_xml = "<dds>"
                                          "<participant>"
                                              "<rtps>"
                                                  "<name>default_xrce_participant</name>"
                                              "</rtps>"
                                          "</participant>"
                                      "</dds>";
        uint16_t participant_req = uxr_buffer_create_participant_xml(&session, output_stream, participant_id, 0, participant_xml, UXR_REPLACE);
    
        // In order to avoid buffer overflow, uxr_flash_output_streams() has to be
        // called everytime entities message is created.
        (void) uxr_flash_output_streams(&session);
    
        uxrObjectId topic_id = uxr_object_id(0x01, UXR_TOPIC_ID);
        const char* topic_xml = "<dds>"
                                    "<topic>"
                                        "<name>rt/joint_states</name>"
                                        "<dataType>sensor_msgs::msg::dds_::JointState_</dataType>"
                                    "</topic>"
                                "</dds>";
        uint16_t topic_req = uxr_buffer_create_topic_xml(&session, output_stream, topic_id, participant_id, topic_xml, UXR_REPLACE);
    
        // In order to avoid buffer overflow, uxr_flash_output_streams() has to be
        // called everytime entities message is created.
        (void) uxr_flash_output_streams(&session);
    
        uxrObjectId subscriber_id = uxr_object_id(0x01, UXR_SUBSCRIBER_ID);
        const char* subscriber_xml = "";
        uint16_t subscriber_req = uxr_buffer_create_subscriber_xml(&session, output_stream, subscriber_id, participant_id, subscriber_xml, UXR_REPLACE);
    
        // In order to avoid buffer overflow, uxr_flash_output_streams() has to be
        // called everytime entities message is created.
        (void) uxr_flash_output_streams(&session);
    
        uxrObjectId datareader_id = uxr_object_id(0x01, UXR_DATAREADER_ID);
        const char* datareader_xml = "<dds>"
                                         "<data_reader>"
                                             "<topic>"
                                                 "<kind>NO_KEY</kind>"
                                                 "<name>rt/joint_states</name>"
                                                 "<dataType>sensor_msgs::msg::dds_::JointState_</dataType>"
                                             "</topic>"
                                         "</data_reader>"
                                     "</dds>";
        uint16_t datareader_req = uxr_buffer_create_datareader_xml(&session, output_stream, datareader_id, subscriber_id, datareader_xml, UXR_REPLACE);
    
        // In order to avoid buffer overflow, uxr_flash_output_streams() has to be
        // called everytime entities message is created.
        (void) uxr_flash_output_streams(&session);
    
        // Request topics
        uxrDeliveryControl delivery_control = {0};
        delivery_control.max_samples = UXR_MAX_SAMPLES_UNLIMITED;
        (void) uxr_buffer_request_data(&session, output_stream, datareader_id, input_stream, &delivery_control);
    
        xTaskCreate(prvUXRManagerTask, "ListenerDemo", configMINIMAL_STACK_SIZE * 5, NULL, 2, NULL);
    }
    
    void loop() {
        // Do nothing
        vTaskDelay(10000);
    }
    
    void on_topic(uxrSession* session, uxrObjectId object_id, uint16_t request_id, uxrStreamId stream_id, struct ucdrBuffer* mb, void* args) {
        (void) session; (void) object_id; (void) request_id; (void) stream_id;
    
        JointState topic;
        JointState_deserialize_topic(mb, &topic);
    
        Serial.println("Received topic: ");
        for(int i = 0; i < topic.position_size; i++){
            Serial.print((char*)topic.name[i]);
            Serial.print("\t");
            Serial.print(topic.position[i]);
            Serial.println();
        }
    
        // Toggle the heartbeat LED
        digitalWrite(PIN_LED1, !digitalRead(PIN_LED1));
    }
    
    void on_agent_found(const uxrAgentAddress* address, void* args) {
        uxrAgentAddress* agent = (uxrAgentAddress*)args;
    
        Serial.print("Found agent => ip: ");
        Serial.print(address->ip);
        Serial.print(", port: ");
        Serial.println(address->port);
    
        memcpy((void*)(agent->ip), address->ip, 32);
        agent->port = address->port;
    }
    
    static void prvUXRManagerTask(void * pvParameters) {
        // Cannot confirm whether client is connected to agent or not.
        while (1)
        {
            // Receive topics
            (void) uxr_run_session_time(&session, 1);
    
            vTaskDelay(1);
        }
    
        // Delete resources
        (void) uxr_delete_session(&session);
        (void) uxr_close_udp_transport(&transport);
    
        // Delete this task
        vTaskDelete(NULL);
    }
    

    rose_ros2_joy.txt
    // Copyright 2018 eSOL Co.,Ltd.
    // Copyright 2018 Proyectos y Sistemas de Mantenimiento SL (eProsima).
    //
    // Licensed under the Apache License, Version 2.0 (the "License");
    // you may not use this file except in compliance with the License.
    // You may obtain a copy of the License at
    //
    //     http://www.apache.org/licenses/LICENSE-2.0
    //
    // Unless required by applicable law or agreed to in writing, software
    // distributed under the License is distributed on an "AS IS" BASIS,
    // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
    // See the License for the specific language governing permissions and
    // limitations under the License.
    
    #include <Arduino.h>
    #include <Ethernet.h>
    #include <stdio.h>
    #include <string.h>
    #include <stdlib.h>
    #include <limits.h>
    
    #include "ros2_msg/Ros2String.h"
    
    #include <uxr/client/client.h>
    #include <ucdr/microcdr.h>
    
    extern "C" {
    #include <FreeRTOS.h>
    #include <task.h>
    #include "queue.h"
    }
    #include "aws_logging_task.h"
    
    #include "Joy.h"
    
    // Micro-XRCE-DDS-Client key identifier of the client.
    // If multiple clients connect to the same agent, each client must have a different key.
    #define CLIENT_KEY      0xCCCCDDDD
    
    #define BUFFER_SIZE     UXR_CONFIG_TCP_TRANSPORT_MTU
    
    byte mac[] = { 0x74, 0x90, 0x50, 0x00, 0x79, 0x03 };
    IPAddress ip(192, 168, 0, 52);
    
    uxrSession session;
    uxrTCPTransport transport;
    uxrTCPPlatform tcp_platform;
    uxrStreamId output_stream;
    uxrStreamId input_stream;
    
    uint8_t output_best_effort_stream_buffer[BUFFER_SIZE];
    uint8_t input_best_effort_stream_buffer[BUFFER_SIZE];
    
    void on_topic(uxrSession* session, uxrObjectId object_id, uint16_t request_id, uxrStreamId stream_id, struct ucdrBuffer* mb, void* args);
    bool on_agent_found(const uxrAgentAddress* address, int64_t timestamp, void* args);
    static void prvUXRManagerTask(void * pvParameters);
    
    void setup() {
        // Initialize the LED pin
        pinMode(PIN_LED1, OUTPUT);
    
        // Serial output to USB
        Serial.begin(9600);
        xLoggingTaskInitialize(512 * 6,	tskIDLE_PRIORITY, 15);
    
        Ethernet.begin(mac, ip);
    	delay(100);
    
        // Discovery Agent
        Serial.println("Discovery Agent...");
        uxrAgentAddress chosen;
    
        // Try forever until Agent is found
        (void) uxr_discovery_agents_multicast(INT_MAX, 1000, on_agent_found, NULL, &chosen);
    
        Serial.print("Chosen agent => ip: ");
        Serial.print(chosen.ip);
        Serial.print(", port: ");
        Serial.println(chosen.port);
    
        // Transport
        if (!uxr_init_tcp_transport(&transport, &tcp_platform, chosen.ip, chosen.port))
        {
            Serial.println("Error at create transport.");
            return;
        }
    
        // Session
        uxr_init_session(&session, &transport.comm, CLIENT_KEY);
        uxr_set_topic_callback(&session, on_topic, NULL);
        if (!uxr_create_session(&session))
        {
            Serial.println("Error at create session.");
            return;
        }
    
        // Streams
        output_stream = uxr_create_output_best_effort_stream(&session, output_best_effort_stream_buffer, BUFFER_SIZE);
        input_stream = uxr_create_input_best_effort_stream(&session);
    
        // Create entities
        uxrObjectId participant_id = uxr_object_id(0x01, UXR_PARTICIPANT_ID);
        const char* participant_xml = "<dds>"
                                          "<participant>"
                                              "<rtps>"
                                                  "<name>default_xrce_participant</name>"
                                              "</rtps>"
                                          "</participant>"
                                      "</dds>";
        uint16_t participant_req = uxr_buffer_create_participant_xml(&session, output_stream, participant_id, 0, participant_xml, UXR_REPLACE);
    
        // In order to avoid buffer overflow, uxr_flash_output_streams() has to be
        // called everytime entities message is created.
        (void) uxr_flash_output_streams(&session);
    
        uxrObjectId topic_id = uxr_object_id(0x01, UXR_TOPIC_ID);
        const char* topic_xml = "<dds>"
                                    "<topic>"
                                        "<name>rt/joy</name>"
                                        "<dataType>sensor_msgs::msg::dds_::Joy_</dataType>"
                                    "</topic>"
                                "</dds>";
        uint16_t topic_req = uxr_buffer_create_topic_xml(&session, output_stream, topic_id, participant_id, topic_xml, UXR_REPLACE);
    
        // In order to avoid buffer overflow, uxr_flash_output_streams() has to be
        // called everytime entities message is created.
        (void) uxr_flash_output_streams(&session);
    
        uxrObjectId subscriber_id = uxr_object_id(0x01, UXR_SUBSCRIBER_ID);
        const char* subscriber_xml = "";
        uint16_t subscriber_req = uxr_buffer_create_subscriber_xml(&session, output_stream, subscriber_id, participant_id, subscriber_xml, UXR_REPLACE);
    
        // In order to avoid buffer overflow, uxr_flash_output_streams() has to be
        // called everytime entities message is created.
        (void) uxr_flash_output_streams(&session);
    
        uxrObjectId datareader_id = uxr_object_id(0x01, UXR_DATAREADER_ID);
        const char* datareader_xml = "<dds>"
                                         "<data_reader>"
                                             "<topic>"
                                                 "<kind>NO_KEY</kind>"
                                                 "<name>rt/joy</name>"
                "<dataType>sensor_msgs::msg::dds_::Joy_</dataType>"
                                             "</topic>"
                                         "</data_reader>"
                                     "</dds>";
        uint16_t datareader_req = uxr_buffer_create_datareader_xml(&session, output_stream, datareader_id, subscriber_id, datareader_xml, UXR_REPLACE);
    
        // In order to avoid buffer overflow, uxr_flash_output_streams() has to be
        // called everytime entities message is created.
        (void) uxr_flash_output_streams(&session);
    
        // Request topics
        uxrDeliveryControl delivery_control = {0};
        delivery_control.max_samples = UXR_MAX_SAMPLES_UNLIMITED;
        (void) uxr_buffer_request_data(&session, output_stream, datareader_id, input_stream, &delivery_control);
    
        xTaskCreate(prvUXRManagerTask, "ListenerDemo", configMINIMAL_STACK_SIZE * 5, NULL, 2, NULL);
    }
    
    void loop() {
        // Do nothing
        vTaskDelay(10000);
    }
    
    void on_topic(uxrSession* session, uxrObjectId object_id, uint16_t request_id, uxrStreamId stream_id, struct ucdrBuffer* mb, void* args) {
        (void) session; (void) object_id; (void) request_id; (void) stream_id;
    
        Joy topic;
        Joy_deserialize_topic(mb, &topic);
    
        Serial.println("Received topic: ");
        Serial.println(topic.header.frame_id);
        Serial.println(topic.header.stamp.sec);
        Serial.println(topic.header.stamp.nanosec);
        for(int i = 0; i < 8; i++){
            Serial.print(topic.axes[i]);
        	Serial.print(" ");
        }
        Serial.println();
        for(int i = 0; i < 11; i++){
            Serial.print(topic.buttons[i]);
        	Serial.print(" ");
        }
        Serial.println();
    
        // Toggle the heartbeat LED
        digitalWrite(PIN_LED1, !digitalRead(PIN_LED1));
    }
    
    bool on_agent_found(const uxrAgentAddress* address, int64_t timestamp, void* args) {
        (void) timestamp; (void) args;
    
        Serial.print("Found agent => ip: ");
        Serial.print(address->ip);
        Serial.print(", port: ");
        Serial.println(address->port);
        return true;
    }
    
    static void prvUXRManagerTask(void * pvParameters) {
        // Cannot confirm whether client is connected to agent or not.
        while (1)
        {
            // Receive topics
            (void) uxr_run_session_time(&session, 1);
    
            vTaskDelay(1);
        }
    
        // Delete resources
        (void) uxr_delete_session(&session);
        (void) uxr_close_tcp_transport(&transport);
    
        // Delete this task
        vTaskDelete(NULL);
    }
    

    • Cancel
    • Up 0 Down
    • Reply
    • Verify Answer
    • Cancel
  • Habanero
    0 Habanero over 1 year ago in reply to Okamiya Yuuki

    早速のご返事、ありがとうございます。

    丁度私もJoyノードを使用して試していた所でした。参考にいたします。

    また、Lixun上のみでサービス通信を行うテストを行った場合は、srv_testディレクトリを作成し、srv_test/original_message/srv/test.msgとして、独自のサービス用メッセージ(実数型a,bをリクエストして、sumをレスポンスするだけの簡単なものです)をoriginal_messageパッケージとして作成、これをインクルードファイルとしてsrv_test/my_srvディレクトリ内に、src/srv.cpp,src/clnt.cppを作成して、サービス通信を行っていました。

    xrce-dds-agentを通してGR-ROSEとサービス通信を行う場合はGR-Rose側にサーバーファイル、Linux側にクライアントファイルを置いたうえで、それぞれビルドすれば良いのでしょうか。

    サーバー通信についてもまだ完璧に理解しているとは言えず混乱しています。

    • Cancel
    • Up 0 Down
    • Reply
    • Verify Answer
    • Cancel
Reply
  • Habanero
    0 Habanero over 1 year ago in reply to Okamiya Yuuki

    早速のご返事、ありがとうございます。

    丁度私もJoyノードを使用して試していた所でした。参考にいたします。

    また、Lixun上のみでサービス通信を行うテストを行った場合は、srv_testディレクトリを作成し、srv_test/original_message/srv/test.msgとして、独自のサービス用メッセージ(実数型a,bをリクエストして、sumをレスポンスするだけの簡単なものです)をoriginal_messageパッケージとして作成、これをインクルードファイルとしてsrv_test/my_srvディレクトリ内に、src/srv.cpp,src/clnt.cppを作成して、サービス通信を行っていました。

    xrce-dds-agentを通してGR-ROSEとサービス通信を行う場合はGR-Rose側にサーバーファイル、Linux側にクライアントファイルを置いたうえで、それぞれビルドすれば良いのでしょうか。

    サーバー通信についてもまだ完璧に理解しているとは言えず混乱しています。

    • Cancel
    • Up 0 Down
    • Reply
    • Verify Answer
    • Cancel
Children
No Data
サイト使用条件
プライバシーポリシー
お問い合わせ
© 2010-2022 Renesas Electronics Corporation. All rights reserved.