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

Revert upstream changes to to run initialization on a separate thread #29

Open
wants to merge 1 commit into
base: por_upstream_sync
Choose a base branch
from
Open
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
2 changes: 0 additions & 2 deletions realsense2_camera/include/realsense_node_factory.h
Original file line number Diff line number Diff line change
Expand Up @@ -77,8 +77,6 @@ namespace realsense2_camera
rs2::context _ctx;
std::string _serial_no;
bool _initial_reset;
std::thread _query_thread;
bool _is_alive;
bool _initialized;
double _data_timeout;

Expand Down
77 changes: 29 additions & 48 deletions realsense2_camera/src/realsense_node_factory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@ constexpr auto realsense_ros_camera_version = REALSENSE_ROS_EMBEDDED_VERSION_STR
PLUGINLIB_EXPORT_CLASS(realsense2_camera::RealSenseNodeFactory, nodelet::Nodelet)

RealSenseNodeFactory::RealSenseNodeFactory() :
_is_alive(true),
_initialized(false)
{
ROS_INFO("RealSense ROS v%s", REALSENSE_ROS_VERSION_STR);
Expand All @@ -44,11 +43,6 @@ RealSenseNodeFactory::~RealSenseNodeFactory()
{
_initialized = false;
_data_monitor_timer.stop();
_is_alive = false;
if (_query_thread.joinable())
{
_query_thread.join();
}

_realSenseNode.reset();
if (_device)
Expand Down Expand Up @@ -125,6 +119,7 @@ void RealSenseNodeFactory::onInit()

void RealSenseNodeFactory::initialize(const ros::WallTimerEvent &ignored)
{
ROS_INFO("Initializing ...");
_device = rs2::device();
try
{
Expand Down Expand Up @@ -174,42 +169,34 @@ void RealSenseNodeFactory::initialize(const ros::WallTimerEvent &ignored)
}
else
{
_is_alive = true;
_query_thread = std::thread([=]()
{
ROS_DEBUG("Waiting for device...");


std::chrono::milliseconds timespan(6000);
while (_is_alive && !_device)
{
ROS_DEBUG("Checking for device...");
_device = getDevice();
if (_device)
{
ROS_DEBUG("got device");
if (_initial_reset)
{
ROS_DEBUG("Resetting device...");
_initial_reset = false;
_device.hardware_reset();
std::this_thread::sleep_for(std::chrono::seconds(10));
_device = getDevice();
}
if (_device)
{
ROS_DEBUG("starting device...");
std::function<void(rs2::event_information&)> change_device_callback_function = [this](rs2::event_information& info){change_device_callback(info);};
_ctx.set_devices_changed_callback(change_device_callback_function);
StartDevice();
}
}
else
{
std::this_thread::sleep_for(timespan);
}
}
});
std::this_thread::sleep_for(std::chrono::seconds(2));
ROS_INFO("Checking for device...");
_device = getDevice();
if (_device)
{
ROS_DEBUG("got device");
if (_initial_reset)
{
ROS_INFO("Resetting device...");
_initial_reset = false;
_device.hardware_reset();
std::this_thread::sleep_for(std::chrono::seconds(10));
_device = getDevice();
}
if (_device)
{
ROS_DEBUG("starting device...");
std::function<void(rs2::event_information&)> change_device_callback_function = [this](rs2::event_information& info){change_device_callback(info);};
_ctx.set_devices_changed_callback(change_device_callback_function);
StartDevice();
}
}
else
{
ROS_ERROR("Failed to file device. Driver exiting...");
shutdown();
return;
}

if (!_shutdown_srv)
{
Expand Down Expand Up @@ -373,12 +360,6 @@ bool RealSenseNodeFactory::reset()

_data_monitor_timer.stop();

_is_alive = false;
if (_query_thread.joinable())
{
_query_thread.join();
}

try
{
_realSenseNode.reset();
Expand Down