PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
Loading...
Searching...
No Matches
attitude.hpp
1/****************************************************************************
2 * Copyright (c) 2024 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_attitude.hpp>
10#include <px4_ros2/common/context.hpp>
11#include <px4_ros2/utils/geometry.hpp>
12#include <px4_ros2/utils/subscription.hpp>
13
14namespace px4_ros2 {
22class OdometryAttitude : public Subscription<px4_msgs::msg::VehicleAttitude> {
23 public:
24 explicit OdometryAttitude(Context& context);
25
31 Eigen::Quaternionf attitude() const
32 {
33 const px4_msgs::msg::VehicleAttitude& att = last();
34 return Eigen::Quaternionf{att.q[0], att.q[1], att.q[2], att.q[3]};
35 }
36
42 float roll() const { return quaternionToRoll(attitude()); }
43
49 float pitch() const { return quaternionToPitch(attitude()); }
50
56 float yaw() const { return quaternionToYaw(attitude()); }
57};
58
60} /* namespace px4_ros2 */
Definition context.hpp:18
Provides access to the vehicle's attitude estimate.
Definition attitude.hpp:22
Eigen::Quaternionf attitude() const
Get the vehicle's attitude.
Definition attitude.hpp:31
float pitch() const
Get the vehicle's pitch in extrinsic RPY order.
Definition attitude.hpp:49
float roll() const
Get the vehicle's roll in extrinsic RPY order.
Definition attitude.hpp:42
float yaw() const
Get the vehicle's yaw in extrinsic RPY order.
Definition attitude.hpp:56
Provides a subscription to arbitrary ROS topics.
Definition subscription.hpp:27
const px4_msgs::msg::VehicleAttitude & last() const
Get the last-received message.
Definition subscription.hpp:57
Type quaternionToRoll(const Eigen::Quaternion< Type > &q)
Convert quaternion to roll angle in extrinsic RPY order (intrinsic YPR)
Definition geometry.hpp:147
Type quaternionToPitch(const Eigen::Quaternion< Type > &q)
Convert quaternion to pitch angle in extrinsic RPY order (intrinsic YPR)
Definition geometry.hpp:159
Type quaternionToYaw(const Eigen::Quaternion< Type > &q)
Convert quaternion to yaw angle in extrinsic RPY order (intrinsic YPR)
Definition geometry.hpp:171