37 #include <boost/shared_ptr.hpp> 46 octomap_msgs::Octomap map;
63 octree_binary_pub->
publish(map);
66 int main(
int argc,
char** argv)
68 ros::init(argc, argv,
"occupancy_map_server");
73 server.setUpdateCallback(boost::bind(&
publishOctomap, &octree_binary_pub, &server));
74 server.startMonitor();
void publish(const boost::shared_ptr< M > &message) const
static void publishOctomap(ros::Publisher *octree_binary_pub, occupancy_map_monitor::OccupancyMapMonitor *server)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
const std::string & getMapFrame() const
#define ROS_ERROR_THROTTLE(period,...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
const OccMapTreePtr & getOcTreePtr()
Get a pointer to the underlying octree for this monitor. Lock the tree before reading or writing usin...
int main(int argc, char **argv)
static bool binaryMapToMsgData(const OctomapT &octomap, std::vector< int8_t > &mapData)