#include <GazeboMapPublisher.h>
Classes | |
class | CollisionMapRequest |
Public Member Functions | |
GazeboMapPublisher () | |
void | Load (physics::WorldPtr _world, sdf::ElementPtr _sdf) |
Private Member Functions | |
void | advertEvent (const ros::TimerEvent &e) |
bool | createMap (const CollisionMapRequest &msg, const std::string &map_frame, nav_msgs::OccupancyGrid &map) |
CollisionMapRequest | getCollisionRequest () |
nav_msgs::OccupancyGrid | getMap () |
nav_msgs::MapMetaData | getMetaData () |
void | onWorldUpdate () |
bool | requestMap (nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res) |
Private Attributes | |
std::string | MAP_FRAME |
float | map_height |
double | map_len_x |
double | map_len_y |
double | map_offset_x |
double | map_offset_y |
ros::Publisher | map_pub |
float | MAP_PUB_FREQ |
float | map_resolution |
std::string | MAP_TOPIC |
ros::Publisher | meta_pub |
std::string | METADATA_TOPIC |
ros::NodeHandle | node |
ros::Timer | publishTimer |
std::string | REQUEST_MAP_SERVICE |
ros::ServiceServer | request_map_srv |
std::string | ROBOT_NAME |
event::ConnectionPtr | update_connection |
physics::WorldPtr | world |
bool | worldChangedSinceLastAdvert |
Publishes a map of the grid in gazebo to a topic that the map is supposed to be published to.
A service is also provided to request a map (service name can be specified with ros paramter "request_map_service") of type nav_msgs/GetMap.
The plugin parameters can be specified in a YAML file, which needs to be loaded onto the parameter server under **namespace gazebo_state_plugins**, as follows:
``` # the topic onto which to continuously publish # the map. publish_map_topic: "/gazebo/map"
# frequency to publish the map map_pub_frequency: 1
# topic onto which to publish the metadata # information of the map. Only will be published # if publish_map_topic is not empty. map_metadata_topic: "/map_metadata"
# topic onto which to provide a service to # request the map. request_map_service: "/dynamic_map"
# The frame ID to assign to the map map_frame_id: "/map"
# the name of the robot in Gazebo robot_name: "robot" ```
Definition at line 51 of file GazeboMapPublisher.h.
Definition at line 63 of file GazeboMapPublisher.cpp.
void GazeboMapPublisher::advertEvent | ( | const ros::TimerEvent & | e | ) | [private] |
Definition at line 125 of file GazeboMapPublisher.cpp.
bool GazeboMapPublisher::createMap | ( | const CollisionMapRequest & | msg, |
const std::string & | map_frame, | ||
nav_msgs::OccupancyGrid & | map | ||
) | [private] |
Definition at line 148 of file GazeboMapPublisher.cpp.
Definition at line 262 of file GazeboMapPublisher.cpp.
nav_msgs::OccupancyGrid GazeboMapPublisher::getMap | ( | ) | [private] |
Definition at line 289 of file GazeboMapPublisher.cpp.
nav_msgs::MapMetaData GazeboMapPublisher::getMetaData | ( | ) | [private] |
Definition at line 275 of file GazeboMapPublisher.cpp.
void GazeboMapPublisher::Load | ( | physics::WorldPtr | _world, |
sdf::ElementPtr | _sdf | ||
) |
Definition at line 98 of file GazeboMapPublisher.cpp.
void GazeboMapPublisher::onWorldUpdate | ( | ) | [private] |
Definition at line 143 of file GazeboMapPublisher.cpp.
bool GazeboMapPublisher::requestMap | ( | nav_msgs::GetMap::Request & | req, |
nav_msgs::GetMap::Response & | res | ||
) | [private] |
Definition at line 118 of file GazeboMapPublisher.cpp.
std::string gazebo::GazeboMapPublisher::MAP_FRAME [private] |
Definition at line 91 of file GazeboMapPublisher.h.
float gazebo::GazeboMapPublisher::map_height [private] |
Definition at line 82 of file GazeboMapPublisher.h.
double gazebo::GazeboMapPublisher::map_len_x [private] |
Definition at line 85 of file GazeboMapPublisher.h.
double gazebo::GazeboMapPublisher::map_len_y [private] |
Definition at line 86 of file GazeboMapPublisher.h.
double gazebo::GazeboMapPublisher::map_offset_x [private] |
Definition at line 83 of file GazeboMapPublisher.h.
double gazebo::GazeboMapPublisher::map_offset_y [private] |
Definition at line 84 of file GazeboMapPublisher.h.
Definition at line 100 of file GazeboMapPublisher.h.
float gazebo::GazeboMapPublisher::MAP_PUB_FREQ [private] |
Definition at line 95 of file GazeboMapPublisher.h.
float gazebo::GazeboMapPublisher::map_resolution [private] |
Definition at line 79 of file GazeboMapPublisher.h.
std::string gazebo::GazeboMapPublisher::MAP_TOPIC [private] |
Definition at line 90 of file GazeboMapPublisher.h.
Definition at line 101 of file GazeboMapPublisher.h.
std::string gazebo::GazeboMapPublisher::METADATA_TOPIC [private] |
Definition at line 92 of file GazeboMapPublisher.h.
Definition at line 88 of file GazeboMapPublisher.h.
Definition at line 105 of file GazeboMapPublisher.h.
std::string gazebo::GazeboMapPublisher::REQUEST_MAP_SERVICE [private] |
Definition at line 93 of file GazeboMapPublisher.h.
Definition at line 103 of file GazeboMapPublisher.h.
std::string gazebo::GazeboMapPublisher::ROBOT_NAME [private] |
Definition at line 94 of file GazeboMapPublisher.h.
Definition at line 99 of file GazeboMapPublisher.h.
physics::WorldPtr gazebo::GazeboMapPublisher::world [private] |
Definition at line 97 of file GazeboMapPublisher.h.
bool gazebo::GazeboMapPublisher::worldChangedSinceLastAdvert [private] |
Definition at line 107 of file GazeboMapPublisher.h.