Go to the documentation of this file.
15 #include <unordered_map>
25 tf2_listener(tf2_buffer, true),
35 gps_satellites_visible(0),
38 fcu_caps_known(false),
40 base_link_frame_id(
"base_link"),
41 odom_frame_id(
"odom"),
48 egm96_5 = std::make_shared<GeographicLib::Geoid>(
"egm96-5",
"",
true,
true);
50 catch (
const std::exception &e) {
53 " | Run install_geographiclib_dataset.sh script in order to install Geoid Model dataset!");
106 bool process_cb_queue =
false;
110 process_cb_queue =
true;
115 process_cb_queue =
true;
120 if (process_cb_queue) {
123 cb(
static_cast<MAV_CAP>(caps));
167 geometry_msgs::Quaternion q;
168 q.w = 1.0; q.x = q.y = q.z = 0.0;
180 geometry_msgs::Quaternion q;
181 q.w = 1.0; q.x = q.y = q.z = 0.0;
193 geometry_msgs::Vector3 v;
194 v.x = v.y = v.z = 0.0;
206 geometry_msgs::Vector3 v;
207 v.x = v.y = v.z = 0.0;
216 float eph,
float epv,
217 int fix_type,
int satellites_visible)
249 void UAS::add_static_transform(
const std::string &frame_id,
const std::string &child_id,
const Eigen::Affine3d &tr, std::vector<geometry_msgs::TransformStamped>& vector)
251 geometry_msgs::TransformStamped static_transform;
254 static_transform.header.frame_id = frame_id;
255 static_transform.child_frame_id = child_id;
258 vector.emplace_back(static_transform);
264 geometry_msgs::TransformStamped static_transformStamped;
267 static_transformStamped.header.frame_id = frame_id;
268 static_transformStamped.child_frame_id = child_id;
277 std::vector<geometry_msgs::TransformStamped> transform_vector;
std::vector< CapabilitiesCb > capabilities_cb_vec
std::recursive_mutex mutex
std::atomic< uint8_t > base_mode
Eigen::Quaterniond quaternion_from_rpy(const Eigen::Vector3d &rpy)
Convert euler angles to quaternion.
void update_attitude_imu_ned(sensor_msgs::Imu::Ptr &imu)
Store IMU data [NED].
mavlink::common::MAV_PROTOCOL_CAPABILITY MAV_CAP
void update_attitude_imu_enu(sensor_msgs::Imu::Ptr &imu)
Store IMU data [ENU].
#define ROS_FATAL_STREAM(args)
geometry_msgs::Quaternion get_attitude_orientation_ned()
Get Attitude orientation quaternion.
std::atomic< uint64_t > fcu_capabilities
std::string odom_frame_id
std::atomic< uint8_t > autopilot
ROSCPP_DECL void shutdown()
std::atomic< uint8_t > type
void update_gps_fix_epts(sensor_msgs::NavSatFix::Ptr &fix, float eph, float epv, int fix_type, int satellites_visible)
Store GPS RAW data.
void add_connection_change_handler(ConnectionCb cb)
Add connection change handler callback.
sensor_msgs::Imu::Ptr get_attitude_imu_ned()
Get IMU data [NED].
sensor_msgs::NavSatFix::Ptr gps_fix
std::vector< ConnectionCb > connection_cb_vec
std::atomic< bool > connected
mavlink::minimal::MAV_AUTOPILOT MAV_AUTOPILOT
static uint64_t get_default_caps(UAS::MAV_AUTOPILOT ap_type)
uint64_t get_capabilities()
geometry_msgs::Quaternion get_attitude_orientation_enu()
Get Attitude orientation quaternion.
MAV_AUTOPILOT get_autopilot()
Returns autopilot type.
sensor_msgs::Imu::Ptr imu_ned_data
void update_connection_status(bool conn_)
void add_static_transform(const std::string &frame_id, const std::string &child_id, const Eigen::Affine3d &tr, std::vector< geometry_msgs::TransformStamped > &vector)
Add static transform. To publish all static transforms at once, we stack them in a std::vector.
std::shared_ptr< MAVConnInterface > Ptr
sensor_msgs::Imu::Ptr get_attitude_imu_enu()
Get IMU data [ENU].
PX4 custom mode constants.
std::string base_link_frame_id
std::function< void(bool)> ConnectionCb
sensor_msgs::Imu::Ptr imu_enu_data
int gps_satellites_visible
geometry_msgs::Vector3 get_attitude_angular_velocity_enu()
Get angular velocity from IMU data.
void update_capabilities(bool known, uint64_t caps=0)
Update the capabilities if they've changed every VERSION/timeout.
void get_gps_epts(float &eph, float &epv, int &fix_type, int &satellites_visible)
Returns EPH, EPV, Fix type and satellites visible.
mavlink::minimal::MAV_TYPE MAV_TYPE
void publish_static_transform(const std::string &frame_id, const std::string &child_id, const Eigen::Affine3d &tr)
Publishes static transform.
void setup_static_tf()
Publish helper TFs used for frame transformation in the odometry plugin.
void transformEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Transform &m)
std::atomic< bool > fcu_caps_known
void add_capabilities_change_handler(CapabilitiesCb cb)
Adds a function to the capabilities callback queue.
std::shared_ptr< GeographicLib::Geoid > egm96_5
Geoid dataset used to convert between AMSL and WGS-84.
constexpr std::underlying_type< _T >::type enum_value(_T e)
void update_heartbeat(uint8_t type_, uint8_t autopilot_, uint8_t base_mode_)
tf2_ros::StaticTransformBroadcaster tf2_static_broadcaster
std::lock_guard< std::recursive_mutex > lock_guard
std::function< void(MAV_CAP)> CapabilitiesCb
geometry_msgs::Vector3 get_attitude_angular_velocity_ned()
Get angular velocity from IMU data.
sensor_msgs::NavSatFix::Ptr get_gps_fix()
Retunrs last GPS RAW message.
mavros
Author(s): Vladimir Ermakov
autogenerated on Tue May 6 2025 02:34:03