#include <tf2_ros/buffer.h>#include "transform_storage.h"#include <string>#include <iostream>#include <math.h>#include <stdexcept>#include <climits>#include <stdint.h>#include <cmath>#include "duration.h"#include <sys/time.h>#include <vector>#include <ostream>#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 <cstdio>#include <sstream>#include <log4cxx/logger.h>#include <boost/static_assert.hpp>#include <cassert>#include <string.h>#include <boost/shared_ptr.hpp>#include "ros/serialization.h"#include "ros/message_operations.h"#include "ros/message.h"#include "btMatrix3x3.h"#include <boost/unordered_map.hpp>#include <boost/thread/mutex.hpp>#include <boost/function.hpp>#include <geometry_msgs/TransformStamped.h>#include <tf2/buffer_core.h>#include "ros/console.h"#include "ros/assert.h"#include <assert.h>#include <stddef.h>#include <map>#include <set>#include <list>#include <boost/weak_ptr.hpp>#include "exceptions.h"#include "ros/types.h"#include <boost/shared_array.hpp>#include "ros/forwards.h"#include "ros/common.h"#include <boost/bind.hpp>#include <typeinfo>#include <boost/type_traits/is_void.hpp>#include <boost/type_traits/is_base_of.hpp>#include <boost/type_traits/is_const.hpp>#include <boost/type_traits/add_const.hpp>#include <boost/make_shared.hpp>#include <ros/static_assert.h>#include "ros/message_traits.h"#include "ros/message_event.h"#include "ros/service_traits.h"#include "forwards.h"#include "timer_options.h"#include "wall_timer_options.h"#include <boost/lexical_cast.hpp>#include "subscription_callback_helper.h"#include "ros/spinner.h"#include <time.h>#include "ros/publisher.h"#include <boost/utility.hpp>#include "ros/service_server.h"#include "ros/subscriber.h"#include "ros/node_handle.h"#include "ros/init.h"#include "XmlRpcValue.h"#include "node_handle.h"#include "ros/names.h"#include "std_msgs/Header.h"#include "geometry_msgs/Vector3.h"#include "geometry_msgs/Point.h"#include "geometry_msgs/Quaternion.h"#include "utilities/kdl-config.h"#include "utilities/utility.h"
Go to the source code of this file.
Namespaces | |
| namespace | tf2 |
Functions | |
| template<> | |
| void | tf2::doTransform (const geometry_msgs::PoseStamped &t_in, geometry_msgs::PoseStamped &t_out, const geometry_msgs::TransformStamped &transform) |
| template<> | |
| void | tf2::doTransform (const geometry_msgs::PointStamped &t_in, geometry_msgs::PointStamped &t_out, const geometry_msgs::TransformStamped &transform) |
| template<> | |
| void | tf2::doTransform (const geometry_msgs::Vector3Stamped &t_in, geometry_msgs::Vector3Stamped &t_out, const geometry_msgs::TransformStamped &transform) |
| void | tf2::fromMsg (const geometry_msgs::PoseStamped &msg, geometry_msgs::PoseStamped &out) |
| void | tf2::fromMsg (const geometry_msgs::PointStamped &msg, geometry_msgs::PointStamped &out) |
| void | tf2::fromMsg (const geometry_msgs::Vector3Stamped &msg, geometry_msgs::Vector3Stamped &out) |
| template<> | |
| const std::string & | tf2::getFrameId (const geometry_msgs::PoseStamped &t) |
| template<> | |
| const std::string & | tf2::getFrameId (const geometry_msgs::PointStamped &t) |
| template<> | |
| const std::string & | tf2::getFrameId (const geometry_msgs::Vector3Stamped &t) |
| template<> | |
| const ros::Time & | tf2::getTimestamp (const geometry_msgs::PoseStamped &t) |
| template<> | |
| const ros::Time & | tf2::getTimestamp (const geometry_msgs::PointStamped &t) |
| template<> | |
| const ros::Time & | tf2::getTimestamp (const geometry_msgs::Vector3Stamped &t) |
| KDL::Frame | tf2::gmTransformToKDL (const geometry_msgs::TransformStamped &t) |
| geometry_msgs::PoseStamped | tf2::toMsg (const geometry_msgs::PoseStamped &in) |
| geometry_msgs::PointStamped | tf2::toMsg (const geometry_msgs::PointStamped &in) |
| geometry_msgs::Vector3Stamped | tf2::toMsg (const geometry_msgs::Vector3Stamped &in) |