#include <VrepVFController.hpp>
Public Types | |
typedef std::tuple< std::string,std::string > | Params |
typedef grl::InverseKinematicsController | parent_type |
enum | VrepVFControllerParamsIndex { DesiredKinematicsObjectName, IKGroupName } |
Public Types inherited from grl::InverseKinematicsController | |
enum | GrlVFControllerParamsIndex { currentKinematicsName, desiredKinematicsName, followVFName, followVFNumRows, jointVelocityLimitsVFName, JointVelocityLimitsVFNumRows, JointPositionVFName, JointPositionNumRows } |
typedef std::tuple< std::string,std::string,std::string,std::size_t,std::string,std::size_t,std::string,std::size_t > | Params |
typedef mtsVFController | parent_type |
Public Member Functions | |
void | construct (Params params=defaultParams()) |
void | run_one () |
void | solve () |
void | updateKinematics () |
check out sawConstraintController More... | |
VrepInverseKinematicsController (size_t num_joints=7, mtsVFBase::CONTROLLERMODE cm=mtsVFBase::CONTROLLERMODE::JPOS) | |
Public Member Functions inherited from grl::InverseKinematicsController | |
void | construct () |
Params | defaultParams () |
InverseKinematicsController (size_t num_joints, mtsVFBase::CONTROLLERMODE cm) | |
InverseKinematicsController () | |
Static Public Member Functions | |
static Params | defaultParams () |
Public Attributes | |
vrep::VrepRobotArmDriver::State | currentArmState_ |
int | ikGroupHandle_ |
std::vector< int > | jointHandles_ |
std::string | positionLimitsName |
std::string | velocityLimitsName |
std::shared_ptr< vrep::VrepRobotArmDriver > | VrepRobotArmDriverP_ |
Public Attributes inherited from grl::InverseKinematicsController | |
std::unique_ptr< prmKinematicsState > | currentKinematicsStateP_ |
This will hold the Jacobian. More... | |
std::unique_ptr< prmKinematicsState > | desiredKinematicsStateP_ |
This will hold the xyz position and the rotation of where I want to go. More... | |
std::unique_ptr< mtsVFDataBase > | followVFP_ |
std::unique_ptr< mtsVFDataJointLimits > | jointPositionLimitsVFP_ |
joints cannot go to certain position More... | |
std::unique_ptr< mtsVFDataJointLimits > | jointVelocityLimitsVFP_ |
need velocity limits for the joints More... | |
Additional Inherited Members | |
Static Public Attributes inherited from grl::InverseKinematicsController | |
static const std::size_t | totalRows = 7 |
Definition at line 31 of file VrepVFController.hpp.
typedef std::tuple< std::string ,std::string > grl::VrepInverseKinematicsController::Params |
Definition at line 47 of file VrepVFController.hpp.
Definition at line 34 of file VrepVFController.hpp.
Enumerator | |
---|---|
DesiredKinematicsObjectName | |
IKGroupName |
Definition at line 39 of file VrepVFController.hpp.
|
inline |
Constructor
Definition at line 57 of file VrepVFController.hpp.
|
inline |
Definition at line 62 of file VrepVFController.hpp.
|
inlinestatic |
Definition at line 49 of file VrepVFController.hpp.
|
inline |
may not need this it is in the base class blocking call, call in separate thread, just allocates memory
Definition at line 292 of file VrepVFController.hpp.
|
inline |
may not need this it is in the base class this will have output blocking call, call in separate thread, just allocates memory this runs the actual optimization algorithm
Definition at line 302 of file VrepVFController.hpp.
|
inline |
check out sawConstraintController
The row/column major order is swapped between cisst and VREP!
Definition at line 140 of file VrepVFController.hpp.
vrep::VrepRobotArmDriver::State grl::VrepInverseKinematicsController::currentArmState_ |
Definition at line 309 of file VrepVFController.hpp.
int grl::VrepInverseKinematicsController::ikGroupHandle_ |
Definition at line 307 of file VrepVFController.hpp.
std::vector<int> grl::VrepInverseKinematicsController::jointHandles_ |
Definition at line 306 of file VrepVFController.hpp.
std::string grl::VrepInverseKinematicsController::positionLimitsName |
Definition at line 310 of file VrepVFController.hpp.
std::string grl::VrepInverseKinematicsController::velocityLimitsName |
Definition at line 311 of file VrepVFController.hpp.
std::shared_ptr<vrep::VrepRobotArmDriver> grl::VrepInverseKinematicsController::VrepRobotArmDriverP_ |
Definition at line 308 of file VrepVFController.hpp.