Drake
Drake C++ Documentation
DrakeKukaIIwaRobot< T > Class Template Reference

Detailed Description

template<typename T>
class drake::multibody::benchmarks::kuka_iiwa_robot::DrakeKukaIIwaRobot< T >

This class is a MultibodyTree model for a 7-DOF Kuka iiwa robot arm.

It is used to compare Drake results for the robot end-effector (rigid linkG) relative to world (Newtonian frame linkN) versus MotionGenesis solution. This class takes input values for each of the 7 joint angles (q) as well as their 1st and 2nd time derivatives (q̇, q̈) and calculates the end-effector rotation matrix (relative to world), position (from world origin) angular velocity, velocity, angular acceleration, and acceleration. Geometrical and connectivity data is in file kuka_iiwa_robot.urdf.

#include <drake/multibody/benchmarks/kuka_iiwa_robot/drake_kuka_iiwa_robot.h>

Public Member Functions

 DrakeKukaIIwaRobot (double gravity)
 Construct a 7-DOF Kuka iiwa robot arm (from file kuka_iiwa_robot.urdf). More...
 
int get_number_of_rigid_bodies () const
 This method gets the number of rigid bodies in this robot. More...
 
test_utilities::SpatialKinematicsPVA< T > CalcEndEffectorKinematics (const Eigen::Ref< const VectorX< T >> &q, const Eigen::Ref< const VectorX< T >> &qDt, const Eigen::Ref< const VectorX< T >> &qDDt)
 This method calculates kinematic properties of the end-effector (herein denoted as rigid body G) of a 7-DOF KUKA LBR iiwa robot (14 kg payload). More...
 
KukaRobotJointReactionForces< T > CalcJointReactionForces (const Eigen::Ref< const VectorX< T >> &q, const Eigen::Ref< const VectorX< T >> &qDt, const Eigen::Ref< const VectorX< T >> &qDDt)
 This method calculates joint reaction torques/forces for a 7-DOF KUKA iiwa robot, from known joint angles and their 1st and 2nd time-derivatives. More...
 
const multibody::internal::MultibodyTree< T > & tree () const
 
const MultibodyPlant< T > & plant () const
 
Does not allow copy, move, or assignment
 DrakeKukaIIwaRobot (const DrakeKukaIIwaRobot &)=delete
 
DrakeKukaIIwaRobotoperator= (const DrakeKukaIIwaRobot &)=delete
 
 DrakeKukaIIwaRobot (DrakeKukaIIwaRobot &&)=delete
 
DrakeKukaIIwaRobotoperator= (DrakeKukaIIwaRobot &&)=delete
 

Constructor & Destructor Documentation

◆ DrakeKukaIIwaRobot() [1/3]

DrakeKukaIIwaRobot ( const DrakeKukaIIwaRobot< T > &  )
delete

◆ DrakeKukaIIwaRobot() [2/3]

DrakeKukaIIwaRobot ( DrakeKukaIIwaRobot< T > &&  )
delete

◆ DrakeKukaIIwaRobot() [3/3]

DrakeKukaIIwaRobot ( double  gravity)
explicit

Construct a 7-DOF Kuka iiwa robot arm (from file kuka_iiwa_robot.urdf).

The robot is constructed with 7 revolute joints.

Parameters
[in]gravityEarth's gravitational acceleration in m/s². The world z-unit vector is vertically upward. If a gravity value of 9.8 is passed to this constructor, it means the gravity vector is directed opposite the world upward z-unit vector (which is correct – gravity is downward).

Member Function Documentation

◆ CalcEndEffectorKinematics()

test_utilities::SpatialKinematicsPVA<T> CalcEndEffectorKinematics ( const Eigen::Ref< const VectorX< T >> &  q,
const Eigen::Ref< const VectorX< T >> &  qDt,
const Eigen::Ref< const VectorX< T >> &  qDDt 
)

This method calculates kinematic properties of the end-effector (herein denoted as rigid body G) of a 7-DOF KUKA LBR iiwa robot (14 kg payload).

Right-handed orthogonal unit vectors Nx, Ny, Nz are fixed in N (Earth) with Nz vertically upward and right-handed orthogonal unit vectors Gx, Gy, Gz are fixed in G. The origin of frame N (Earth) is denoted No. The origin Go of end-effector G is located at G's inboard revolute joint.

Parameters
[in]qrobot's joint angles (generalized coordinates).
[in]qDt1st-time-derivative of q.
[in]qDDt2nd-time-derivative of q.
Returns
G's kinematics in N, expressed in N.

◆ CalcJointReactionForces()

KukaRobotJointReactionForces<T> CalcJointReactionForces ( const Eigen::Ref< const VectorX< T >> &  q,
const Eigen::Ref< const VectorX< T >> &  qDt,
const Eigen::Ref< const VectorX< T >> &  qDDt 
)

This method calculates joint reaction torques/forces for a 7-DOF KUKA iiwa robot, from known joint angles and their 1st and 2nd time-derivatives.

Parameters
[in]qrobot's joint angles (generalized coordinates).
[in]qDt1st-time-derivative of q.
[in]qDDt2nd-time-derivative of q.
Returns
a structure holding the quantities defined below. -----—|-------------------------------------------------------— F_Ao_W | Spatial force on Ao from W, expressed in frame W (world). F_Bo_W | Spatial force on Bo from A, expressed in frame W (world). F_Co_W | Spatial force on Co from B, expressed in frame W (world). F_Do_W | Spatial force on Do from C, expressed in frame W (world). F_Eo_W | Spatial force on Eo from D, expressed in frame W (world). F_Fo_W | Spatial force on Fo from E, expressed in frame W (world). F_Go_W | Spatial force on Go from F, expressed in frame W (world).

◆ get_number_of_rigid_bodies()

int get_number_of_rigid_bodies ( ) const

This method gets the number of rigid bodies in this robot.

Returns
the number of rigid bodies in this robot.

◆ operator=() [1/2]

DrakeKukaIIwaRobot& operator= ( DrakeKukaIIwaRobot< T > &&  )
delete

◆ operator=() [2/2]

DrakeKukaIIwaRobot& operator= ( const DrakeKukaIIwaRobot< T > &  )
delete

◆ plant()

const MultibodyPlant<T>& plant ( ) const

◆ tree()

const multibody::internal::MultibodyTree<T>& tree ( ) const

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