Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

rs-enumerate-devices and libusb handling fixes #5716

Merged
merged 4 commits into from
Feb 4, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
23 changes: 13 additions & 10 deletions src/command_transfer.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,21 +42,24 @@ namespace librealsense
throw std::runtime_error("can't find VENDOR_SPECIFIC interface of device: " + _device->get_info().id);

auto hwm = *it;
const auto& m = _device->open(hwm->get_number());

uint32_t transfered_count = 0;
auto sts = m->bulk_transfer(hwm->first_endpoint(RS2_USB_ENDPOINT_DIRECTION_WRITE), const_cast<uint8_t*>(data.data()), static_cast<uint32_t>(data.size()), transfered_count, timeout_ms);
std::vector<uint8_t> output;
if (const auto& m = _device->open(hwm->get_number()))
{
uint32_t transfered_count = 0;
auto sts = m->bulk_transfer(hwm->first_endpoint(RS2_USB_ENDPOINT_DIRECTION_WRITE), const_cast<uint8_t*>(data.data()), static_cast<uint32_t>(data.size()), transfered_count, timeout_ms);

if (sts != RS2_USB_STATUS_SUCCESS)
throw std::runtime_error("command transfer failed to execute bulk transfer, error: " + usb_status_to_string.at(sts));
if (sts != RS2_USB_STATUS_SUCCESS)
throw std::runtime_error("command transfer failed to execute bulk transfer, error: " + usb_status_to_string.at(sts));

std::vector<uint8_t> output(DEFAULT_BUFFER_SIZE);
sts = m->bulk_transfer(hwm->first_endpoint(RS2_USB_ENDPOINT_DIRECTION_READ), output.data(), static_cast<uint32_t>(output.size()), transfered_count, timeout_ms);
output.resize(DEFAULT_BUFFER_SIZE);
sts = m->bulk_transfer(hwm->first_endpoint(RS2_USB_ENDPOINT_DIRECTION_READ), output.data(), static_cast<uint32_t>(output.size()), transfered_count, timeout_ms);

if (sts != RS2_USB_STATUS_SUCCESS)
throw std::runtime_error("command transfer failed to execute bulk transfer, error: " + usb_status_to_string.at(sts));
if (sts != RS2_USB_STATUS_SUCCESS)
throw std::runtime_error("command transfer failed to execute bulk transfer, error: " + usb_status_to_string.at(sts));

output.resize(transfered_count);
output.resize(transfered_count);
}
return output;
}

Expand Down
4 changes: 2 additions & 2 deletions src/ds5/ds5-motion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -458,9 +458,9 @@ namespace librealsense
calib_id = *reinterpret_cast<uint16_t*>(raw.data());
valid = true;
}
catch(const std::exception& exc)
catch(const std::exception&)
{
LOG_INFO("IMU EEPROM Read error: " << exc.what());
LOG_WARNING("IMU Calibration is not available, see the previous message");
}

std::shared_ptr<mm_calib_parser> prs = nullptr;
Expand Down
27 changes: 14 additions & 13 deletions src/tm2/tm-boot.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,21 +22,22 @@ namespace librealsense {
LOG_INFO("Found a T265 to boot");
found = true;
auto dev = usb_enumerator::create_usb_device(device_info);
const auto& m = dev->open(0);
if (const auto& m = dev->open(0))
{
// transfer the firmware data
int size{};
auto target_hex = fw_get_target(size);

// transfer the firmware data
int size;
auto target_hex = fw_get_target(size);
if(!target_hex)
LOG_ERROR("librealsense failed to get T265 FW resource");

if(!target_hex)
LOG_ERROR("librealsense failed to get T265 FW resource");

auto iface = dev->get_interface(0);
auto endpoint = iface->first_endpoint(RS2_USB_ENDPOINT_DIRECTION_WRITE);
uint32_t transfered = 0;
auto status = m->bulk_transfer(endpoint, const_cast<uint8_t*>(target_hex), static_cast<uint32_t>(size), transfered, 1000);
if(status != RS2_USB_STATUS_SUCCESS)
LOG_ERROR("Error booting T265");
auto iface = dev->get_interface(0);
auto endpoint = iface->first_endpoint(RS2_USB_ENDPOINT_DIRECTION_WRITE);
uint32_t transfered = 0;
auto status = m->bulk_transfer(endpoint, const_cast<uint8_t*>(target_hex), static_cast<uint32_t>(size), transfered, 1000);
if(status != RS2_USB_STATUS_SUCCESS)
LOG_ERROR("Error booting T265");
}
}
}
return found;
Expand Down
44 changes: 31 additions & 13 deletions tools/enumerate-devices/readme.md
Original file line number Diff line number Diff line change
@@ -1,27 +1,45 @@
# rs-enumerate-devices Tool

## Goal
`rs-enumerate-devices` tool is a console application providing information about connected devices.
`rs-enumerate-devices` tool is a console application providing information about Realsense devices.

## Usage
After installing `librealsense` run ` rs-enumerate-devices` to launch the tool.
An example for output for a D415 camera is:
An example output for a D415 camera (using `-S` option) is:

```
Name : Intel RealSense 415
Serial Number : 725112060346
Firmware Version : 05.08.14.00
Physical Port : /sys/devices/pci0000:00/0000:00:14.0/usb2/2-2/2-2:1.0/video4linux/video1
Debug Op Code : 15
Advanced Mode : YES
Product Id : 0AD3
Device Name Serial Number Firmware Version
Intel RealSense D415 725112060411 05.12.02.100
Device info:
Name : Intel RealSense D415
Serial Number : 725112060411
Firmware Version : 05.12.02.100
Recommended Firmware Version : 05.12.02.100
Physical Port : \\?\usb#vid_8086&pid_0ad3&mi_00#6&2a371216&0&0000#{e5323777-f976-4f5b-9b55-b94699c46e44}\global
Debug Op Code : 15
Advanced Mode : YES
Product Id : 0AD3
Camera Locked : NO
Usb Type Descriptor : 3.2
Product Line : D400
Asic Serial Number : 012345678901
Firmware Update Id : 012345678901

```

## Command Line Parameters

|Flag |Description |
|---|---|
|`-s`|Provide short summary, one line per device|
|`-o`|List supported device controls and options|
|`-c`|Provide calibration (Intrinsic/Extrinsic) information|
| None| List supported streaming modes|
|`-s`|Generate a one-line info for each connected device|
|`-S`|Extends `-s` by providing a short summary per device|
|`-o`|List supported device controls, options and streaming modes|
|`-c`|Provide calibration (Intrinsic/Extrinsic) and streaming modes information|
|`-p`|Enumerate streams contained in ROSBag record file. Usage `-p <rosbag_full_path_name>`.|
| None| The default mode. Equivalent to `-S` plus the list of all the supported streaming profiles|

The options `-o`, `-c` and `-p` are additive and can be combined, e.g. call
`rs-enumerate-devices -o -c -p rosbag.rec` to print the camera info, streaming modes, supported options and the calibration data both for the live cameras and the prerecorded `rosbag.rec` file.

The options `-S`, `-s` are restrictive and therefore incompatible with `-o` and `-c`,
but still can be used with `-p <file_name>`.
Loading