names.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * $Id: file.h 3496 2011-11-22 15:14:32Z fnovotny $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2012 by INRIA. All rights reserved.
7  *
8  * This software is free software; you can redistribute it and/or
9  * modify it under the terms of the GNU General Public License
10  * ("GPL") version 2 as published by the Free Software Foundation.
11  * See the file LICENSE.txt at the root directory of this source
12  * distribution for additional information about the GNU GPL.
13  *
14  * For using ViSP with software that can not be combined with the GNU
15  * GPL, please contact INRIA about acquiring a ViSP Professional
16  * Edition License.
17  *
18  * See http://www.irisa.fr/lagadic/visp/visp.html for more information.
19  *
20  * This software was developed at:
21  * INRIA Rennes - Bretagne Atlantique
22  * Campus Universitaire de Beaulieu
23  * 35042 Rennes Cedex
24  * France
25  * http://www.irisa.fr/lagadic
26  *
27  * If you have questions regarding the use of this file, please contact
28  * INRIA at visp@inria.fr
29  *
30  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
31  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
32  *
33  * Contact visp@irisa.fr if any conditions of this licensing are
34  * not clear to you.
35  *
36  * Description:
37  * File containing names of topics or services used all accross the package
38  *
39  * Authors:
40  * Filip Novotny
41  *
42  *
43  *****************************************************************************/
44 
50 #include "names.h"
51 #include "ros/ros.h"
52 
54 {
55  std::string camera_prefix("/visp_camera_calibration");
56  std::string raw_image_topic(camera_prefix + "/image_raw");
57  std::string set_camera_info_service(camera_prefix + "/set_camera_info");
58  std::string point_correspondence_topic("point_correspondence");
59  std::string calibrate_service("calibrate");
60  std::string set_camera_info_bis_service("set_camera_info_bis");
61 
62  std::string gray_level_precision_param("/visp_camera_calibration/visp_camera_calibration_image_processing/gray_level_precision");
63  std::string size_precision_param("/visp_camera_calibration/visp_camera_calibration_image_processing/size_precision");
64  std::string pause_at_each_frame_param("/visp_camera_calibration/visp_camera_calibration_image_processing/pause_at_each_frame");
65  std::string images_path_param("/visp_camera_calibration/visp_camera_calibration_camera/images_path");
66 
67  std::string model_points_x_param("/visp_camera_calibration/visp_camera_calibration_image_processing/model_points_x");
68  std::string model_points_y_param("/visp_camera_calibration/visp_camera_calibration_image_processing/model_points_y");
69  std::string model_points_z_param("/visp_camera_calibration/visp_camera_calibration_image_processing/model_points_z");
70 
71  std::string selected_points_x_param("/visp_camera_calibration/visp_camera_calibration_image_processing/selected_points_x");
72  std::string selected_points_y_param("/visp_camera_calibration/visp_camera_calibration_image_processing/selected_points_y");
73  std::string selected_points_z_param("/visp_camera_calibration/visp_camera_calibration_image_processing/selected_points_z");
74 
75  std::string calibration_path_param("/visp_camera_calibration/visp_camera_calibration_image_processing/calibration_path");
76 
77  void remap(){
78  if (ros::names::remap("camera_prefix") != "camera_prefix") {
79  camera_prefix = ros::names::remap("camera_prefix");
80  raw_image_topic = camera_prefix + "/image_raw";
81  set_camera_info_service = camera_prefix + "/set_camera_info";
82  }
83  }
84 }
85 
86 
std::string raw_image_topic
std::string size_precision_param
std::string selected_points_y_param
std::string model_points_z_param
std::string model_points_x_param
std::string point_correspondence_topic
std::string calibrate_service
std::string set_camera_info_bis_service
ROSCPP_DECL std::string remap(const std::string &name)
std::string gray_level_precision_param
std::string model_points_y_param
std::string pause_at_each_frame_param
std::string images_path_param
std::string set_camera_info_service
std::string calibration_path_param
std::string selected_points_z_param
std::string selected_points_x_param


visp_camera_calibration
Author(s): Filip Novotny
autogenerated on Wed Jul 3 2019 19:48:03