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);
117 return layered_costmap_->isCurrent();
125 bool getRobotPose(geometry_msgs::PoseStamped& global_pose)
const;
136 return transform_tolerance_;
144 return layered_costmap_->getCostmap();
153 return global_frame_;
162 return robot_base_frame_;
166 return layered_costmap_;
185 return padded_footprint_;
197 return unpadded_footprint_;
204 void getOrientedFootprint(std::vector<geometry_msgs::Point>& oriented_footprint)
const;
216 void setUnpaddedRobotFootprint(
const std::vector<geometry_msgs::Point>& points);
228 void setUnpaddedRobotFootprintPolygon(
const geometry_msgs::Polygon& footprint);
243 void readFootprintFromConfig(
const costmap_2d::Costmap2DConfig &new_config,
244 const costmap_2d::Costmap2DConfig &old_config);
248 void checkOldParam(
ros::NodeHandle& nh,
const std::string ¶m_name);
249 void copyParentParameters(
const std::string& plugin_name,
const std::string& plugin_type,
ros::NodeHandle& nh);
250 void reconfigureCB(costmap_2d::Costmap2DConfig &config, uint32_t level);
252 void mapUpdateLoop(
double frequency);
254 bool stop_updates_, initialized_,
stopped_, robot_stopped_;
262 dynamic_reconfigure::Server<costmap_2d::Costmap2DConfig> *
dsrv_;
276 #endif // COSTMAP_2D_COSTMAP_2D_ROS_H
boost::recursive_mutex configuration_mutex_
std::vector< XmlRpcValue > ValueArray
tf2_ros::Buffer & tf_
Used for transforming point clouds.
bool map_update_thread_shutdown_
costmap_2d::Costmap2DConfig old_config_
std::string getGlobalFrameID()
Returns the global frame of the costmap.
dynamic_reconfigure::Server< costmap_2d::Costmap2DConfig > * dsrv_
ros::Duration publish_cycle
std::string getName() const
Returns costmap name.
boost::thread * map_update_thread_
A thread for updating the map.
LayeredCostmap * layered_costmap_
union XmlRpc::XmlRpcValue::@0 _value
std::map< std::string, XmlRpcValue > ValueStruct
ros::Subscriber footprint_sub_
std::string global_frame_
The global frame for the costmap.
std::string getBaseFrameID()
Returns the local frame of the costmap.
Costmap2DPublisher * publisher_
double getTransformTolerance() const
Returns the delay in transform (tf) data that is tolerable in seconds.
geometry_msgs::PoseStamped old_pose_
pluginlib::ClassLoader< Layer > plugin_loader_
std::string robot_base_frame_
The frame_id of the robot base.
geometry_msgs::Polygon toPolygon(std::vector< geometry_msgs::Point > pts)
Convert vector of Points to Polygon msg.
A tool to periodically publish visualization data from a Costmap2D.
geometry_msgs::Polygon getRobotFootprintPolygon()
Returns the current padded footprint as a geometry_msgs::Polygon.
double transform_tolerance_
timeout before transform errors
bool isCurrent()
Same as getLayeredCostmap()->isCurrent().
ros::Publisher footprint_pub_
std::vector< geometry_msgs::Point > getUnpaddedRobotFootprint()
Return the current unpadded footprint of the robot as a vector of points.
A 2D costmap provides a mapping between points in the world and their associated "costs".
Costmap2D * getCostmap()
Return a pointer to the "master" costmap which receives updates from all the layers.
A ROS wrapper for a 2D Costmap. Handles subscribing to topics that provide observations about obstacl...
std::vector< geometry_msgs::Point > getRobotFootprint()
Return the current footprint of the robot as a vector of points.
Instantiates different layer plugins and aggregates them into one score.
void setArray(XmlRpc::XmlRpcValue::ValueArray *a)
void setStruct(XmlRpc::XmlRpcValue::ValueStruct *a)
std::vector< geometry_msgs::Point > padded_footprint_
LayeredCostmap * getLayeredCostmap()
std::vector< geometry_msgs::Point > unpadded_footprint_