SMACC2
Loading...
Searching...
No Matches
smacc2_client_library
cl_px4_mr
include
cl_px4_mr
components
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
22
namespace
cl_px4_mr
23
{
24
25
class
CpVehicleLocalPosition
:
public
smacc2::ISmaccComponent
26
{
27
public
:
28
CpVehicleLocalPosition
();
29
virtual
~CpVehicleLocalPosition
();
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
39
smacc2::SmaccSignal
<void()>
onPositionReceived_
;
40
41
private
:
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
cl_px4_mr::CpVehicleLocalPosition
Definition
cp_vehicle_local_position.hpp:26
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
Definition
component.hpp:30
smacc2::SmaccSignal
Definition
smacc_signal.hpp:46
cl_px4_mr
Definition
cl_px4_mr.hpp:28
smacc.hpp
Generated by
1.12.0