#include "general.h"
#include <ros/assert.h>
#include <cstdlib>
#include <boost/foreach.hpp>
#include <map>
#include <set>
#include <stdexcept>
#include <string>
#include <vector>
#include <ostream>
#include <stdint.h>
#include <ros/time.h>
#include "serialized_message.h"
#include "message_forward.h"
#include <boost/utility/enable_if.hpp>
#include <boost/type_traits/remove_const.hpp>
#include <boost/type_traits/remove_reference.hpp>
#include "message_traits.h"
#include "ros/exception.h"
#include <boost/array.hpp>
#include <boost/call_traits.hpp>
#include <boost/mpl/and.hpp>
#include <boost/mpl/or.hpp>
#include <boost/mpl/not.hpp>
#include <cstring>
#include "ros/builtin_message_traits.h"
#include "ros/macros.h"
#include <string.h>
#include <boost/shared_ptr.hpp>
#include "ros/serialization.h"
#include "ros/message_operations.h"
#include "ros/message.h"
#include "std_msgs/Header.h"
#include "geometry_msgs/Point.h"
#include "geometry_msgs/Quaternion.h"
#include "geometry_msgs/Vector3.h"
#include "geometry_msgs/PoseStamped.h"
#include "btMatrix3x3.h"
#include "ros/console.h"
#include <geometry_msgs/Pose.h>
#include "geometry_msgs/Point32.h"
Go to the source code of this file.
Namespaces | |
namespace | graph_mapping_utils |
Functions | |
tf::Pose | graph_mapping_utils::absolutePose (const tf::Pose &base, const gm::Pose &offset) |
Adjust a pose given a relative offset. | |
gm::Pose | graph_mapping_utils::absolutePose (const gm::Pose &base, const tf::Pose &offset) |
Adjust a pose given a relative offset. | |
btVector3 | graph_mapping_utils::barycenter (const sensor_msgs::LaserScan &scan) |
Return the barycenter of a laser scan (in the laser frame). | |
gm::Point | graph_mapping_utils::barycenter (const sensor_msgs::PointCloud &cloud) |
Return the barycenter of the cloud, in the same frame as the cloud itself. | |
double | graph_mapping_utils::euclideanDistance (const gm::Point &p1, const gm::Point &p2) |
Return euclidean distance between two 3d-positions. | |
double | graph_mapping_utils::length (const gm::Point &p) |
double | graph_mapping_utils::length (const btVector3 &v) |
gm::Point | graph_mapping_utils::makePoint (const double x, const double y, const double z=0.0) |
Construct a geometry_msgs Point. | |
tf::Pose | graph_mapping_utils::makePose (double x, double y, double theta) |
Construct a tf::Pose from x,y,theta. | |
gm::Pose2D | graph_mapping_utils::makePose2D (double x, double y, double theta=0.0) |
Construct a pose2d. | |
gm::Pose2D | graph_mapping_utils::projectToPose2D (const tf::Pose &pose) |
Project tf pose to pose2d. | |
gm::Pose2D | graph_mapping_utils::projectToPose2D (const gm::Pose &pose) |
Project Pose to Pose2D. | |
tf::Pose | graph_mapping_utils::relativePose (const tf::Pose &pose1, const tf::Pose &pose2) |
gm::Point | graph_mapping_utils::toPoint (const btVector3 &p) |
btVector3 | graph_mapping_utils::toPoint (const gm::Point &p) |
tf::Pose | graph_mapping_utils::toPose (const gm::Pose2D &p) |
Make a pose from a pose2d. | |
tf::Pose | graph_mapping_utils::toPose (const gm::Pose &p) |
gm::Pose | graph_mapping_utils::toPose (const tf::Pose &p) |
tf::Transform | graph_mapping_utils::transformBetween (const tf::Pose &pose1, const tf::Pose &pose2) |
Return the transform that sends pose1 to pose2. | |
gm::Point | graph_mapping_utils::transformPoint (const tf::Transform &trans, const gm::Point &point) |
Apply Bullet transformation to a ROS point. | |
gm::Point32 | graph_mapping_utils::transformPoint (const tf::Transform &trans, const gm::Point32 &point) |
Apply Bullet transformation to a ROS point. | |
gm::Pose | graph_mapping_utils::transformPose (const tf::Transform &trans, const gm::Pose &pose) |
Apply Bullet transformation to a ROS pose. |
Operations on and conversions between the ros and tf/bullet geometry types
Definition in file geometry.h.