35 #include <octomap_msgs/GetOctomap.h>
36 using octomap_msgs::GetOctomap;
38 #define USAGE "\nUSAGE: octomap_server_static <mapfile.[bt|ot]>\n" \
39 " mapfile.bt: OctoMap filename to be loaded (.bt: binary tree, .ot: general octree)\n"
47 : m_octree(NULL), m_worldFrameId(
"/map")
51 private_nh.
param(
"frame_id", m_worldFrameId, m_worldFrameId);
55 if (filename.length() <= 3){
56 ROS_ERROR(
"Octree file does not have .ot extension");
60 std::string suffix = filename.substr(filename.length()-3, 3);
67 }
else if (suffix ==
".ot"){
70 ROS_ERROR(
"Could not read octree from file");
77 ROS_ERROR(
"Octree file does not have .bt or .ot extension");
82 ROS_ERROR(
"Could not read right octree class in file");
86 ROS_INFO(
"Read octree type \"%s\" from file %s", m_octree->getTreeType().c_str(), filename.c_str());
87 ROS_INFO(
"Octree resultion: %f, size: %zu", m_octree->getResolution(), m_octree->size());
101 GetOctomap::Response &res)
103 ROS_INFO(
"Sending binary map data on service request");
104 res.map.header.frame_id = m_worldFrameId;
113 GetOctomap::Response &res)
115 ROS_INFO(
"Sending full map data on service request");
116 res.map.header.frame_id = m_worldFrameId;
134 int main(
int argc,
char** argv){
135 ros::init(argc, argv,
"octomap_server_static");
136 std::string mapFilename(
"");
139 mapFilename = std::string(argv[1]);
148 }
catch(std::runtime_error& e){
149 ROS_ERROR(
"octomap_server_static exception: %s", e.what());