costmap_2d_ros.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 /*****************************************************************************
4 ** Includes
5 *****************************************************************************/
6 
10 #if ROS_VERSION_MINIMUM(1,14,0)
12 #else
13 #include <tf/transform_listener.h>
14 #endif
15 
16 #include <atomic>
17 #include <map>
18 #include <string>
19 #include <thread>
20 
21 /*****************************************************************************
22 ** Transforms
23 *****************************************************************************/
24 
29 public:
31  virtual ~TransformBroadcaster();
32  void add(const std::string& name, tf::Vector3 origin, const tf::Quaternion& orientation);
33 
35  void broadcast();
36  void shutdown();
37 
38 private:
39  std::map<std::string, tf::Transform> transforms_;
40  std::thread broadcastingThread_;
41  std::atomic<bool> shutdownFlag_;
42 };
43 
55 public:
57  typedef std::shared_ptr<ROSCostmap> ROSCostmapPtr;
58 
59  ROSCostmapServer(const std::string& name, const std::string& baseLinkTransformName,
60  const grid_map::Position& origin, const double& width, const double& height);
61 
62  ROSCostmapPtr getROSCostmap() { return costmap_; };
63 
64 private:
65  ROSCostmapPtr costmap_;
66 #if ROS_VERSION_MINIMUM(1,14,0)
67  tf2_ros::Buffer tfBuffer_;
68  tf2_ros::TransformListener tfListener_;
69 #else
71 #endif
72 };
73 
74 
75 /*****************************************************************************
76 ** Helpers
77 *****************************************************************************/
78 
86 
Broadcast a set of transforms useful for various demos.
std::thread broadcastingThread_
void broadcastCostmap2DROSTestSuiteTransforms(TransformBroadcaster &broadcaster)
std::map< std::string, tf::Transform > transforms_
void add(const std::string &name, tf::Vector3 origin, const tf::Quaternion &orientation)
tf::TransformListener tfListener_
costmap_2d::Costmap2DROS ROSCostmap
ROSCostmapPtr getROSCostmap()
Eigen::Vector2d Position
virtual ~TransformBroadcaster()
std::shared_ptr< ROSCostmap > ROSCostmapPtr
std::atomic< bool > shutdownFlag_


grid_map_costmap_2d
Author(s): Péter Fankhauser
autogenerated on Tue Jun 25 2019 20:02:11