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;
111 has_local_position_ned =
true;
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;
135 if (!has_local_position_ned_cov) {
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;
152 local_velocity_body.
publish(twist_body);
155 auto twist_local = boost::make_shared<geometry_msgs::TwistStamped>();
156 twist_local->header.stamp = twist_body->header.stamp;
160 twist_body->twist.angular);
161 local_velocity_local.
publish(twist_local);
169 has_local_position_ned_cov =
true;
176 Eigen::Quaterniond enu_orientation;
180 auto odom = boost::make_shared<nav_msgs::Odometry>();
185 odom->pose.pose.orientation = enu_orientation_msg;
187 odom->twist.twist.angular = baselink_angular_msg;
189 odom->pose.covariance[0] = pos_ned.covariance[0];
190 odom->pose.covariance[7] = pos_ned.covariance[9];
191 odom->pose.covariance[14] = pos_ned.covariance[17];
193 odom->twist.covariance[0] = pos_ned.covariance[24];
194 odom->twist.covariance[7] = pos_ned.covariance[30];
195 odom->twist.covariance[14] = pos_ned.covariance[35];
202 auto pose_cov = boost::make_shared<geometry_msgs::PoseWithCovarianceStamped>();
203 pose_cov->header = odom->header;
204 pose_cov->pose = odom->pose;
205 local_position_cov.
publish(pose_cov);
208 auto twist_cov = boost::make_shared<geometry_msgs::TwistWithCovarianceStamped>();
209 twist_cov->header.stamp = odom->header.stamp;
210 twist_cov->header.frame_id = odom->child_frame_id;
211 twist_cov->twist = odom->twist;
212 local_velocity_cov.
publish(twist_cov);
215 if (!has_local_position_ned) {
216 auto pose = boost::make_shared<geometry_msgs::PoseStamped>();
217 pose->header = odom->header;
218 pose->pose = odom->pose.pose;
221 auto twist = boost::make_shared<geometry_msgs::TwistStamped>();
222 twist->header.stamp = odom->header.stamp;
223 twist->header.frame_id = odom->child_frame_id;
224 twist->twist = odom->twist.twist;
225 local_velocity_body.
publish(twist);
232 auto accel = boost::make_shared<geometry_msgs::AccelWithCovarianceStamped>();
233 accel->header = odom->header;
238 accel->accel.covariance[0] = pos_ned.covariance[39];
239 accel->accel.covariance[7] = pos_ned.covariance[42];
240 accel->accel.covariance[14] = pos_ned.covariance[44];
MAVROS Plugin base class.
std_msgs::Header synchronized_header(const std::string &frame_id, const T time_stamp)
Create message header from time_boot_ms or time_usec stamps and frame_id.
void publish(const boost::shared_ptr< M > &message) const
geometry_msgs::Quaternion get_attitude_orientation_enu()
Get Attitude orientation quaternion.
ros::Publisher local_velocity_body
void handle_local_position_ned(const mavlink::mavlink_message_t *msg, mavlink::common::msg::LOCAL_POSITION_NED &pos_ned)
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
ros::Publisher local_odom
tf2_ros::TransformBroadcaster tf2_broadcaster
ros::Publisher local_velocity_cov
void handle_local_position_ned_cov(const mavlink::mavlink_message_t *msg, mavlink::common::msg::LOCAL_POSITION_NED_COV &pos_ned)
T transform_frame_enu_baselink(const T &in, const Eigen::Quaterniond &q)
Transform data expressed in ENU to base_link frame. Assumes quaternion represents rotation from ENU t...
PluginBase()
Plugin constructor Should not do anything before initialize()
Local position plugin. Publish local position to TF, PositionStamped, TwistStamped and Odometry...
ros::Publisher local_velocity_local
bool has_local_position_ned
std::string tf_child_frame_id
frame for TF
void vectorEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Vector3 &m)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
T transform_frame_ned_enu(const T &in)
Transform data expressed in NED to ENU frame.
Eigen::Vector3d to_eigen(const geometry_msgs::Point r)
Helper to convert common ROS geometry_msgs::Point to Eigen::Vector3d.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void pointEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Point &m)
std::string frame_id
frame for Pose
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
ros::Publisher local_accel
Subscriptions get_subscriptions()
Return vector of MAVLink message subscriptions (handlers)
void quaternionMsgToEigen(const geometry_msgs::Quaternion &m, Eigen::Quaterniond &e)
void publish_tf(boost::shared_ptr< nav_msgs::Odometry > &odom)
ros::Publisher local_position
void initialize(UAS &uas_)
Plugin initializer.
ros::Publisher local_position_cov
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
geometry_msgs::Vector3 get_attitude_angular_velocity_enu()
Get angular velocity from IMU data.
T transform_frame_baselink_enu(const T &in, const Eigen::Quaterniond &q)
Transform data expressed in baselink to ENU frame. Assumes quaternion represents rotation from basel_...
std::string tf_frame_id
origin for TF
bool has_local_position_ned_cov