|
int | getHandle (const std::string ¶m) |
|
template<std::size_t I, typename Param > |
int | getHandleFromParam (const Param ¶ms_) |
|
template<std::size_t I, typename Params , typename OutputIterator > |
OutputIterator | getHandleFromParam (const Params params_, OutputIterator out) |
|
template<typename SinglePassRange , typename OutputIterator > |
OutputIterator | getHandles (const SinglePassRange inputRange, OutputIterator out) |
|
Eigen::MatrixXf | getJacobian (vrep::VrepRobotArmDriver &driver, bool jacobianOnly=false) |
| get the Jacobian as calculated by vrep in an Eigen::MatrixXf in column major format More...
|
|
std::vector< std::string > | jointToLink (const std::vector< std::string > &jointNames) |
|
std::vector< std::string > | jointToLinkRespondable (std::vector< std::string > jointNames) |
|
void | SetRBDynArmFromVrep (const std::vector< std::string > &vrepJointNames, const std::vector< int > &vrepJointHandles, const rbd::MultiBody &simArmMultiBody, rbd::MultiBodyConfig &simArmConfig, std::string debug="") |
|
void | SetVRepArmFromRBDyn (const std::vector< std::string > &vrepJointNames, const std::vector< int > &vrepJointHandles, const rbd::MultiBody &simArmMultiBody, const rbd::MultiBodyConfig &simArmConfig, std::string debug="") |
|
get the Jacobian as calculated by vrep in an Eigen::MatrixXf in column major format
- Parameters
-
driver | the vrep arm driver object that provides access to vrep simulation state for a specific arm |
jacobianOnly | true calls simComputeJacobian, false uses simCheckIKGroup which incidentally calculates the Jacobian |
The jacobianOnly option is provided because some irregularities were seen with simComputeJacobian (jacobianOnly == true). Thus (jacobianOnly == false) falls back on using the full vrep provided inverse kinematics calculation which is slower but didn't have the previously seen irregularities. The jacobianOnly option should be eliminated in favor of the simComputeJacobian (jacobianOnly == true) case once all issues are fully resolved.
- Returns
- jacobian in ColumnMajor format where each row is a joint from base to tip, first 3 columns are translation component, last 3 columns are rotation component
- Todo:
- get target position, probably relative to base
Run inverse kinematics, but all we really want is the jacobian
- See also
- http://www.coppeliarobotics.com/helpFiles/en/apiFunctions.htm#simCheckIkGroup
- Todo:
- do we need to use these options?
- See also
- http://www.coppeliarobotics.com/helpFiles/en/apiConstants.htm#ikCalculationResults
- Todo:
- FIX HACK jacobianSize include orientation component, should be 7x6 instead of 7x3
Definition at line 35 of file VrepRobotArmJacobian.hpp.