Skip to content
Snippets Groups Projects
Commit 41b265bb authored by Harald Scheirich's avatar Harald Scheirich
Browse files

[BUG] Fixes issue with haptice device destructor

Previously the instance of the haptic device might have been in the middle of processing
a callback as the destructor gets exectued, calling hdUnschedule should prevent this

Also defers posting of the button events to the update call to prevent another process
from holding up the callback
parent 10f8e2bf
No related branches found
No related tags found
No related merge requests found
...@@ -71,6 +71,7 @@ HapticDeviceClient::initialize() ...@@ -71,6 +71,7 @@ HapticDeviceClient::initialize()
hdEnable(HD_FORCE_OUTPUT); hdEnable(HD_FORCE_OUTPUT);
hdEnable(HD_FORCE_RAMPING); hdEnable(HD_FORCE_RAMPING);
m_schedulerHandle = hdScheduleAsynchronous(hapticCallback, this, HD_MAX_SCHEDULER_PRIORITY); // Call sometime later
// Success // Success
LOG(INFO) << "\"" << this->getDeviceName() << "\" successfully initialized."; LOG(INFO) << "\"" << this->getDeviceName() << "\" successfully initialized.";
} }
...@@ -78,13 +79,25 @@ HapticDeviceClient::initialize() ...@@ -78,13 +79,25 @@ HapticDeviceClient::initialize()
void void
HapticDeviceClient::update() HapticDeviceClient::update()
{ {
//hdScheduleSynchronous(hapticCallback, this, HD_MAX_SCHEDULER_PRIORITY); std::vector<std::pair<int, int>> localEvents;
hdScheduleAsynchronous(hapticCallback, this, HD_MAX_SCHEDULER_PRIORITY); // Call sometime later m_dataLock.lock();
std::swap(m_events, localEvents);
m_dataLock.unlock();
for (const auto& item : localEvents)
{
postEvent(ButtonEvent(HapticDeviceClient::buttonStateChanged(), item.first, item.second));
}
} }
void void
HapticDeviceClient::disable() HapticDeviceClient::disable()
{ {
// HS 2021-oct-07 There is no documentation on whether hdUnschedule is synchronous
// or asynchronous, but as all the examples set the sequence to shutdown an HD device
// with hdStopScheduler, hdUnschedule, hdDisableDevice i'm assuming an hdWaitForCompletion
// is unnecessary here
hdUnschedule(m_schedulerHandle);
hdDisableDevice(m_handle); hdDisableDevice(m_handle);
} }
...@@ -125,23 +138,26 @@ HapticDeviceClient::hapticCallback(void* pData) ...@@ -125,23 +138,26 @@ HapticDeviceClient::hapticCallback(void* pData)
client->m_orientation = orientation; client->m_orientation = orientation;
client->m_transformLock.unlock(); client->m_transformLock.unlock();
client->m_dataLock.lock();
for (int i = 0; i < 4; i++) for (int i = 0; i < 4; i++)
{ {
// If button down and not previously down // If button down and not previously down
if ((state.buttons & (1 << i)) && !client->m_buttons[i]) if ((state.buttons & (1 << i)) && !client->m_buttons[i])
{ {
client->m_buttons[i] = true; client->m_buttons[i] = true;
client->postEvent(ButtonEvent(HapticDeviceClient::buttonStateChanged(), i, BUTTON_PRESSED)); client->m_events.push_back({ i, BUTTON_PRESSED });
} }
// If button not down, and previously down // If button not down, and previously down
else if (!(state.buttons & (1 << i)) && client->m_buttons[i]) else if (!(state.buttons & (1 << i)) && client->m_buttons[i])
{ {
client->m_buttons[i] = false; client->m_buttons[i] = false;
client->postEvent(ButtonEvent(HapticDeviceClient::buttonStateChanged(), i, BUTTON_RELEASED)); client->m_events.push_back({ i, BUTTON_RELEASED });
} }
} }
client->m_dataLock.unlock();
client->m_trackingEnabled = true; client->m_trackingEnabled = true;
return HD_CALLBACK_DONE; return HD_CALLBACK_CONTINUE;
} }
} // imstk } // imstk
...@@ -26,6 +26,8 @@ ...@@ -26,6 +26,8 @@
#include <HD/hd.h> #include <HD/hd.h>
#include <array>
namespace imstk namespace imstk
{ {
struct HDstate struct HDstate
...@@ -51,7 +53,6 @@ friend class HapticDeviceManager; ...@@ -51,7 +53,6 @@ friend class HapticDeviceManager;
public: public:
virtual ~HapticDeviceClient() = default; virtual ~HapticDeviceClient() = default;
public:
/// ///
/// \brief Use callback to get tracking data from phantom omni /// \brief Use callback to get tracking data from phantom omni
/// ///
...@@ -86,5 +87,7 @@ private: ...@@ -86,5 +87,7 @@ private:
HHD m_handle; ///< device handle HHD m_handle; ///< device handle
HDstate m_state; ///< device reading state HDstate m_state; ///< device reading state
HDSchedulerHandle m_schedulerHandle = 0;
std::vector<std::pair<int, int>> m_events;
}; };
} }
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment