RobWorkProject
24.12.4-
|
Calculates the closed form inverse kinematics of a device using Piepers method. More...
#include <PieperSolver.hpp>
Inherits ClosedFormIK.
Public Types | |
typedef rw::core::Ptr< PieperSolver > | Ptr |
smart pointer type to this class | |
Public Types inherited from ClosedFormIK | |
typedef rw::core::Ptr< ClosedFormIK > | Ptr |
smart pointer type to this class | |
Public Types inherited from InvKinSolver | |
typedef rw::core::Ptr< InvKinSolver > | Ptr |
smart pointer type to this class | |
typedef rw::core::Ptr< const InvKinSolver > | CPtr |
smart pointer type to this const class | |
Public Member Functions | |
PieperSolver (const std::vector< rw::models::DHParameterSet > &dhparams, const rw::math::Transform3D< double > &joint6Tend, const rw::math::Transform3D< double > &baseTdhRef=rw::math::Transform3D<>::identity()) | |
Constructor. More... | |
PieperSolver (rw::models::SerialDevice &dev, const rw::math::Transform3D< double > &joint6Tend, const rw::kinematics::State &state) | |
Constructor - the DH parameters is expected to be on each joint in the serial device. When specifying the DH params in the workcell file this constructor can be used. More... | |
virtual std::vector< math::Q > | solve (const rw::math::Transform3D< double > &baseTend, const rw::kinematics::State &state) const |
Calculates the inverse kinematics. More... | |
virtual void | setCheckJointLimits (bool check) |
Specifies whether to check joint limits before returning a solution. More... | |
virtual rw::core::Ptr< const rw::kinematics::Frame > | getTCP () const |
Returns the Tool Center Point (TCP) used when solving the IK problem. More... | |
Public Member Functions inherited from ClosedFormIK | |
virtual | ~ClosedFormIK () |
Destructor. | |
Public Member Functions inherited from InvKinSolver | |
virtual | ~InvKinSolver () |
destructor | |
Additional Inherited Members | |
Static Public Member Functions inherited from ClosedFormIK | |
static ClosedFormIK::Ptr | make (const rw::models::Device &device, const rw::kinematics::State &state) |
Closed-form IK solver for a device. More... | |
Protected Member Functions inherited from ClosedFormIK | |
ClosedFormIK () | |
Constructor. | |
Calculates the closed form inverse kinematics of a device using Piepers method.
To use Piepers method it is required that the device has 6 DOF revolute joints, and that last three axis intersects. In this implementation it will be assumed that the that rotation of these last three axis are equivalent to an Euler ZYZ or Z(-Y)Z rotation.
See Introduction to Robotics Mechanics and Control, by John J. Craig for further information about the algorithm.
PieperSolver | ( | const std::vector< rw::models::DHParameterSet > & | dhparams, |
const rw::math::Transform3D< double > & | joint6Tend, | ||
const rw::math::Transform3D< double > & | baseTdhRef = rw::math::Transform3D<>::identity() |
||
) |
Constructor.
dhparams | [in] DH-parameters corresponding to the device |
joint6Tend | [in] transform from the 6th joint to the end of the device |
baseTdhRef | [in] Transformation between the robot base and the reference frame for the DH-parameters. |
PieperSolver | ( | rw::models::SerialDevice & | dev, |
const rw::math::Transform3D< double > & | joint6Tend, | ||
const rw::kinematics::State & | state | ||
) |
Constructor - the DH parameters is expected to be on each joint in the serial device. When specifying the DH params in the workcell file this constructor can be used.
dev | [in] the device for which to extract the DH parameters. |
joint6Tend | [in] transform from the 6th joint to the end of the device |
state | [in] State using which the transformation between robot base and the DH-parameters reference frame are calculated. |
|
virtual |
Returns the Tool Center Point (TCP) used when solving the IK problem.
Implements InvKinSolver.
|
virtual |
Specifies whether to check joint limits before returning a solution.
check | [in] If true the method should perform a check that joints are within bounds. |
Implements InvKinSolver.
|
virtual |
Calculates the inverse kinematics.
Given a desired \(\robabx{}{desired}{\mathbf{T}}\) and the current state, the method solves the inverse kinematics problem.
If the algorithm is able to identify multiple solutions (e.g. elbow up and down) it will return all of these. Before returning a solution, they may be checked to be within the bounds of the configuration space. (See setCheckJointLimits(bool) )
baseTend | [in] Desired base to end transformation \( \robabx{}{desired}{\mathbf{T}}\) |
state | [in] State of the device from which to start the iterations |
Implements InvKinSolver.