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 | |
DrakeKukaIIwaRobot & | operator= (const DrakeKukaIIwaRobot &)=delete |
DrakeKukaIIwaRobot (DrakeKukaIIwaRobot &&)=delete | |
DrakeKukaIIwaRobot & | operator= (DrakeKukaIIwaRobot &&)=delete |
|
delete |
|
delete |
|
explicit |
Construct a 7-DOF Kuka iiwa robot arm (from file kuka_iiwa_robot.urdf).
The robot is constructed with 7 revolute joints.
[in] | gravity | Earth'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). |
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.
[in] | q | robot's joint angles (generalized coordinates). |
[in] | qDt | 1st-time-derivative of q. |
[in] | qDDt | 2nd-time-derivative of q. |
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.
[in] | q | robot's joint angles (generalized coordinates). |
[in] | qDt | 1st-time-derivative of q. |
[in] | qDDt | 2nd-time-derivative of q. |
int get_number_of_rigid_bodies | ( | ) | const |
This method gets the number of rigid bodies in this robot.
|
delete |
|
delete |
const MultibodyPlant<T>& plant | ( | ) | const |
const multibody::internal::MultibodyTree<T>& tree | ( | ) | const |