select_map.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2014-2017, the neonavigation authors
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its 
00014  *       contributors may be used to endorse or promote products derived from 
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <ros/ros.h>
00031 
00032 #include <map_organizer_msgs/OccupancyGridArray.h>
00033 #include <std_msgs/Int32.h>
00034 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
00035 #include <tf2_ros/transform_broadcaster.h>
00036 
00037 #include <vector>
00038 
00039 #include <neonavigation_common/compatibility.h>
00040 
00041 map_organizer_msgs::OccupancyGridArray maps;
00042 std::vector<nav_msgs::MapMetaData> orig_mapinfos;
00043 int floor_cur = 0;
00044 
00045 void cbMaps(const map_organizer_msgs::OccupancyGridArray::Ptr& msg)
00046 {
00047   ROS_INFO("Map array received");
00048   maps = *msg;
00049   orig_mapinfos.clear();
00050   for (auto& map : maps.maps)
00051   {
00052     orig_mapinfos.push_back(map.info);
00053     map.info.origin.position.z = 0.0;
00054   }
00055 }
00056 void cbFloor(const std_msgs::Int32::Ptr& msg)
00057 {
00058   floor_cur = msg->data;
00059 }
00060 
00061 int main(int argc, char** argv)
00062 {
00063   ros::init(argc, argv, "select_map");
00064   ros::NodeHandle pnh("~");
00065   ros::NodeHandle nh("");
00066 
00067   neonavigation_common::compat::checkCompatMode();
00068   auto subMaps = neonavigation_common::compat::subscribe(
00069       nh, "maps",
00070       nh, "/maps", 1, cbMaps);
00071   auto subFloor = neonavigation_common::compat::subscribe(
00072       nh, "floor",
00073       pnh, "floor", 1, cbFloor);
00074   auto pubMap = neonavigation_common::compat::advertise<nav_msgs::OccupancyGrid>(
00075       nh, "map",
00076       nh, "/map", 1, true);
00077 
00078   tf2_ros::TransformBroadcaster tfb;
00079   geometry_msgs::TransformStamped trans;
00080   trans.header.frame_id = "map_ground";
00081   trans.child_frame_id = "map";
00082   trans.transform.rotation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), 0.0));
00083 
00084   ros::Rate wait(10);
00085   int floor_prev = -1;
00086   while (ros::ok())
00087   {
00088     wait.sleep();
00089     ros::spinOnce();
00090 
00091     if (maps.maps.size() == 0)
00092       continue;
00093 
00094     if (floor_cur != floor_prev)
00095     {
00096       if (floor_cur >= 0 && floor_cur < static_cast<int>(maps.maps.size()))
00097       {
00098         pubMap.publish(maps.maps[floor_cur]);
00099         trans.transform.translation.z = orig_mapinfos[floor_cur].origin.position.z;
00100       }
00101       else
00102       {
00103         ROS_INFO("Floor out of range");
00104       }
00105       floor_prev = floor_cur;
00106     }
00107     trans.header.stamp = ros::Time::now() + ros::Duration(0.15);
00108     tfb.sendTransform(trans);
00109   }
00110 
00111   return 0;
00112 }


map_organizer
Author(s): Atsushi Watanabe
autogenerated on Sat Jun 22 2019 20:07:17