PoseInfoContainer.cpp
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2012, Stefan Kohlbrecher, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Simulation, Systems Optimization and Robotics
13 // group, TU Darmstadt nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 #include "PoseInfoContainer.h"
30 
31 void PoseInfoContainer::update(const Eigen::Vector3f& slamPose, const Eigen::Matrix3f& slamCov, const ros::Time& stamp, const std::string& frame_id)
32 {
33  //Fill stampedPose
34  std_msgs::Header& header = stampedPose_.header;
35  header.stamp = stamp;
36  header.frame_id = frame_id;
37 
38  geometry_msgs::Pose& pose = stampedPose_.pose;
39  pose.position.x = slamPose.x();
40  pose.position.y = slamPose.y();
41 
42  pose.orientation.w = cos(slamPose.z()*0.5f);
43  pose.orientation.z = sin(slamPose.z()*0.5f);
44 
45  //Fill covPose
46  //geometry_msgs::PoseWithCovarianceStamped covPose;
47  covPose_.header = header;
48  covPose_.pose.pose = pose;
49 
50  boost::array<double, 36>& cov(covPose_.pose.covariance);
51 
52  cov[0] = static_cast<double>(slamCov(0,0));
53  cov[7] = static_cast<double>(slamCov(1,1));
54  cov[35] = static_cast<double>(slamCov(2,2));
55 
56  double xyC = static_cast<double>(slamCov(0,1));
57  cov[1] = xyC;
58  cov[6] = xyC;
59 
60  double xaC = static_cast<double>(slamCov(0,2));
61  cov[5] = xaC;
62  cov[30] = xaC;
63 
64  double yaC = static_cast<double>(slamCov(1,2));
65  cov[11] = yaC;
66  cov[31] = yaC;
67 
68  //Fill tf tansform
70 }
static void poseMsgToTF(const geometry_msgs::Pose &msg, Pose &bt)
tf::Transform poseTransform_
void update(const Eigen::Vector3f &slamPose, const Eigen::Matrix3f &slamCov, const ros::Time &stamp, const std::string &frame_id)
geometry_msgs::PoseWithCovarianceStamped covPose_
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
geometry_msgs::PoseStamped stampedPose_


hector_mapping
Author(s): Stefan Kohlbrecher
autogenerated on Sun Nov 3 2019 03:18:33