Go to the documentation of this file.
   38 #ifndef COSTMAP_2D_COSTMAP_2D_ROS_H_ 
   39 #define COSTMAP_2D_COSTMAP_2D_ROS_H_ 
   44 #include <costmap_2d/Costmap2DConfig.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> 
   64     _value.asArray = 
new std::vector<XmlRpc::XmlRpcValue>(*a);
 
  133   bool getRobotPose(geometry_msgs::PoseStamped& global_pose) 
const;
 
  136   inline const std::string& 
getName() const noexcept
 
  252                                const costmap_2d::Costmap2DConfig &old_config);
 
  258   void reconfigureCB(costmap_2d::Costmap2DConfig &config, uint32_t level);
 
  268   dynamic_reconfigure::Server<costmap_2d::Costmap2DConfig> *
dsrv_;
 
  282 #endif  // COSTMAP_2D_COSTMAP_2D_ROS_H 
  
costmap_2d::Costmap2DConfig old_config_
tf2_ros::Buffer & tf_
Used for transforming point clouds.
std::map< std::string, XmlRpcValue > ValueStruct
void readFootprintFromConfig(const costmap_2d::Costmap2DConfig &new_config, const costmap_2d::Costmap2DConfig &old_config)
Set the footprint from the new_config object.
void setUnpaddedRobotFootprintPolygon(const geometry_msgs::Polygon &footprint)
Set the footprint of the robot to be the given polygon, padded by footprint_padding.
geometry_msgs::Polygon getRobotFootprintPolygon() const
Returns the current padded footprint as a geometry_msgs::Polygon.
bool isStopped() const
Is the costmap stopped.
void movementCB(const ros::TimerEvent &event)
void loadOldParameters(ros::NodeHandle &nh)
void resume()
Resumes costmap updates.
const std::string & getBaseFrameID() const noexcept
Returns the local frame of the costmap.
void setArray(XmlRpc::XmlRpcValue::ValueArray *a)
A 2D costmap provides a mapping between points in the world and their associated "costs".
void checkOldParam(ros::NodeHandle &nh, const std::string ¶m_name)
void setStruct(XmlRpc::XmlRpcValue::ValueStruct *a)
double transform_tolerance_
timeout before transform errors
boost::thread * map_update_thread_
A thread for updating the map.
std::string robot_base_frame_
The frame_id of the robot base.
void mapUpdateLoop(double frequency)
const std::vector< geometry_msgs::Point > & getRobotFootprint() const noexcept
Return the current footprint of the robot as a vector of points.
ros::Publisher footprint_pub_
double getTransformTolerance() const
Returns the delay in transform (tf) data that is tolerable in seconds.
std::vector< geometry_msgs::Point > unpadded_footprint_
void resetLayers()
Reset each individual layer.
std::string global_frame_
The global frame for the costmap.
Costmap2DROS(const std::string &name, tf2_ros::Buffer &tf)
Constructor for the wrapper.
dynamic_reconfigure::Server< costmap_2d::Costmap2DConfig > * dsrv_
LayeredCostmap * getLayeredCostmap() const
ros::Subscriber footprint_sub_
pluginlib::ClassLoader< Layer > plugin_loader_
void getOrientedFootprint(std::vector< geometry_msgs::Point > &oriented_footprint) const
Build the oriented footprint of the robot at the robot's current pose.
std::vector< XmlRpcValue > ValueArray
void reconfigureCB(costmap_2d::Costmap2DConfig &config, uint32_t level)
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.
boost::recursive_mutex configuration_mutex_
void start()
Subscribes to sensor topics if necessary and starts costmap updates, can be called to restart the cos...
void warnForOldParameters(ros::NodeHandle &nh)
const std::vector< geometry_msgs::Point > & getUnpaddedRobotFootprint() const noexcept
Return the current unpadded footprint of the robot as a vector of points.
Costmap2DPublisher * publisher_
bool getRobotPose(geometry_msgs::PoseStamped &global_pose) const
Get the pose of the robot in the global frame of the costmap.
void pause()
Stops the costmap from updating, but sensor data still comes in over the wire.
union XmlRpc::XmlRpcValue::@0 _value
ros::Duration publish_cycle
bool isCurrent() const
Same as getLayeredCostmap()->isCurrent().
void stop()
Stops costmap updates and unsubscribes from sensor topics.
const std::string & getName() const noexcept
Returns costmap name.
Instantiates different layer plugins and aggregates them into one score.
A tool to periodically publish visualization data from a Costmap2D.
Costmap2D * getCostmap() const
Return a pointer to the "master" costmap which receives updates from all the layers.
const std::string & getGlobalFrameID() const noexcept
Returns the global frame of the costmap.
void copyParentParameters(const std::string &plugin_name, const std::string &plugin_type, ros::NodeHandle &nh)
std::vector< geometry_msgs::Point > padded_footprint_
LayeredCostmap * layered_costmap_
A ROS wrapper for a 2D Costmap. Handles subscribing to topics that provide observations about obstacl...
bool map_update_thread_shutdown_
geometry_msgs::Polygon toPolygon(std::vector< geometry_msgs::Point > pts)
Convert vector of Points to Polygon msg.
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17