Hello World example using ROS2 in C++ to communicate with the CreOS SDK ROS2 node.
This example demonstrates how to use ROS2 in C++ to communicate with the CreOS SDK ROS2 node. 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(rclcpp REQUIRED)
10find_package(sensor_msgs REQUIRED)
11find_package(ament_cmake REQUIRED)
12find_package(geometry_msgs REQUIRED)
15find_package(creos_sdk_msgs REQUIRED)
20add_executable(creos_hello_world_ros main.cpp)
24ament_target_dependencies(creos_hello_world_ros
main.cpp
13#include <rclcpp/rclcpp.hpp>
24class HelloWorldNode :
public rclcpp::Node {
26 HelloWorldNode() : Node(
"hello_world") {
30 velocity_publisher_ = this->create_publisher<geometry_msgs::msg::Twist>(
31 "cmd_vel", rclcpp::QoS(10).best_effort().durability_volatile());
32 publishing_timer_ = this->create_wall_timer(std::chrono::milliseconds(1000), [
this]() {
34 message.linear.x = 0.5;
35 message.angular.z = 0.5;
36 velocity_publisher_->publish(message);
37 RCLCPP_INFO(this->get_logger(),
"Sent command velocity message");
42 gnss_subscriber_ = this->create_subscription<sensor_msgs::msg::NavSatFix>(
43 "gnss", rclcpp::QoS(10).best_effort().durability_volatile(),
44 [
this](
const sensor_msgs::msg::NavSatFix::SharedPtr msg) {
45 auto status =
"UNKNOWN";
46 switch (msg->status.status) {
62 RCLCPP_INFO(this->get_logger(),
"Received GNSS message: %s", status);
67 low_power_client_ = this->create_client<creos_sdk_msgs::srv::EnterLowPowerMode>(
"enter_low_power_mode");
68 auto request = std::make_shared<creos_sdk_msgs::srv::EnterLowPowerMode::Request>();
69 low_power_client_->async_send_request(
70 request, [
this](rclcpp::Client<creos_sdk_msgs::srv::EnterLowPowerMode>::SharedFuture future) {
72 auto response = future.get();
73 RCLCPP_INFO(this->get_logger(),
"Low power mode entered: %s", response->success ?
"true" :
"false");
75 RCLCPP_ERROR(this->get_logger(),
"Failed to enter low power mode");
82 rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr velocity_publisher_;
83 rclcpp::Subscription<sensor_msgs::msg::NavSatFix>::SharedPtr gnss_subscriber_;
84 rclcpp::Client<creos_sdk_msgs::srv::EnterLowPowerMode>::SharedPtr low_power_client_;
85 rclcpp::TimerBase::SharedPtr publishing_timer_;
89int main(
int argc,
char* argv[]) {
90 rclcpp::init(argc, argv);
92 auto node = std::make_shared<HelloWorldNode>();
Interface definition of the creos_sdk_msgs/srv/EnterLowPowerMode service.
Interface definition of the geometry_msgs/msg/Twist message.
ROS message class definition for Twist.
Definition twist.hpp:15
static const int8_t STATUS_GBAS_FIX
with ground-based augmentation
Definition nav_sat_status.hpp:30
static const int8_t STATUS_SBAS_FIX
with satellite-based augmentation
Definition nav_sat_status.hpp:29
static const int8_t STATUS_NO_FIX
unable to fix position
Definition nav_sat_status.hpp:27
static const int8_t STATUS_FIX
unaugmented fix
Definition nav_sat_status.hpp:28
Interface definition of the sensor_msgs/msg/NavSatFix message.
Interface definition of the sensor_msgs/msg/NavSatStatus message.
Explanation
At the top of the main.cpp file, we include the necessary headers for the example. Specifically, we include rclcpp to interact with ROS2, and the necessary messages packages to communicate with the CreOS SDK ROS2 node. These also include the EnterLowPowerMode service type from the creos_sdk_msgs package.
13#include <rclcpp/rclcpp.hpp>
14
18
20
For this example, we create a class that extends from rclcpp::Node
. Most of our implementation will be inside this class' constructor.
24class HelloWorldNode : public rclcpp::Node {
25public:
26 HelloWorldNode() : Node("hello_world") {
We create a publisher that publishes geometry_msgs::msg::Twist messages to the cmd_vel
topic. This message contains the linear and angular velocity of the robot. We also create a timer that triggers every second. In the callback of the timer, we create a geometry_msgs::msg::Twist message and publish it. Note that we match the Quality of Service settings with the settings used by the CreOS SDK ROS2 node, as specified in the Input Topics section.
30 velocity_publisher_ = this->create_publisher<geometry_msgs::msg::Twist>(
31 "cmd_vel", rclcpp::QoS(10).best_effort().durability_volatile());
32 publishing_timer_ = this->create_wall_timer(std::chrono::milliseconds(1000), [this]() {
34 message.linear.x = 0.5;
35 message.angular.z = 0.5;
36 velocity_publisher_->publish(message);
37 RCLCPP_INFO(this->get_logger(), "Sent command velocity message");
38 });
Next, we create a subscriber that subscribes to the gnss
topic. In the callback of the subscriber, we extract the NavSatStatus from the received message, and print the status in a human-readable format. Note that we also match the Quality of Service settings here.
42 gnss_subscriber_ = this->create_subscription<sensor_msgs::msg::NavSatFix>(
43 "gnss", rclcpp::QoS(10).best_effort().durability_volatile(),
44 [this](const sensor_msgs::msg::NavSatFix::SharedPtr msg) {
45 auto status = "UNKNOWN";
46 switch (msg->status.status) {
48 status = "NO_FIX";
49 break;
51 status = "FIX";
52 break;
54 status = "SBAS_FIX";
55 break;
57 status = "GBAS_FIX";
58 break;
59 default:
60 break;
61 }
62 RCLCPP_INFO(this->get_logger(), "Received GNSS message: %s", status);
63 });
We also create a service client that calls the enter_low_power_mode
service. We immediately use this client to send an asynchronous request to the service. In the callback of the request, we print whether the transition to low-power mode was successful. If any exception has happened during the request, we print the failure to the console as well.
67 low_power_client_ = this->create_client<creos_sdk_msgs::srv::EnterLowPowerMode>("enter_low_power_mode");
68 auto request = std::make_shared<creos_sdk_msgs::srv::EnterLowPowerMode::Request>();
69 low_power_client_->async_send_request(
70 request, [this](rclcpp::Client<creos_sdk_msgs::srv::EnterLowPowerMode>::SharedFuture future) {
71 try {
72 auto response = future.get();
73 RCLCPP_INFO(this->get_logger(), "Low power mode entered: %s", response->success ? "true" : "false");
74 } catch (...) {
75 RCLCPP_ERROR(this->get_logger(), "Failed to enter low power mode");
76 }
77 });
78 };
79
In the main function, we simply create a new instance of our HelloWorldNode class and spin the node.
89int main(int argc, char* argv[]) {
90 rclcpp::init(argc, argv);
91
92 auto node = std::make_shared<HelloWorldNode>();
93 rclcpp::spin(node);
94
95 rclcpp::shutdown();
96 return 0;
97}
98
Interface definition of the creos_sdk_msgs/srv/EnterLowPowerMode service.
Interface definition of the geometry_msgs/msg/Twist message.
ROS message class definition for Twist.
Definition twist.hpp:15
static const int8_t STATUS_GBAS_FIX
with ground-based augmentation
Definition nav_sat_status.hpp:30
static const int8_t STATUS_SBAS_FIX
with satellite-based augmentation
Definition nav_sat_status.hpp:29
static const int8_t STATUS_NO_FIX
unable to fix position
Definition nav_sat_status.hpp:27
static const int8_t STATUS_FIX
unaugmented fix
Definition nav_sat_status.hpp:28
Interface definition of the sensor_msgs/msg/NavSatFix message.
Interface definition of the sensor_msgs/msg/NavSatStatus message.