get_debug_info.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  Copyright (c) 2017, Intel Corporation
3  All rights reserved.
4 
5  Redistribution and use in source and binary forms, with or without
6  modification, are permitted provided that the following conditions are met:
7 
8  1. Redistributions of source code must retain the above copyright notice, this
9  list of conditions and the following disclaimer.
10 
11  2. Redistributions in binary form must reproduce the above copyright notice,
12  this list of conditions and the following disclaimer in the documentation
13  and/or other materials provided with the distribution.
14 
15  3. Neither the name of the copyright holder nor the names of its contributors
16  may be used to endorse or promote products derived from this software without
17  specific prior written permission.
18 
19  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22  DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
23  FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
24  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
25  SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
27  OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
28  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29  *******************************************************************************/
30 
31 #include <ros/ros.h>
32 #include <std_msgs/String.h>
33 #include <librealsense/rs.hpp>
34 #include <librealsense/rs.h>
35 #include <string>
36 #include <sstream>
37 #include <ros/package.h>
38 #include <sys/utsname.h>
39 #include <cstdlib>
40 #include <stdlib.h>
41 #include <array>
42 
45 
46 std::string getSystemCallOutput(const char* cmd)
47 {
48  std::array<char, 128> buffer;
49  std::string result;
50  std::shared_ptr<FILE>pipe(popen(cmd, "r"), pclose);
51 
52  if (!pipe)
53  {
54  throw std::runtime_error("popen(\"" + std::string(cmd) + "\", \"r\") failed");
55  }
56 
57  while (!feof(pipe.get()))
58  {
59  if (fgets(buffer.data(), 128, pipe.get()) != NULL)
60  {
61  result += buffer.data();
62  }
63  }
64 
65  std::string::size_type pos = result.find_last_not_of("\n \t");
66  if (pos != std::string::npos)
67  {
68  result = result.substr(0, pos + 1);
69  }
70  return result;
71 }
72 
73 int main(int argc, char **argv)
74 {
75  ros::init(argc, argv, "debug_tool");
77  std::string message = "\n----------CUT-PASTE-THIS----------\n";
78  message = message + "|Version | Your Configuration | \n|:----------|:----------| \n";
79 
80  /* Acquire OS */
81  message = message + "|Operating System | ";
82  std::string operating_system;
83  try
84  {
85  operating_system = getSystemCallOutput("lsb_release -ds");
86  if (operating_system.empty())
87  {
88  operating_system = "Unable to detect operating system";
89  }
90  }
91  catch(const std::exception& e)
92  {
93  operating_system = e.what();
94  }
95  message = message + operating_system + "|\n";
96 
97  /* Acquire Kernel Release */
98  struct utsname* buf = new utsname();
99  int uname_return = uname(buf);
100  std::string kernel;
101  if (uname_return == 0)
102  {
103  kernel = buf->release;
104  }
105  else
106  {
107  kernel = "Unable to detect Kernel";
108  }
109  message = message + "|Kernel | ";
110  message = message + kernel + "|\n";
111 
112  /* Acquire ROS Version */
113  message = message + "|ROS | ";
114  std::string ros_version;
115  char* ros_version_char = getenv("ROS_DISTRO");
116  if (ros_version_char == NULL)
117  {
118  ros_version = "Unable to detect ROS version";
119  }
120  else
121  {
122  ros_version = ros_version_char;
123  }
124  message = message + ros_version + "| \n";
125 
126  /* Acquire ROS RealSense Version */
127  message = message + "|ROS RealSense | ";
128  std::string realsense_version;
129  try
130  {
131  realsense_version = getSystemCallOutput("rosversion realsense_camera");
132  if (realsense_version.empty())
133  {
134  realsense_version = "Unable to detect realsense version";
135  }
136  }
137  catch(const std::exception& e)
138  {
139  realsense_version = e.what();
140  }
141  message = message + realsense_version + "|\n";
142 
143  /* Acquire librealsense version */
144  message = message + "|librealsense | ";
145  std::string librealsense_version;
146  try
147  {
148  librealsense_version = getSystemCallOutput("rosversion librealsense");
149  if (librealsense_version.empty())
150  {
151  librealsense_version = "Unable to detect librealsense version";
152  }
153  }
154  catch(const std::exception& e)
155  {
156  librealsense_version = e.what();
157  }
158  message = message + librealsense_version + "|";
159 
160  /* Acquire detected cameras' types and firmwares */
161  rs_context_ = rs_create_context(RS_API_VERSION, &rs_error_);
162 
163  int num_of_cameras = rs_get_device_count(rs_context_, &rs_error_);
164 
165  if (rs_error_)
166  {
167  message = message + "\n|Camera Type-Firmware | Error detecting cameras |";
168  rs_error_ = NULL;
169  }
170  else
171  {
172  if (num_of_cameras == 0)
173  {
174  message = message + "\n|Camera Type-Firmware | No Cameras Detected |";
175  }
176 
177  for (int i = 0; i < num_of_cameras; i++)
178  {
179  rs_device* rs_detected_device = rs_get_device(rs_context_, i, &rs_error_);
180  if (rs_error_)
181  {
182  message = message + "\n|Camera Type-Firmware | Error detecting camera|";
183  rs_error_ = NULL;
184  }
185  else
186  {
187  std::string camera_name = rs_get_device_name(rs_detected_device, &rs_error_);
188  if (rs_error_)
189  {
190  camera_name = "Error detecting camera name";
191  rs_error_ = NULL;
192  }
193  std::string camera_fw = rs_get_device_firmware_version(rs_detected_device, &rs_error_);
194  if (rs_error_)
195  {
196  camera_fw = "Error detecting camera firmware";
197  rs_error_ = NULL;
198  }
199  message = message + "\n|Camera Type | " + camera_name + "|\n|Camera Firmware | " + camera_fw + "|";
200  if (rs_supports(rs_detected_device, RS_CAPABILITIES_ADAPTER_BOARD, &rs_error_))
201  {
202  std::string adapter_fw = rs_get_device_info(rs_detected_device,
204  if (rs_error_)
205  {
206  adapter_fw = "Error detecting adapter firmware";
207  rs_error_ = NULL;
208  }
209  message = message + "\n|Adapter Firmware | " + adapter_fw + "|";
210  }
211  if (rs_supports(rs_detected_device, RS_CAPABILITIES_MOTION_EVENTS, &rs_error_))
212  {
213  std::string motion_module_fw = rs_get_device_info(rs_detected_device,
215  if (rs_error_)
216  {
217  motion_module_fw = "Error detecting motion module firmware";
218  rs_error_ = NULL;
219  }
220  message = message + "\n|Motion Module Firmware | " + motion_module_fw + "|";
221  }
222  }
223  }
224  }
225  message = message + "\n----------CUT-PASTE-THIS----------";
226 
227  ROS_INFO_STREAM(message);
228 
229  return 0;
230 }
#define RS_API_VERSION
RS_CAPABILITIES_MOTION_EVENTS
rs_error * e
const char * rs_get_device_info(const rs_device *device, rs_camera_info info, rs_error **error)
GLuint GLsizei const GLchar * message
RS_CAPABILITIES_ADAPTER_BOARD
GLenum GLuint GLenum GLsizei const GLchar * buf
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
GLdouble n
GLuint buffer
rs_device * rs_get_device(rs_context *context, int index, rs_error **error)
rs_error * rs_error_
RS_CAMERA_INFO_MOTION_MODULE_FIRMWARE_VERSION
const char * rs_get_device_firmware_version(const rs_device *device, rs_error **error)
int main(int argc, char **argv)
int rs_get_device_count(const rs_context *context, rs_error **error)
int rs_supports(rs_device *device, rs_capabilities capability, rs_error **error)
const char * rs_get_device_name(const rs_device *device, rs_error **error)
#define ROS_INFO_STREAM(args)
rs_context * rs_context_
std::string getSystemCallOutput(const char *cmd)
GLuint64EXT * result
rs_context * rs_create_context(int api_version, rs_error **error)
RS_CAMERA_INFO_ADAPTER_BOARD_FIRMWARE_VERSION


realsense_camera
Author(s): Rajvi Jingar , Reagan Lopez , Matt Hansen , Mark Horn
autogenerated on Mon Jun 10 2019 14:40:37