pose_cov_ops.h
Go to the documentation of this file.
00001 #ifndef POSE_COV_OPS_H_
00002 #define POSE_COV_OPS_H_
00003 
00004 #include <mrpt_bridge/pose.h>
00005 #include <geometry_msgs/Pose.h>
00006 #include <geometry_msgs/PoseWithCovariance.h>
00007 
00008 namespace pose_cov_ops
00009 {
00012         void compose(const geometry_msgs::Pose& a, const geometry_msgs::Pose& b, geometry_msgs::Pose& out);
00013         void compose(const geometry_msgs::PoseWithCovariance& a, const geometry_msgs::PoseWithCovariance& b, geometry_msgs::PoseWithCovariance& out);
00014         void compose(const geometry_msgs::PoseWithCovariance& a, const geometry_msgs::Pose& b, geometry_msgs::PoseWithCovariance& out);
00015         void compose(const geometry_msgs::Pose& a, const geometry_msgs::PoseWithCovariance& b, geometry_msgs::PoseWithCovariance& out);
00020         void inverseCompose(const geometry_msgs::Pose& a, const geometry_msgs::Pose& b, geometry_msgs::Pose& out);
00021         void inverseCompose(const geometry_msgs::PoseWithCovariance& a, const geometry_msgs::PoseWithCovariance& b, geometry_msgs::PoseWithCovariance& out);
00022         void inverseCompose(const geometry_msgs::PoseWithCovariance& a, const geometry_msgs::Pose& b, geometry_msgs::PoseWithCovariance& out);
00023         void inverseCompose(const geometry_msgs::Pose& a, const geometry_msgs::PoseWithCovariance& b, geometry_msgs::PoseWithCovariance& out);
00026 }
00027 
00028 #endif /* POSE_COV_OPS_H_ */


pose_cov_ops
Author(s):
autogenerated on Sun Apr 7 2019 02:31:09