PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
context.hpp
1 /****************************************************************************
2  * Copyright (c) 2023 PX4 Development Team.
3  * SPDX-License-Identifier: BSD-3-Clause
4  ****************************************************************************/
5 
6 #pragma once
7 
8 #include <string>
9 #include <rclcpp/rclcpp.hpp>
10 #include <utility>
11 
12 #include "requirement_flags.hpp"
13 
14 namespace px4_ros2
15 {
16 
17 class SetpointBase;
18 
19 class Context
20 {
21 public:
22  explicit Context(rclcpp::Node & node, std::string topic_namespace_prefix = "")
23  : _node(node), _topic_namespace_prefix(std::move(topic_namespace_prefix)) {}
24 
25  rclcpp::Node & node() {return _node;}
26  const std::string & topicNamespacePrefix() const {return _topic_namespace_prefix;}
27 
28  virtual void addSetpointType(SetpointBase * setpoint) {}
29  virtual void setRequirement(const RequirementFlags & requirement_flags) {}
30 
31 private:
32  rclcpp::Node & _node;
33  const std::string _topic_namespace_prefix;
34 };
35 
36 } // namespace px4_ros2
Definition: context.hpp:20
Definition: setpoint_base.hpp:20
Requirement flags used by modes.
Definition: requirement_flags.hpp:17