#include <iomanip>
#include <iostream>
int main(int argc,
char *argv[])
{
std::cout.rdbuf()->pubsetbuf(nullptr, 512);
std::cout << std::nounitbuf;
std::ios_base::sync_with_stdio(false);
std::cout << "Copyright (C) 2001-2023 Force Dimension" << std::endl;
std::cout << "All Rights Reserved." << std::endl << std::endl;
{
std::cout <<
"error: failed to open device (" <<
dhdErrorGetLastStr() <<
")" << std::endl;
return -1;
}
std::cout <<
dhdGetSystemName() <<
" device detected" << std::endl << std::endl;
std::cout << "press 'q' to quit" << std::endl << std::endl;
{
std::cout <<
"error: failed to enable force rendering (" <<
dhdErrorGetLastStr() <<
")" << std::endl;
return -1;
}
double px = 0.0;
double py = 0.0;
double pz = 0.0;
double fx = 0.0;
double fy = 0.0;
double fz = 0.0;
while (true)
{
{
std::cout <<
"error: failed to render force (" <<
dhdErrorGetLastStr() <<
")" << std::endl;
break;
}
{
std::cout << std::endl <<
"error: failed to read position (" <<
dhdErrorGetLastStr() <<
")" << std::endl;
break;
}
{
std::cout << std::endl <<
"error: failed to read forces (" <<
dhdErrorGetLastStr() <<
")" << std::endl;
break;
}
if (time - lastDisplayUpdateTime > 0.1)
{
lastDisplayUpdateTime = time;
std::cout << std::showpos << std::fixed << std::setprecision(3);
std::cout << "p (" << std::setw(6) << px << " " << std::setw(6) << py << " " << std::setw(6) << pz << ") m | ";
std::cout << "f (" << std::setw(6) << fx << " " << std::setw(6) << fy << " " << std::setw(6) << fz << ") N | ";
std::cout <<
"freq " << std::noshowpos << std::setprecision(2) << std::setw(4) <<
dhdGetComFreq() <<
" kHz \r";
std::cout.flush();
}
{
std::cout << std::endl << std::endl << "exiting at user's request" << std::endl;
break;
}
}
{
std::cout <<
"error: failed to close the connection (" <<
dhdErrorGetLastStr() <<
")" << std::endl;
return -1;
}
std::cout << "connection closed" << std::endl;
return 0;
}
char __SDK dhdKbGet()
Definition: dhdc.cpp:4743
double __SDK dhdGetComFreq(char ID=-1)
Definition: dhdc.cpp:4654
int __SDK dhdGetForce(double *fx, double *fy, double *fz, char ID=-1)
Definition: dhdc.cpp:1676
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
void __SDK dhdSleep(double sec)
Definition: dhdc.cpp:4754
const char *__SDK dhdGetSDKVersionStr()
Definition: dhdc.cpp:925
@ DHD_NO_ERROR
Definition: dhdc.h:52
const char *__SDK dhdErrorGetLastStr()
Definition: dhdError.cpp:197
const char *__SDK dhdGetSystemName(char ID=-1)
Definition: dhdc.cpp:814
bool __SDK dhdKbHit()
Definition: dhdc.cpp:4731
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
double __SDK dhdGetTime()
Definition: dhdc.cpp:190