SMACC2
Loading...
Searching...
No Matches
smacc2_client_library
cl_px4_mr
src
cl_px4_mr
components
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
15
#include <
cl_px4_mr/components/cp_vehicle_local_position.hpp
>
16
17
namespace
cl_px4_mr
18
{
19
20
CpVehicleLocalPosition::CpVehicleLocalPosition
() {}
21
22
CpVehicleLocalPosition::~CpVehicleLocalPosition
() {}
23
24
void
CpVehicleLocalPosition::onInitialize
()
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
33
void
CpVehicleLocalPosition::onPositionMessage
(
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
43
onPositionReceived_
();
44
}
45
46
float
CpVehicleLocalPosition::getX
()
const
47
{
48
std::lock_guard<std::mutex> lock(
mutex_
);
49
return
x_
;
50
}
51
52
float
CpVehicleLocalPosition::getY
()
const
53
{
54
std::lock_guard<std::mutex> lock(
mutex_
);
55
return
y_
;
56
}
57
58
float
CpVehicleLocalPosition::getZ
()
const
59
{
60
std::lock_guard<std::mutex> lock(
mutex_
);
61
return
z_
;
62
}
63
64
float
CpVehicleLocalPosition::getHeading
()
const
65
{
66
std::lock_guard<std::mutex> lock(
mutex_
);
67
return
heading_
;
68
}
69
70
bool
CpVehicleLocalPosition::isValid
()
const
71
{
72
std::lock_guard<std::mutex> lock(
mutex_
);
73
return
valid_
;
74
}
75
76
}
// namespace cl_px4_mr
cl_px4_mr::CpVehicleLocalPosition::onInitialize
void onInitialize() override
Definition
cp_vehicle_local_position.cpp:24
cl_px4_mr::CpVehicleLocalPosition::getY
float getY() const
Definition
cp_vehicle_local_position.cpp:52
cl_px4_mr::CpVehicleLocalPosition::z_
float z_
Definition
cp_vehicle_local_position.hpp:47
cl_px4_mr::CpVehicleLocalPosition::CpVehicleLocalPosition
CpVehicleLocalPosition()
Definition
cp_vehicle_local_position.cpp:20
cl_px4_mr::CpVehicleLocalPosition::~CpVehicleLocalPosition
virtual ~CpVehicleLocalPosition()
Definition
cp_vehicle_local_position.cpp:22
cl_px4_mr::CpVehicleLocalPosition::mutex_
std::mutex mutex_
Definition
cp_vehicle_local_position.hpp:50
cl_px4_mr::CpVehicleLocalPosition::onPositionReceived_
smacc2::SmaccSignal< void()> onPositionReceived_
Definition
cp_vehicle_local_position.hpp:39
cl_px4_mr::CpVehicleLocalPosition::x_
float x_
Definition
cp_vehicle_local_position.hpp:45
cl_px4_mr::CpVehicleLocalPosition::getX
float getX() const
Definition
cp_vehicle_local_position.cpp:46
cl_px4_mr::CpVehicleLocalPosition::onPositionMessage
void onPositionMessage(const px4_msgs::msg::VehicleLocalPosition::SharedPtr msg)
Definition
cp_vehicle_local_position.cpp:33
cl_px4_mr::CpVehicleLocalPosition::y_
float y_
Definition
cp_vehicle_local_position.hpp:46
cl_px4_mr::CpVehicleLocalPosition::valid_
bool valid_
Definition
cp_vehicle_local_position.hpp:49
cl_px4_mr::CpVehicleLocalPosition::isValid
bool isValid() const
Definition
cp_vehicle_local_position.cpp:70
cl_px4_mr::CpVehicleLocalPosition::subscriber_
rclcpp::Subscription< px4_msgs::msg::VehicleLocalPosition >::SharedPtr subscriber_
Definition
cp_vehicle_local_position.hpp:44
cl_px4_mr::CpVehicleLocalPosition::getHeading
float getHeading() const
Definition
cp_vehicle_local_position.cpp:64
cl_px4_mr::CpVehicleLocalPosition::heading_
float heading_
Definition
cp_vehicle_local_position.hpp:48
cl_px4_mr::CpVehicleLocalPosition::getZ
float getZ() const
Definition
cp_vehicle_local_position.cpp:58
smacc2::ISmaccComponent::getLogger
rclcpp::Logger getLogger() const
Definition
smacc_component.cpp:44
smacc2::ISmaccComponent::getNode
rclcpp::Node::SharedPtr getNode()
Definition
smacc_component.cpp:42
cp_vehicle_local_position.hpp
cl_px4_mr
Definition
cl_px4_mr.hpp:28
Generated by
1.12.0