cisst-saw
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
mtsVFController Class Reference

mtsVFController: A class that is responsible for managing the virtual fixtures, relevant state data, and the control optimizer More...

#include <mtsVFController.h>

Inheritance diagram for mtsVFController:
cmnGenericObject mtsIntuitiveResearchKitOptimizer

Public Member Functions

 mtsVFController ()
 
 mtsVFController (size_t num_joints, mtsVFBase::CONTROLLERMODE cm)
 
 ~mtsVFController ()
 
nmrConstraintOptimizer GetOptimizer ()
 
- Public Member Functions inherited from cmnGenericObject
virtual ~cmnGenericObject (void)
 
virtual const
cmnClassServicesBase
Services (void) const =0
 
bool ReconstructFrom (const cmnGenericObject &other)
 
std::string ToString (void) const
 
virtual void ToStream (std::ostream &outputStream) const
 
virtual void ToStreamRaw (std::ostream &outputStream, const char delimiter= ' ', bool headerOnly=false, const std::string &headerPrefix="") const
 
virtual bool FromStreamRaw (std::istream &inputStream, const char delimiter= ' ')
 
virtual void SerializeRaw (std::ostream &outputStream) const
 
virtual void DeSerializeRaw (std::istream &inputStream)
 
virtual cmnLogger::StreamBufTypeGetLogMultiplexer (void) const
 
virtual size_t ScalarNumber (void) const
 
virtual bool ScalarNumberIsFixed (void) const
 
virtual double Scalar (const size_t CMN_UNUSED(index)) const throw (std::out_of_range)
 
virtual std::string ScalarDescription (const size_t CMN_UNUSED(index), const std::string &CMN_UNUSED(userDescription)) const
 

Protected Member Functions

void AddVFJointVelocity (const mtsVFDataBase &vf)
 Adds/Updates a vf data object. More...
 
void AddVFJointPosition (const mtsVFDataBase &vf)
 Adds/Updates a vf data object. More...
 
void AddVFCartesianTranslation (const mtsVFDataBase &vf)
 Adds/Updates a vf data object. More...
 
void AddVFCartesianOrientation (const mtsVFDataBase &vf)
 Adds/Updates a vf data object. More...
 
void AddVFSensorCompliance (const mtsVFDataSensorCompliance &vf)
 Adds/Updates a vf data object. More...
 
void AddVFPlane (const mtsVFDataPlane &vf)
 Adds/Updates a vf plane object. More...
 
void AddVFFollowPath (const mtsVFDataBase &vf)
 
void SetSensor (const prmSensorState &sen)
 Adds/Updates a sensor to the map. More...
 
void SetSensorOffset (const prmOffsetState &sen)
 Adds/Updates a sensor to the map. More...
 
void RemoveSensorFromMap (const std::string &senName)
 Removes a sensor from the map. More...
 
void SetMode (const mtsVFBase::CONTROLLERMODE &m)
 Changes the variable the optimizer is solving for. More...
 
void LookupBaseData (void)
 Finds the "base" object for kinematics and sensor data that has an offset. More...
 
void SetKinematics (const prmKinematicsState &kin)
 Adds/Updates a kinematics object to the map. More...
 
void RemoveKinematicsFromMap (const std::string &kinName)
 Removes a kinematics object from the map. More...
 
void UpdateOptimizer (double TickTime)
 Updates the robot state data and control optimizer. More...
 
nmrConstraintOptimizer::STATUS Solve (vctDoubleVec &dq)
 Solves the constraint optimization problem and fills the result into the parameter. More...
 
void IncrementUsers (const std::vector< std::string > kin_names, const std::vector< std::string > sensor_names)
 Helper function that increments users of new vf. More...
 
void DecrementUsers (const std::vector< std::string > kin_names, const std::vector< std::string > sensor_names)
 Helper function that decrements users of new data in an old vf. More...
 
bool SetVFData (const mtsVFDataBase &data, const std::type_info &type)
 
bool SetVFDataSensorCompliance (const mtsVFDataSensorCompliance &data, const std::type_info &type)
 
bool SetVFDataPlane (const mtsVFDataPlane &data, const std::type_info &type)
 

Protected Attributes

std::map< std::string,
mtsVFBase * > 
VFMap
 
std::map< std::string,
prmKinematicsState * > 
Kinematics
 
std::map< std::string,
prmSensorState * > 
Sensors
 
prmJointState JointState
 
nmrConstraintOptimizer Optimizer
 
mtsVFBase::CONTROLLERMODE ControllerMode
 

Detailed Description

mtsVFController: A class that is responsible for managing the virtual fixtures, relevant state data, and the control optimizer

Constructor & Destructor Documentation

mtsVFController::mtsVFController ( )
inline

Constructor

mtsVFController::mtsVFController ( size_t  num_joints,
mtsVFBase::CONTROLLERMODE  cm 
)
inline

Constructor

mtsVFController::~mtsVFController ( )
inline

Member Function Documentation

void mtsVFController::AddVFCartesianOrientation ( const mtsVFDataBase &  vf)
protected

Adds/Updates a vf data object.

void mtsVFController::AddVFCartesianTranslation ( const mtsVFDataBase &  vf)
protected

Adds/Updates a vf data object.

void mtsVFController::AddVFFollowPath ( const mtsVFDataBase &  vf)
protected
void mtsVFController::AddVFJointPosition ( const mtsVFDataBase &  vf)
protected

Adds/Updates a vf data object.

void mtsVFController::AddVFJointVelocity ( const mtsVFDataBase &  vf)
protected

Adds/Updates a vf data object.

void mtsVFController::AddVFPlane ( const mtsVFDataPlane &  vf)
protected

Adds/Updates a vf plane object.

void mtsVFController::AddVFSensorCompliance ( const mtsVFDataSensorCompliance &  vf)
protected

Adds/Updates a vf data object.

void mtsVFController::DecrementUsers ( const std::vector< std::string >  kin_names,
const std::vector< std::string >  sensor_names 
)
protected

Helper function that decrements users of new data in an old vf.

nmrConstraintOptimizer mtsVFController::GetOptimizer ( )
inline
void mtsVFController::IncrementUsers ( const std::vector< std::string >  kin_names,
const std::vector< std::string >  sensor_names 
)
protected

Helper function that increments users of new vf.

void mtsVFController::LookupBaseData ( void  )
protected

Finds the "base" object for kinematics and sensor data that has an offset.

void mtsVFController::RemoveKinematicsFromMap ( const std::string &  kinName)
protected

Removes a kinematics object from the map.

void mtsVFController::RemoveSensorFromMap ( const std::string &  senName)
protected

Removes a sensor from the map.

void mtsVFController::SetKinematics ( const prmKinematicsState &  kin)
protected

Adds/Updates a kinematics object to the map.

void mtsVFController::SetMode ( const mtsVFBase::CONTROLLERMODE m)
protected

Changes the variable the optimizer is solving for.

void mtsVFController::SetSensor ( const prmSensorState &  sen)
protected

Adds/Updates a sensor to the map.

void mtsVFController::SetSensorOffset ( const prmOffsetState &  sen)
protected

Adds/Updates a sensor to the map.

bool mtsVFController::SetVFData ( const mtsVFDataBase &  data,
const std::type_info &  type 
)
protected
bool mtsVFController::SetVFDataPlane ( const mtsVFDataPlane &  data,
const std::type_info &  type 
)
protected
bool mtsVFController::SetVFDataSensorCompliance ( const mtsVFDataSensorCompliance &  data,
const std::type_info &  type 
)
protected
nmrConstraintOptimizer::STATUS mtsVFController::Solve ( vctDoubleVec dq)
protected

Solves the constraint optimization problem and fills the result into the parameter.

void mtsVFController::UpdateOptimizer ( double  TickTime)
protected

Updates the robot state data and control optimizer.

Member Data Documentation

mtsVFBase::CONTROLLERMODE mtsVFController::ControllerMode
protected
prmJointState mtsVFController::JointState
protected
std::map<std::string, prmKinematicsState *> mtsVFController::Kinematics
protected
nmrConstraintOptimizer mtsVFController::Optimizer
protected
std::map<std::string, prmSensorState *> mtsVFController::Sensors
protected
std::map<std::string, mtsVFBase *> mtsVFController::VFMap
protected

The documentation for this class was generated from the following file: