Are you sure you want to delete this task? Once this task is deleted, it cannot be recovered.
|
|
6 months ago | |
|---|---|---|
| .. | ||
| src | 6 months ago | |
| Cargo.toml | 6 months ago | |
| README.md | 1 year ago | |
| build.rs | 5 months ago | |
Dora supports nodes written in C++ through this API crate.
dora repository:
> git clone https://github.com/dora-rs/dora.git
> cd dora
dora-node-api-cxx package:
cargo build --package dora-node-api-cxx
dora-node-api.h and dora-node-api.cc files in the target/cxxbridge/dora-node-api-cxx directory.dora-node-api.h header file in your source file.dora-node-api.cc file to your compile and link steps.Dora features an experimental ROS2 Bridge that enables dora nodes to publish and subscribe to ROS2 topics.
To enable the bridge, use these steps:
dora repository (see above).dora-node-api-cxx package with the ros2-bridge feature enabled:
cargo build --package dora-node-api-cxx --features ros2-bridge
dora-node-api.h and dora-node-api.cc files, this will place a dora-ros2-bindings.h and a dora-ros2-bindings.cc file in the target/cxxbridge/dora-node-api-cxx directory.dora-node-api.h and the dora-ros2-bindings.h header files in your source file.dora-node-api.cc and dora-ros2-bindings.cc files to your compile and link steps.The dora-node-api.h header provides various functions to interact with Dora.
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();
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.
DoraEventType::AllInputsClosed, the node should exit and not call next anymoreDoraEventType::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.
id can be converted to a C++ string through std::string(input.id).data of inputs is currently of type rust::Vec<uint8_t>. Use the provided methods for reading or converting the data.
Nodes can send outputs using the send_output 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
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;
}
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.
The first step is to initialize a ROS2 context:
auto ros2_context = init_ros2_context();
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.
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 messages 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:
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);
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:
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.
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.
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 a 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:
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.
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 a event instance of type CombinedEvent, which can be downcasted to Dora events or ROS2 messages.
To handle an event, you should check it's 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.Example:
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;
}
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.)
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",
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;
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.
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.
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));
std::cout << "Received sum response with value " << response.sum << std::endl;
...
}
DORA (Dataflow-Oriented Robotic Architecture) is middleware designed to streamline and simplify the creation of AI-based robotic applications. It offers low latency, composable, and distributed datafl
Rust Python TOML Markdown C other