RobWorkProject  24.12.4-
Public Types | Public Member Functions | List of all members
ClosedFormIKSolverUR Class Reference

Analytical inverse kinematics solver to the kinematics of a Universal Robots. More...

#include <ClosedFormIKSolverUR.hpp>

Inherits ClosedFormIK.

Public Types

typedef rw::core::Ptr< ClosedFormIKSolverURPtr
 Smart pointer type to ClosedFormURSolver.
 
typedef rw::core::Ptr< const ClosedFormIKSolverURCPtr
 Smart pointer type to const ClosedFormURSolver.
 
- Public Types inherited from ClosedFormIK
typedef rw::core::Ptr< ClosedFormIKPtr
 smart pointer type to this class
 
- Public Types inherited from InvKinSolver
typedef rw::core::Ptr< InvKinSolverPtr
 smart pointer type to this class
 
typedef rw::core::Ptr< const InvKinSolverCPtr
 smart pointer type to this const class
 

Public Member Functions

 ClosedFormIKSolverUR (const rw::core::Ptr< const rw::models::SerialDevice > device, const rw::kinematics::State &state)
 Construct new closed form solver for a Universal Robot. More...
 
virtual ~ClosedFormIKSolverUR ()
 Destructor.
 
std::vector< rw::math::Qsolve (const rw::math::Transform3D< double > &baseTend, const rw::kinematics::State &state) const
 Calculates the inverse kinematics. More...
 
void setCheckJointLimits (bool check)
 Specifies whether to check joint limits before returning a solution. More...
 
virtual rw::core::Ptr< const rw::kinematics::FramegetTCP () 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.
 

Detailed Description

Analytical inverse kinematics solver to the kinematics of a Universal Robots.

Constructor & Destructor Documentation

◆ ClosedFormIKSolverUR()

ClosedFormIKSolverUR ( const rw::core::Ptr< const rw::models::SerialDevice device,
const rw::kinematics::State state 
)

Construct new closed form solver for a Universal Robot.

Note
The dimensions will be automatically extracted from the device, using an arbitrary state.
Parameters
device[in] the device.
state[in] the state to use to extract dimensions.

Member Function Documentation

◆ getTCP()

virtual rw::core::Ptr<const rw::kinematics::Frame> getTCP ( ) const
virtual

Returns the Tool Center Point (TCP) used when solving the IK problem.

Returns
The TCP Frame used when solving the IK.

Implements InvKinSolver.

◆ setCheckJointLimits()

void setCheckJointLimits ( bool  check)
virtual

Specifies whether to check joint limits before returning a solution.

Parameters
check[in] If true the method should perform a check that joints are within bounds.

Implements InvKinSolver.

◆ solve()

std::vector<rw::math::Q> solve ( const rw::math::Transform3D< double > &  baseTend,
const rw::kinematics::State state 
) const
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) )

Parameters
baseTend[in] Desired base to end transformation \( \robabx{}{desired}{\mathbf{T}}\)
state[in] State of the device from which to start the iterations
Returns
List of solutions. Notice that the list may be empty.
Note
The targets baseTend must be defined relative to the base of the robot/device.

Implements InvKinSolver.


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