#include <cmath>
#include <iomanip>
#include <iostream>
#if defined(WIN32) || defined(WIN64)
#define NOMINMAX
#include "windows.h"
#endif
#ifdef MACOSX
#include "OpenGL/glu.h"
#else
#include "GL/glu.h"
#endif
#include <GLFW/glfw3.h>
#include "CMatrixGL.h"
#include "FontGL.h"
constexpr double Stiffness = 2000.0;
constexpr double TorqueGain = 2.0;
constexpr float CubeSize = 0.06f;
constexpr float CubeHalfSize = CubeSize / 2.0f;
const GLfloat CubeNormals[6][3] =
{
{ -1.0, 0.0, 0.0 },
{ 0.0, 1.0, 0.0 },
{ 1.0, 0.0, 0.0 },
{ 0.0, -1.0, 0.0 },
{ 0.0, 0.0, 1.0 },
{ 0.0, 0.0, -1.0 }
};
const GLint CubeFaces[6][4] =
{
{ 0, 1, 2, 3 },
{ 3, 2, 6, 7 },
{ 7, 6, 5, 4 },
{ 4, 5, 1, 0 },
{ 5, 6, 2, 1 },
{ 7, 4, 0, 3 }
};
const GLfloat CubeVertices[8][3] =
{
{ -1.0 * CubeHalfSize, -1.0 * CubeHalfSize, 1.0 * CubeHalfSize },
{ -1.0 * CubeHalfSize, -1.0 * CubeHalfSize, -1.0 * CubeHalfSize },
{ -1.0 * CubeHalfSize, 1.0 * CubeHalfSize, -1.0 * CubeHalfSize },
{ -1.0 * CubeHalfSize, 1.0 * CubeHalfSize, 1.0 * CubeHalfSize },
{ 1.0 * CubeHalfSize, -1.0 * CubeHalfSize, 1.0 * CubeHalfSize },
{ 1.0 * CubeHalfSize, -1.0 * CubeHalfSize, -1.0 * CubeHalfSize },
{ 1.0 * CubeHalfSize, 1.0 * CubeHalfSize, -1.0 * CubeHalfSize },
{ 1.0 * CubeHalfSize, 1.0 * CubeHalfSize, 1.0 * CubeHalfSize }
};
constexpr int SwapInterval = 1;
bool simulationRunning = true;
bool simulationFinished = false;
bool showRefreshRate = true;
GLFWwindow* window = nullptr;
int windowWidth = 0;
int windowHeight = 0;
bool renderTorque = true;
bool renderForce = true;
int updateGraphics()
{
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
double px = 0.0;
double py = 0.0;
double pz = 0.0;
{
return -1;
}
Eigen::Vector3d devicePosition;
devicePosition << px, py, pz;
double deviceRotation[3][3] = {};
{
return -1;
}
cMatrixGL matrix;
matrix.set(devicePosition, deviceRotation);
matrix.glMatrixPushMultiply();
glEnable(GL_COLOR_MATERIAL);
glColor3f(0.1f, 0.3f, 0.5f);
for (int index = 0; index < 6; index++)
{
glBegin(GL_QUADS);
glNormal3fv(&CubeNormals[index][0]);
glVertex3fv(&CubeVertices[CubeFaces[index][0]][0]);
glVertex3fv(&CubeVertices[CubeFaces[index][1]][0]);
glVertex3fv(&CubeVertices[CubeFaces[index][2]][0]);
glVertex3fv(&CubeVertices[CubeFaces[index][3]][0]);
glEnd();
}
matrix.glMatrixPop();
glColor3f(0.8f, 0.8f, 0.8f);
GLUquadricObj* sphere = gluNewQuadric();
gluSphere(sphere, 0.005, 64, 64);
if (showRefreshRate)
{
static double lastFrequencyUpdateTime =
dhdGetTime();
static char frequencyString[16] = "0.000 kHz";
if (time - lastFrequencyUpdateTime > 0.1)
{
lastFrequencyUpdateTime = time;
snprintf(frequencyString, 10, "%0.03f kHz", frequency);
}
glDisable(GL_LIGHTING);
glColor3f(1.0, 1.0, 1.0);
glRasterPos3f(0.0f, -0.01f, -0.1f);
for (char* character = frequencyString; *character != '\0'; character++)
{
render_character(*character, HELVETICA12);
}
glEnable(GL_LIGHTING);
}
GLenum err = glGetError();
if (err != GL_NO_ERROR)
{
return -1;
}
return 0;
}
void computeForceAndTorque(const Eigen::Vector3d& a_position,
const Eigen::Matrix3d& a_rotation,
Eigen::Vector3d& a_force,
Eigen::Vector3d& a_torque)
{
Eigen::Vector3d localForce(0, 0, 0);
Eigen::Vector3d localTorque(0, 0, 0);
Eigen::Matrix3d localRotationTransposed = a_rotation.transpose();
Eigen::Vector3d localPosition = -1.0 * localRotationTransposed * a_position;
if ((localPosition(0) < CubeHalfSize) && (localPosition(0) > -CubeHalfSize) &&
(localPosition(1) < CubeHalfSize) && (localPosition(1) > -CubeHalfSize) &&
(localPosition(2) < CubeHalfSize) && (localPosition(2) > -CubeHalfSize))
{
double maxPenetration = CubeHalfSize;
Eigen::Vector3d normalDirection(0, 0, 1);
for (int axis = 0; axis < 3; axis++)
{
std::vector<double> directionsList = { -1.0, 1.0 };
for (double currentDirection : directionsList)
{
double penetration = std::abs(currentDirection * CubeHalfSize - localPosition(axis));
if (penetration < maxPenetration)
{
maxPenetration = penetration;
normalDirection << 0.0, 0.0, 0.0;
normalDirection(axis) = currentDirection;
}
}
}
localForce = -maxPenetration * Stiffness * normalDirection;
Eigen::Vector3d normalForce = -1.0 * localForce;
localTorque = -TorqueGain * localPosition.cross(normalForce);
}
a_force = a_rotation * localForce;
a_torque = a_rotation * localTorque;
}
void* hapticsLoop(void* a_userData)
{
double px = 0.0;
double py = 0.0;
double pz = 0.0;
double rot[3][3] = {};
Eigen::Vector3d deviceForce;
Eigen::Vector3d deviceTorque;
Eigen::Vector3d devicePosition;
Eigen::Matrix3d deviceRotation;
{
std::cout <<
"error: failed to enable force rendering (" <<
dhdErrorGetLastStr() <<
")" << std::endl;
simulationRunning = false;
return nullptr;
}
while (simulationRunning)
{
{
std::cout << std::endl <<
"error: failed to read position (" <<
dhdErrorGetLastStr() <<
")" << std::endl;
break;
}
devicePosition << px, py, pz;
deviceRotation << rot[0][0], rot[0][1], rot[0][2],
rot[1][0], rot[1][1], rot[1][2],
rot[2][0], rot[2][1], rot[2][2];
computeForceAndTorque(devicePosition, deviceRotation, deviceForce, deviceTorque);
static bool safeToRenderHaptics = false;
if (!safeToRenderHaptics)
{
if (deviceForce.norm() == 0)
{
safeToRenderHaptics = true;
}
else
{
deviceForce.setZero();
deviceTorque.setZero();
}
}
if (!renderTorque)
{
deviceTorque.setZero();
}
deviceTorque(0), deviceTorque(1), deviceTorque(2),
0.0);
}
simulationRunning = false;
simulationFinished = true;
return nullptr;
}
void onExit()
{
simulationRunning = false;
while (!simulationFinished)
{
}
{
std::cout <<
"error: failed to close the connection (" <<
dhdErrorGetLastStr() <<
")" << std::endl;
return;
}
std::cout << "connection closed" << std::endl;
return;
}
void onWindowResized(GLFWwindow* a_window,
int a_width,
int a_height)
{
windowWidth = a_width;
windowHeight = a_height;
double glAspect = (static_cast<double>(a_width) / static_cast<double>(a_height));
glViewport(0, 0, a_width, a_height);
glMatrixMode(GL_PROJECTION);
glLoadIdentity();
gluPerspective(60, glAspect, 0.01, 10);
gluLookAt(0.2, 0.0, 0.0,
0.0, 0.0, 0.0,
0.0, 0.0, 1.0);
glMatrixMode(GL_MODELVIEW);
glLoadIdentity();
}
void onKeyPressed(GLFWwindow* a_window,
int a_key,
int a_scanCode,
int a_action,
int a_modifiers)
{
if (a_action != GLFW_PRESS)
{
return;
}
if ((a_key == GLFW_KEY_ESCAPE) || (a_key == GLFW_KEY_Q))
{
exit(0);
}
if (a_key == GLFW_KEY_R)
{
showRefreshRate = !showRefreshRate;
}
if (a_key == GLFW_KEY_T)
{
renderTorque = !renderTorque;
}
if (a_key == GLFW_KEY_F)
{
renderForce = !renderForce;
{
std::cout <<
"warning: failed to change force status (" <<
dhdErrorGetLastStr() <<
")" << std::endl;
}
}
}
void onError(int a_error,
const char* a_description)
{
std::cout << "error: " << a_description << std::endl;
}
int initializeGLFW()
{
if (!glfwInit())
{
return -1;
}
glfwSetErrorCallback(onError);
const GLFWvidmode* mode = glfwGetVideoMode(glfwGetPrimaryMonitor());
windowWidth = static_cast<int>(0.8 * mode->height);
windowHeight = static_cast<int>(0.5 * mode->height);
int x = static_cast<int>(0.5 * (mode->width - windowWidth));
int y = static_cast<int>(0.5 * (mode->height - windowHeight));
glfwWindowHint(GLFW_CONTEXT_VERSION_MAJOR, 2);
glfwWindowHint(GLFW_CONTEXT_VERSION_MINOR, 1);
glfwWindowHint(GLFW_DOUBLEBUFFER, GLFW_TRUE);
glfwWindowHint(GLFW_SAMPLES, 4);
glfwWindowHint(GLFW_STEREO, GL_FALSE);
glfwWindowHint(GLFW_VISIBLE, GL_FALSE);
#ifdef MACOSX
glfwWindowHint(GLFW_COCOA_RETINA_FRAMEBUFFER, GL_FALSE);
#endif
window = glfwCreateWindow(windowWidth, windowHeight, "Force Dimension - Torques Example", nullptr, nullptr);
if (!window)
{
return -1;
}
glfwMakeContextCurrent(window);
glfwSetKeyCallback(window, onKeyPressed);
glfwSetWindowSizeCallback(window, onWindowResized);
glfwSetWindowPos(window, x, y);
glfwSwapInterval(SwapInterval);
glfwShowWindow(window);
onWindowResized(window, windowWidth, windowHeight);
GLfloat lightAmbient[] = {0.5f, 0.5f, 0.5f, 1.0f};
GLfloat lightDiffuse[] = {0.8f, 0.8f, 0.8f, 1.0f};
GLfloat lightSpecular[] = {1.0f, 1.0f, 1.0f, 1.0f};
GLfloat lightPosition[] = {1.0f, 0.5f, 0.8f, 0.0f};
glLightfv(GL_LIGHT0, GL_AMBIENT, lightAmbient);
glLightfv(GL_LIGHT0, GL_DIFFUSE, lightDiffuse);
glLightfv(GL_LIGHT0, GL_SPECULAR, lightSpecular);
glLightfv(GL_LIGHT0, GL_POSITION, lightPosition);
glEnable(GL_LIGHT0);
glEnable(GL_LIGHTING);
glEnable(GL_DEPTH_TEST);
glClearColor(0.0, 0.0, 0.0, 1.0);
return 0;
}
int initializeHaptics()
{
{
return -1;
}
return 0;
}
int main(int argc,
char* argv[])
{
std::cout << "Copyright (C) 2001-2023 Force Dimension" << std::endl;
std::cout << "All Rights Reserved." << std::endl << std::endl;
if (initializeHaptics() < 0)
{
std::cout << "error: failed to initialize haptics" << std::endl;
return -1;
}
if (initializeGLFW() < 0)
{
std::cout << "error: failed to initialize GLFW" << std::endl;
return -1;
}
#if defined(WIN32) || defined(WIN64)
DWORD threadHandle;
CreateThread(nullptr, 0, (LPTHREAD_START_ROUTINE)(hapticsLoop), nullptr, 0x0000, &threadHandle);
SetThreadPriority(&threadHandle, THREAD_PRIORITY_ABOVE_NORMAL);
#else
pthread_t threadHandle;
pthread_create(&threadHandle, nullptr, hapticsLoop, nullptr);
struct sched_param schedulerParameters;
memset(&schedulerParameters, 0, sizeof(struct sched_param));
schedulerParameters.sched_priority = 10;
pthread_setschedparam(threadHandle, SCHED_RR, &schedulerParameters);
#endif
atexit(onExit);
std::cout <<
dhdGetSystemName() <<
" device detected" << std::endl << std::endl;
std::cout << "press 'r' to toggle display of the haptic rate" << std::endl;
std::cout << " 't' to enable or disable torque on wrist actuated devices" << std::endl;
std::cout << " 'f' to enable or disable force" << std::endl;
std::cout << " 'q' to quit" << std::endl << std::endl;
while (simulationRunning && !glfwWindowShouldClose(window))
{
if (updateGraphics() < 0)
{
std::cout << "error: failed to update graphics" << std::endl;
break;
}
glfwSwapBuffers(window);
glfwPollEvents();
}
glfwDestroyWindow(window);
glfwTerminate();
return 0;
}
double __SDK dhdGetComFreq(char ID=-1)
Definition: dhdc.cpp:4654
int __SDK dhdSetForceAndTorqueAndGripperForce(double fx, double fy, double fz, double tx, double ty, double tz, double fg, char ID=-1)
Definition: dhdc.cpp:2040
int __SDK dhdEnableForce(uchar val, char ID=-1)
Definition: dhdc.cpp:4378
int __SDK dhdClose(char ID=-1)
Definition: dhdc.cpp:443
int __SDK dhdGetPositionAndOrientationFrame(double *px, double *py, double *pz, double matrix[3][3], char ID=-1)
Definition: dhdc.cpp:1923
void __SDK dhdSleep(double sec)
Definition: dhdc.cpp:4754
@ DHD_NO_ERROR
Definition: dhdc.h:52
#define DHD_OFF
Definition: dhdc.h:129
const char *__SDK dhdGetSDKVersionStr()
Definition: dhdc.cpp:925
int __SDK dhdOpen()
Definition: dhdc.cpp:265
#define DHD_ON
Definition: dhdc.h:128
int __SDK dhdGetPosition(double *px, double *py, double *pz, char ID=-1)
Definition: dhdc.cpp:1614
const char *__SDK dhdGetSystemName(char ID=-1)
Definition: dhdc.cpp:814
double __SDK dhdGetTime()
Definition: dhdc.cpp:190
int __SDK dhdGetOrientationFrame(double matrix[3][3], char ID=-1)
Definition: dhdc.cpp:4552
const char *__SDK dhdErrorGetLastStr()
Definition: dhdError.cpp:197