Skip to content

Commit

Permalink
Reorder query_devices to prioritize D400 over T265.
Browse files Browse the repository at this point in the history
TM2 Logger to report errors
GCC/Cland fixes/enhancement: fix atomic load/store, remove unused variables, -wpedantic
rs-multicam: Remove debug messages & code cleanup
  • Loading branch information
ev-mp authored and Evgeni Raikhel committed Mar 18, 2019
1 parent a13f824 commit e50f067
Show file tree
Hide file tree
Showing 9 changed files with 31 additions and 52 deletions.
2 changes: 1 addition & 1 deletion examples/align/rs-align.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ float get_depth_scale(rs2::device dev)
return dpt.get_depth_scale();
}
}
throw std::runtime_error("Device does not have a depth sensor");
throw std::runtime_error("The demo requires a Depth sensor to run");
}

void render_slider(rect location, float& clipping_dist)
Expand Down
2 changes: 1 addition & 1 deletion examples/measure/rs-measure.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -501,7 +501,7 @@ void render_shortest_path(const rs2::depth_frame& depth,
auto y = (float(pixel1.second) / depth.get_height()) * app.height();
glVertex2f(x, y);

if (i == path.size() / 2) center = { x, y };
if (i == (path.size() / 2)) center = { int(x), int(y) };
}
glEnd();

Expand Down
25 changes: 4 additions & 21 deletions examples/multicam/rs-multicam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ class device_container
class frames_container
{
public:
frames_container() : _raw(1){};
frames_container() : _raw(1){}
rs2::frame_queue _raw;
rs2::frame _processed;
};
Expand All @@ -53,10 +53,8 @@ class device_container
struct view_port
{
public:
view_port()
{
}
~view_port() {};
view_port(){}
~view_port(){}
view_port(const view_port&) = delete; // non construction-copyable
view_port(view_port&& vp): // moveable
colorize_frame(std::move(vp.colorize_frame)),
Expand All @@ -83,7 +81,6 @@ class device_container
remove_devices(info);
for (auto&& dev : info.get_new_devices())
{
std::cout << "Adding new device !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!" << dev.get_info(RS2_CAMERA_INFO_NAME) << " , " << dev.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER) << std::endl;
enable_device(dev);
}
}
Expand Down Expand Up @@ -163,14 +160,11 @@ class device_container

if (_devices.find(serial_number) != _devices.end())
{
std::cout << __FUNCTION__ << " Device s.n " << serial_number << " is already registered, skipped" << std::endl;
return; //already in
}
std::cout << __FUNCTION__ << " !!!!!!!!!!!!!!!!!!!!!!!!!!!!!! Enabling device " << dev.get_info(RS2_CAMERA_INFO_NAME) << " s.n: " << serial_number << std::endl;
// Ignoring platform cameras (webcams, etc..)
if (platform_camera_name == dev.get_info(RS2_CAMERA_INFO_NAME))
{
std::cout << __FUNCTION__ << " !!!!!!!!!!!!!!!!!!!!!!!!!! Platform camera found, return" << std::endl;
return;
}
// Create a pipeline from the given device
Expand All @@ -182,31 +176,24 @@ class device_container

rs2::pipeline_profile profile = p.start(c, [serial_number, this](const rs2::frame& frame)
{
std::lock_guard<std::mutex> lock(_mutex);
// With callbacks, both the synchronized and unsynchronized frames would arrive in a single frameset
if (auto fs = frame.as<rs2::frameset>())
{
for (const rs2::frame& f : fs)
{
//std::cout << "Enq: Frame type " << f.get_profile().stream_name() << " format: " << f.get_profile().format() << " stream id: " << f.get_profile().unique_id() << " fn: " << f.get_frame_number() << std::endl;
if (_devices.find(serial_number) != _devices.end())
_devices[serial_number].frames_per_stream[f.get_profile().unique_id()]._raw.enqueue(f);
}
}
else
else // Single frames
{
// Stream that bypass synchronization (such as IMU) will produce single frames
if (_devices.find(serial_number) != _devices.end())
_devices[serial_number].frames_per_stream[frame.get_profile().unique_id()]._raw.enqueue(frame);
/*std::cout << "Enq: Single type " << frame.get_profile().stream_name() << " format: " << frame.get_profile().format()
<< " stream id: " << frame.get_profile().unique_id() << " fn: " << frame.get_frame_number() << std::endl;*/
}
});

_devices[serial_number].pipe = p;
_devices[serial_number].profile = profile;
// Hold it internally
std::cout << "!!!!!!!!!!!!!! Starting with device " << profile.get_device().get_info(RS2_CAMERA_INFO_SERIAL_NUMBER) << " streams: " << profile.get_streams().size() << std::endl;
}

void remove_devices(const rs2::event_information& info)
Expand All @@ -218,9 +205,7 @@ class device_container
{
if (info.was_removed(itr->second.profile.get_device()))
{
std::cout << "Device erased !!!!!!!!!!!!!!!!! " << itr->first << std::endl;
itr = _devices.erase(itr);
std::cout << "Devices left = " << _devices.size() << std::endl;
}
else
{
Expand Down Expand Up @@ -250,14 +235,12 @@ int main(int argc, char * argv[]) try
// Enumerate all the connected devices
for (auto&& dev : ctx.query_devices())
{
std::cout << "Enabling device " << dev.get_info(RS2_CAMERA_INFO_NAME) << " , " << dev.get_info(RS2_CAMERA_INFO_SERIAL_NUMBER) << std::endl;
connected_devices.enable_device(dev);
}

// Register user callback for tracking device connect/disconnect events
ctx.set_devices_changed_callback([&](rs2::event_information& info)
{
std::cout << "set_devices_changed_callback fired !!!!!!!!!!!!!!! " << std::endl;
connected_devices.add_dev_event(info);
});

Expand Down
34 changes: 16 additions & 18 deletions src/context.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,9 +123,8 @@ namespace librealsense
break;
case backend_type::playback:
_backend = std::make_shared<platform::playback_backend>(filename, section, min_api_version);

break;
default: throw invalid_value_exception(to_string() << "Undefined backend type " << static_cast<int>(type));
// Strongly-typed enum. Default is redundant
}

environment::get_instance().set_time_service(_backend->create_time_service());
Expand Down Expand Up @@ -212,7 +211,7 @@ namespace librealsense
class platform_camera_sensor : public uvc_sensor
{
public:
platform_camera_sensor(const std::shared_ptr<context>& ctx,
platform_camera_sensor(const std::shared_ptr<context>&,
device* owner,
std::shared_ptr<platform::uvc_device> uvc_device,
std::unique_ptr<frame_timestamp_reader> timestamp_reader)
Expand Down Expand Up @@ -283,7 +282,7 @@ namespace librealsense
color_ep->try_register_pu(RS2_OPTION_ENABLE_AUTO_WHITE_BALANCE);
}

virtual rs2_intrinsics get_intrinsics(unsigned int subdevice, const stream_profile& profile) const
virtual rs2_intrinsics get_intrinsics(unsigned int, const stream_profile&) const
{
return rs2_intrinsics {};
}
Expand All @@ -293,13 +292,12 @@ namespace librealsense
std::vector<tagged_profile> markers;
markers.push_back({ RS2_STREAM_COLOR, -1, 640, 480, RS2_FORMAT_RGB8, 30, profile_tag::PROFILE_TAG_SUPERSET | profile_tag::PROFILE_TAG_DEFAULT });
return markers;
};
}
};

std::shared_ptr<device_interface> platform_camera_info::create(std::shared_ptr<context> ctx,
bool register_device_notifications) const
{
auto&& backend = ctx->get_backend();
return std::make_shared<platform_camera>(ctx, _uvcs, this->get_device_data(), register_device_notifications);
}

Expand Down Expand Up @@ -328,29 +326,29 @@ namespace librealsense
// to allow them to modify context later on
auto ctx = t->shared_from_this();

#ifdef WITH_TRACKING
if (_tm2_context)
{
auto tm2_devices = tm2_info::pick_tm2_devices(ctx, _tm2_context->get_manager(), _tm2_context->query_devices());
std::copy(begin(tm2_devices), end(tm2_devices), std::back_inserter(list));
}
#endif

auto l500_devices = l500_info::pick_l500_devices(ctx, devices.uvc_devices, devices.usb_devices);
std::copy(begin(l500_devices), end(l500_devices), std::back_inserter(list));

if (mask & RS2_PRODUCT_LINE_D400)
{
auto ds5_devices = ds5_info::pick_ds5_devices(ctx, devices);
std::copy(begin(ds5_devices), end(ds5_devices), std::back_inserter(list));
}

auto l500_devices = l500_info::pick_l500_devices(ctx, devices.uvc_devices, devices.usb_devices);
std::copy(begin(l500_devices), end(l500_devices), std::back_inserter(list));

if (mask & RS2_PRODUCT_LINE_SR300)
{
auto sr300_devices = sr300_info::pick_sr300_devices(ctx, devices.uvc_devices, devices.usb_devices);
std::copy(begin(sr300_devices), end(sr300_devices), std::back_inserter(list));
}

#ifdef WITH_TRACKING
if (_tm2_context)
{
auto tm2_devices = tm2_info::pick_tm2_devices(ctx, _tm2_context->get_manager(), _tm2_context->query_devices());
std::copy(begin(tm2_devices), end(tm2_devices), std::back_inserter(list));
}
#endif

auto recovery_devices = recovery_info::pick_recovery_devices(ctx, devices.usb_devices);
std::copy(begin(recovery_devices), end(recovery_devices), std::back_inserter(list));

Expand Down Expand Up @@ -565,7 +563,7 @@ namespace librealsense
void context::unload_tracking_module()
{
_tm2_context.reset();
};
}
#endif

std::vector<std::vector<platform::uvc_device_info>> group_devices_by_unique_id(const std::vector<platform::uvc_device_info>& devices)
Expand Down
5 changes: 2 additions & 3 deletions src/tm2/tm-context.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,6 @@ namespace librealsense
{
std::this_thread::sleep_for(std::chrono::milliseconds(10));
elapsed = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::high_resolution_clock::now() - started);
//LOG_WARNING("_manager: " << _manager << " init state: " << (_manager ? _manager->isInitialized() : 0));
}
LOG_DEBUG("T265 query acomplished after " << std::dec << elapsed.count() << " ms]");
return _devices;
Expand All @@ -78,13 +77,13 @@ namespace librealsense
case TrackingManager::ATTACH:
{
_devices.push_back(dev);
LOG_WARNING("TM2 Device Attached - " << dev);
LOG_INFO("TM2 Device Attached - " << dev);
added = std::make_shared<tm2_info>(get_manager(), dev, _ctx->shared_from_this());
break;
}
case TrackingManager::DETACH:
{
LOG_WARNING("TM2 Device Detached");
LOG_INFO("TM2 Device Detached");
removed = std::make_shared<tm2_info>(get_manager(), dev, _ctx->shared_from_this());
auto itr = std::find_if(_devices.begin(), _devices.end(), [dev](TrackingDevice* d) { return dev == d; });
_devices.erase(itr);
Expand Down
2 changes: 1 addition & 1 deletion third-party/libtm/libtm/src/Manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ void TrackingManager::ReleaseInstance(TrackingManager*& manager)
// -[interface]----------------------------------------------------------------
Manager::Manager(Listener* lis, void* param) : mDispatcher(new Dispatcher()), mListener(nullptr), mContext(nullptr), mFwFileName(""), mLibUsbDeviceToTrackingDeviceMap(), mEvent(), mCompleteQMutex(), mCompleteQ(), mTrackingDeviceInfoMap()
{
setHostLogControl({ LogVerbosityLevel::None, LogOutputMode::LogOutputModeScreen, true });
setHostLogControl({ LogVerbosityLevel::Error, LogOutputMode::LogOutputModeScreen, true });

// start running context
mThread = std::thread([this] {
Expand Down
10 changes: 5 additions & 5 deletions third-party/libtm/libtm/src/UsbPlugListener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,10 +156,10 @@ void perc::UsbPlugListener::EnumerateDevices()
// free the list
libusb_free_device_list(list, 1);

switch (mInitialized)
switch (mInitialized.load())
{
case usb_setup_init:
mInitialized = usb_setup_progress;
mInitialized.store(usb_setup_progress);
// Schedule 1000ms for loading if DFU device(s) were found, otherwise 500msec
mUSBMinTimeout = mUSBSetupTimeout = systemTime() + (bootLoader_count ? 1000000000 : 500000000);
mDevicesToProcess = bootLoader_count;
Expand All @@ -182,14 +182,14 @@ void perc::UsbPlugListener::EnumerateDevices()

if (systemTime() >= mUSBSetupTimeout)
{
mInitialized = usb_setup_timeout;
mInitialized.store(usb_setup_timeout);
LOGE("EnumerateDevices: ,timeout occurred time=%lu, timeout=%lu", systemTime(), mUSBSetupTimeout);
}
else
{
if ((systemTime() >= mUSBMinTimeout) && (!mDevicesToProcess))
{
mInitialized = usb_setup_success;
mInitialized.store(usb_setup_success);
LOGE("EnumerateDevices: ,usb_setup_success time=%lu, timeout=%lu", systemTime(), mUSBSetupTimeout);
}
// else wait for process co complete
Expand All @@ -199,6 +199,6 @@ void perc::UsbPlugListener::EnumerateDevices()
break;
}

if (mInitialized & (usb_setup_success | usb_setup_timeout))
if (mInitialized.load() & (usb_setup_success | usb_setup_timeout))
mNextScanIntervalMs = ENUMERATE_TIMEOUT_NSEC;
}
2 changes: 1 addition & 1 deletion third-party/libtm/libtm/src/UsbPlugListener.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ namespace perc
static const char *usbSpeed(uint16_t bcdUSB);

enum usb_setup_e { usb_setup_init = 1, usb_setup_progress = 1<<1, usb_setup_success = 1<<2, usb_setup_timeout= 1<<3};
bool isInitialized(void) const { return mInitialized & (usb_setup_success | usb_setup_timeout); }
bool isInitialized(void) const { return mInitialized.load() & (usb_setup_success | usb_setup_timeout); }

private:
void EnumerateDevices();
Expand Down
1 change: 0 additions & 1 deletion third-party/libtm/libtm/src/infra/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,6 @@ const char* logPrioritySign[] = { "U" ,/* LOG_UNKNOWN */
const LogVerbosityLevel prio2verbosity[] = {None, None, Verbose, Debug, Trace, Info, Warning, Error, Error, None};

// LOG_FATAL is always enabled by default
//Ev #define isPriorityEnabled(prio) (LOG_FATAL == prio || (gLogManager.configuration[LogSourceHost].verbosityMask & LOG_PRI2MASK(prio)))
bool isPriorityEnabled(int prio)
{
return (LOG_FATAL == prio || (gLogManager.configuration[LogSourceHost].verbosityMask & LOG_PRI2MASK(prio)));
Expand Down

0 comments on commit e50f067

Please sign in to comment.