Hello World example using the CreOS SDK client library.
This example demonstrates how to use the CreOS SDK client library to interact with an Avular robot. Below you can find the full source code, including a CMakeLists.txt file that links the necessary libraries. You can also find a more detailed explanation of the code.
Source code
CMakeLists.txt
9find_package(creos_client REQUIRED)
14add_executable(creos_hello_world main.cpp)
17target_link_libraries(creos_hello_world PRIVATE creos::client)
main.cpp
13#include <creos/client.hpp>
27 if (
auto sensors_interface = client.sensors()) {
30 std::cout <<
"Received GNSS message: " << message.
augmentation << std::endl;
33 std::cerr <<
"The robot does not provide GNSS messages: " << e.
what() << std::endl;
35 std::cerr <<
"Failed to subscribe to GNSS messages: " << e.
what() << std::endl;
41 if (
auto power_management_interface = client.power_management()) {
43 power_management_interface->enterLowPowerMode();
45 std::cerr <<
"Failed to enter low power mode: " << e.
what() << std::endl;
48 std::cerr <<
"The robot does not support power management" << std::endl;
53 if (
auto setpoint_control_interface = client.setpoint_control()) {
60 setpoint_control_interface->publishVelocityCommand(message);
61 std::cout <<
"Sent command velocity message" << std::endl;
67 std::cerr <<
"The robot does not support setpoint control" << std::endl;
77 std::cerr <<
"Failed to connect to the robot: " << e.
what() << std::endl;
The client class.
Definition client.hpp:154
Connection error.
Definition errors.hpp:55
Exception class for the CreOS client library.
Definition errors.hpp:32
const char * what() const noexcept override
Returns the error message.
Definition errors.hpp:43
An error occurred while subscribing to data.
Definition errors.hpp:150
A part of the API is not supported by the connected robot.
Definition errors.hpp:120
The GNSS message contains the GNSS data of the robot.
Definition gnss.hpp:97
Augmentation augmentation
The augmentation of the GNSS sensor.
Definition gnss.hpp:140
The Twist message contains the linear and angular velocity of the robot.
Definition twist.hpp:27
Vector3d linear
Linear velocity of the robot in the world frame [m/s].
Definition twist.hpp:31
Vector3d angular
Angular velocity of the robot in the world frame [rad/s].
Definition twist.hpp:36
Explanation
At the top of the main.cpp file, we include the necessary headers for the example. Once the creos::client
library is linked to the executable, we can simply include the creos/client.hpp
header to start using the library. Our example also includes iostream
to print messages to the console.
13#include <creos/client.hpp>
14#include <iostream>
15
In the main
function, we create a creos::Client
object. This object is the main entry point for the CreOS SDK. Once created, the object immediately connects to the robot at the specified address. If the client fails to connect, it will throw a creos::ConnectionError.
19int main() {
20 try {
21
Once the client is connected, we can start interacting with the robot. In this example, we subscribe to the GNSS data source, we call a callable to put the robot in low-power mode, and we publish velocity commands to a data sink.
First, we subscribe to the GNSS data source. This data source is available through the sensors interface, using the subscribeToGnss() function. We first check whether the sensors interface is available, and then subscribe to the GNSS data source. Possible creos::UnsupportedError
s and creos::SubscriptionError
s thrown by the subscription call are printed to the console. We provide a callback function that will be called whenever new data is available. In this example, we simply print the received data to the console.
26
27 if (auto sensors_interface = client.sensors()) {
28 try {
30 std::cout <<
"Received GNSS message: " << message.
augmentation << std::endl;
31 });
33 std::cerr <<
"The robot does not provide GNSS messages: " << e.
what() << std::endl;
35 std::cerr <<
"Failed to subscribe to GNSS messages: " << e.
what() << std::endl;
36 }
37 }
Next, we call a callable to put the robot in low-power mode. This callable is available through the power management interface as enterLowPowerMode(). Before we call the callable, we first check whether the power management interface is available. This callable does not return a value, but throws a creos::Exception if the transition to low-power mode fails. Here, we simply print the exception message to the console.
41 if (auto power_management_interface = client.power_management()) {
42 try {
43 power_management_interface->enterLowPowerMode();
45 std::cerr <<
"Failed to enter low power mode: " << e.
what() << std::endl;
46 }
47 } else {
48 std::cerr << "The robot does not support power management" << std::endl;
49 }
After the low-power mode request completes (or fails), we check whether the setpoint control interface is available. If it is, we start publishing velocity commands to the robot in an infinite loop. This data sink is available through the setpoint control interface, using the publishVelocityCommand() function. This data sink accepts creos_messages::Twist messages. We first create a message with a linear velocity of 0.5 m/s along the x-axis, as well as an angular velocity of 0.5 rad/s around the z-axis. Then we publish this message to the robot, print a message to the console, and sleep for 1 second.
53 if (auto setpoint_control_interface = client.setpoint_control()) {
54
55 while (true) {
56
60 setpoint_control_interface->publishVelocityCommand(message);
61 std::cout << "Sent command velocity message" << std::endl;
62
63
64 usleep(1000000);
65 }
66 } else {
67 std::cerr << "The robot does not support setpoint control" << std::endl;
68
69
70 while (true) {
71 usleep(1000000);
72 }
73 }