SMACC2
Loading...
Searching...
No Matches
cp_vehicle_local_position.cpp
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
16
17namespace cl_px4_mr
18{
19
21
23
25{
26 auto node = this->getNode();
27 subscriber_ = node->create_subscription<px4_msgs::msg::VehicleLocalPosition>(
28 "/fmu/out/vehicle_local_position", rclcpp::SensorDataQoS(),
29 std::bind(&CpVehicleLocalPosition::onPositionMessage, this, std::placeholders::_1));
30 RCLCPP_INFO(getLogger(), "CpVehicleLocalPosition: subscribed to /fmu/out/vehicle_local_position");
31}
32
34 const px4_msgs::msg::VehicleLocalPosition::SharedPtr msg)
35{
36 std::lock_guard<std::mutex> lock(mutex_);
37 x_ = msg->x;
38 y_ = msg->y;
39 z_ = msg->z;
40 heading_ = msg->heading;
41 valid_ = msg->xy_valid && msg->z_valid;
42
44}
45
47{
48 std::lock_guard<std::mutex> lock(mutex_);
49 return x_;
50}
51
53{
54 std::lock_guard<std::mutex> lock(mutex_);
55 return y_;
56}
57
59{
60 std::lock_guard<std::mutex> lock(mutex_);
61 return z_;
62}
63
65{
66 std::lock_guard<std::mutex> lock(mutex_);
67 return heading_;
68}
69
71{
72 std::lock_guard<std::mutex> lock(mutex_);
73 return valid_;
74}
75
76} // 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_
rclcpp::Logger getLogger() const
rclcpp::Node::SharedPtr getNode()