geometry.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  */
00030 
00031 
00039 #ifndef POSE_GRAPH_GEOMETRY_H
00040 #define POSE_GRAPH_GEOMETRY_H
00041 
00042 #include <Eigen3/Dense>
00043 #include <iostream>
00044 #include <geometry_msgs/Pose.h>
00045 #include <geometry_msgs/Point32.h>
00046 #include <geometry_msgs/Pose2D.h>
00047 #include <sensor_msgs/LaserScan.h>
00048 
00049 namespace pose_graph
00050 {
00051 
00052 using std::ostream;
00053 
00054 typedef Eigen3::Matrix<double, 6, 6> PrecisionMatrix;
00055 
00057 struct PoseConstraint
00058 {
00059   PoseConstraint ();
00060   PoseConstraint (const Eigen3::Vector3d& translation, const Eigen3::Quaterniond& rotation);
00061   PoseConstraint (const Eigen3::Vector3d& translation, const Eigen3::Quaterniond& rotation, const PrecisionMatrix& precision);
00062 
00063   Eigen3::Vector3d translation;
00064   Eigen3::Quaterniond rotation;
00065   PrecisionMatrix precision;
00066 
00067   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00068 };
00069 
00070 ostream& operator<< (ostream& str, const PoseConstraint& constraint);
00071 
00073 double length (const Eigen3::Vector3d& v);
00074 
00076 double length (const PoseConstraint& constraint);
00077 
00078 // Norm of a Point
00079 double length (const geometry_msgs::Point& p);
00080 
00082 geometry_msgs::Pose getPose (const PoseConstraint& c);
00083 
00084 // Given a transform between two frames, get a PoseConstraint.
00085 PoseConstraint makeConstraint (const Eigen3::Affine3d& trans, const Eigen3::Matrix<double, 6, 6>& prec);
00086 
00087 // Get distance between two points
00088 double euclideanDistance (const geometry_msgs::Point& p1, const geometry_msgs::Point& p2);
00089 
00090 // Get distance between two poses using a multiplier for the angular part
00091 double euclideanDistance (const geometry_msgs::Pose2D& p1, const geometry_msgs::Pose2D& p2,
00092                           const double rad_to_m=1.0);
00093 
00094 // Transform between point32 and point
00095 geometry_msgs::Point convertToPoint (const geometry_msgs::Point32& p);
00096 
00097 // Barycenter of a scan
00098 geometry_msgs::Point computeBarycenter (const sensor_msgs::LaserScan& scan);
00099 
00103 PrecisionMatrix makePrecisionMatrix (const double x_prec, const double y_prec, const double theta_prec);
00104 
00108 PrecisionMatrix makePrecisionMatrix (const double x_prec, const double y_prec, const double xy_prec,
00109                                      const double theta_prec);
00110 
00111 } // namespace pose_graph
00112 
00113 #endif // POSE_GRAPH_GEOMETRY_H


pose_graph
Author(s): Bhaskara Marthi
autogenerated on Tue Jan 7 2014 11:17:15