API Documentation
|
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();
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();
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.
DoraEventType::AllInputsClosed
, the node should exit and not call
next
anymore.
DoraEventType::Input
can be
downcasted using
event_as_input
:
auto input = event_as_input(std::move(event));
DoraInput
instance, which
has an id
and
data
field.
id
can be
converted to a C++ string through
std::string(input.id)
.
rust::Vec<uint8_t>
.
Use the provided methods for reading or
converting the data.
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.
// 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
rust::Slice<const uint8_t> out_slice{out_vec.data(), out_vec.size()};
// send the slice as output
auto result = send_output(dora_node.send_output, "output_id", out_slice);
// check for errors
auto error = std::string(result.error);
if (!error.empty())
{
std::cerr << "Error: " << error << std::endl;
return -1;
}
To use Arrow with Dora, you'll need to include the Arrow headers:
#include <arrow/api.h>
#include <arrow/c/bridge.h>
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)
);
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();
// Now you can use input_array with Arrow's API
}
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.
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.
auto ros2_context = init_ros2_context();
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.
auto ros2_context = init_ros2_context();
auto node = ros2_context->new_node("/ros2_demo", "turtle_teleop");
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());
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);
auto vel_publisher = node->create_publisher(vel_topic, qos);
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);
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.
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);
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.
dora_events_into_combined
function:
auto event_stream = dora_events_into_combined(std::move(dora_node.events));
auto event_stream = empty_combined_events();
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.
next
method:
auto event = event_stream.next();
CombinedEvent
, which can be
downcasted to Dora events or ROS2 messages. To
handle an event, you should check its type and
then downcast it:
is_dora()
function. If it
returns true, you can downcast the
combined event to a Dora event using the
downcast_dora
function.
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.
if (event.is_dora())
{
auto dora_event = downcast_dora(std::move(event));
// handle dora_event as described above
auto ty = event_type(dora_event);
if (ty == DoraEventType::Input)
{
auto input = event_as_input(std::move(dora_event));
// etc
}
// .. else if
}
else if (pose_subscription->matches(event))
{
auto pose = pose_subscription->downcast(std::move(event));
std::cout << "Received pose x:" << pose.x << ", y:" << pose.y << std::endl;
}
else
{
std::cout << "received unexpected event" << std::endl;
}
STATUS_NO_FIX
constant of the
NavSatStatus
message can be
accessed as follows:
assert((sensor_msgs::const_NavSatStatus_STATUS_NO_FIX() == -1));
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",
qos,
merged_events
);
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;
wait_for_service()
method for that,
e.g.:
add_two_ints->wait_for_service(node);
send_request
method:
add_two_ints->send_request(request);
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));
std::cout << "Received sum response with value " << response.sum << std::endl;
...
}