PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
Loading...
Searching...
No Matches
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 <rclcpp/rclcpp.hpp>
9#include <string>
10#include <utility>
11
12#include "requirement_flags.hpp"
13
14namespace px4_ros2 {
15
16class SetpointBase;
17
18class Context {
19 public:
20 explicit Context(rclcpp::Node& node, std::string topic_namespace_prefix = "")
21 : _node(node), _topic_namespace_prefix(std::move(topic_namespace_prefix))
22 {
23 }
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:18
Definition setpoint_base.hpp:19
Requirement flags used by modes.
Definition requirement_flags.hpp:15