encoders.cpp
////////////////////////////////////////////////////////////////////////////////
//
// Copyright (C) 2001-2023 Force Dimension, Switzerland.
// All Rights Reserved.
//
// Force Dimension SDK 3.17.1
//
////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////////
///
/// This example illustrates how to retrieve a Force Dimension haptic device
/// low-level encoders using the expert functions of the SDK. If the haptic
/// device is initialized, it places it in a gravity compensation loop.
///
////////////////////////////////////////////////////////////////////////////////
// C++ library headers
#include <iomanip>
#include <iostream>
// Force Dimension SDK library header
#include "dhdc.h"
///////////////////////////////////////////////////////////////////////////////
int main(int argc,
char *argv[])
{
// Optimize console output performance.
std::cout.rdbuf()->pubsetbuf(nullptr, 512);
std::cout << std::nounitbuf;
std::ios_base::sync_with_stdio(false);
// Display version information.
std::cout << "Encoder Reading Example " << dhdGetSDKVersionStr() << std::endl;
std::cout << "Copyright (C) 2001-2023 Force Dimension" << std::endl;
std::cout << "All Rights Reserved." << std::endl << std::endl;
// Enable expert mode to allow access to the encoder values.
// Open the first available haptic device.
if (dhdOpen() < 0)
{
std::cout << "error: failed to open device (" << dhdErrorGetLastStr() << ")" << std::endl;
dhdSleep(2.0);
return -1;
}
// Display the device type.
std::cout << dhdGetSystemName() << " device detected" << std::endl << std::endl;
// Display user instructions.
std::cout << "press 'q' to quit" << std::endl << std::endl;
// Enable force rendering on the haptic device.
{
std::cout << "error: failed to enable force rendering (" << dhdErrorGetLastStr() << ")" << std::endl;
dhdSleep(2.0);
return -1;
}
// Determine the number of encoders to display based on the device capabilities.
int numEncoders = 3;
if (dhdHasWrist())
{
numEncoders += 3;
}
if (dhdHasWrist())
{
numEncoders += 1;
}
// Allocate and initialize the encoders buffer.
int encoders[DHD_MAX_DOF] = {};
double lastDisplayUpdateTime = dhdGetTime();
// Run the haptic loop.
while (true)
{
// Apply zero force on the haptic device.
if (dhdSetForceAndTorqueAndGripperForce(0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0) < DHD_NO_ERROR)
{
std::cout << "error: failed to render force (" << dhdErrorGetLastStr() << ")" << std::endl;
dhdSleep(2.0);
break;
}
// Retrieve encoders.
if (dhdGetEnc(encoders) < 0)
{
std::cout << "error: failed to read encoders (" << dhdErrorGetLastStr() << ")" << std::endl;
dhdSleep(2.0);
break;
}
// Periodically the haptic device encoders and flush stdout.
double time = dhdGetTime();
if (time - lastDisplayUpdateTime > 0.1)
{
lastDisplayUpdateTime = time;
std::cout << std::internal << std::showpos << std::setfill('0');
for (int index = 0; index < numEncoders; index++)
{
std::cout << std::setw(7) << encoders[index] << " ";
}
std::cout << " \r";
std::cout.flush();
}
// Process user input.
if (dhdKbHit() && dhdKbGet() == 'q')
{
std::cout << std::endl << std::endl << "exiting at user's request" << std::endl;
break;
}
}
// Close the connection to the haptic device.
if (dhdClose() < 0)
{
std::cout << "error: failed to close the connection (" << dhdErrorGetLastStr() << ")" << std::endl;
dhdSleep(2.0);
return -1;
}
// Report success.
std::cout << "connection closed" << std::endl;
return 0;
}
DHD_ON
#define DHD_ON
Definition: dhdc.h:128
DHD_NO_ERROR
@ DHD_NO_ERROR
Definition: dhdc.h:54
dhdGetEnc
int __SDK dhdGetEnc(int enc[DHD_MAX_DOF], uchar mask=0xff, char ID=-1)
Definition: dhdc.cpp:4435
dhdErrorGetLastStr
const char *__SDK dhdErrorGetLastStr()
Definition: dhdError.cpp:197
dhdSetForceAndTorqueAndGripperForce
int __SDK dhdSetForceAndTorqueAndGripperForce(double fx, double fy, double fz, double tx, double ty, double tz, double fg, char ID=-1)
Definition: dhdc.cpp:2040
dhdc.h
DHD header file.
dhdEnableExpertMode
int __SDK dhdEnableExpertMode()
Definition: dhdc.cpp:2895
dhdKbHit
bool __SDK dhdKbHit()
Definition: dhdc.cpp:4731
dhdEnableForce
int __SDK dhdEnableForce(uchar val, char ID=-1)
Definition: dhdc.cpp:4378
dhdGetSystemName
const char *__SDK dhdGetSystemName(char ID=-1)
Definition: dhdc.cpp:814
dhdClose
int __SDK dhdClose(char ID=-1)
Definition: dhdc.cpp:443
dhdKbGet
char __SDK dhdKbGet()
Definition: dhdc.cpp:4743
dhdOpen
int __SDK dhdOpen()
Definition: dhdc.cpp:265
dhdSleep
void __SDK dhdSleep(double sec)
Definition: dhdc.cpp:4754
dhdHasWrist
bool __SDK dhdHasWrist(char ID=-1)
Definition: dhdc.cpp:641
DHD_MAX_DOF
#define DHD_MAX_DOF
Definition: dhdc.h:133
dhdGetSDKVersionStr
const char *__SDK dhdGetSDKVersionStr()
Definition: dhdc.cpp:925
dhdGetTime
double __SDK dhdGetTime()
Definition: dhdc.cpp:190