Go to the documentation of this file.
65 layered_costmap_(NULL),
68 transform_tolerance_(0.3),
69 map_update_thread_shutdown_(false),
73 map_update_thread_(NULL),
75 plugin_loader_(
"costmap_2d",
"costmap_2d::Layer"),
78 footprint_padding_(0.0)
97 ROS_WARN(
"Timed out waiting for transform from %s to %s to become available before running costmap, tf error: %s",
107 bool rolling_window, track_unknown_space, always_send_full_costmap;
108 private_nh.
param(
"rolling_window", rolling_window,
false);
109 private_nh.
param(
"track_unknown_space", track_unknown_space,
false);
110 private_nh.
param(
"always_send_full_costmap", always_send_full_costmap,
false);
114 if (!private_nh.
hasParam(
"plugins"))
124 private_nh.
getParam(
"plugins", my_list);
125 for (int32_t i = 0; i < my_list.
size(); ++i)
127 std::string pname =
static_cast<std::string
>(my_list[i][
"name"]);
128 std::string type =
static_cast<std::string
>(my_list[i][
"type"]);
129 ROS_INFO(
"%s: Using plugin \"%s\"",
name_.c_str(), pname.c_str());
140 std::string topic_param, topic;
141 if (!private_nh.
searchParam(
"footprint_topic", topic_param))
143 topic_param =
"footprint_topic";
146 private_nh.
param(topic_param, topic, std::string(
"footprint"));
149 if (!private_nh.
searchParam(
"published_footprint_topic", topic_param))
151 topic_param =
"published_footprint";
154 private_nh.
param(topic_param, topic, std::string(
"footprint"));
160 always_send_full_costmap);
168 dynamic_reconfigure::Server<Costmap2DConfig>::CallbackType cb = [
this](
auto& config,
auto level){
reconfigureCB(config, level); };
169 dsrv_->setCallback(cb);
194 ROS_WARN(
"%s: Parameter \"plugins\" not provided, loading pre-Hydro parameters",
name_.c_str());
197 std::vector < XmlRpc::XmlRpcValue > plugins;
203 if (nh.
getParam(
"static_map", flag) && flag)
208 plugins.push_back(super_map);
218 if (nh.
getParam(
"map_type",
s) &&
s ==
"voxel")
223 plugins.push_back(super_map);
237 plugins.push_back(super_map);
244 nh.
param(
"observation_sources",
s, std::string(
""));
245 std::stringstream ss(
s);
259 plugins.push_back(super_map);
262 nh.
setParam(
"plugins", super_array);
269 if(plugin_type ==
"costmap_2d::StaticLayer")
276 else if(plugin_type ==
"costmap_2d::VoxelLayer")
285 else if(plugin_type ==
"costmap_2d::ObstacleLayer")
292 else if(plugin_type ==
"costmap_2d::InflationLayer")
307 ROS_WARN(
"%s: Pre-Hydro parameter \"%s\" unused since \"plugins\" is provided",
name_.c_str(), param_name.c_str());
322 double map_update_frequency = config.update_frequency;
324 double map_publish_frequency = config.publish_frequency;
325 if (map_publish_frequency > 0)
331 double map_width_meters = config.width, map_height_meters = config.height, resolution = config.resolution, origin_x =
333 origin_y = config.origin_y;
338 (
unsigned int)(map_height_meters / resolution), resolution, origin_x, origin_y);
354 if(map_update_frequency > 0.0)
359 const costmap_2d::Costmap2DConfig &old_config)
365 if (new_config.footprint == old_config.footprint &&
366 new_config.robot_radius == old_config.robot_radius)
371 if (new_config.footprint !=
"" && new_config.footprint !=
"[]")
373 std::vector<geometry_msgs::Point> new_footprint;
380 ROS_ERROR(
"Invalid footprint string from dynamic reconfigure");
404 geometry_msgs::PoseStamped new_pose;
418 #ifdef HAVE_SYS_TIME_H
419 struct timeval
start, end;
420 double start_t, end_t, t_diff;
421 gettimeofday(&
start, NULL);
426 #ifdef HAVE_SYS_TIME_H
427 gettimeofday(&end, NULL);
428 start_t =
start.tv_sec + double(
start.tv_usec) / 1e6;
429 end_t = end.tv_sec + double(end.tv_usec) / 1e6;
430 t_diff = end_t - start_t;
431 ROS_DEBUG(
"Map update time: %.9f", t_diff);
436 unsigned int x0, y0, xn, yn;
450 ROS_WARN(
"Map update loop missed its desired rate of %.4fHz... the loop actually took %.4f seconds", frequency,
460 geometry_msgs::PoseStamped pose;
463 double x = pose.pose.position.x,
464 y = pose.pose.position.y,
469 geometry_msgs::PolygonStamped footprint;
490 (*plugin)->activate();
511 (*plugin)->deactivate();
549 geometry_msgs::PoseStamped robot_pose;
572 ROS_ERROR_THROTTLE(1.0,
"No Transform available Error looking up robot pose: %s\n", ex.what());
582 ROS_ERROR_THROTTLE(1.0,
"Extrapolation Error looking up robot pose: %s\n", ex.what());
586 if (!global_pose.header.stamp.isZero() && current_time.
toSec() - global_pose.header.stamp.toSec() >
transform_tolerance_)
589 "Costmap2DROS transform timeout. Current time: %.4f, global_pose stamp: %.4f, tolerance: %.4f",
599 geometry_msgs::PoseStamped global_pose;
603 double yaw =
tf2::getYaw(global_pose.pose.orientation);
#define ROS_ERROR_THROTTLE(period,...)
void setParam(const std::string &key, bool b) const
costmap_2d::Costmap2DConfig old_config_
void padFootprint(std::vector< geometry_msgs::Point > &footprint, double padding)
Adds the specified amount of padding to the footprint (in place)
std::vector< geometry_msgs::Point > toPointVector(geometry_msgs::Polygon polygon)
Convert Polygon msg to vector of Points.
tf2_ros::Buffer & tf_
Used for transforming point clouds.
std::map< std::string, XmlRpcValue > ValueStruct
double getYaw(const A &a)
void readFootprintFromConfig(const costmap_2d::Costmap2DConfig &new_config, const costmap_2d::Costmap2DConfig &old_config)
Set the footprint from the new_config object.
bool getParam(const std::string &key, bool &b) const
void setUnpaddedRobotFootprintPolygon(const geometry_msgs::Polygon &footprint)
Set the footprint of the robot to be the given polygon, padded by footprint_padding.
#define ROS_WARN_THROTTLE(period,...)
void setFootprint(const std::vector< geometry_msgs::Point > &footprint_spec)
Updates the stored footprint, updates the circumscribed and inscribed radii, and calls onFootprintCha...
void transformFootprint(double x, double y, double theta, const std::vector< geometry_msgs::Point > &footprint_spec, std::vector< geometry_msgs::Point > &oriented_footprint)
Given a pose and base footprint, build the oriented footprint of the robot (list of Points)
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y, bool size_locked=false)
ROSCPP_DECL void spinOnce()
bool deleteParam(const std::string &key) const
std::vector< geometry_msgs::Point > makeFootprintFromParams(ros::NodeHandle &nh)
Read the ros-params "footprint" and/or "robot_radius" from the given NodeHandle using searchParam() t...
void movementCB(const ros::TimerEvent &event)
void loadOldParameters(ros::NodeHandle &nh)
void resume()
Resumes costmap updates.
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
void publishCostmap()
Publishes the visualization data over ROS.
boost::thread * map_update_thread_
A thread for updating the map.
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
std::string robot_base_frame_
The frame_id of the robot base.
void mapUpdateLoop(double frequency)
ros::Publisher footprint_pub_
virtual bool canTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout, std::string *errstr=NULL) const
void getBounds(unsigned int *x0, unsigned int *xn, unsigned int *y0, unsigned int *yn)
std::vector< geometry_msgs::Point > unpadded_footprint_
void resetLayers()
Reset each individual layer.
std::vector< boost::shared_ptr< Layer > > * getPlugins()
std::string global_frame_
The global frame for the costmap.
dynamic_reconfigure::Server< costmap_2d::Costmap2DConfig > * dsrv_
ros::Subscriber footprint_sub_
bool searchParam(const std::string &key, std::string &result) const
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.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
bool hasParam(const std::string &key) const
bool makeFootprintFromString(const std::string &footprint_string, std::vector< geometry_msgs::Point > &footprint)
Make the footprint from the given string.
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.
void resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
void addPlugin(boost::shared_ptr< Layer > plugin)
void start()
Subscribes to sensor topics if necessary and starts costmap updates, can be called to restart the cos...
void warnForOldParameters(ros::NodeHandle &nh)
std::vector< geometry_msgs::Point > makeFootprintFromRadius(double radius)
Create a circular footprint from a given radius.
Costmap2DPublisher * publisher_
void move_parameter(ros::NodeHandle &old_h, ros::NodeHandle &new_h, std::string name, bool should_delete=true)
B & transform(const A &in, B &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
void updateBounds(unsigned int x0, unsigned int xn, unsigned int y0, unsigned int yn)
Include the given bounds in the changed-rectangle.
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
Duration cycleTime() const
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.
ros::Duration publish_cycle
void stop()
Stops costmap updates and unsubscribes from sensor topics.
void updateMap(double robot_x, double robot_y, double robot_yaw)
Update the underlying costmap with new data. If you want to update the map outside of the update loop...
T param(const std::string ¶m_name, const T &default_val) const
Instantiates different layer plugins and aggregates them into one score.
A tool to periodically publish visualization data from a Costmap2D.
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
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_
bool map_update_thread_shutdown_
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout) const
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17