$search
00001 /****************************************************************************** 00002 * \file 00003 * 00004 * $Id:$ 00005 * 00006 * Copyright (C) Brno University of Technology 00007 * 00008 * This file is part of software developed by dcgm-robotics@FIT group. 00009 * 00010 * Author: Michal Spanel (spanel@fit.vutbr.cz) 00011 * Supervised by: Michal Spanel (spanel@fit.vutbr.cz) 00012 * Date: dd/mm/2012 00013 * 00014 * This file is free software: you can redistribute it and/or modify 00015 * it under the terms of the GNU Lesser General Public License as published by 00016 * the Free Software Foundation, either version 3 of the License, or 00017 * (at your option) any later version. 00018 * 00019 * This file is distributed in the hope that it will be useful, 00020 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00021 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00022 * GNU Lesser General Public License for more details. 00023 * 00024 * You should have received a copy of the GNU Lesser General Public License 00025 * along with this file. If not, see <http://www.gnu.org/licenses/>. 00026 */ 00027 00028 #pragma once 00029 #ifndef BUT_ENV_MDOEL_TOPICS_LIST_H 00030 #define BUT_ENV_MDOEL_TOPICS_LIST_H 00031 00032 #include "services_list.h" 00033 00034 namespace srs_env_model 00035 { 00039 static const std::string WORLD_FRAME_ID = "/map"; 00040 static const std::string BASE_FRAME_ID = "/base_footprint"; 00041 static const int NUM_PCFRAMES_PROCESSED = 3; 00042 00046 static const std::string COLLISION_MAP_PUBLISHER_NAME = PACKAGE_NAME_PREFIX + std::string("/collision_map"); 00047 static const std::string COLLISION_MAP_FRAME_ID = "/base_footprint"; 00048 static const double COLLISION_MAP_RADIUS_LIMIT = 2.0; 00049 00053 static const std::string COLLISION_OBJECT_PUBLISHER_NAME = PACKAGE_NAME_PREFIX + std::string("/collision_object"); 00054 static const std::string COLLISION_OBJECT_FRAME_ID = "/map"; 00055 00059 static const std::string IM_SERVER_FRAME_ID = "/map"; 00060 static const std::string IM_SERVER_TOPIC_NAME = PACKAGE_NAME_PREFIX + std::string("/im_server"); 00061 00065 static const std::string OLD_IM_SERVER_TOPIC_NAME = PACKAGE_NAME_PREFIX + std::string("/old_im_server"); 00066 00070 static const std::string MARKERARRAY_PUBLISHER_NAME = PACKAGE_NAME_PREFIX + std::string("/marker_array_object"); 00071 static const std::string MARKERARRAY_FRAME_ID = "/map"; 00072 00076 static const std::string MAP2D_PUBLISHER_NAME = PACKAGE_NAME_PREFIX + std::string("/map2d_object"); 00077 static const std::string MAP2D_FRAME_ID = "/map"; 00078 00082 static const std::string COLLISIONGRID_PUBLISHER_NAME = PACKAGE_NAME_PREFIX + std::string("/collision_grid_object"); 00083 00084 00088 static const std::string OCTOMAP_PUBLISHER_NAME = PACKAGE_NAME_PREFIX + std::string("/binary_octomap"); 00089 static const std::string OCTOMAP_FRAME_ID = "/map"; 00090 static const std::string CAMERA_INFO_TOPIC_NAME = "camera_info"; // /cam3d/rgb/camera_info 00091 static const std::string MARKERS_TOPIC_NAME = "/visualization_marker"; 00092 00096 static const std::string POINTCLOUD_CENTERS_PUBLISHER_NAME = PACKAGE_NAME_PREFIX + std::string("/pointcloud_centers"); 00097 static const std::string SUBSCRIBER_POINT_CLOUD_NAME = "points_in"; // /cam3d/rgb/points 00098 //static const std::string DEFAULT_FRAME_ID = "/head_cam3d_link"; 00099 static const std::string SUBSCRIBER_FILTERING_CLOUD_NAME="points_filter"; 00100 00104 static const std::string SUBSCRIBER_CAMERA_POSITION_NAME = "rviz_camera_position"; // /rviz_camera_position 00105 static const std::string VISIBLE_POINTCLOUD_CENTERS_PUBLISHER_NAME = PACKAGE_NAME_PREFIX 00106 + std::string("/visible_pointcloud_centers"); 00107 00111 static const std::string CPC_CAMERA_INFO_PUBLISHER_NAME = CAMERA_INFO_TOPIC_NAME; // /cam3d/rgb/camera_info 00112 static const std::string CPC_SIMPLE_PC_PUBLISHING_TOPIC_NAME = PACKAGE_NAME_PREFIX + std::string("/differential_pointcloud_centers"); 00113 static const std::string CPC_COMPLETE_TOPIC_NAME = PACKAGE_NAME_PREFIX + std::string("/octomap_updates"); 00114 static const int CPC_NUM_DIFFERENTIAL_FRAMES = 5; 00115 00119 static const std::string REGISTRATION_CONSTRAINED_CLOUD_PUBLISHER_NAME = PACKAGE_NAME_PREFIX + std::string("/registration_constrained_cloud"); 00120 00124 static const std::string CPC_INPUT_TOPIC_NAME = "input"; // /but_env_model/octomap_updates 00125 static const std::string CPC_OUTPUT_TOPIC_NAME = "output"; //PACKAGE_NAME_PREFIX + std::string("/cpc_pointcloud_centers"); 00126 static const std::string CPC_CAMERA_FRAME = std::string("/head_cam3d_link"); 00127 static const std::string CPC_WORLD_FRAME = std::string("/map"); 00128 00132 static const std::string ContextChanged_TOPIC = PACKAGE_NAME_PREFIX + std::string("/context/changed"); 00133 00134 } 00135 00136 #endif // BUT_ENV_MDOEL_TOPICS_LIST_H