Go to the documentation of this file.00001
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <ros/ros.h>
00039 #include <octomap_msgs/conversions.h>
00040 #include <octomap/octomap.h>
00041 #include <fstream>
00042
00043 #include <octomap_msgs/GetOctomap.h>
00044 using octomap_msgs::GetOctomap;
00045
00046 #define USAGE "\nUSAGE: octomap_server <mapfile.[bt|ot]>\n" \
00047 " mapfile.bt: filename of map to be saved (.bt: binary tree, .ot: general octree)\n"
00048
00049 using namespace std;
00050 using namespace octomap;
00051
00052 class OctomapServerStatic{
00053 public:
00054 OctomapServerStatic(const std::string& filename)
00055 : m_octree(NULL), m_worldFrameId("/map")
00056 {
00057
00058 ros::NodeHandle private_nh("~");
00059 private_nh.param("frame_id", m_worldFrameId, m_worldFrameId);
00060
00061
00062
00063 if (filename.length() <= 3){
00064 ROS_ERROR("Octree file does not have .ot extension");
00065 exit(1);
00066 }
00067
00068 std::string suffix = filename.substr(filename.length()-3, 3);
00069
00070
00071 if (suffix == ".bt"){
00072 OcTree* octree = new OcTree(filename);
00073
00074 m_octree = octree;
00075 } else if (suffix == ".ot"){
00076 AbstractOcTree* tree = AbstractOcTree::read(filename);
00077 if (!tree){
00078 ROS_ERROR("Could not read octree from file");
00079 exit(1);
00080 }
00081
00082 m_octree = dynamic_cast<AbstractOccupancyOcTree*>(tree);
00083
00084 } else{
00085 ROS_ERROR("Octree file does not have .bt or .ot extension");
00086 exit(1);
00087 }
00088
00089 if (!m_octree ){
00090 ROS_ERROR("Could not read right octree class in file");
00091 exit(1);
00092 }
00093
00094 ROS_INFO("Read octree type \"%s\" from file %s", m_octree->getTreeType().c_str(), filename.c_str());
00095 ROS_INFO("Octree resultion: %f, size: %zu", m_octree->getResolution(), m_octree->size());
00096
00097
00098 m_octomapBinaryService = m_nh.advertiseService("octomap_binary", &OctomapServerStatic::octomapBinarySrv, this);
00099 m_octomapFullService = m_nh.advertiseService("octomap_full", &OctomapServerStatic::octomapFullSrv, this);
00100
00101 }
00102
00103 ~OctomapServerStatic(){
00104
00105
00106 }
00107
00108 bool octomapBinarySrv(GetOctomap::Request &req,
00109 GetOctomap::Response &res)
00110 {
00111 ROS_INFO("Sending binary map data on service request");
00112 res.map.header.frame_id = m_worldFrameId;
00113 res.map.header.stamp = ros::Time::now();
00114 if (!octomap_msgs::binaryMapToMsg(*m_octree, res.map))
00115 return false;
00116
00117 return true;
00118 }
00119
00120 bool octomapFullSrv(GetOctomap::Request &req,
00121 GetOctomap::Response &res)
00122 {
00123 ROS_INFO("Sending full map data on service request");
00124 res.map.header.frame_id = m_worldFrameId;
00125 res.map.header.stamp = ros::Time::now();
00126
00127
00128 if (!octomap_msgs::fullMapToMsg(*m_octree, res.map))
00129 return false;
00130
00131 return true;
00132 }
00133
00134 private:
00135 ros::ServiceServer m_octomapBinaryService, m_octomapFullService;
00136 ros::NodeHandle m_nh;
00137 std::string m_worldFrameId;
00138 AbstractOccupancyOcTree* m_octree;
00139
00140 };
00141
00142 int main(int argc, char** argv){
00143 ros::init(argc, argv, "octomap_server_static");
00144 std::string mapFilename("");
00145
00146 if (argc == 2)
00147 mapFilename = std::string(argv[1]);
00148 else{
00149 ROS_ERROR("%s", USAGE);
00150 exit(1);
00151 }
00152
00153 try{
00154 OctomapServerStatic ms(mapFilename);
00155 ros::spin();
00156 }catch(std::runtime_error& e){
00157 ROS_ERROR("octomap_server_static exception: %s", e.what());
00158 exit(2);
00159 }
00160
00161 exit(0);
00162 }
00163
00164