Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031 #include <ros/ros.h>
00032 #include <std_msgs/String.h>
00033 #include <librealsense/rs.hpp>
00034 #include <librealsense/rs.h>
00035 #include <string>
00036 #include <sstream>
00037 #include <ros/package.h>
00038 #include <sys/utsname.h>
00039 #include <cstdlib>
00040 #include <stdlib.h>
00041 #include <array>
00042
00043 rs_context *rs_context_ = NULL;
00044 rs_error *rs_error_ = NULL;
00045
00046 std::string getSystemCallOutput(const char* cmd)
00047 {
00048 std::array<char, 128> buffer;
00049 std::string result;
00050 std::shared_ptr<FILE>pipe(popen(cmd, "r"), pclose);
00051
00052 if (!pipe)
00053 {
00054 throw std::runtime_error("popen(\"" + std::string(cmd) + "\", \"r\") failed");
00055 }
00056
00057 while (!feof(pipe.get()))
00058 {
00059 if (fgets(buffer.data(), 128, pipe.get()) != NULL)
00060 {
00061 result += buffer.data();
00062 }
00063 }
00064
00065 std::string::size_type pos = result.find_last_not_of("\n \t");
00066 if (pos != std::string::npos)
00067 {
00068 result = result.substr(0, pos + 1);
00069 }
00070 return result;
00071 }
00072
00073 int main(int argc, char **argv)
00074 {
00075 ros::init(argc, argv, "debug_tool");
00076 ros::NodeHandle n;
00077 std::string message = "\n----------CUT-PASTE-THIS----------\n";
00078 message = message + "|Version | Your Configuration | \n|:----------|:----------| \n";
00079
00080
00081 message = message + "|Operating System | ";
00082 std::string operating_system;
00083 try
00084 {
00085 operating_system = getSystemCallOutput("lsb_release -ds");
00086 if (operating_system.empty())
00087 {
00088 operating_system = "Unable to detect operating system";
00089 }
00090 }
00091 catch(const std::exception& e)
00092 {
00093 operating_system = e.what();
00094 }
00095 message = message + operating_system + "|\n";
00096
00097
00098 struct utsname* buf = new utsname();
00099 int uname_return = uname(buf);
00100 std::string kernel;
00101 if (uname_return == 0)
00102 {
00103 kernel = buf->release;
00104 }
00105 else
00106 {
00107 kernel = "Unable to detect Kernel";
00108 }
00109 message = message + "|Kernel | ";
00110 message = message + kernel + "|\n";
00111
00112
00113 message = message + "|ROS | ";
00114 std::string ros_version;
00115 char* ros_version_char = getenv("ROS_DISTRO");
00116 if (ros_version_char == NULL)
00117 {
00118 ros_version = "Unable to detect ROS version";
00119 }
00120 else
00121 {
00122 ros_version = ros_version_char;
00123 }
00124 message = message + ros_version + "| \n";
00125
00126
00127 message = message + "|ROS RealSense | ";
00128 std::string realsense_version;
00129 try
00130 {
00131 realsense_version = getSystemCallOutput("rosversion realsense_camera");
00132 if (realsense_version.empty())
00133 {
00134 realsense_version = "Unable to detect realsense version";
00135 }
00136 }
00137 catch(const std::exception& e)
00138 {
00139 realsense_version = e.what();
00140 }
00141 message = message + realsense_version + "|\n";
00142
00143
00144 message = message + "|librealsense | ";
00145 std::string librealsense_version;
00146 try
00147 {
00148 librealsense_version = getSystemCallOutput("rosversion librealsense");
00149 if (librealsense_version.empty())
00150 {
00151 librealsense_version = "Unable to detect librealsense version";
00152 }
00153 }
00154 catch(const std::exception& e)
00155 {
00156 librealsense_version = e.what();
00157 }
00158 message = message + librealsense_version + "|";
00159
00160
00161 rs_context_ = rs_create_context(RS_API_VERSION, &rs_error_);
00162
00163 int num_of_cameras = rs_get_device_count(rs_context_, &rs_error_);
00164
00165 if (rs_error_)
00166 {
00167 message = message + "\n|Camera Type-Firmware | Error detecting cameras |";
00168 rs_error_ = NULL;
00169 }
00170 else
00171 {
00172 if (num_of_cameras == 0)
00173 {
00174 message = message + "\n|Camera Type-Firmware | No Cameras Detected |";
00175 }
00176
00177 for (int i = 0; i < num_of_cameras; i++)
00178 {
00179 rs_device* rs_detected_device = rs_get_device(rs_context_, i, &rs_error_);
00180 if (rs_error_)
00181 {
00182 message = message + "\n|Camera Type-Firmware | Error detecting camera|";
00183 rs_error_ = NULL;
00184 }
00185 else
00186 {
00187 std::string camera_name = rs_get_device_name(rs_detected_device, &rs_error_);
00188 if (rs_error_)
00189 {
00190 camera_name = "Error detecting camera name";
00191 rs_error_ = NULL;
00192 }
00193 std::string camera_fw = rs_get_device_firmware_version(rs_detected_device, &rs_error_);
00194 if (rs_error_)
00195 {
00196 camera_fw = "Error detecting camera firmware";
00197 rs_error_ = NULL;
00198 }
00199 message = message + "\n|Camera Type | " + camera_name + "|\n|Camera Firmware | " + camera_fw + "|";
00200 if (rs_supports(rs_detected_device, RS_CAPABILITIES_ADAPTER_BOARD, &rs_error_))
00201 {
00202 std::string adapter_fw = rs_get_device_info(rs_detected_device,
00203 RS_CAMERA_INFO_ADAPTER_BOARD_FIRMWARE_VERSION, &rs_error_);
00204 if (rs_error_)
00205 {
00206 adapter_fw = "Error detecting adapter firmware";
00207 rs_error_ = NULL;
00208 }
00209 message = message + "\n|Adapter Firmware | " + adapter_fw + "|";
00210 }
00211 if (rs_supports(rs_detected_device, RS_CAPABILITIES_MOTION_EVENTS, &rs_error_))
00212 {
00213 std::string motion_module_fw = rs_get_device_info(rs_detected_device,
00214 RS_CAMERA_INFO_MOTION_MODULE_FIRMWARE_VERSION, &rs_error_);
00215 if (rs_error_)
00216 {
00217 motion_module_fw = "Error detecting motion module firmware";
00218 rs_error_ = NULL;
00219 }
00220 message = message + "\n|Motion Module Firmware | " + motion_module_fw + "|";
00221 }
00222 }
00223 }
00224 }
00225 message = message + "\n----------CUT-PASTE-THIS----------";
00226
00227 ROS_INFO_STREAM(message);
00228
00229 return 0;
00230 }