PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
global_position.hpp
1
/****************************************************************************
2
* Copyright (c) 2023 PX4 Development Team.
3
* SPDX-License-Identifier: BSD-3-Clause
4
****************************************************************************/
5
6
#pragma once
7
8
#include <Eigen/Eigen>
9
#include <px4_msgs/msg/vehicle_global_position.hpp>
10
#include <px4_ros2/common/context.hpp>
11
#include <px4_ros2/utils/subscription.hpp>
12
13
namespace
px4_ros2
14
{
22
class
OdometryGlobalPosition
:
public
Subscription
<px4_msgs::msg::VehicleGlobalPosition>
23
{
24
public
:
25
explicit
OdometryGlobalPosition
(
Context
& context);
26
32
Eigen::Vector3d
position
()
const
33
{
34
const
px4_msgs::msg::VehicleGlobalPosition & pos =
last
();
35
return
{pos.lat, pos.lon, pos.alt};
36
}
37
};
38
40
}
/* namespace px4_ros2 */
px4_ros2::Context
Definition:
context.hpp:20
px4_ros2::OdometryGlobalPosition
Provides access to the vehicle's global position estimate.
Definition:
global_position.hpp:23
px4_ros2::OdometryGlobalPosition::position
Eigen::Vector3d position() const
Get the vehicle's global position.
Definition:
global_position.hpp:32
px4_ros2::Subscription
Provides a subscription to arbitrary ROS topics.
Definition:
subscription.hpp:23
px4_ros2::Subscription< px4_msgs::msg::VehicleGlobalPosition >::last
const px4_msgs::msg::VehicleGlobalPosition & last() const
Get the last-received message.
Definition:
subscription.hpp:58
px4_ros2_cpp
include
px4_ros2
odometry
global_position.hpp
Generated by
1.9.1