Skip to content
Snippets Groups Projects
Commit 6dbb9a6a authored by Andrew Wilson's avatar Andrew Wilson :elephant:
Browse files

STYLE: Uncrustify

parent 594d7fc8
No related branches found
No related tags found
No related merge requests found
Showing
with 208 additions and 208 deletions
......@@ -53,7 +53,7 @@ main()
imstkNew<Scene> scene("CameraController");
// Device Server
imstkNew<HapticDeviceManager> server;
imstkNew<HapticDeviceManager> server;
std::shared_ptr<HapticDeviceClient> client = server->makeDeviceClient();
// Load Mesh
......
......@@ -492,14 +492,14 @@ main()
// Add an extra control
connect<KeyPressEvent>(viewer->getKeyboardDevice(), EventType::KeyEvent,
[&](KeyPressEvent* e)
{
if (e->m_key == 'b' && e->m_keyPressType == KEY_PRESS)
{
if (e->m_key == 'b' && e->m_keyPressType == KEY_PRESS)
for (auto& dir : dirs)
{
for (auto& dir : dirs)
{
dir = -dir;
}
dir = -dir;
}
}
});
}
......
......@@ -139,8 +139,8 @@ main()
// Rotate after every scene update
connect<Event>(sceneManager, EventType::PostUpdate,
[&](Event*)
{
surfaceMesh->rotate(Vec3d(1.0, 0.0, 0.0), PI * scene->getElapsedTime(), Geometry::TransformType::ApplyToData);
{
surfaceMesh->rotate(Vec3d(1.0, 0.0, 0.0), PI * scene->getElapsedTime(), Geometry::TransformType::ApplyToData);
});
// Add mouse and keyboard controls to the viewer
......
......@@ -308,29 +308,29 @@ testMultipleScenesInRenderMode()
connect<KeyPressEvent>(viewer->getKeyboardDevice(), EventType::KeyEvent,
[&, driver](KeyPressEvent* e)
{
if (e->m_keyPressType == KEY_PRESS)
{
if (e->m_keyPressType == KEY_PRESS)
if (e->m_key == 's' || e->m_key == 'S')
{
if (e->m_key == 's' || e->m_key == 'S')
if (sceneManager->getActiveScene() == scene1)
{
if (sceneManager->getActiveScene() == scene1)
{
LOG(INFO) << "Switching to scene2";
sceneManager->setActiveScene(scene2);
viewer->setActiveScene(scene2);
}
else
{
LOG(INFO) << "Switching to scene1";
sceneManager->setActiveScene(scene1);
viewer->setActiveScene(scene1);
}
LOG(INFO) << "Switching to scene2";
sceneManager->setActiveScene(scene2);
viewer->setActiveScene(scene2);
}
else if (e->m_key == 'q' || e->m_key == 'Q')
else
{
driver->requestStatus(ModuleDriverStopped);
LOG(INFO) << "Switching to scene1";
sceneManager->setActiveScene(scene1);
viewer->setActiveScene(scene1);
}
}
else if (e->m_key == 'q' || e->m_key == 'Q')
{
driver->requestStatus(ModuleDriverStopped);
}
}
});
driver->start();
......@@ -342,8 +342,8 @@ testMultipleScenesInBackgroundMode()
imstkNew<ConsoleModule> console;
imstkNew<SceneManager> sceneManager("SceneManager");
auto scene1 = createClothScene("clothScene");
auto scene2 = createSoftBodyScene("deformableBodyScene");
auto scene1 = createClothScene("clothScene");
auto scene2 = createSoftBodyScene("deformableBodyScene");
sceneManager->addScene(scene1);
sceneManager->addScene(scene2);
......
......@@ -236,8 +236,8 @@ main()
scene->getActiveCamera()->setPosition(cubeObj->getRigidBody()->getPosition() + dx);
});
connect<Event>(sceneManager, EventType::PostUpdate, [&](Event*)
{
cubeObj->getRigidBodyModel2()->getConfig()->m_dt = sceneManager->getDt();
{
cubeObj->getRigidBodyModel2()->getConfig()->m_dt = sceneManager->getDt();
});
driver->start();
......
......@@ -264,17 +264,17 @@ main()
Vec3d prevCubePos = rbdModel->getModelGeometry()->getTranslation();
connect<Event>(sceneManager, EventType::PostUpdate,
[&](Event*)
{
const Vec3d& devPos = controller->getPosition();
const Quatd& devQ = controller->getRotation();
rbdModel->getModelGeometry()->rotate(devQ);
auto cubeGeo = std::dynamic_pointer_cast<Cube>(cubeObj->getPhysicsGeometry());
const Vec3d cubePos = rbdModel->getModelGeometry()->getTranslation();
const Vec3d cubeVelocity = (cubePos - prevCubePos) / 2.0;
const Vec3d damp = -1000000 * cubeVelocity;
const Vec3d force = -1000 * (cubePos - devPos) + damp;
rbdModel->addForce(force, Vec3d(0.0, 0.0, 0.0));
prevCubePos = cubePos;
{
const Vec3d& devPos = controller->getPosition();
const Quatd& devQ = controller->getRotation();
rbdModel->getModelGeometry()->rotate(devQ);
auto cubeGeo = std::dynamic_pointer_cast<Cube>(cubeObj->getPhysicsGeometry());
const Vec3d cubePos = rbdModel->getModelGeometry()->getTranslation();
const Vec3d cubeVelocity = (cubePos - prevCubePos) / 2.0;
const Vec3d damp = -1000000 * cubeVelocity;
const Vec3d force = -1000 * (cubePos - devPos) + damp;
rbdModel->addForce(force, Vec3d(0.0, 0.0, 0.0));
prevCubePos = cubePos;
});
driver->start();
......
......@@ -127,14 +127,14 @@ main()
connect<KeyPressEvent>(viewer->getKeyboardDevice(), EventType::KeyEvent,
[&](KeyPressEvent* e)
{
if (e->m_keyPressType == KEY_PRESS)
{
if (e->m_keyPressType == KEY_PRESS)
if (e->m_key == 'b')
{
if (e->m_key == 'b')
{
viewer->getScreenCaptureUtility()->saveScreenShot();
}
viewer->getScreenCaptureUtility()->saveScreenShot();
}
}
});
}
......
......@@ -72,28 +72,28 @@ main()
StopWatch timer;
timer.start();
int currMatId = 0;
int prevMatId = -1;
auto updateFunc = [&](Event*)
{
prevMatId = currMatId;
currMatId = static_cast<int>(timer.getTimeElapsed() / 1000.0 / 2.0) % 25;
if (currMatId != prevMatId)
{
// Change view background to black every other frame
std::cout << "Displaying with volume material preset: " << currMatId << std::endl;
// Query for a volume material preset
std::shared_ptr<VolumeRenderMaterial> volumeMaterial = VolumeRenderMaterialPresets::getPreset(currMatId);
// Apply the preset to the visual object
volumeObj->getVisualModel(0)->setRenderMaterial(volumeMaterial);
std::ostringstream ss;
ss << "Volume Material Preset: " << imstk::VolumeRenderMaterialPresets::getPresetName(currMatId);
statusManager->setCustomStatus(ss.str());
}
};
int currMatId = 0;
int prevMatId = -1;
auto updateFunc = [&](Event*)
{
prevMatId = currMatId;
currMatId = static_cast<int>(timer.getTimeElapsed() / 1000.0 / 2.0) % 25;
if (currMatId != prevMatId)
{
// Change view background to black every other frame
std::cout << "Displaying with volume material preset: " << currMatId << std::endl;
// Query for a volume material preset
std::shared_ptr<VolumeRenderMaterial> volumeMaterial = VolumeRenderMaterialPresets::getPreset(currMatId);
// Apply the preset to the visual object
volumeObj->getVisualModel(0)->setRenderMaterial(volumeMaterial);
std::ostringstream ss;
ss << "Volume Material Preset: " << imstk::VolumeRenderMaterialPresets::getPresetName(currMatId);
statusManager->setCustomStatus(ss.str());
}
};
// Run the simulation
{
......
......@@ -80,7 +80,7 @@ ImplicitGeometryToPointSetCCD::computeCollisionData()
PositionDirectionCollisionDataElement elem;
elem.dirAtoB = -centralGrad(currPos).normalized(); // Contact Normal
elem.nodeIdx = static_cast<uint32_t>(idx);
elem.penetrationDepth = std::abs(currVal); // Could also reverse march in gradient direction
elem.penetrationDepth = std::abs(currVal); // Could also reverse march in gradient direction
elem.posB = currPos;
m_colData->PDColData.safeAppend(elem);
return; // No need to find an other root
......@@ -108,7 +108,7 @@ ImplicitGeometryToPointSetCCD::computeCollisionData()
PositionDirectionCollisionDataElement elem;
elem.dirAtoB = -centralGrad(contactPt).normalized(); // Contact Normal
//elem.dirAtoB = dir;
//elem.dirAtoB = dir;
elem.nodeIdx = static_cast<uint32_t>(idx);
elem.penetrationDepth = (contactPt - pt).norm();
elem.posB = contactPt;
......
......@@ -71,7 +71,7 @@ public:
///
/// \brief Unmask all points
///
///
void unmaskAllPoints() { m_ptIdMask.clear(); }
///
......
......@@ -36,77 +36,77 @@ namespace imstk
class Module : public EventObject
{
public:
///
/// \brief Currently 3 execution types are provided.
/// These inform the driver on how it should run
///
enum class ExecutionType
{
SEQUENTIAL, // Should run in sync with other sequential modules
PARALLEL, // Should run in parallel
ADAPTIVE // Runs governed by module
};
///
/// \brief Currently 3 execution types are provided.
/// These inform the driver on how it should run
///
enum class ExecutionType
{
SEQUENTIAL, // Should run in sync with other sequential modules
PARALLEL, // Should run in parallel
ADAPTIVE // Runs governed by module
};
public:
Module() = default;
virtual ~Module() override = default;
Module() = default;
virtual ~Module() override = default;
public:
///
/// \brief Get/Set the timestep
///
double getDt() const { return m_dt; }
void setDt(const double dt) { m_dt = dt; }
///
/// \brief Get/Set the timestep
///
double getDt() const { return m_dt; }
void setDt(const double dt) { m_dt = dt; }
///
/// \brief Get whether the module is initialized yet
///
bool getInit() const { return m_init; }
///
/// \brief Get whether the module is initialized yet
///
bool getInit() const { return m_init; }
///
/// \brief Get whether the module is currently paused
///
bool getPaused() const { return m_paused; }
///
/// \brief Get whether the module is currently paused
///
bool getPaused() const { return m_paused; }
ExecutionType getExecutionType() const { return m_executionType; }
void setExecutionType(ExecutionType type) { m_executionType = type; }
ExecutionType getExecutionType() const { return m_executionType; }
void setExecutionType(ExecutionType type) { m_executionType = type; }
void pause() { m_paused = true; }
void resume() { m_paused = false; }
void pause() { m_paused = true; }
void resume() { m_paused = false; }
public:
void init() { m_init = initModule(); }
void update()
{
if (m_init && !m_paused)
{
this->postEvent(Event(EventType::PreUpdate));
this->updateModule();
this->postEvent(Event(EventType::PostUpdate));
}
}
void uninit()
{
if (!m_init)
{
uninitModule();
m_init = false;
}
}
void init() { m_init = initModule(); }
void update()
{
if (m_init && !m_paused)
{
this->postEvent(Event(EventType::PreUpdate));
this->updateModule();
this->postEvent(Event(EventType::PostUpdate));
}
}
void uninit()
{
if (!m_init)
{
uninitModule();
m_init = false;
}
}
public:
virtual bool initModule() = 0;
virtual bool initModule() = 0;
virtual void updateModule() = 0;
virtual void updateModule() = 0;
virtual void uninitModule() { }
virtual void uninitModule() { }
protected:
bool m_init = false;
bool m_paused = false;
double m_dt = 0.0;
ExecutionType m_executionType = ExecutionType::PARALLEL; // Defaults to parallel, subclass and set
bool m_init = false;
bool m_paused = false;
double m_dt = 0.0;
ExecutionType m_executionType = ExecutionType::PARALLEL; // Defaults to parallel, subclass and set
};
}
\ No newline at end of file
......@@ -38,9 +38,9 @@ class Module;
///
/// \class ModuleDriver
///
///
/// \brief Defines the control of modules
///
///
class ModuleDriver : public EventObject
{
protected:
......@@ -53,7 +53,7 @@ public:
///
/// \brief Add a module to run
///
///
virtual void addModule(std::shared_ptr<Module> module)
{
m_modules.push_back(module);
......@@ -66,7 +66,7 @@ public:
///
/// \brief Wait for all modules to init
///
///
void waitForInit();
protected:
......
......@@ -36,41 +36,41 @@ namespace expiremental
///
struct RigidBody
{
public:
double m_mass = 1.0;
Mat3d m_intertiaTensor = Mat3d::Identity();
Vec3d m_initPos = Vec3d(0.0, 0.0, 0.0);
Quatd m_initOrientation = Quatd(1.0, 0.0, 0.0, 0.0);
Vec3d m_initVelocity = Vec3d(0.0, 0.0, 0.0);
Vec3d m_initAngularVelocity = Vec3d(0.0, 0.0, 0.0);
Vec3d m_initForce = Vec3d(0.0, 0.0, 0.0);
Vec3d m_initTorque = Vec3d(0.0, 0.0, 0.0);
bool m_isStatic = false;
Vec3d m_prevForce = Vec3d(0.0, 0.0, 0.0);
// Vec3d m_externalForce;
//RigidBodyState2* m_state; // A RigidBody can only belong to one state
Vec3d* m_pos;
Quatd* m_orientation;
Vec3d* m_velocity;
Vec3d* m_angularVelocity;
Vec3d* m_force;
Vec3d* m_torque;
public:
const Vec3d& getPosition() const { return *m_pos; }
const Quatd& getOrientation() const { return *m_orientation; }
const Vec3d& getVelocity() const { return *m_velocity; }
const Vec3d& getAngularVelocity() const { return *m_angularVelocity; }
const Vec3d& getForce() const { return *m_force; }
const Vec3d& getTorque() const { return *m_torque; }
///
/// \brief Convience function to set the inertia tensor based off provided geometry
/// assuming uniform mass at each point.
///
void setInertiaFromPointSet(std::shared_ptr<PointSet> pointset, const double scale = 1.0, const bool useBoundingBoxOrigin = true);
public:
double m_mass = 1.0;
Mat3d m_intertiaTensor = Mat3d::Identity();
Vec3d m_initPos = Vec3d(0.0, 0.0, 0.0);
Quatd m_initOrientation = Quatd(1.0, 0.0, 0.0, 0.0);
Vec3d m_initVelocity = Vec3d(0.0, 0.0, 0.0);
Vec3d m_initAngularVelocity = Vec3d(0.0, 0.0, 0.0);
Vec3d m_initForce = Vec3d(0.0, 0.0, 0.0);
Vec3d m_initTorque = Vec3d(0.0, 0.0, 0.0);
bool m_isStatic = false;
Vec3d m_prevForce = Vec3d(0.0, 0.0, 0.0);
// Vec3d m_externalForce;
//RigidBodyState2* m_state; // A RigidBody can only belong to one state
Vec3d* m_pos;
Quatd* m_orientation;
Vec3d* m_velocity;
Vec3d* m_angularVelocity;
Vec3d* m_force;
Vec3d* m_torque;
public:
const Vec3d& getPosition() const { return *m_pos; }
const Quatd& getOrientation() const { return *m_orientation; }
const Vec3d& getVelocity() const { return *m_velocity; }
const Vec3d& getAngularVelocity() const { return *m_angularVelocity; }
const Vec3d& getForce() const { return *m_force; }
const Vec3d& getTorque() const { return *m_torque; }
///
/// \brief Convience function to set the inertia tensor based off provided geometry
/// assuming uniform mass at each point.
///
void setInertiaFromPointSet(std::shared_ptr<PointSet> pointset, const double scale = 1.0, const bool useBoundingBoxOrigin = true);
};
///
......
......@@ -69,15 +69,15 @@ RigidObjectController::update(const double dt)
if (m_deviceClient->getTrackingEnabled() && m_useSpring)
{
const Vec3d& currPos = m_rigidObject->getRigidBody()->getPosition();
const Quatd& currOrientation = m_rigidObject->getRigidBody()->getOrientation();
const Vec3d& currVelocity = m_rigidObject->getRigidBody()->getVelocity();
const Quatd& currOrientation = m_rigidObject->getRigidBody()->getOrientation();
const Vec3d& currVelocity = m_rigidObject->getRigidBody()->getVelocity();
const Vec3d& currAngularVelocity = m_rigidObject->getRigidBody()->getAngularVelocity();
Vec3d& currForce = *m_rigidObject->getRigidBody()->m_force;
Vec3d& currTorque = *m_rigidObject->getRigidBody()->m_torque;
Vec3d& currForce = *m_rigidObject->getRigidBody()->m_force;
Vec3d& currTorque = *m_rigidObject->getRigidBody()->m_torque;
const Vec3d& devicePos = getPosition();
const Quatd& deviceOrientation = getRotation();
const Vec3d& deviceVelocity = getVelocity();
const Quatd& deviceOrientation = getRotation();
const Vec3d& deviceVelocity = getVelocity();
const Vec3d& deviceAngularVelocity = getAngularVelocity();
const Vec3d& deviceOffset = Vec3d(0.0, 0.0, 0.0);
......@@ -88,10 +88,10 @@ RigidObjectController::update(const double dt)
//printf("Device velocity %f, %f, %f\n", deviceVelocity[0], deviceVelocity[1], deviceVelocity[2]);
const Quatd dq = deviceOrientation * currOrientation.inverse();
const Rotd angleAxes = Rotd(dq);
const Rotd angleAxes = Rotd(dq);
tS = deviceOffset.cross(fS) + m_angularKs.cwiseProduct(angleAxes.axis() * angleAxes.angle()) + m_angularKd * -currAngularVelocity;
currForce += fS;
currForce += fS;
currTorque += tS;
}
// Uses relative force
......@@ -114,7 +114,7 @@ RigidObjectController::update(const double dt)
else
{
// Zero out external force/torque
*m_rigidObject->getRigidBody()->m_force = Vec3d(0.0, 0.0, 0.0);
*m_rigidObject->getRigidBody()->m_force = Vec3d(0.0, 0.0, 0.0);
*m_rigidObject->getRigidBody()->m_torque = Vec3d(0.0, 0.0, 0.0);
// Directly set position/rotation
(*m_rigidObject->getRigidBody()->m_pos) = getPosition();
......
......@@ -81,13 +81,13 @@ public:
///
/// \brief Set/Get the scaling of the force on the device, set to 0 for no force
///
///
double getForceScaling() const { return m_forceScaling; }
void setForceScaling(const double forceScaling) { m_forceScaling = forceScaling; }
///
/// \brief Set/Get whether to use spring or not
///
///
bool getUseSpring() const { return m_useSpring; }
void setUseSpring(const bool useSpring) { m_useSpring = useSpring; }
......@@ -106,7 +106,7 @@ protected:
std::shared_ptr<RigidObject2> m_rigidObject;
double m_linearKd = 10000.0; ///> Damping coefficient, linear
double m_angularKd = 300.0; ///> Damping coefficient, rotational
double m_angularKd = 300.0; ///> Damping coefficient, rotational
Vec3d m_linearKs = Vec3d(8000000.0, 8000000.0, 8000000.0); ///> Spring coefficient, linear
Vec3d m_angularKs = Vec3d(10000.0, 10000.0, 10000.0); ///> Spring coefficient, rotational
......@@ -114,7 +114,7 @@ protected:
Vec3d tS = Vec3d(0.0, 0.0, 0.0);
double m_forceScaling = 0.0000075;
bool m_useSpring = true; ///> Controller has ability to toggle to from springs
bool m_useSpring = true; ///> Controller has ability to toggle to from springs
};
}
}
......@@ -55,39 +55,39 @@ TrackingDeviceControl::updateTrackingData(const double dt)
const Quatd prevOrientation = m_currentOrientation;
m_currentPos = m_deviceClient->getPosition();
m_currentOrientation = m_deviceClient->getOrientation();
m_currentVelocity = m_deviceClient->getVelocity();
m_currentOrientation = m_deviceClient->getOrientation();
m_currentVelocity = m_deviceClient->getVelocity();
m_currentAngularVelocity = m_deviceClient->getAngularVelocity();
// Apply inverse if needed
if (m_invertFlags & InvertFlag::transX)
{
m_currentPos[0] = -m_currentPos[0];
m_currentPos[0] = -m_currentPos[0];
m_currentVelocity[0] = -m_currentVelocity[0];
}
if (m_invertFlags & InvertFlag::transY)
{
m_currentPos[1] = -m_currentPos[1];
m_currentPos[1] = -m_currentPos[1];
m_currentVelocity[1] = -m_currentVelocity[1];
}
if (m_invertFlags & InvertFlag::transZ)
{
m_currentPos[2] = -m_currentPos[2];
m_currentPos[2] = -m_currentPos[2];
m_currentVelocity[2] = -m_currentVelocity[2];
}
if (m_invertFlags & InvertFlag::rotX)
{
m_currentOrientation.x() = -m_currentOrientation.x();
m_currentOrientation.x() = -m_currentOrientation.x();
m_currentAngularVelocity[0] = -m_currentAngularVelocity[0];
}
if (m_invertFlags & InvertFlag::rotY)
{
m_currentOrientation.y() = -m_currentOrientation.y();
m_currentOrientation.y() = -m_currentOrientation.y();
m_currentAngularVelocity[1] = -m_currentAngularVelocity[1];
}
if (m_invertFlags & InvertFlag::rotZ)
{
m_currentOrientation.z() = -m_currentOrientation.z();
m_currentOrientation.z() = -m_currentOrientation.z();
m_currentAngularVelocity[2] = -m_currentAngularVelocity[2];
}
......@@ -102,13 +102,13 @@ TrackingDeviceControl::updateTrackingData(const double dt)
if (m_computeVelocity)
{
m_currentDisplacement = (m_currentPos - prevPos);
m_currentVelocity = m_currentDisplacement / dt;
m_currentVelocity = m_currentDisplacement / dt;
}
if (m_computeAngularVelocity)
{
m_currentRotation = prevOrientation * m_currentOrientation.inverse();
/* Rotd r = Rotd(m_currentRotation);
r.angle() /= timestepInfo.m_dt;*/
/* Rotd r = Rotd(m_currentRotation);
r.angle() /= timestepInfo.m_dt;*/
m_currentAngularVelocity = m_currentRotation.toRotationMatrix().eulerAngles(0, 1, 2) /= dt;
}
......
......@@ -92,26 +92,26 @@ public:
///
/// \brief Set/Get whether to compute the velocity from previous and current samples
/// Useful if a device does not provide the quantity
///
///
void setComputeVelocity(const bool computeVelocity) { m_computeVelocity = computeVelocity; }
bool getComputeVelocity() const { return m_computeVelocity; }
///
/// \brief Set/Get whether to compute the anular velocity from previous and current samples
/// Useful if the device does not provide the quantity
///
///
void setComputeAngularVelocity(const bool computeAngularVelocity) { m_computeAngularVelocity = computeAngularVelocity; }
bool getComputeAngularVelocity() const { return m_computeAngularVelocity; }
///
/// \brief Get/Set the angular velocity
///
///
const Vec3d& getAngularVelocity() const { return m_currentAngularVelocity; }
void setAngularVelocity(const Vec3d& angularVelocity) { m_currentAngularVelocity = angularVelocity; }
///
/// \brief Get/Set the linear velocity
///
///
const Vec3d& getVelocity() const { return m_currentVelocity; }
void setVelocity(const Vec3d& velocity) { m_currentVelocity = velocity; }
......@@ -141,7 +141,7 @@ public:
///
/// \brief Update tracking data
///
///
virtual bool updateTrackingData(const double dt);
protected:
......
......@@ -110,7 +110,7 @@ public:
///
/// \brief Get the device angular velocity
///
///
const Vec3d& getAngularVelocity() const;
///
......@@ -120,7 +120,7 @@ public:
///
/// \brief Get offset from position for device end effector
///
///
const Vec3d& getOffset() const { return m_endEffectorOffset; }
///
......@@ -152,19 +152,19 @@ public:
protected:
DeviceClient(const std::string& name, const std::string& ip);
std::string m_deviceName; ///< Device Name
std::string m_ip; ///< Connection device IP
std::string m_deviceName; ///< Device Name
std::string m_ip; ///< Connection device IP
bool m_trackingEnabled = true; ///< Tracking enabled if true
bool m_analogicEnabled = true; ///< Analogic enabled if true
bool m_buttonsEnabled = true; ///< Buttons enabled if true
bool m_forceEnabled = false; ///< Force enabled if true
bool m_trackingEnabled = true; ///< Tracking enabled if true
bool m_analogicEnabled = true; ///< Analogic enabled if true
bool m_buttonsEnabled = true; ///< Buttons enabled if true
bool m_forceEnabled = false; ///< Force enabled if true
Vec3d m_position; ///< Position of end effector
Vec3d m_velocity; ///< Linear velocity of end effector
Vec3d m_angularVelocity; ///< Angular velocity of the end effector
Quatd m_orientation; ///< Orientation of the end effector
Vec3d m_force; ///< Force vector
Vec3d m_position; ///< Position of end effector
Vec3d m_velocity; ///< Linear velocity of end effector
Vec3d m_angularVelocity; ///< Angular velocity of the end effector
Quatd m_orientation; ///< Orientation of the end effector
Vec3d m_force; ///< Force vector
Vec3d m_endEffectorOffset = Vec3d(0.0, 0.0, 0.0); ///> Offset from origin
std::unordered_map<int, int> m_buttons;
......
......@@ -38,7 +38,7 @@ HapticDeviceClient::initialize()
//flush error stack
HDErrorInfo errorFlush;
while (HD_DEVICE_ERROR(errorFlush = hdGetError())) {}
// Initialize the device
if (m_deviceName == "")
{
......
......@@ -150,7 +150,7 @@ protected:
std::vector<std::shared_ptr<RigidBody>> m_bodies;
std::unordered_map<RigidBody*, StorageIndex> m_locations;
bool m_modified = true;
Eigen::VectorXd F; // Reaction forces
};
}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment