vrpn 07.36
Virtual Reality Peripheral Network
Loading...
Searching...
No Matches
vrpn_Tracker_NovintFalcon.C
Go to the documentation of this file.
1// -*- c++ -*-
2// This file provides an interface to a Novint Falcon.
3// http://home.novint.com/products/novint_falcon.php
4// It uses libnifalcon to communicate with the device.
5// http://libnifalcon.nonpolynomial.org/
6//
7// File: vrpn_Tracker_NovintFalcon.C
8// Author: Axel Kohlmeyer akohlmey@gmail.com
9// Date: 2010-08-12
10// Copyright: (C) 2010 Axel Kohlmeyer
11// License: Boost Software License 1.0
12// depends: libnifalcon-1.0.1+, libusb-1.0, boost 1.39, VRPN 07_27
13// tested on: Linux x86_64 w/ gcc 4.4.1
14
16
17#ifdef VRPN_USE_LIBNIFALCON
18#include <array>
19#include <memory>
20#include "falcon/core/FalconDevice.h"
21#include "falcon/firmware/FalconFirmwareNovintSDK.h"
22#include "falcon/grip/FalconGripFourButton.h"
23#include "falcon/kinematic/FalconKinematicStamper.h"
24#include "falcon/util/FalconFirmwareBinaryNvent.h"
25
26/**************************************************************************/
27// number of retries for the I/O loop.
28#define FALCON_NUM_RETRIES 10
29
30// define to activate additional messages about
31// what the driver is currently trying to do.
32#undef VERBOSE
33
34// define for detailed status tracking. very verbose.
35#undef VERBOSE2
36/**************************************************************************/
37
38// save us some typing
39typedef std::array<double, 3> d_vector;
40
42static d_vector operator+(const d_vector &a,const d_vector &b)
43{
44 d_vector ret;
45 ret[0] = a[0] + b[0];
46 ret[1] = a[1] + b[1];
47 ret[2] = a[2] + b[2];
48 return ret;
49}
50
52static d_vector operator-(const d_vector &a,const d_vector &b)
53{
54 d_vector ret;
55 ret[0] = a[0] + b[0];
56 ret[1] = a[1] + b[1];
57 ret[2] = a[2] + b[2];
58 return ret;
59}
60
62static double d_length(const d_vector &a)
63{
64 double ret;
65 ret = a[0] * a[0];
66 ret += a[1] * a[1];
67 ret += a[2] * a[2];
68 return sqrt(ret);
69}
70
71/*************************************************************************/
72// compute time difference in microseconds.
73static double timediff(struct timeval t1, struct timeval t2) {
74 return (t1.tv_usec - t2.tv_usec)*1.0 + 1000000.0 * (t1.tv_sec - t2.tv_sec);
75}
76
77/*************************************************************************/
78
79class vrpn_NovintFalcon_Device
80{
81public:
82 vrpn_NovintFalcon_Device(int flags)
83 : m_flags(flags)
84 {
85 if (m_flags < 0) {
86 m_falconDevice = NULL;
87 return;
88 } else {
89 m_falconDevice = new libnifalcon::FalconDevice;
90 m_falconDevice->setFalconFirmware<libnifalcon::FalconFirmwareNovintSDK>();
91 }
92
93 if (m_flags & KINE_STAMPER) {
94 m_falconDevice->setFalconKinematic<libnifalcon::FalconKinematicStamper>();
95 } else {
96 try {
97 delete m_falconDevice;
98 } catch (...) {
99 fprintf(stderr, "vrpn_NovintFalcon_Device::vrpn_NovintFalcon_Device(): delete failed\n");
100 return;
101 }
102 m_falconDevice=NULL;
103 return;
104 }
105
106 if (m_flags & GRIP_FOURBUTTON) {
107 m_falconDevice->setFalconGrip<libnifalcon::FalconGripFourButton>();
108 } else {
109 try {
110 delete m_falconDevice;
111 } catch (...) {
112 fprintf(stderr, "vrpn_NovintFalcon_Device::vrpn_NovintFalcon_Device(): delete failed\n");
113 return;
114 }
115 m_falconDevice=NULL;
116 return;
117 }
118 }
119
120 ~vrpn_NovintFalcon_Device() {
121#ifdef VERBOSE
122 fprintf(stderr, "Closing Falcon device %d.\n", m_flags & MASK_DEVICEIDX);
123#endif
124 if (m_falconDevice) {
125 std::shared_ptr<libnifalcon::FalconFirmware> f;
126 f=m_falconDevice->getFalconFirmware();
127 if(f) {
128 f->setLEDStatus(libnifalcon::FalconFirmware::RED_LED |
129 libnifalcon::FalconFirmware::BLUE_LED |
130 libnifalcon::FalconFirmware::GREEN_LED);
131 for (int i=0; !m_falconDevice->runIOLoop() && i < FALCON_NUM_RETRIES; ++i) continue;
132 }
133 m_falconDevice->close();
134 }
135 try {
136 delete m_falconDevice;
137 } catch (...) {
138 fprintf(stderr, "vrpn_NovintFalcon_Device::~vrpn_NovintFalcon_Device(): delete failed\n");
139 return;
140 }
141 m_flags=-1;
142 };
143
144public:
145 // open device, load firmware and calibrate.
146 bool init() {
147 if (!m_falconDevice)
148 return false;
149
150 unsigned int count;
151 m_falconDevice->getDeviceCount(count);
152 int devidx = m_flags & MASK_DEVICEIDX;
153
154#ifdef VERBOSE
155 fprintf(stderr, "Trying to open Falcon device %d/%d.\n", devidx, count);
156#endif
157 if (devidx < count) {
158 if (!m_falconDevice->open(devidx)) {
159 fprintf(stderr, "Cannot open falcon device %d - Lib Error Code: %d - Device Error Code: %d\n",
160 devidx, m_falconDevice->getErrorCode(), m_falconDevice->getFalconComm()->getDeviceErrorCode());
161 return false;
162 }
163 } else {
164 fprintf(stderr, "Trying to open non-existing Novint Falcon device %d\n", devidx);
165 return false;
166 }
167
168 if (!m_falconDevice->isFirmwareLoaded()) {
169#ifdef VERBOSE
170 fprintf(stderr, "Loading Falcon Firmware\n");
171#endif
172 int i;
173 // 10 chances to load the firmware.
174 for (i=0; i<FALCON_NUM_RETRIES; ++i) {
175 if(!m_falconDevice->getFalconFirmware()->loadFirmware(true, libnifalcon::NOVINT_FALCON_NVENT_FIRMWARE_SIZE, const_cast<uint8_t*>(libnifalcon::NOVINT_FALCON_NVENT_FIRMWARE)))
176 {
177 fprintf(stderr, "Firmware loading attempt %d failed.\n", i);
178 if(i==FALCON_NUM_RETRIES-1){
179 fprintf(stderr, "Cannot load falcon device %d firmware - Device Error Code: %d - Comm Lib Error Code: %d\n",
180 devidx, m_falconDevice->getErrorCode(), m_falconDevice->getFalconComm()->getDeviceErrorCode());
181 return false;
182 }
183 } else {
184#ifdef VERBOSE
185 fprintf(stderr, "Falcon firmware successfully loaded.\n");
186#endif
187 break;
188 }
189 }
190 } else {
191#ifdef VERBOSE
192
193 fprintf(stderr, "Falcon Firmware already loaded.\n");
194#endif
195 }
196
197 int i;
198 bool message = false;
199 std::shared_ptr<libnifalcon::FalconFirmware> f;
200 f=m_falconDevice->getFalconFirmware();
201 for (i=0; !m_falconDevice->runIOLoop() && i < FALCON_NUM_RETRIES; ++i) continue;
202 while(1) { // XXX: add timeout to declare device dead after a while.
203 f->setHomingMode(true);
204 for (i=0; !m_falconDevice->runIOLoop() && i < FALCON_NUM_RETRIES; ++i) continue;
205 if(!f->isHomed()) {
206 f->setLEDStatus(libnifalcon::FalconFirmware::RED_LED);
207 for (i=0; !m_falconDevice->runIOLoop() && i < FALCON_NUM_RETRIES; ++i) continue;
208 if (!message) {
209 fprintf(stderr, "Falcon not currently calibrated. Move control all the way out then push straight all the way in.\n");
210 message = true;
211 }
212 } else {
213 f->setLEDStatus(libnifalcon::FalconFirmware::BLUE_LED);
214 for (i=0; !m_falconDevice->runIOLoop() && i < FALCON_NUM_RETRIES; ++i) continue;
215#ifdef VERBOSE
216 fprintf(stderr, "Falcon calibrated successfully.\n");
217#endif
218 break;
219 }
220 }
221
222 message = false;
223 while(1) { // XXX: add timeout to declare device dead after a while.
224 int i;
225
226 for (i=0; !m_falconDevice->runIOLoop() && i < FALCON_NUM_RETRIES; ++i) continue;
227 d_vector pos = m_falconDevice->getPosition();
228 m_oldpos = pos;
229 vrpn_gettimeofday(&m_oldtime, NULL);
230
231 if (!message) {
232 fprintf(stderr, "Move control all the way out until led turns green to activate device.\n");
233 message = true;
234 }
235 if (pos[2] > 0.170) { // XXX: value taken from libnifalcon test example
236 f->setLEDStatus(libnifalcon::FalconFirmware::GREEN_LED);
237 for (i=0; !m_falconDevice->runIOLoop() && i < FALCON_NUM_RETRIES; ++i) continue;
238#ifdef VERBOSE
239 fprintf(stderr, "Falcon activated successfully.\n");
240#endif
241 break;
242 }
243 }
244 return true;
245 };
246
247 // query status of device.
248 bool get_status(vrpn_float64 *pos, vrpn_float64 *vel,
249 vrpn_float64 *quat, vrpn_float64 *vel_quat,
250 vrpn_float64 *vel_dt, unsigned char *buttons) {
251 if (!m_falconDevice)
252 return false;
253
254 int i;
255 for (i=0; !m_falconDevice->runIOLoop() && i < FALCON_NUM_RETRIES; ++i) continue;
256 if ( i == FALCON_NUM_RETRIES )
257 return false;
258
259 // we have no orientation of the effector.
260 // so we just pick the identity quaternion.
261 if (quat) {
262 quat[0] = 0.0;
263 quat[1] = 0.0;
264 quat[2] = 0.0;
265 quat[3] = 1.0;
266 }
267
268 if (vel_quat) {
269 vel_quat[0] = 0.0;
270 vel_quat[1] = 0.0;
271 vel_quat[2] = 0.0;
272 vel_quat[3] = 0.0;
273 }
274
275 // update position information
276 d_vector my_pos = m_falconDevice->getPosition();
277 const double convert_pos = 1.0; // empirical. need to measure properly.
278 pos[0] = convert_pos * my_pos[0];
279 pos[1] = convert_pos * my_pos[1];
280 pos[2] = convert_pos * (my_pos[2]-0.125); // apply offset to make z axis data centered.
281#ifdef VERBOSE2
282 fprintf(stderr, "position %5.3f %5.3f %5.3f\n", pos[0],pos[1],pos[2]);
283#endif
284 if (vel) {
285 struct timeval current_time;
286 vrpn_gettimeofday(&current_time, NULL);
287 double deltat = timediff(current_time, m_oldtime);
288 *vel_dt= deltat;
289 if (deltat > 0) {
290 vel[0] = convert_pos * (my_pos[0] - m_oldpos[0]) / deltat;
291 vel[1] = convert_pos * (my_pos[1] - m_oldpos[1]) / deltat;
292 vel[2] = convert_pos * (my_pos[2] - m_oldpos[2]) / deltat;
293 } else {
294 vel[0] = 0.0;
295 vel[1] = 0.0;
296 vel[2] = 0.0;
297 }
298#ifdef VERBOSE2
299 fprintf(stderr, "velocity %5.3f %5.3f %5.3f\n", vel[0],vel[1],vel[2]);
300#endif
301 m_oldpos = my_pos;
302 m_oldtime.tv_sec = current_time.tv_sec;
303 m_oldtime.tv_usec = current_time.tv_usec;
304 }
305
306 // update button information
307 unsigned int my_buttons = m_falconDevice->getFalconGrip()->getDigitalInputs();
308 if (m_flags & GRIP_FOURBUTTON) {
309 buttons[0] = (my_buttons & libnifalcon::FalconGripFourButton::CENTER_BUTTON) ? 1 : 0;
310 buttons[1] = (my_buttons & libnifalcon::FalconGripFourButton::PLUS_BUTTON) ? 1 : 0;
311 buttons[2] = (my_buttons & libnifalcon::FalconGripFourButton::MINUS_BUTTON) ? 1 : 0;
312 buttons[3] = (my_buttons & libnifalcon::FalconGripFourButton::FORWARD_BUTTON) ? 1 : 0;
313 }
314 return true;
315 };
316
317 // set feedback force
318 bool set_force(const d_vector &force) {
319 if (!m_falconDevice)
320 return false;
321
322 // update position information
323 m_falconDevice->setForce(force);
324 if(!m_falconDevice->runIOLoop())
325 return false;
326
327 return true;
328 };
329
330protected:
331 int m_flags;
332 libnifalcon::FalconDevice *m_falconDevice;
333 d_vector m_oldpos;
334 struct timeval m_oldtime;
335
336private:
338 vrpn_NovintFalcon_Device() {};
340 vrpn_NovintFalcon_Device(const vrpn_NovintFalcon_Device &dev) {};
341
342public:
344 enum falconflags {
345 NONE = 0x0000, //< empty
346 MASK_DEVICEIDX = 0x000f, //< max. 15 falcons
347 KINE_STAMPER = 0x0010, //< stamper kinematics model
348 GRIP_FOURBUTTON = 0x0100 //< 4-button grip (the default)
349 };
350};
351
353class ForceFieldEffect
354{
355public:
357 ForceFieldEffect() : m_active(false), m_time(0), m_cutoff(0.0), m_damping(0.9)
358 {
359 int i,j;
360 for (i=0; i < 3; i++) {
361 m_origin[i] = 0.0;
362 m_addforce[i] = 0.0;
363 for (j=0; j < 3; j++) {
364 m_jacobian[i][j] = 0.0;
365 }
366 }
367 };
368
370 ~ForceFieldEffect() {}
371
372public:
374 void setForce(vrpn_float32 ori[3], vrpn_float32 frc[3], vrpn_float32 jac[3][3], vrpn_float32 rad) {
375 int i,j;
376 for (i=0; i < 3; i++) {
377 m_neworig[i] = ori[i];
378 m_newadd[i] = frc[i];
379 for (j=0; j < 3; j++) {
380 m_newjacob[i][j] = jac[i][j];
381 }
382 }
383 m_newcut = rad;
384 }
385
387 void setDamping(double damp) {
388 m_damping = damp;
389 }
390
392 virtual bool start() {
393 m_active = true;
394 m_time = 0.0;
395 // this will delay the effect until it
396 // is (re-)initialized with setForce()
397 m_cutoff = 0.0;
398 return m_active;
399 }
400
402 virtual void stop() {
403 m_active = false;
404 }
405
407 virtual bool isActive() const { return m_active; }
408
410 d_vector calcForce(const d_vector &pos) {
411 d_vector force, offset;
412 force.fill(0.0);
413 if (m_active) {
414 // apply damping to effect values
415 const double mix = 1.0 - m_damping;
416 int i,j;
417 for (i=0; i < 3; i++) {
418 m_origin[i] = m_damping*m_origin[i] + mix*m_neworig[i];
419 m_addforce[i] = m_damping*m_addforce[i] + mix*m_newadd[i];
420 for (j=0; j < 3; j++) {
421 m_jacobian[i][j] = m_damping*m_jacobian[i][j] + mix*m_newjacob[i][j];
422 }
423 }
424 m_cutoff = m_damping*m_cutoff + mix*m_newcut;
425
426 offset = pos - m_origin;
427 // no force too far away.
428 if (d_length(offset) > m_cutoff) {
429 return force;
430 }
431 // Compute the force, which is the constant force plus
432 // a force that varies as the effector position deviates
433 // from the origin of the force field. The Jacobian
434 // determines how the force changes in different directions
435 // away from the origin (generalizing spring forces of different
436 // magnitudes that constrain the Phantom to the point of the
437 // origin, to a line containing the origin, or to a plane
438 // containing the origin).
439 force = m_addforce;
440 for (i=0; i<3; ++i) {
441 for (j=0; j<3; ++j) {
442 force[i] += offset[j]*m_jacobian[i][j];
443 }
444 }
445 }
446 return force;
447 }
448
449protected:
450 bool m_active;
451 double m_time;
452 double m_cutoff;
453 d_vector m_origin;
454 d_vector m_addforce;
455 double m_jacobian[3][3];
456 double m_newcut;
457 d_vector m_neworig;
458 d_vector m_newadd;
459 double m_newjacob[3][3];
460 double m_damping;
461};
462
464static int VRPN_CALLBACK handle_forcefield_change_message(void *userdata, vrpn_HANDLERPARAM p)
465{
466 vrpn_Tracker_NovintFalcon *dev = (vrpn_Tracker_NovintFalcon *)userdata;
467 dev->update_forcefield_effect(p);
468 return 0;
469}
470
472class vrpn_NovintFalcon_ForceObjects {
473public:
474 vrpn_vector<ForceFieldEffect*> m_FFEffects;
475
476protected:
477 d_vector m_curforce; //< collected force value
478 d_vector m_curpos; //< position for force calculation
479 d_vector m_curvel; //< velocity for force calculation
480
481public:
483 vrpn_NovintFalcon_ForceObjects() {
484 m_curforce.fill(0.0);
485 m_curpos.fill(0.0);
486 };
488 ~vrpn_NovintFalcon_ForceObjects() {};
489public:
491 d_vector getObjForce(vrpn_float64 *pos, vrpn_float64 *vel) {
492 int i;
493
494 for (i=0; i<3; ++i) {
495 m_curforce[i]=0.0;
496 m_curpos[i]=pos[i];
497 m_curvel[i]=vel[i];
498 }
499
500 // force field objects
501 int nobj = m_FFEffects.size();
502 for (i=0; i<nobj; ++i) {
503 m_curforce = m_curforce + m_FFEffects[i]->calcForce (m_curpos);
504 }
505 return m_curforce;
506 };
507};
508
510vrpn_Tracker_NovintFalcon::vrpn_Tracker_NovintFalcon(const char *name,
512 const int devidx,
513 const char *grip,
514 const char *kine,
515 const char *damp)
516 : vrpn_Tracker(name, c), vrpn_Button_Filter(name, c),
517 vrpn_ForceDevice(name, c), m_dev(NULL), m_obj(NULL), m_update_rate(1000.0), m_damp(0.9)
518{
519 m_devflags=vrpn_NovintFalcon_Device::MASK_DEVICEIDX & devidx;
520 if (grip != NULL) {
521 if (0 == strcmp(grip,"4-button")) {
522 m_devflags |= vrpn_NovintFalcon_Device::GRIP_FOURBUTTON;
524 } else {
525 fprintf(stderr, "WARNING: Unknown grip for Novint Falcon #%d: %s \n", devidx, grip);
526 m_devflags = -1;
527 return;
528 }
529 }
530
531 if (kine != NULL) {
532 if (0 == strcmp(kine,"stamper")) {
533 m_devflags |= vrpn_NovintFalcon_Device::KINE_STAMPER;
534 } else {
535 fprintf(stderr, "WARNING: Unknown kinematic model for Novint Falcon #%d: %s \n", devidx, kine);
536 m_devflags = -1;
537 return;
538 }
539 }
540
541 if (damp != NULL) {
542 vrpn_float64 val= atof(damp);
543 if (val >= 1.0 && val <= 10000.0) {
544 m_damp = 1.0 - 1.0/val;
545 } else {
546 fprintf(stderr, "WARNING: Ignoring illegal force effect damping factor: %g \n", val);
547 }
548 }
549 clear_values();
550
551 if (register_autodeleted_handler(forcefield_message_id,
552 handle_forcefield_change_message, this, vrpn_ForceDevice::d_sender_id)) {
553 fprintf(stderr,"vrpn_Tracker_NovintFalcon:can't register force handler\n");
554 return;
555 }
556 vrpn_gettimeofday(&m_timestamp, NULL);
557 status = vrpn_TRACKER_RESETTING;
558}
559
560void vrpn_Tracker_NovintFalcon::clear_values()
561{
562 // nothing to do
563 if (m_devflags < 0) return;
564
565 int i;
566 for (i=0; i <vrpn_Button::num_buttons; i++)
568
569 if (m_obj) {
570 try {
571 delete m_obj;
572 } catch (...) {
573 fprintf(stderr, "vrpn_Tracker_NovintFalcon::clear_values(): delete failed\n");
574 return;
575 }
576 }
577 try { m_obj = new vrpn_NovintFalcon_ForceObjects; }
578 catch (...) { m_obj = NULL; return; }
579
580 // add dummy effect object
581 ForceFieldEffect *ffe;
582 try { ffe = new ForceFieldEffect; }
583 catch (...) { return; }
584 ffe->setDamping(m_damp);
585 ffe->stop();
586 m_obj->m_FFEffects.push_back(ffe);
587}
588
589vrpn_Tracker_NovintFalcon::~vrpn_Tracker_NovintFalcon()
590{
591 try {
592 if (m_dev) delete m_dev;
593 if (m_obj) delete m_obj;
594 } catch (...) {
595 fprintf(stderr, "vrpn_Tracker_NovintFalcon::~vrpn_Tracker_NovintFalcon(): delete failed\n");
596 return;
597 }
598}
599
600void vrpn_Tracker_NovintFalcon::reset()
601{
602
603 // nothing to do
604 if (m_devflags < 0) return;
605
606 int ret, i;
607 clear_values();
608
609 fprintf(stderr, "Resetting the NovintFalcon #%d\n",
610 vrpn_NovintFalcon_Device::MASK_DEVICEIDX & m_devflags);
611
612 if (m_dev) {
613 try {
614 delete m_dev;
615 } catch (...) {
616 fprintf(stderr, "vrpn_Tracker_NovintFalcon::reset(): delete failed\n");
617 return;
618 }
619 }
620
621 try { m_dev = new vrpn_NovintFalcon_Device(m_devflags); }
622 catch (...) {
623#ifdef VERBOSE
624 fprintf(stderr, "Device constructor failed!\n");
625#endif
626 status = vrpn_TRACKER_FAIL;
627 m_dev = NULL;
628 return;
629 }
630
631 if (!m_dev->init()) {
632#ifdef VERBOSE
633 fprintf(stderr, "Device init failed!\n");
634#endif
635 status = vrpn_TRACKER_FAIL;
636 return;
637 }
638
639 fprintf(stderr, "Reset Completed.\n");
640 status = vrpn_TRACKER_SYNCING; // We're trying for a new reading
641}
642
643int vrpn_Tracker_NovintFalcon::get_report(void)
644{
645 if (!m_dev)
646 return 0;
647
648 if (status == vrpn_TRACKER_SYNCING) {
649 if (m_dev->get_status(pos, vel, d_quat, vel_quat, &vel_quat_dt, buttons)) {
650 // if all buttons are pressed. we force a reset.
651 int i,j;
652 j=0;
653 for (i=0; i < num_buttons; i++)
654 j += buttons[i];
655 // all buttons pressed
656 if (j == num_buttons) {
657 status = vrpn_TRACKER_FAIL;
658 return 0;
659 }
660 } else {
661 status = vrpn_TRACKER_FAIL;
662 return 0;
663 }
664 }
665 status = vrpn_TRACKER_SYNCING;
666
667#ifdef VERBOSE2
668 print_latest_report();
669#endif
670
671 return 1;
672}
673
674void vrpn_Tracker_NovintFalcon::send_report(void)
675{
676 if (d_connection) {
677 char msgbuf[1000];
678 int len = vrpn_Tracker::encode_to(msgbuf);
679 if (d_connection->pack_message(len, m_timestamp, position_m_id, d_sender_id, msgbuf,
681 }
682 len = vrpn_Tracker::encode_vel_to(msgbuf);
683 if (d_connection->pack_message(len, m_timestamp, velocity_m_id, d_sender_id, msgbuf,
685 }
686 }
687}
688
689void vrpn_Tracker_NovintFalcon::handle_forces(void)
690{
691 if (!m_dev) return;
692 if (!m_obj) return;
693
694 // we have just updated our published position and can use that
695 d_vector force= m_obj->getObjForce(pos,vel);
696 m_dev->set_force(force);
697}
698
699
700int vrpn_Tracker_NovintFalcon::update_forcefield_effect(vrpn_HANDLERPARAM p)
701{
702 if (!m_obj) return 1;
703
704 vrpn_float32 center[3];
705 vrpn_float32 force[3];
706 vrpn_float32 jacobian[3][3];
707 vrpn_float32 radius;
708
709 decode_forcefield(p.buffer, p.payload_len, center, force, jacobian, &radius);
710 // XXX: only one force field effect. sufficient for VMD.
711 // we have just updated our published position and can use that
712 m_obj->m_FFEffects[0]->start();
713 m_obj->m_FFEffects[0]->setForce(center, force, jacobian, radius);
714 return 0;
715}
716
717
718void vrpn_Tracker_NovintFalcon::mainloop()
719{
720 struct timeval current_time;
721 server_mainloop();
722
723 // no need to report more often than we can poll the device
724 vrpn_gettimeofday(&current_time, NULL);
725 if ( timediff(current_time, m_timestamp) >= 1000000.0/m_update_rate) {
726
727 // Update the time
728 m_timestamp.tv_sec = current_time.tv_sec;
729 m_timestamp.tv_usec = current_time.tv_usec;
730 switch(status)
731 {
735 if (get_report()) {
736 send_report();
738 handle_forces();
739 }
740 break;
742 reset();
743 break;
744
746 break;
747
748 default:
749 fprintf(stderr, "NovintFalcon #%d , unknown status message: %d)\n",
750 vrpn_NovintFalcon_Device::MASK_DEVICEIDX & m_devflags, status);
751 break;
752 }
753 }
754}
755
756#endif
vrpn_int32 d_sender_id
Sender ID registered with the connection.
All button servers should derive from this class, which provides the ability to turn any of the butto...
Definition vrpn_Button.h:66
vrpn_int32 num_buttons
Definition vrpn_Button.h:48
virtual void report_changes(void)
unsigned char lastbuttons[vrpn_BUTTON_MAX_BUTTONS]
Definition vrpn_Button.h:46
unsigned char buttons[vrpn_BUTTON_MAX_BUTTONS]
Definition vrpn_Button.h:45
Generic connection class not specific to the transport mechanism.
virtual int encode_to(char *buf)
virtual int encode_vel_to(char *buf)
size_type size() const
This structure is what is passed to a vrpn_Connection message callback.
const char * buffer
#define VRPN_CALLBACK
const vrpn_uint32 vrpn_CONNECTION_LOW_LATENCY
#define vrpn_gettimeofday
const int vrpn_TRACKER_FAIL
const int vrpn_TRACKER_RESETTING
const int vrpn_TRACKER_SYNCING
const int vrpn_TRACKER_PARTIAL
const int vrpn_TRACKER_AWAITING_STATION