9 #include <px4_msgs/msg/home_position.hpp>
10 #include <px4_ros2/common/context.hpp>
11 #include <px4_ros2/utils/subscription.hpp>
37 const px4_msgs::msg::HomePosition & home =
last();
38 return Eigen::Vector3f{home.x, home.y, home.z};
48 const px4_msgs::msg::HomePosition & home =
last();
49 return Eigen::Vector3d{home.lat, home.lon, home.alt};
99 return last().manual_home;
Definition: context.hpp:20
Provides access to the vehicle's home position.
Definition: home_position.hpp:25
bool localPositionValid() const
Check if vehicle's local home position is valid (xyz).
Definition: home_position.hpp:67
bool globaHorizontalPositionValid() const
Check if vehicle's global horizontal home position is valid (lat, lon).
Definition: home_position.hpp:77
Eigen::Vector3d globalPosition() const
Get the vehicle's home position in global coordinates.
Definition: home_position.hpp:46
Eigen::Vector3f localPosition() const
Get the vehicle's home position in local coordinates.
Definition: home_position.hpp:35
float yaw() const
Get the vehicle's home position yaw.
Definition: home_position.hpp:57
bool manualHome() const
Check if home position has been set manually.
Definition: home_position.hpp:97
bool altitudeValid() const
Check if vehicle's home position altitude is valid.
Definition: home_position.hpp:87
Provides a subscription to arbitrary ROS topics.
Definition: subscription.hpp:23
bool lastValid(const std::chrono::duration< int64_t, DurationT > max_delay=500ms) const
Check whether the last message is still valid. To be valid, the message must have been received withi...
Definition: subscription.hpp:84
const px4_msgs::msg::HomePosition & last() const
Get the last-received message.
Definition: subscription.hpp:58