costmap_client.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015-2016, Jiri Horner.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Jiri Horner nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  *********************************************************************/
36 
37 #ifndef COSTMAP_CLIENT_
38 #define COSTMAP_CLIENT_
39 
40 #include <costmap_2d/costmap_2d.h>
41 #include <geometry_msgs/Pose.h>
42 #include <map_msgs/OccupancyGridUpdate.h>
43 #include <nav_msgs/OccupancyGrid.h>
44 #include <ros/ros.h>
45 #include <tf/tf.h>
46 #include <tf/transform_listener.h>
47 
48 namespace explore
49 {
51 {
52 public:
63  Costmap2DClient(ros::NodeHandle& param_nh, ros::NodeHandle& subscription_nh,
64  const tf::TransformListener* tf_listener);
69  geometry_msgs::Pose getRobotPose() const;
70 
78  {
79  return &costmap_;
80  }
81 
89  {
90  return &costmap_;
91  }
92 
97  const std::string& getGlobalFrameID() const
98  {
99  return global_frame_;
100  }
101 
106  const std::string& getBaseFrameID() const
107  {
108  return robot_base_frame_;
109  }
110 
111 protected:
112  void updateFullMap(const nav_msgs::OccupancyGrid::ConstPtr& msg);
113  void updatePartialMap(const map_msgs::OccupancyGridUpdate::ConstPtr& msg);
114 
116 
117  const tf::TransformListener* const tf_;
118  std::string global_frame_;
120  std::string robot_base_frame_;
122 
123 private:
124  // will be unsubscribed at destruction
127 };
128 
129 } // namespace explore
130 
131 #endif
double transform_tolerance_
timeout before transform errors
geometry_msgs::Pose getRobotPose() const
Get the pose of the robot in the global frame of the costmap.
costmap_2d::Costmap2D * getCostmap()
Return a pointer to the "master" costmap which receives updates from all the layers.
void updatePartialMap(const map_msgs::OccupancyGridUpdate::ConstPtr &msg)
ros::Subscriber costmap_updates_sub_
void updateFullMap(const nav_msgs::OccupancyGrid::ConstPtr &msg)
const std::string & getGlobalFrameID() const
Returns the global frame of the costmap.
const costmap_2d::Costmap2D * getCostmap() const
Return a pointer to the "master" costmap which receives updates from all the layers.
ros::Subscriber costmap_sub_
std::string robot_base_frame_
The frame_id of the robot base.
costmap_2d::Costmap2D costmap_
Costmap2DClient(ros::NodeHandle &param_nh, ros::NodeHandle &subscription_nh, const tf::TransformListener *tf_listener)
Contructs client and start listening.
const std::string & getBaseFrameID() const
Returns the local frame of the costmap.
const tf::TransformListener *const tf_
Used for transforming point clouds.
std::string global_frame_
The global frame for the costmap.


explore
Author(s): Jiri Horner
autogenerated on Mon Jun 10 2019 13:56:49