#include <RobotAPI/components/units/TCPControlUnit.h>
|
void | applyDOFWeightsToJacobian (Eigen::MatrixXf &Jacobian) |
|
void | applyTCPWeights (Eigen::MatrixXf &invJacobian) |
|
void | applyTCPWeights (VirtualRobot::RobotNodePtr tcp, Eigen::MatrixXf &partJacobian) |
|
Eigen::MatrixXf | calcFullJacobian () |
|
void | clearGoals () |
|
Eigen::VectorXf | computeStep (float stepSize) override |
|
Eigen::VectorXf | computeStepIndependently (float stepSize) |
|
bool | computeSteps (Eigen::VectorXf &resultJointDelta, float stepSize=1.f, float mininumChange=0.01f, int maxNStep=50, ComputeFunction computeFunction=&DifferentialIK::computeStep) |
|
bool | computeSteps (float stepSize=1.f, float mininumChange=0.01f, int maxNStep=50) override |
|
| EDifferentialIK (VirtualRobot::RobotNodeSetPtr rns, VirtualRobot::RobotNodePtr coordSystem=VirtualRobot::RobotNodePtr(), VirtualRobot::JacobiProvider::InverseJacobiMethod invJacMethod=eSVD) |
|
int | getJacobianRows () |
|
VirtualRobot::RobotNodePtr | getRefFrame () |
|
float | getWeightedError () |
|
float | getWeightedErrorPosition (VirtualRobot::SceneObjectPtr tcp) |
|
void | setDOFWeights (Eigen::VectorXf dofWeights) |
|
void | setGoal (const Eigen::Matrix4f &goal, VirtualRobot::RobotNodePtr tcp, VirtualRobot::IKSolver::CartesianSelection mode, float tolerancePosition, float toleranceRotation, Eigen::VectorXf tcpWeight) |
|
void | setRefFrame (VirtualRobot::RobotNodePtr coordSystem) |
|
bool | solveIK (float stepSize=1, float minChange=0.01f, int maxSteps=50, bool useAlternativeOnFail=false) |
|
SpamFilterDataPtr | deactivateSpam (float deactivationDurationSec=10.0f, const std::string &identifier="", bool deactivate=true) const |
| disables the logging for the current line for the given amount of seconds. More...
|
|
MessageTypeT | getEffectiveLoggingLevel () const |
|
| Logging () |
|
void | setLocalMinimumLoggingLevel (MessageTypeT level) |
| With setLocalMinimumLoggingLevel the minimum verbosity-level of log-messages can be set. More...
|
|
void | setTag (const LogTag &tag) |
|
void | setTag (const std::string &tagName) |
|
virtual | ~Logging () |
|
Definition at line 238 of file TCPControlUnit.h.
◆ ComputeFunction
typedef Eigen::VectorXf(EDifferentialIK::* ComputeFunction(float) |
◆ EDifferentialIK()
EDifferentialIK |
( |
VirtualRobot::RobotNodeSetPtr |
rns, |
|
|
VirtualRobot::RobotNodePtr |
coordSystem = VirtualRobot::RobotNodePtr() , |
|
|
VirtualRobot::JacobiProvider::InverseJacobiMethod |
invJacMethod = eSVD |
|
) |
| |
◆ adjustDOFWeightsToJointLimits()
bool adjustDOFWeightsToJointLimits |
( |
const Eigen::VectorXf & |
plannedJointDeltas | ) |
|
|
protected |
◆ applyDOFWeightsToJacobian()
void applyDOFWeightsToJacobian |
( |
Eigen::MatrixXf & |
Jacobian | ) |
|
◆ applyTCPWeights() [1/2]
void applyTCPWeights |
( |
Eigen::MatrixXf & |
invJacobian | ) |
|
◆ applyTCPWeights() [2/2]
void applyTCPWeights |
( |
VirtualRobot::RobotNodePtr |
tcp, |
|
|
Eigen::MatrixXf & |
partJacobian |
|
) |
| |
◆ calcFullJacobian()
Eigen::MatrixXf calcFullJacobian |
( |
| ) |
|
◆ clearGoals()
◆ computeStep()
VectorXf computeStep |
( |
float |
stepSize | ) |
|
|
override |
◆ computeStepIndependently()
VectorXf computeStepIndependently |
( |
float |
stepSize | ) |
|
◆ computeSteps() [1/2]
bool computeSteps |
( |
Eigen::VectorXf & |
resultJointDelta, |
|
|
float |
stepSize = 1.f , |
|
|
float |
mininumChange = 0.01f , |
|
|
int |
maxNStep = 50 , |
|
|
ComputeFunction |
computeFunction = &DifferentialIK::computeStep |
|
) |
| |
◆ computeSteps() [2/2]
bool computeSteps |
( |
float |
stepSize = 1.f , |
|
|
float |
mininumChange = 0.01f , |
|
|
int |
maxNStep = 50 |
|
) |
| |
|
override |
◆ getJacobianRows()
◆ getRefFrame()
VirtualRobot::RobotNodePtr getRefFrame |
( |
| ) |
|
|
inline |
◆ getWeightedError()
float getWeightedError |
( |
| ) |
|
◆ getWeightedErrorPosition()
float getWeightedErrorPosition |
( |
VirtualRobot::SceneObjectPtr |
tcp | ) |
|
◆ setDOFWeights()
void setDOFWeights |
( |
Eigen::VectorXf |
dofWeights | ) |
|
◆ setGoal()
void setGoal |
( |
const Eigen::Matrix4f & |
goal, |
|
|
VirtualRobot::RobotNodePtr |
tcp, |
|
|
VirtualRobot::IKSolver::CartesianSelection |
mode, |
|
|
float |
tolerancePosition, |
|
|
float |
toleranceRotation, |
|
|
Eigen::VectorXf |
tcpWeight |
|
) |
| |
◆ setRefFrame()
void setRefFrame |
( |
VirtualRobot::RobotNodePtr |
coordSystem | ) |
|
◆ solveIK()
bool solveIK |
( |
float |
stepSize = 1 , |
|
|
float |
minChange = 0.01f , |
|
|
int |
maxSteps = 50 , |
|
|
bool |
useAlternativeOnFail = false |
|
) |
| |
◆ dofWeights
Eigen::VectorXf dofWeights |
|
protected |
◆ tcpWeights
std::map<VirtualRobot:: SceneObjectPtr, Eigen::VectorXf> tcpWeights |
|
protected |
◆ tcpWeightVec
Eigen::VectorXf tcpWeightVec |
|
protected |
The documentation for this class was generated from the following files: