From 9a4b6a38080ed656484cba906e1d85aa9f6c2a8a Mon Sep 17 00:00:00 2001 From: Mati-ur-rehman-017 Date: Wed, 2 Apr 2025 13:42:05 +0500 Subject: [PATCH] Documentation for Arrow cpp Functions --- .gitignore | 1 + package-lock.json | 4 +- package.json | 1 + static/cpp/cpp-api.html | 1204 +++++++++++++++++++++++---------------- 4 files changed, 709 insertions(+), 501 deletions(-) diff --git a/.gitignore b/.gitignore index 6b249e51..ecd4c678 100644 --- a/.gitignore +++ b/.gitignore @@ -19,5 +19,6 @@ npm-debug.log* yarn-debug.log* yarn-error.log* +yarn.lock .vscode diff --git a/package-lock.json b/package-lock.json index aaa6fc65..4588e130 100644 --- a/package-lock.json +++ b/package-lock.json @@ -15,6 +15,7 @@ "@docusaurus/theme-mermaid": "^3.2.0", "@docusaurus/theme-search-algolia": "^3.2.0", "@fontsource/work-sans": "^5.0.18", + "@popperjs/core": "^2.11.8", "apexcharts": "^3.40.0", "bootstrap-icons": "^1.10.5", "clsx": "^1.2.1", @@ -3089,8 +3090,7 @@ "version": "2.11.8", "resolved": "https://registry.npmjs.org/@popperjs/core/-/core-2.11.8.tgz", "integrity": "sha512-P1st0aksCrn9sGZhp8GMYwBnQsbvAWsZAX44oXNNvLHGqAOcoVxmjZiohstwQ7SqKnbR47akdNi+uleWD8+g6A==", - "dev": true, - "peer": true, + "license": "MIT", "funding": { "type": "opencollective", "url": "https://opencollective.com/popperjs" diff --git a/package.json b/package.json index db7d638b..026ea20f 100644 --- a/package.json +++ b/package.json @@ -27,6 +27,7 @@ "@docusaurus/theme-mermaid": "^3.2.0", "@docusaurus/theme-search-algolia": "^3.2.0", "@fontsource/work-sans": "^5.0.18", + "@popperjs/core": "^2.11.8", "apexcharts": "^3.40.0", "bootstrap-icons": "^1.10.5", "clsx": "^1.2.1", diff --git a/static/cpp/cpp-api.html b/static/cpp/cpp-api.html index 67e1f5e5..966aca75 100644 --- a/static/cpp/cpp-api.html +++ b/static/cpp/cpp-api.html @@ -1,283 +1,321 @@ - - - - - dora.c++ API Documentation - - - - - - - - - - - - - - -
- -
- - - - - - -
-
- API Documentation   + + + + + dora.c++ API Documentation + + + + + + + + + + + + + + +
+ +
+ + + + + + +
+
+ API Documentation   +
+
+
+ + + + + + + +
+ +
-
- - - - - - - -
- -
- -
-
- - -
- -
+ +
+ +
- -
- -
+ +
+ +
-
-
- This documentation is experimental and is not yet linked with the - source code. Be aware of any error within this documentation. For - more: https://github.com/dora-rs/dora/pull/611 -
+
+
+ This documentation is experimental and is not yet linked + with the source code. Be aware of any error within this + documentation. For more: + https://github.com/dora-rs/dora/pull/611 +
-

Interface Documentation

-
-

dora-node-api.h

-
-

Functions

-
-
Init Dora Node
-
- All nodes need to register themselves with Dora at startup. To - do that, call the init_dora_node() function. The - function returns a DoraNode instance, which gives - access to dora events and enables sending Dora outputs. -
-
-

+                

Interface Documentation

+
+

dora-node-api.h

+
+

Functions

+
+
Init Dora Node
+
+ All nodes need to register themselves with Dora + at startup. To do that, call the + init_dora_node() function. The + function returns a + DoraNode instance, which gives + access to dora events and enables sending Dora + outputs. +
+
+

 auto dora_node = init_dora_node();
 
-
+
-
Receiving Events
-
- The dora_node.events field is a stream of incoming - events. To wait for the next incoming event, call - dora_node.events->next(): -
-

+                            
+ Receiving Events +
+
+ The dora_node.events field is a + stream of incoming events. To wait for the next + incoming event, call + dora_node.events->next(): +
+

 auto event = dora_node.events->next();
     
-
- The next function returns an opaque - DoraEvent type, which cannot be inspected from C++ - directly. Instead, use the following functions to read and - destructure the event: -
-
-
    -
  • - event_type(event) returns a - DoraEventType, which describes the kind of - event. For example, an event could be an input or a stop - instruction. -
  • -
  • - When receiving a - DoraEventType::AllInputsClosed, the node should - exit and not call next anymore. -
  • -
  • - Events of type DoraEventType::Input can be - downcasted using event_as_input: -
    -
    
    +                                
    + The next function returns an opaque + DoraEvent type, which cannot be + inspected from C++ directly. Instead, use the + following functions to read and destructure the + event: +
+
+
    +
  • + event_type(event) returns a + DoraEventType, which + describes the kind of event. For + example, an event could be an input or a + stop instruction. +
  • +
  • + When receiving a + DoraEventType::AllInputsClosed, the node should exit and not call + next anymore. +
  • +
  • + Events of type + DoraEventType::Input can be + downcasted using + event_as_input: +
    +
    
     auto input = event_as_input(std::move(event));
                 
    -
    - The function returns a DoraInput instance, - which has an id and data field. -
  • -
  • - The input id can be converted to a C++ string - through std::string(input.id). -
  • -
  • - The data of inputs is currently of type - rust::Vec<uint8_t>. Use the provided - methods for reading or converting the data. -
  • -
  • - Note: In the future, we plan to change the data type to the - Apache Arrow data format to support typed inputs. -
  • -
-
+
+ The function returns a + DoraInput instance, which + has an id and + data field. + +
  • + The input id can be + converted to a C++ string through + std::string(input.id). +
  • +
  • + The data of inputs is currently of type + rust::Vec<uint8_t>. + Use the provided methods for reading or + converting the data. +
  • +
  • + Note: For sending more datatypes, use Arrow api functions as described in Arrow section. +
  • + +
    -
    Sending Outputs
    -
    - Nodes can send outputs using the - send_output function and the - dora_node.send_output field. Note that all outputs - need to be listed in the dataflow YAML declaration file, - otherwise an error will occur. -
    -
    - Example: -
    -
    
    +                            
    Sending Outputs
    +
    + Nodes can send outputs using the + send_output function and the + dora_node.send_output field. Note + that all outputs need to be listed in the + dataflow YAML declaration file, otherwise an + error will occur. +
    +
    + Example: +
    +
    
     // the data you want to send (NOTE: only byte vectors are supported right now)
     std::vector<uint8_t> out_vec{42};
     // create a Rust slice from the output vector
    @@ -293,179 +331,326 @@ 

    Functions

    return -1; }
    -
    -
    +
    +
    + + +
    + Using Arrow for I/O +
    +
    +

    To use Arrow with Dora, you'll need to include the Arrow headers:

    +
    
    +#include <arrow/api.h>
    +#include <arrow/c/bridge.h>
    +                            
    +
    + +
    +

    Receiving Arrow Data

    +

    After receiving events of type DoraEventType::Input, we can downcast using event_as_arrow_input. We need to pass two pointers to receive results in them which can be imported using the Arrow C Data Interface.

    +
    +
    
    +auto event = dora_node.events->next();
    +auto type = event_type(event);
    +if(type == DoraEventType::Input)
    +{
    +    struct ArrowArray c_array;
    +    struct ArrowSchema c_schema;
    +
    +    auto result = event_as_arrow_input(
    +    std::move(event),
    +    reinterpret_cast(&c_array),
    +    reinterpret_cast(&c_schema)
    +    );
     
    -              
    Using the ROS2 Bridge
    -
    - The dora-ros2-bindings.h contains function and - struct definitions that allow interacting with ROS2 nodes. - Currently, the bridge supports publishing and subscribing to - ROS2 topics. In the future, we plan to support ROS2 services and - ROS2 actions as well. -
    + if (!result.error.empty()) { + std::cerr << "Error getting Arrow array: " << result.error << std::endl; + return -1; + } + + auto result2 = arrow::ImportArray(&c_array, &c_schema); + if (!result2.ok()) { + std::cerr << "Error importing Arrow array: " << result2.status().ToString() << std::endl; + return -1; + } + std::shared_ptr input_array = result2.ValueOrDie(); -
    - Initializing the ROS2 - Context -
    -
    - The first step is to initialize a ROS2 context: -
    -
    
    +    // Now you can use input_array with Arrow's API
    +}
    +                            
    +
    +
    + +
    +

    Sending Arrow Data

    +

    Nodes can send outputs using send_arrow_output. To do this, the data must first be converted to the Arrow format and then sent using the provided function. This uses the Arrow C Data interface and supports all types from the Arrow C Data Interface.

    +
    +
    
    +// Create an Arrow array
    +std::shared_ptr output_array;
    +
    +arrow::Int32Builder builder;
    +builder.Append(10);
    +builder.Append(100);
    +builder.Append(1000);
    +builder.Finish(&output_array);
    +
    +// Export it to C Data Interface
    +struct ArrowArray out_c_array;
    +struct ArrowSchema out_c_schema;
    +
    +arrow::ExportArray(*output_array, &out_c_array, &out_c_schema);
    +
    +// Send it as output
    +auto send_result = send_arrow_output(
    +    dora_node.send_output,
    +    "counter",
    +    reinterpret_cast(&out_c_array),
    +    reinterpret_cast(&out_c_schema)
    +);
    +
    +// Check for errors
    +auto error = std::string(send_result.error);
    +if (!error.empty())
    +{
    +    std::cerr << "Error sending Arrow output: " << error << std::endl;
    +    return -1;
    +}
    +                            
    +
    +
    + +
    +

    For a complete working example using Arrow with Dora, see the C++ Arrow dataflow example in the Dora repository.

    +
    +
    + Using the ROS2 + Bridge +
    +
    + The dora-ros2-bindings.h contains + function and struct definitions that allow + interacting with ROS2 nodes. Currently, the + bridge supports publishing and subscribing to + ROS2 topics. In the future, we plan to support + ROS2 services and ROS2 actions as well. +
    + +
    + Initializing the ROS2 Context +
    +
    + The first step is to initialize a ROS2 context: +
    +
    
     auto ros2_context = init_ros2_context();
         
    -
    -
    +
    +
    +
    + Using the ROS2 + Bridge +
    +
    + The dora-ros2-bindings.h contains + function and struct definitions that allow + interacting with ROS2 nodes. Currently, the + bridge supports publishing and subscribing to + ROS2 topics. In the future, we plan to support + ROS2 services and ROS2 actions as well. +
    + +
    + Initializing the ROS2 Context +
    +
    + The first step is to initialize a ROS2 context: +
    +
    
    +auto ros2_context = init_ros2_context();
    +    
    +
    +
    -
    Creating Nodes
    -
    - After initializing a ROS2 context, you can use it to create ROS2 - nodes: -
    -
    
    +                            
    Creating Nodes
    +
    + After initializing a ROS2 context, you can use + it to create ROS2 nodes: +
    +
    
     auto node = ros2_context->new_node("/ros2_demo", "turtle_teleop");
         
    -
    - The first argument is the namespace of the node and the second - argument is its name. -
    +
    + The first argument is the namespace of the node + and the second argument is its name. +
    -
    Creating Topics
    -
    - After creating a node, you can use one of the - create_topic_<TYPE> functions to create a - topic on it. The <TYPE> describes the message - type that will be sent on the topic. The Dora ROS2 bridge - automatically creates - create_topic_<TYPE> functions for all message - types found in the sourced ROS2 environment. -
    -
    
    +                            
    Creating Topics
    +
    + After creating a node, you can use one of the + create_topic_<TYPE> functions + to create a topic on it. The + <TYPE> describes the message + type that will be sent on the topic. The Dora + ROS2 bridge automatically creates + create_topic_<TYPE> functions + for all message types found in the sourced ROS2 + environment. +
    +
    
     auto vel_topic = node->create_topic_geometry_msgs_Twist("/turtle1", "cmd_vel", qos_default());
         
    -
    - The first argument is the namespace of the topic and the second - argument is its name. The third argument is the QoS (quality of - service) setting for the topic. It can be adjusted as desired, - for example: -
    -
    
    +                                
    + The first argument is the namespace of the topic + and the second argument is its name. The third + argument is the QoS (quality of service) setting + for the topic. It can be adjusted as desired, + for example: +
    +
    
     auto qos = qos_default();
     qos.durability = Ros2Durability::Volatile;
     qos.liveliness = Ros2Liveliness::Automatic;
     auto vel_topic = node->create_topic_geometry_msgs_Twist("/turtle1", "cmd_vel", qos);
         
    -
    -
    +
    +
    -
    Publish
    -
    - After creating a topic, it is possible to publish messages on - it. First, create a publisher: -
    -
    
    +                            
    Publish
    +
    + After creating a topic, it is possible to + publish messages on it. First, create a + publisher: +
    +
    
     auto vel_publisher = node->create_publisher(vel_topic, qos);
         
    -
    - The returned publisher is typed by the chosen topic. It will - only accept messages of the topic's type, otherwise a compile - error will occur. After creating a publisher, you can use the - publish function to publish one or more messages. - For example: -
    -
    
    +                                
    + The returned publisher is typed by the chosen + topic. It will only accept messages of the + topic's type, otherwise a compile error will + occur. After creating a publisher, you can use + the + publish function to publish one or + more messages. For example: +
    +
    
     geometry_msgs::Twist twist = {
         .linear = {.x = 1, .y = 0, .z = 0},
         .angular = {.x = 0, .y = 0, .z = 0.5}
     };
     vel_publisher->publish(twist);
         
    -
    - The geometry_msgs::Twist struct is automatically - generated from the sourced ROS2 environment. Since the publisher - is typed, its publish method only accepts - geometry_msgs::Twist messages. -
    +
    + The geometry_msgs::Twist struct is + automatically generated from the sourced ROS2 + environment. Since the publisher is typed, its + publish method only accepts + geometry_msgs::Twist messages. +
    -
    Subscriptions
    -
    - Subscribing to a topic is possible through the - create_subscription function on nodes: -
    -
    
    +                            
    Subscriptions
    +
    + Subscribing to a topic is possible through the + create_subscription function on + nodes: +
    +
    
     auto pose_topic = node->create_topic_turtlesim_Pose("/turtle1", "pose", qos_default());
     auto pose_subscription = node->create_subscription(pose_topic, qos_default(), event_stream);
         
    -
    - The topic is the topic you want to subscribe to, created using a - create_topic_<TYPE> function. The second - argument is the quality of service setting, which can be - customized as described above. The third parameter is the event - stream that the received messages should be merged into. - Multiple subscriptions can be merged into the same event stream. -
    +
    + The topic is the topic you want to subscribe to, + created using a + create_topic_<TYPE> function. + The second argument is the quality of service + setting, which can be customized as described + above. The third parameter is the event stream + that the received messages should be merged + into. Multiple subscriptions can be merged into + the same event stream. +
    -
    Combined Event Streams
    -
    - Combined event streams enable the merging of multiple event - streams into one. The combined stream will then deliver messages - from all sources, in order of arrival. You can create such an - event stream from Dora's event stream using the - dora_events_into_combined function: -
    -
    
    +                            
    + Combined + Event Streams +
    +
    + Combined event streams enable the merging of + multiple event streams into one. The combined + stream will then deliver messages from all + sources, in order of arrival. You can create + such an event stream from Dora's event stream + using the + dora_events_into_combined function: +
    +
    
     auto event_stream = dora_events_into_combined(std::move(dora_node.events));
         
    -
    - Alternatively, if you don't want to use Dora, you can also - create an empty event stream: -
    -
    
    +                                
    + Alternatively, if you don't want to use Dora, + you can also create an empty event stream: +
    +
    
     auto event_stream = empty_combined_events();
         
    -
    - Note: You should only use empty_combined_events if - you're running your executable independent of Dora. Ignoring the - events from the dora_node.events channel can result - in unintended behavior. -
    +
    + Note: You should only use + empty_combined_events if you're + running your executable independent of Dora. + Ignoring the events from the + dora_node.events channel can result + in unintended behavior. +
    -
    - Receiving Messages from Combined Event Stream -
    -
    - The merged event stream will receive all incoming events of the - node, including Dora events and ROS2 messages. To wait for the - next incoming event, use its next method: -
    -
    
    +                            
    + Receiving Messages from Combined Event Stream +
    +
    + The merged event stream will receive all + incoming events of the node, including Dora + events and ROS2 messages. To wait for the next + incoming event, use its + next method: +
    +
    
     auto event = event_stream.next();
         
    -
    - This returns an event instance of type - CombinedEvent, which can be downcasted to Dora - events or ROS2 messages. To handle an event, you should check - its type and then downcast it: -
      -
    • - To check for a Dora event, you can use the - is_dora() function. If it returns true, you can - downcast the combined event to a Dora event using the - downcast_dora function. -
    • -
    • - ROS2 subscriptions support a matches function - to check whether a combined event is an instance of the - respective ROS2 subscription. If it returns true, you can - downcast the event to the respective ROS2 message struct - using the subscription's downcast function. -
    • -
    - Example: -
    -
    
    +                                
    + This returns an event instance of type + CombinedEvent, which can be + downcasted to Dora events or ROS2 messages. To + handle an event, you should check its type and + then downcast it: +
      +
    • + To check for a Dora event, you can use + the + is_dora() function. If it + returns true, you can downcast the + combined event to a Dora event using the + downcast_dora function. +
    • +
    • + ROS2 subscriptions support a + matches function to check + whether a combined event is an instance + of the respective ROS2 subscription. If + it returns true, you can downcast the + event to the respective ROS2 message + struct using the subscription's + downcast function. +
    • +
    + Example: +
    +
    
     if (event.is_dora())
     {
         auto dora_event = downcast_dora(std::move(event));
    @@ -488,36 +673,42 @@ 

    Functions

    std::cout << "received unexpected event" << std::endl; }
    -
    -
    +
    +
    -
    Constants
    -
    - Some ROS2 message definitions define constants, e.g., to specify - the values of an enum-like integer field. The Dora ROS2 bridge - exposes these constants in the generated bindings as functions. - For example, the STATUS_NO_FIX constant of the - NavSatStatus message can be accessed as follows: -
    -
    
    +                            
    Constants
    +
    + Some ROS2 message definitions define constants, + e.g., to specify the values of an enum-like + integer field. The Dora ROS2 bridge exposes + these constants in the generated bindings as + functions. For example, the + STATUS_NO_FIX constant of the + NavSatStatus message can be + accessed as follows: +
    +
    
     assert((sensor_msgs::const_NavSatStatus_STATUS_NO_FIX() == -1));
         
    -
    - (Note: Exposing them as C++ constants is not possible because - it's not supported by cxx yet.) -
    +
    + (Note: Exposing them as C++ constants is not + possible because it's not supported by cxx yet.) +
    -
    Service Clients
    -
    - To create a service client, use one of the - create_client_<TYPE> functions. The - <TYPE> describes the service type, which - specifies the request and response types. The Dora ROS2 bridge - automatically creates - create_client_<TYPE> functions for all - service types found in the sourced ROS2 environment. -
    -
    
    +                            
    Service Clients
    +
    + To create a service client, use one of the + create_client_<TYPE> + functions. The + <TYPE> describes the service + type, which specifies the request and response + types. The Dora ROS2 bridge automatically + creates + create_client_<TYPE> + functions for all service types found in the + sourced ROS2 environment. +
    +
    
     auto add_two_ints = node->create_client_example_interfaces_AddTwoInts(
       "/",
       "add_two_ints",
    @@ -525,64 +716,79 @@ 

    Functions

    merged_events );
    -
    - The first argument is the namespace of the service and the - second argument is its name. The third argument is the QoS - (quality of service) setting for the service. It can be set to - qos_default() or adjusted as desired, for example: -
    -
    
    +                                
    + The first argument is the namespace of the + service and the second argument is its name. The + third argument is the QoS (quality of service) + setting for the service. It can be set to + qos_default() or adjusted as + desired, for example: +
    +
    
     auto qos = qos_default();
     qos.reliable = true;
     qos.max_blocking_time = 0.1;
     qos.keep_last = 1;
         
    -
    - The last argument is the combined event stream that the received - service responses should be merged into. -
    +
    + The last argument is the combined event stream + that the received service responses should be + merged into. +
    -
    - Waiting for the Service -
    -
    - In order to achieve reliable service communication, it is - recommended to wait until the service is available before - sending requests. Use the wait_for_service() method - for that, e.g.: -
    -
    
    +                            
    + Waiting for + the Service +
    +
    + In order to achieve reliable service + communication, it is recommended to wait until + the service is available before sending + requests. Use the + wait_for_service() method for that, + e.g.: +
    +
    
     add_two_ints->wait_for_service(node);
         
    -
    - The given node must be the node on which the service was - created. -
    +
    + The given node must be the node on which the + service was created. +
    -
    Sending Requests
    -
    - To send a request, use the send_request method: -
    -
    
    +                            
    + Sending Requests +
    +
    + To send a request, use the + send_request method: +
    +
    
     add_two_ints->send_request(request);
         
    -
    - The method sends the request asynchronously without waiting for - a response. When the response is received, it is automatically - sent to the combined event stream that was given on client - creation. -
    +
    + The method sends the request asynchronously + without waiting for a response. When the + response is received, it is automatically sent + to the combined event stream that was given on + client creation. +
    -
    Receiving Responses
    -
    - See the "Receiving Messages from Combined Event Stream" section - for how to receive events from the combined event stream. To - check if a received event is a service response, use the - matches method. If it returns true, you can use the - downcast method to convert the event to the correct - service response type. Example: -
    -
    
    +                            
    + Receiving + Responses +
    +
    + See the "Receiving Messages from Combined Event + Stream" section for how to receive events from + the combined event stream. To check if a + received event is a service response, use the + matches method. If it returns true, + you can use the downcast method to + convert the event to the correct service + response type. Example: +
    +
    
     if (add_two_ints->matches(event))
     {
         auto response = add_two_ints->downcast(std::move(event));
    @@ -590,31 +796,31 @@ 

    Functions

    ... }
    +
    +
    +
    +
    - - -
    +
    + +
    + + + -
    - - - - - - +