#define _USE_MATH_DEFINES
#include <algorithm>
#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 "CGeometry.h"
#include "FontGL.h"
constexpr int SwapInterval = 1;
bool simulationRunning = true;
bool simulationFinished = false;
chai3d::cVector3d devicePosition;
chai3d::cMatrix3d deviceRotation;
double deviceGripperAngleDeg = 0.0;
chai3d::cVector3d deviceLinearVelocity;
chai3d::cVector3d deviceAngularVelocity;
uint32_t deviceSwitches = 0x00000000;
chai3d::cVector3d deviceForce;
chai3d::cVector3d deviceTorque;
double deviceGripperForce = 0.0;
double deviceRollAngleRad = 0.0;
bool flagSaturation = false;
chai3d::cVector3d holdPosition;
chai3d::cMatrix3d holdRotation;
bool flagHoldPosition = false;
bool flagHoldPositionReady = false;
chai3d::cVector3d framePosition;
chai3d::cMatrix3d frameRotation;
chai3d::cTransform device_T_frame;
bool flagMoveFrame = false;
GLFWwindow* window = nullptr;
int windowWidth = 0;
int windowHeight = 0;
int updateGraphics()
{
GLUquadricObj *sphere;
chai3d::cTransform mat;
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
glEnable(GL_DEPTH_TEST);
glClearColor(0.0, 0.0, 0.0, 1.0);
mat.set(devicePosition, deviceRotation);
glPushMatrix();
glMultMatrixd((const double *)mat.getData());
glEnable(GL_COLOR_MATERIAL);
glColor3f(0.5f, 0.5f, 0.5f);
sphere = gluNewQuadric();
gluSphere(sphere, 0.005, 32, 32);
glDisable(GL_LIGHTING);
glBegin(GL_LINES);
glColor3f(1.0f, 0.0f, 0.0f);
glVertex3d(0.00, 0.00, 0.00);
glVertex3d(0.02, 0.00, 0.00);
glColor3f(0.0f, 1.0f, 0.0f);
glVertex3d(0.00, 0.00, 0.00);
glVertex3d(0.00, 0.02, 0.00);
glColor3f(0.0f, 0.0f, 1.0f);
glVertex3d(0.00, 0.00, 0.00);
glVertex3d(0.00, 0.00, 0.02);
glEnd();
glEnable(GL_LIGHTING);
glDisable(GL_LIGHTING);
glBegin(GL_LINE_STRIP);
glColor3f(1.0f, 1.0f, 1.0f);
glVertex3d(0.0, 0.0, 0.0);
for (int index = -10; index <= 10; index++)
{
double angle = 0.1 * (double)(index) * deviceGripperAngleDeg;
double px = 0.1 * chai3d::cCosDeg(angle);
double py = 0.1 * chai3d::cSinDeg(angle);
glVertex3d(-px, py, 0.0);
}
glVertex3d(0.0, 0.0, 0.0);
glColor3f(0.5f, 0.5f, 0.5f);
glVertex3d(-0.1, 0.0, 0.0);
glEnd();
glEnable(GL_LIGHTING);
glPopMatrix();
mat.set(framePosition, frameRotation);
glPushMatrix();
glMultMatrixd((const double *)mat.getData());
glEnable(GL_COLOR_MATERIAL);
glColor3f(0.5f, 0.5f, 0.5f);
sphere = gluNewQuadric();
gluSphere(sphere, 0.01, 32, 32);
glDisable(GL_LIGHTING);
glBegin(GL_LINES);
glColor3f(1.0f, 0.0f, 0.0f);
glVertex3d(0.00, 0.00, 0.00);
glVertex3d(0.04, 0.00, 0.00);
glColor3f(0.0f, 1.0f, 0.0f);
glVertex3d(0.00, 0.00, 0.00);
glVertex3d(0.00, 0.04, 0.00);
glColor3f(0.0f, 0.0f, 1.0f);
glVertex3d(0.00, 0.00, 0.00);
glVertex3d(0.00, 0.00, 0.04);
glEnd();
glEnable(GL_LIGHTING);
glPopMatrix();
glDisable(GL_LIGHTING);
glBegin(GL_LINES);
glColor3f(0.5f, 0.5f, 0.5f);
glVertex3d(devicePosition(0), devicePosition(1), devicePosition(2));
glVertex3d(framePosition(0), framePosition(1), framePosition(2));
glEnd();
glEnable(GL_LIGHTING);
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);
glDisable(GL_LIGHTING);
glColor3f(1.0, 1.0, 1.0);
glRasterPos3f(0.0f, -0.03f, 0.1f);
for (int index = 0; index < 16; index++)
{
if (chai3d::cCheckBit(deviceSwitches, index))
{
render_character('1', HELVETICA12);
}
else
{
render_character('0', HELVETICA12);
}
render_character(' ', HELVETICA12);
}
glEnable(GL_LIGHTING);
GLenum err = glGetError();
if (err != GL_NO_ERROR)
{
return -1;
}
return 0;
}
void* hapticsLoop(void* a_userData)
{
double px = 0.0;
double py = 0.0;
double pz = 0.0;
double rot[3][3] = {};
double vx = 0.0;
double vy = 0.0;
double vz = 0.0;
double wx = 0.0;
double wy = 0.0;
double wz = 0.0;
{
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.set(px, py, pz);
deviceRotation.set(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]);
{
std::cout << std::endl <<
"error: failed to read gripper angle (" <<
dhdErrorGetLastStr() <<
")" << std::endl;
break;
}
{
std::cout << std::endl <<
"error: failed to read linear velocity (" <<
dhdErrorGetLastStr() <<
")" << std::endl;
break;
}
deviceLinearVelocity.set(vx, vy, vz);
{
std::cout << std::endl <<
"error: failed to read gripper angle (" <<
dhdErrorGetLastStr() <<
")" << std::endl;
break;
}
deviceAngularVelocity.set(wx, wy, wz);
if (chai3d::cCheckBit(deviceSwitches, 0))
{
if (flagMoveFrame)
{
chai3d::cTransform world_T_device;
world_T_device.set(devicePosition, deviceRotation);
chai3d::cTransform world_T_frame = world_T_device * device_T_frame;
framePosition = world_T_frame.getLocalPos();
frameRotation = world_T_frame.getLocalRot();
}
else
{
chai3d::cTransform world_T_device;
world_T_device.set(devicePosition, deviceRotation);
chai3d::cTransform world_T_frame;
world_T_frame.set(framePosition, frameRotation);
chai3d::cTransform device_T_world = world_T_device;
device_T_world.invert();
device_T_frame = device_T_world * world_T_frame;
flagMoveFrame = true;
}
}
else
{
flagMoveFrame = false;
}
deviceForce.zero();
deviceTorque.zero();
deviceGripperForce = 0.0;
constexpr double Kp = 2000.0;
constexpr double Kv = 10.0;
constexpr double Kr = 5.0;
constexpr double Kw = 0.05;
if (flagHoldPosition)
{
if (flagHoldPositionReady)
{
chai3d::cVector3d force = -Kp * (devicePosition - holdPosition) - Kv * deviceLinearVelocity;
chai3d::cMatrix3d deltaRotation = chai3d::cTranspose(deviceRotation) * holdRotation;
chai3d::cVector3d axis;
double angle = 0.0;
deltaRotation.toAxisAngle(axis, angle);
chai3d::cVector3d torque = deviceRotation * ((Kr * angle) * axis) - Kw * deviceAngularVelocity;
deviceForce = deviceForce + force;
deviceTorque = deviceTorque + torque;
}
else
{
holdPosition = devicePosition;
holdRotation = deviceRotation;
flagHoldPositionReady = true;
}
}
constexpr double MaxTorque = 0.3;
if (deviceTorque.length() > MaxTorque)
{
deviceTorque = MaxTorque * chai3d::cNormalize(deviceTorque);
}
deviceTorque(0), deviceTorque(1), deviceTorque(2),
deviceGripperForce);
if (error == 2)
{
flagSaturation = true;
}
else
{
flagSaturation = false;
}
}
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_H)
{
flagHoldPosition = !flagHoldPosition;
flagHoldPositionReady = false;
}
}
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 - OpenGL Sphere 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 mat_ambient[] = { 0.5f, 0.5f, 0.5f };
GLfloat mat_diffuse[] = { 0.5f, 0.5f, 0.5f };
GLfloat mat_specular[] = { 0.5f, 0.5f, 0.5f };
glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT, mat_ambient);
glMaterialfv(GL_FRONT_AND_BACK, GL_DIFFUSE, mat_diffuse);
glMaterialfv(GL_FRONT_AND_BACK, GL_SPECULAR, mat_specular);
glMaterialf(GL_FRONT_AND_BACK, GL_SHININESS, 1.0);
GLfloat ambient[] = { 0.5f, 0.5f, 0.5f, 1.0f };
GLfloat diffuse[] = { 0.8f, 0.8f, 0.8f, 1.0f };
GLfloat specular[] = { 1.0f, 1.0f, 1.0f, 1.0f };
glLightfv(GL_LIGHT0, GL_AMBIENT, ambient);
glLightfv(GL_LIGHT0, GL_DIFFUSE, diffuse);
glLightfv(GL_LIGHT0, GL_SPECULAR, specular);
glLightf(GL_LIGHT0, GL_CONSTANT_ATTENUATION, 1.0);
glLightf(GL_LIGHT0, GL_LINEAR_ATTENUATION, 0.0);
glLightf(GL_LIGHT0, GL_QUADRATIC_ATTENUATION, 0.0);
GLfloat lightPos[] = { 2.0, 0.0, 0.0, 1.0f };
GLfloat lightDir[] = { -1.0, 0.0, 0.0, 1.0f };
glLightfv(GL_LIGHT0, GL_POSITION, lightPos);
glLightfv(GL_LIGHT0, GL_SPOT_DIRECTION, lightDir);
glLightf(GL_LIGHT0, GL_SPOT_CUTOFF, 180);
glLightf(GL_LIGHT0, GL_SPOT_EXPONENT, 1.0);
glEnable(GL_LIGHTING);
glEnable(GL_LIGHT0);
return 0;
}
int initializeHaptics()
{
{
return -1;
}
{
return -1;
}
return 0;
}
int initializeSimulation()
{
framePosition.set(0.0, 0.0, 0.0);
frameRotation.identity();
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 (initializeSimulation() < 0)
{
std::cout << "error: failed to initialize the simulation" << 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 << std::endl;
std::cout << "press 'r' to toggle display of the haptic rate" << 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 dhdGetGripperAngleDeg(double *a, char ID=-1)
Definition: dhdc.cpp:4854
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 dhdGetLinearVelocity(double *vx, double *vy, double *vz, char ID=-1)
Definition: dhdc.cpp:2191
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
uint __SDK dhdGetButtonMask(char ID=-1)
Definition: dhdc.cpp:1217
void __SDK dhdSleep(double sec)
Definition: dhdc.cpp:4754
bool __SDK dhdHasActiveGripper(char ID=-1)
Definition: dhdc.cpp:726
const char *__SDK dhdGetSDKVersionStr()
Definition: dhdc.cpp:925
@ DHD_NO_ERROR
Definition: dhdc.h:52
int __SDK dhdEmulateButton(uchar val, char ID=-1)
Definition: dhdc.cpp:2941
const char *__SDK dhdErrorGetLastStr()
Definition: dhdError.cpp:197
int __SDK dhdOpen()
Definition: dhdc.cpp:265
#define DHD_ON
Definition: dhdc.h:128
int __SDK dhdGetAngularVelocityRad(double *wx, double *wy, double *wz, char ID=-1)
Definition: dhdc.cpp:2270
double __SDK dhdGetTime()
Definition: dhdc.cpp:190