PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
Loading...
Searching...
No Matches
vehicle_status.hpp
1
/****************************************************************************
2
* Copyright (c) 2023-2024 PX4 Development Team.
3
* SPDX-License-Identifier: BSD-3-Clause
4
****************************************************************************/
5
6
#pragma once
7
8
#include <px4_msgs/msg/vehicle_status.hpp>
9
#include <px4_ros2/common/context.hpp>
10
#include <px4_ros2/utils/subscription.hpp>
11
#include <px4_ros2/utils/message_version.hpp>
12
13
namespace
px4_ros2
14
{
24
class
VehicleStatus
:
public
Subscription
<px4_msgs::msg::VehicleStatus>
25
{
26
public
:
27
explicit
VehicleStatus
(
Context
& context)
28
:
Subscription<px4_msgs::msg::VehicleStatus>
(context,
29
"fmu/out/vehicle_status"
+ px4_ros2::getMessageNameVersion<px4_msgs::msg::VehicleStatus>()) {}
30
36
bool
armed
()
const
37
{
38
return
last
().arming_state == px4_msgs::msg::VehicleStatus::ARMING_STATE_ARMED;
39
}
40
47
uint8_t
navState
()
const
48
{
49
return
last
().nav_state;
50
}
51
52
};
53
55
}
/* namespace px4_ros2 */
px4_ros2::Context
Definition
context.hpp:20
px4_ros2::Subscription
Provides a subscription to arbitrary ROS topics.
Definition
subscription.hpp:23
px4_ros2::Subscription< px4_msgs::msg::VehicleStatus >::last
const px4_msgs::msg::VehicleStatus & last() const
Get the last-received message.
Definition
subscription.hpp:58
px4_ros2::VehicleStatus
Provides access to the vehicle's status.
Definition
vehicle_status.hpp:25
px4_ros2::VehicleStatus::navState
uint8_t navState() const
Get the vehicle's current active flight mode.
Definition
vehicle_status.hpp:47
px4_ros2::VehicleStatus::armed
bool armed() const
Get the vehicle's arming status.
Definition
vehicle_status.hpp:36
px4_ros2_cpp
include
px4_ros2
vehicle_state
vehicle_status.hpp
Generated by
1.9.8