22 #include <geometry_msgs/AccelWithCovarianceStamped.h>
23 #include <geometry_msgs/PoseStamped.h>
24 #include <geometry_msgs/PoseWithCovarianceStamped.h>
25 #include <geometry_msgs/TwistStamped.h>
26 #include <geometry_msgs/TwistWithCovarianceStamped.h>
27 #include <geometry_msgs/TransformStamped.h>
29 #include <nav_msgs/Odometry.h>
32 namespace std_plugins {
41 lp_nh(
"~local_position"),
49 PluginBase::initialize(uas_);
97 geometry_msgs::TransformStamped transform;
98 transform.header.stamp = odom->header.stamp;
101 transform.transform.translation.x = odom->pose.pose.position.x;
102 transform.transform.translation.y = odom->pose.pose.position.y;
103 transform.transform.translation.z = odom->pose.pose.position.z;
104 transform.transform.rotation = odom->pose.pose.orientation;
121 Eigen::Quaterniond enu_orientation;
125 auto odom = boost::make_shared<nav_msgs::Odometry>();
130 odom->pose.pose.orientation = enu_orientation_msg;
132 odom->twist.twist.angular = baselink_angular_msg;
140 auto pose = boost::make_shared<geometry_msgs::PoseStamped>();
141 pose->header = odom->header;
142 pose->pose = odom->pose.pose;
147 auto twist_body = boost::make_shared<geometry_msgs::TwistStamped>();
148 twist_body->header.stamp = odom->header.stamp;
150 twist_body->twist.linear = odom->twist.twist.linear;
151 twist_body->twist.angular = baselink_angular_msg;
155 auto twist_local = boost::make_shared<geometry_msgs::TwistStamped>();
156 twist_local->header.stamp = twist_body->header.stamp;
160 twist_local->twist.angular);
177 Eigen::Quaterniond enu_orientation;
181 auto odom = boost::make_shared<nav_msgs::Odometry>();
186 odom->pose.pose.orientation = enu_orientation_msg;
188 odom->twist.twist.angular = baselink_angular_msg;
190 odom->pose.covariance[0] = pos_ned.covariance[0];
191 odom->pose.covariance[7] = pos_ned.covariance[9];
192 odom->pose.covariance[14] = pos_ned.covariance[17];
194 odom->twist.covariance[0] = pos_ned.covariance[24];
195 odom->twist.covariance[7] = pos_ned.covariance[30];
196 odom->twist.covariance[14] = pos_ned.covariance[35];
203 auto pose_cov = boost::make_shared<geometry_msgs::PoseWithCovarianceStamped>();
204 pose_cov->header = odom->header;
205 pose_cov->pose = odom->pose;
209 auto twist_cov = boost::make_shared<geometry_msgs::TwistWithCovarianceStamped>();
210 twist_cov->header.stamp = odom->header.stamp;
211 twist_cov->header.frame_id = odom->child_frame_id;
212 twist_cov->twist = odom->twist;
217 auto pose = boost::make_shared<geometry_msgs::PoseStamped>();
218 pose->header = odom->header;
219 pose->pose = odom->pose.pose;
222 auto twist = boost::make_shared<geometry_msgs::TwistStamped>();
223 twist->header.stamp = odom->header.stamp;
224 twist->header.frame_id = odom->child_frame_id;
225 twist->twist = odom->twist.twist;
233 auto accel = boost::make_shared<geometry_msgs::AccelWithCovarianceStamped>();
234 accel->header = odom->header;
239 accel->accel.covariance[0] = pos_ned.covariance[39];
240 accel->accel.covariance[7] = pos_ned.covariance[42];
241 accel->accel.covariance[14] = pos_ned.covariance[44];