costmap_2d_ros.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
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 Willow Garage, Inc. 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  * Author: Eitan Marder-Eppstein
36  * David V. Lu!!
37  *********************************************************************/
38 #ifndef COSTMAP_2D_COSTMAP_2D_ROS_H_
39 #define COSTMAP_2D_COSTMAP_2D_ROS_H_
40 
42 #include <costmap_2d/layer.h>
44 #include <costmap_2d/Costmap2DConfig.h>
45 #include <costmap_2d/footprint.h>
46 #include <geometry_msgs/Polygon.h>
47 #include <geometry_msgs/PolygonStamped.h>
48 #include <geometry_msgs/PoseStamped.h>
49 #include <dynamic_reconfigure/server.h>
52 
54 {
55 public:
57  {
58  _type = TypeStruct;
59  _value.asStruct = new XmlRpc::XmlRpcValue::ValueStruct(*a);
60  }
62  {
63  _type = TypeArray;
64  _value.asArray = new std::vector<XmlRpc::XmlRpcValue>(*a);
65  }
66 };
67 
68 namespace costmap_2d
69 {
70 
75 {
76 public:
82  Costmap2DROS(const std::string &name, tf2_ros::Buffer& tf);
83  ~Costmap2DROS();
84 
90  void start();
91 
95  void stop();
96 
100  void pause();
101 
105  void resume();
106 
107  void updateMap();
108 
112  void resetLayers();
113 
115  bool isCurrent() const
116  {
117  return layered_costmap_->isCurrent();
118  }
119 
123  bool isStopped() const
124  {
125  return stopped_;
126  }
127 
133  bool getRobotPose(geometry_msgs::PoseStamped& global_pose) const;
134 
136  inline const std::string& getName() const noexcept
137  {
138  return name_;
139  }
140 
142  double getTransformTolerance() const
143  {
144  return transform_tolerance_;
145  }
146 
151  {
152  return layered_costmap_->getCostmap();
153  }
154 
159  inline const std::string& getGlobalFrameID() const noexcept
160  {
161  return global_frame_;
162  }
163 
168  inline const std::string& getBaseFrameID() const noexcept
169  {
170  return robot_base_frame_;
171  }
173  {
174  return layered_costmap_;
175  }
176 
178  geometry_msgs::Polygon getRobotFootprintPolygon() const
179  {
181  }
182 
191  inline const std::vector<geometry_msgs::Point>& getRobotFootprint() const noexcept
192  {
193  return padded_footprint_;
194  }
195 
203  inline const std::vector<geometry_msgs::Point>& getUnpaddedRobotFootprint() const noexcept
204  {
205  return unpadded_footprint_;
206  }
207 
212  void getOrientedFootprint(std::vector<geometry_msgs::Point>& oriented_footprint) const;
213 
224  void setUnpaddedRobotFootprint(const std::vector<geometry_msgs::Point>& points);
225 
236  void setUnpaddedRobotFootprintPolygon(const geometry_msgs::Polygon& footprint);
237 
238 protected:
240  std::string name_;
242  std::string global_frame_;
243  std::string robot_base_frame_;
245 
246 private:
251  void readFootprintFromConfig(const costmap_2d::Costmap2DConfig &new_config,
252  const costmap_2d::Costmap2DConfig &old_config);
253 
256  void checkOldParam(ros::NodeHandle& nh, const std::string &param_name);
257  void copyParentParameters(const std::string& plugin_name, const std::string& plugin_type, ros::NodeHandle& nh);
258  void reconfigureCB(costmap_2d::Costmap2DConfig &config, uint32_t level);
259  void movementCB(const ros::TimerEvent &event);
260  void mapUpdateLoop(double frequency);
263  boost::thread* map_update_thread_;
268  dynamic_reconfigure::Server<costmap_2d::Costmap2DConfig> *dsrv_;
269 
270  boost::recursive_mutex configuration_mutex_;
271 
274  std::vector<geometry_msgs::Point> unpadded_footprint_;
275  std::vector<geometry_msgs::Point> padded_footprint_;
277  costmap_2d::Costmap2DConfig old_config_;
278 };
279 // class Costmap2DROS
280 } // namespace costmap_2d
281 
282 #endif // COSTMAP_2D_COSTMAP_2D_ROS_H
ros::Publisher
costmap_2d::Costmap2DROS::old_config_
costmap_2d::Costmap2DConfig old_config_
Definition: costmap_2d_ros.h:277
costmap_2d::Costmap2DROS::tf_
tf2_ros::Buffer & tf_
Used for transforming point clouds.
Definition: costmap_2d_ros.h:241
XmlRpc::XmlRpcValue::ValueStruct
std::map< std::string, XmlRpcValue > ValueStruct
costmap_2d::Costmap2DROS::readFootprintFromConfig
void readFootprintFromConfig(const costmap_2d::Costmap2DConfig &new_config, const costmap_2d::Costmap2DConfig &old_config)
Set the footprint from the new_config object.
Definition: costmap_2d_ros.cpp:358
costmap_2d::Costmap2DROS::setUnpaddedRobotFootprintPolygon
void setUnpaddedRobotFootprintPolygon(const geometry_msgs::Polygon &footprint)
Set the footprint of the robot to be the given polygon, padded by footprint_padding.
Definition: costmap_2d_ros.cpp:172
costmap_2d::Costmap2DROS::getRobotFootprintPolygon
geometry_msgs::Polygon getRobotFootprintPolygon() const
Returns the current padded footprint as a geometry_msgs::Polygon.
Definition: costmap_2d_ros.h:178
costmap_2d::Costmap2DROS::isStopped
bool isStopped() const
Is the costmap stopped.
Definition: costmap_2d_ros.h:123
costmap_2d::Costmap2DROS::~Costmap2DROS
~Costmap2DROS()
Definition: costmap_2d_ros.cpp:177
layered_costmap.h
costmap_2d::Costmap2DROS::movementCB
void movementCB(const ros::TimerEvent &event)
Definition: costmap_2d_ros.cpp:399
costmap_2d::Costmap2DROS::loadOldParameters
void loadOldParameters(ros::NodeHandle &nh)
Definition: costmap_2d_ros.cpp:192
layer.h
costmap_2d::Costmap2DROS::resume
void resume()
Resumes costmap updates.
Definition: costmap_2d_ros.cpp:523
costmap_2d::Costmap2DROS::getBaseFrameID
const std::string & getBaseFrameID() const noexcept
Returns the local frame of the costmap.
Definition: costmap_2d_ros.h:168
SuperValue::setArray
void setArray(XmlRpc::XmlRpcValue::ValueArray *a)
Definition: costmap_2d_ros.h:97
costmap_2d::Costmap2D
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.h:96
costmap_2d::Costmap2DROS::checkOldParam
void checkOldParam(ros::NodeHandle &nh, const std::string &param_name)
Definition: costmap_2d_ros.cpp:305
SuperValue::setStruct
void setStruct(XmlRpc::XmlRpcValue::ValueStruct *a)
Definition: costmap_2d_ros.h:92
costmap_2d::Costmap2DROS::transform_tolerance_
double transform_tolerance_
timeout before transform errors
Definition: costmap_2d_ros.h:244
costmap_2d::Costmap2DROS::map_update_thread_
boost::thread * map_update_thread_
A thread for updating the map.
Definition: costmap_2d_ros.h:263
costmap_2d::Costmap2DROS::robot_base_frame_
std::string robot_base_frame_
The frame_id of the robot base.
Definition: costmap_2d_ros.h:243
XmlRpc::XmlRpcValue::TypeStruct
TypeStruct
costmap_2d::Costmap2DROS::mapUpdateLoop
void mapUpdateLoop(double frequency)
Definition: costmap_2d_ros.cpp:412
costmap_2d::Costmap2DROS::getRobotFootprint
const std::vector< geometry_msgs::Point > & getRobotFootprint() const noexcept
Return the current footprint of the robot as a vector of points.
Definition: costmap_2d_ros.h:191
costmap_2d::Costmap2DROS::footprint_pub_
ros::Publisher footprint_pub_
Definition: costmap_2d_ros.h:273
costmap_2d::Costmap2DROS::getTransformTolerance
double getTransformTolerance() const
Returns the delay in transform (tf) data that is tolerable in seconds.
Definition: costmap_2d_ros.h:142
costmap_2d::Costmap2DROS::unpadded_footprint_
std::vector< geometry_msgs::Point > unpadded_footprint_
Definition: costmap_2d_ros.h:274
costmap_2d::Costmap2DROS::resetLayers
void resetLayers()
Reset each individual layer.
Definition: costmap_2d_ros.cpp:534
costmap_2d::Costmap2DROS::global_frame_
std::string global_frame_
The global frame for the costmap.
Definition: costmap_2d_ros.h:242
costmap_2d::Costmap2DROS::Costmap2DROS
Costmap2DROS(const std::string &name, tf2_ros::Buffer &tf)
Constructor for the wrapper.
Definition: costmap_2d_ros.cpp:64
costmap_2d::Costmap2DROS::dsrv_
dynamic_reconfigure::Server< costmap_2d::Costmap2DConfig > * dsrv_
Definition: costmap_2d_ros.h:268
costmap_2d::Costmap2DROS::name_
std::string name_
Definition: costmap_2d_ros.h:240
costmap_2d::Costmap2DROS::getLayeredCostmap
LayeredCostmap * getLayeredCostmap() const
Definition: costmap_2d_ros.h:172
XmlRpc::XmlRpcValue::_type
Type _type
costmap_2d::Costmap2DROS::footprint_sub_
ros::Subscriber footprint_sub_
Definition: costmap_2d_ros.h:272
costmap_2d::Costmap2DROS::plugin_loader_
pluginlib::ClassLoader< Layer > plugin_loader_
Definition: costmap_2d_ros.h:266
costmap_2d::Costmap2DROS::getOrientedFootprint
void getOrientedFootprint(std::vector< geometry_msgs::Point > &oriented_footprint) const
Build the oriented footprint of the robot at the robot's current pose.
Definition: costmap_2d_ros.cpp:597
XmlRpc::XmlRpcValue::ValueArray
std::vector< XmlRpcValue > ValueArray
tf2_ros::Buffer
costmap_2d::Costmap2DROS::initialized_
bool initialized_
Definition: costmap_2d_ros.h:262
costmap_2d::Costmap2DROS::reconfigureCB
void reconfigureCB(costmap_2d::Costmap2DConfig &config, uint32_t level)
Definition: costmap_2d_ros.cpp:311
costmap_2d::Costmap2DROS::setUnpaddedRobotFootprint
void setUnpaddedRobotFootprint(const std::vector< geometry_msgs::Point > &points)
Set the footprint of the robot to be the given set of points, padded by footprint_padding.
Definition: costmap_2d_ros.cpp:390
costmap_2d::Costmap2DROS::stopped_
bool stopped_
Definition: costmap_2d_ros.h:262
costmap_2d::Costmap2DROS::stop_updates_
bool stop_updates_
Definition: costmap_2d_ros.h:262
pluginlib::ClassLoader
class_loader.hpp
ros::TimerEvent
costmap_2d::Costmap2DROS::last_publish_
ros::Time last_publish_
Definition: costmap_2d_ros.h:264
costmap_2d::Costmap2DROS::configuration_mutex_
boost::recursive_mutex configuration_mutex_
Definition: costmap_2d_ros.h:270
costmap_2d::LayeredCostmap::isCurrent
bool isCurrent()
Definition: layered_costmap.cpp:165
costmap_2d::Costmap2DROS::start
void start()
Subscribes to sensor topics if necessary and starts costmap updates, can be called to restart the cos...
Definition: costmap_2d_ros.cpp:480
costmap_2d::Costmap2DROS::warnForOldParameters
void warnForOldParameters(ros::NodeHandle &nh)
Definition: costmap_2d_ros.cpp:299
costmap_2d::Costmap2DROS::getUnpaddedRobotFootprint
const std::vector< geometry_msgs::Point > & getUnpaddedRobotFootprint() const noexcept
Return the current unpadded footprint of the robot as a vector of points.
Definition: costmap_2d_ros.h:203
XmlRpc::XmlRpcValue::TypeArray
TypeArray
footprint.h
costmap_2d_publisher.h
costmap_2d::Costmap2DROS::publisher_
Costmap2DPublisher * publisher_
Definition: costmap_2d_ros.h:267
ros::Time
costmap_2d::Costmap2DROS::getRobotPose
bool getRobotPose(geometry_msgs::PoseStamped &global_pose) const
Get the pose of the robot in the global frame of the costmap.
Definition: costmap_2d_ros.cpp:546
costmap_2d::Costmap2DROS::footprint_padding_
float footprint_padding_
Definition: costmap_2d_ros.h:276
costmap_2d::Costmap2DROS::pause
void pause()
Stops the costmap from updating, but sensor data still comes in over the wire.
Definition: costmap_2d_ros.cpp:517
XmlRpc::XmlRpcValue::_value
union XmlRpc::XmlRpcValue::@0 _value
costmap_2d::Costmap2DROS::publish_cycle
ros::Duration publish_cycle
Definition: costmap_2d_ros.h:265
costmap_2d::Costmap2DROS::isCurrent
bool isCurrent() const
Same as getLayeredCostmap()->isCurrent().
Definition: costmap_2d_ros.h:115
SuperValue
Definition: costmap_2d_ros.h:53
costmap_2d::Costmap2DROS::stop
void stop()
Stops costmap updates and unsubscribes from sensor topics.
Definition: costmap_2d_ros.cpp:503
costmap_2d::Costmap2DROS::getName
const std::string & getName() const noexcept
Returns costmap name.
Definition: costmap_2d_ros.h:136
costmap_2d::LayeredCostmap
Instantiates different layer plugins and aggregates them into one score.
Definition: layered_costmap.h:91
tf
costmap_2d::LayeredCostmap::getCostmap
Costmap2D * getCostmap()
Definition: layered_costmap.h:128
costmap_2d::Costmap2DPublisher
A tool to periodically publish visualization data from a Costmap2D.
Definition: costmap_2d_publisher.h:87
costmap_2d::Costmap2DROS::getCostmap
Costmap2D * getCostmap() const
Return a pointer to the "master" costmap which receives updates from all the layers.
Definition: costmap_2d_ros.h:150
costmap_2d::Costmap2DROS::updateMap
void updateMap()
Definition: costmap_2d_ros.cpp:455
costmap_2d::Costmap2DROS::getGlobalFrameID
const std::string & getGlobalFrameID() const noexcept
Returns the global frame of the costmap.
Definition: costmap_2d_ros.h:159
costmap_2d::Costmap2DROS::copyParentParameters
void copyParentParameters(const std::string &plugin_name, const std::string &plugin_type, ros::NodeHandle &nh)
Definition: costmap_2d_ros.cpp:265
costmap_2d::Costmap2DROS::padded_footprint_
std::vector< geometry_msgs::Point > padded_footprint_
Definition: costmap_2d_ros.h:275
costmap_2d
Definition: array_parser.h:37
ros::Duration
costmap_2d::Costmap2DROS::layered_costmap_
LayeredCostmap * layered_costmap_
Definition: costmap_2d_ros.h:239
costmap_2d::Costmap2DROS
A ROS wrapper for a 2D Costmap. Handles subscribing to topics that provide observations about obstacl...
Definition: costmap_2d_ros.h:74
costmap_2d::Costmap2DROS::map_update_thread_shutdown_
bool map_update_thread_shutdown_
Definition: costmap_2d_ros.h:261
Transform.h
XmlRpc::XmlRpcValue
ros::NodeHandle
ros::Subscriber
costmap_2d::toPolygon
geometry_msgs::Polygon toPolygon(std::vector< geometry_msgs::Point > pts)
Convert vector of Points to Polygon msg.
Definition: footprint.cpp:87


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17