32 #include <std_msgs/String.h> 38 #include <sys/utsname.h> 48 std::array<char, 128>
buffer;
50 std::shared_ptr<FILE>pipe(popen(cmd,
"r"), pclose);
54 throw std::runtime_error(
"popen(\"" + std::string(cmd) +
"\", \"r\") failed");
57 while (!feof(pipe.get()))
59 if (fgets(buffer.data(), 128, pipe.get()) != NULL)
61 result += buffer.data();
65 std::string::size_type pos = result.find_last_not_of(
"\n \t");
66 if (pos != std::string::npos)
68 result = result.substr(0, pos + 1);
73 int main(
int argc,
char **argv)
77 std::string
message =
"\n----------CUT-PASTE-THIS----------\n";
78 message = message +
"|Version | Your Configuration | \n|:----------|:----------| \n";
81 message = message +
"|Operating System | ";
82 std::string operating_system;
86 if (operating_system.empty())
88 operating_system =
"Unable to detect operating system";
91 catch(
const std::exception&
e)
93 operating_system = e.what();
95 message = message + operating_system +
"|\n";
98 struct utsname*
buf =
new utsname();
99 int uname_return = uname(buf);
101 if (uname_return == 0)
103 kernel = buf->release;
107 kernel =
"Unable to detect Kernel";
109 message = message +
"|Kernel | ";
110 message = message + kernel +
"|\n";
113 message = message +
"|ROS | ";
114 std::string ros_version;
115 char* ros_version_char = getenv(
"ROS_DISTRO");
116 if (ros_version_char == NULL)
118 ros_version =
"Unable to detect ROS version";
122 ros_version = ros_version_char;
124 message = message + ros_version +
"| \n";
127 message = message +
"|ROS RealSense | ";
128 std::string realsense_version;
132 if (realsense_version.empty())
134 realsense_version =
"Unable to detect realsense version";
137 catch(
const std::exception& e)
139 realsense_version = e.what();
141 message = message + realsense_version +
"|\n";
144 message = message +
"|librealsense | ";
145 std::string librealsense_version;
149 if (librealsense_version.empty())
151 librealsense_version =
"Unable to detect librealsense version";
154 catch(
const std::exception& e)
156 librealsense_version = e.what();
158 message = message + librealsense_version +
"|";
167 message = message +
"\n|Camera Type-Firmware | Error detecting cameras |";
172 if (num_of_cameras == 0)
174 message = message +
"\n|Camera Type-Firmware | No Cameras Detected |";
177 for (
int i = 0; i < num_of_cameras; i++)
182 message = message +
"\n|Camera Type-Firmware | Error detecting camera|";
190 camera_name =
"Error detecting camera name";
196 camera_fw =
"Error detecting camera firmware";
199 message = message +
"\n|Camera Type | " + camera_name +
"|\n|Camera Firmware | " + camera_fw +
"|";
206 adapter_fw =
"Error detecting adapter firmware";
209 message = message +
"\n|Adapter Firmware | " + adapter_fw +
"|";
217 motion_module_fw =
"Error detecting motion module firmware";
220 message = message +
"\n|Motion Module Firmware | " + motion_module_fw +
"|";
225 message = message +
"\n----------CUT-PASTE-THIS----------";
RS_CAPABILITIES_MOTION_EVENTS
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)
rs_device * rs_get_device(rs_context *context, int index, rs_error **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)
std::string getSystemCallOutput(const char *cmd)
rs_context * rs_create_context(int api_version, rs_error **error)
RS_CAMERA_INFO_ADAPTER_BOARD_FIRMWARE_VERSION