SMACC2
Loading...
Searching...
No Matches
cp_vehicle_local_position.hpp
Go to the documentation of this file.
1// Copyright 2025 Robosoft Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#pragma once
16
17#include <mutex>
18#include <px4_msgs/msg/vehicle_local_position.hpp>
19#include <rclcpp/rclcpp.hpp>
20#include <smacc2/smacc.hpp>
21
22namespace cl_px4_mr
23{
24
26{
27public:
30
31 void onInitialize() override;
32
33 float getX() const;
34 float getY() const;
35 float getZ() const;
36 float getHeading() const;
37 bool isValid() const;
38
40
41private:
42 void onPositionMessage(const px4_msgs::msg::VehicleLocalPosition::SharedPtr msg);
43
44 rclcpp::Subscription<px4_msgs::msg::VehicleLocalPosition>::SharedPtr subscriber_;
45 float x_ = 0.0f;
46 float y_ = 0.0f;
47 float z_ = 0.0f;
48 float heading_ = 0.0f;
49 bool valid_ = false;
50 mutable std::mutex mutex_;
51};
52
53} // namespace cl_px4_mr
smacc2::SmaccSignal< void()> onPositionReceived_
void onPositionMessage(const px4_msgs::msg::VehicleLocalPosition::SharedPtr msg)
rclcpp::Subscription< px4_msgs::msg::VehicleLocalPosition >::SharedPtr subscriber_