ros_env.hpp
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Aldebaran
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 
19 #ifndef ROS_ENV_HPP
20 #define ROS_ENV_HPP
21 
22 /*
23 * ROS includes
24 */
25 #include <ros/ros.h>
26 
27 
28 /*
29 * ALDEBARAN includes
30 */
31 #include <qi/os.hpp>
32 
33 #include <stdlib.h>
34 
35 #include <boost/algorithm/string.hpp>
36 
37 namespace naoqi
38 {
39 namespace ros_env
40 {
41 
46 static std::string getROSIP(std::string network_interface)
47 {
48  if (network_interface.empty())
49  network_interface = "eth0";
50 
51  typedef std::map< std::string, std::vector<std::string> > Map_IP;
52  Map_IP map_ip = static_cast<Map_IP>(qi::os::hostIPAddrs());
53  if ( map_ip.find(network_interface) == map_ip.end() ) {
54  std::cerr << "Could not find network interface named " << network_interface << ", possible interfaces are ... ";
55  for (Map_IP::iterator it=map_ip.begin(); it!=map_ip.end(); ++it) std::cerr << it->first << " ";
56  std::cerr << std::endl;
57  exit(1);
58  }
59 
60  static const std::string ip = map_ip[network_interface][0];
61  return ip;
62 }
63 
64 static std::string prefix = "";
65 
66 static void setPrefix( std::string s )
67 {
68  prefix = s;
69  std::cout << "set prefix successfully to " << prefix << std::endl;
70 }
71 
72 static std::string getPrefix()
73 {
74  return prefix;
75 }
76 
77 static void setMasterURI( const std::string& uri, const std::string& network_interface )
78 {
79  if (ros::isInitialized() )
80  {
81  std::cout << "stopping ros init" << std::endl;
82  ros::shutdown();
83  }
84 
85  setenv("ROS_MASTER_URI", uri.c_str(), 1);
86 
87  std::string my_master = "__master="+uri;
88  std::map< std::string, std::string > remap;
89  remap["__master"] = uri;
90  remap["__ip"] = ::naoqi::ros_env::getROSIP(network_interface);
91  // init ros without a sigint-handler in order to shutdown correctly by naoqi
92  const char* ns_env = std::getenv("ROS_NAMESPACE");
94  // to prevent shutdown based on no existing nodehandle
95  ros::start();
96 
97  std::cout << "using master ip: " << ros::master::getURI() << std::endl;
98 }
99 
100 static std::string getMasterURI( )
101 {
102  return getenv("ROS_MASTER_URI");
103 }
104 
105 
106 } // ros_env
107 } // naoqi
108 #endif
ROSCPP_DECL const std::string & getURI()
static std::string getPrefix()
Definition: ros_env.hpp:72
ROSCPP_DECL void start()
ROSCPP_DECL bool isInitialized()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static std::string prefix
Definition: ros_env.hpp:64
ROSCPP_DECL std::string remap(const std::string &name)
static void setPrefix(std::string s)
Definition: ros_env.hpp:66
static std::string getMasterURI()
Definition: ros_env.hpp:100
static void setMasterURI(const std::string &uri, const std::string &network_interface)
Definition: ros_env.hpp:77
static std::string getROSIP(std::string network_interface)
Definition: ros_env.hpp:46
ROSCPP_DECL void shutdown()


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 15 2020 03:24:26