tf_visual_tools.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015, University of Colorado, Boulder
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Univ of CO, Boulder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Dave Coleman <dave@dav.ee>
00036    Desc:   Helps debug and visualize transforms via the TF infrastructure
00037    Note:   We shouldn't have to publish the transforms at interval since they are static, but we do
00038    because of https://github.com/ros/geometry_experimental/issues/108
00039 */
00040 
00041 #ifndef RVIZ_VISUAL_TOOLS_TF_VISUAL_TOOLS_H
00042 #define RVIZ_VISUAL_TOOLS_TF_VISUAL_TOOLS_H
00043 
00044 // C++
00045 #include <vector>
00046 #include <string>
00047 
00048 // ROS
00049 #include <ros/ros.h>
00050 #include <geometry_msgs/TransformStamped.h>
00051 
00052 // Eigen
00053 #include <Eigen/Geometry>
00054 
00055 #include <tf2_ros/transform_broadcaster.h>
00056 
00057 // namespace tf2_ros
00058 // {
00059 // class StaticTransformBroadcaster;
00060 // };
00061 
00062 namespace rviz_visual_tools
00063 {
00064 class TFVisualTools
00065 {
00066 public:
00070   TFVisualTools();
00071 
00076   bool publishTransform(const Eigen::Affine3d& transform, const std::string& from_frame, const std::string& to_frame);
00077 
00081   void publishAllTransforms(const ros::TimerEvent& e);
00082 
00083 private:
00084   // A shared node handle
00085   ros::NodeHandle nh_;
00086 
00087   // Send tf messages
00088   tf2_ros::TransformBroadcaster tf_pub_;
00089 
00090   // Separate thread to publish transforms
00091   ros::Timer non_realtime_loop_;
00092 
00093   // Collect the transfroms
00094   std::vector<geometry_msgs::TransformStamped> transforms_;
00095 };  // end class
00096 
00097 // Create boost pointers for this class
00098 typedef boost::shared_ptr<TFVisualTools> TFVisualToolsPtr;
00099 typedef boost::shared_ptr<const TFVisualTools> TFVisualToolsConstPtr;
00100 
00101 }  // namespace rviz_visual_tools
00102 
00103 #endif  // RVIZ_VISUAL_TOOLS_TF_VISUAL_TOOLS_H


rviz_visual_tools
Author(s): Dave Coleman
autogenerated on Thu Jun 6 2019 19:01:23