LabVIEW Robotics Module

Table of Contents

Inverse Dynamics VI

  • Updated2023-02-21
  • 5 minute(s) read

Inverse Dynamics VI

Owning Palette: Dynamics VIs

Returns the amount of torque required for the robotic arm to achieve the joint positions, velocities, and accelerations you specify. Wire data to the joint positions input to determine the polymorphic instance to use or manually select the instance.

.m file: rne

Inverse Dynamics (Point)

Use this instance to calculate values at a single point.

gravity specifies the gravitational acceleration that acts on the robotic arm. gravity is a three-element array in which the elements specify the force of gravity in the x, y, and z directions, respectively, of the coordinate frame of the world. The default is the gravity of the arm as defined for each link using the Initialize Serial Arm VI.
external force specifies an additional, external force that acts on the end effector of the robotic arm. external force is a six-element array in the form [Fx, Fy, Fz, Mx, My, Mz] in the end-effector coordinate frame, where F refers to force, and M refers to momentum. The default is 0.
serial arm in is a reference to a serial robotics arm. Use the Initialize Serial Arm VI to generate this LabVIEW class object.
joint positions specifies the joint angles that make up the robotic arm pose for which you want to calculate the solution.
joint velocities specifies the velocity of each joint in joint positions.
joint accelerations specifies the acceleration of each joint in joint positions.
error in describes error conditions that occur before this node runs. This input provides standard error in functionality.
serial arm out is a reference to a serial robotic arm. You can wire this output to other Robotic Arm VIs.
required torques contains the amount of force required to generate the joint accelerations you specify, given the gravity and external force that act on the arm.
error out contains error information. This output provides standard error out functionality.

Inverse Dynamics (Trajectory)

Use this instance to calculate values at points along a trajectory.

gravity specifies the gravitational acceleration that acts on the robotic arm. gravity is a three-element array in which the elements specify the force of gravity in the x, y, and z directions, respectively, of the coordinate frame of the world. The default is the gravity of the arm as defined for each link using the Initialize Serial Arm VI.
external force specifies an additional, external force that acts on the end effector of the robotic arm. external force is a six-element array in the form [Fx, Fy, Fz, Mx, My, Mz] in the end-effector coordinate frame, where F refers to force, and M refers to momentum. The default is 0.
serial arm in is a reference to a serial robotics arm. Use the Initialize Serial Arm VI to generate this LabVIEW class object.
joint position trajectory specifies the joint angles of the robotic arm pose at points along a trajectory where each row represents a pose at a particular time and each column represents a particular joint.
joint velocity trajectory specifies the velocity of each joint in joint position trajectory.
joint acceleration trajectory specifies the acceleration of each joint in joint position trajectory.
error in describes error conditions that occur before this node runs. This input provides standard error in functionality.
serial arm out is a reference to a serial robotic arm. You can wire this output to other Robotic Arm VIs.
required torque trajectory contains the amount of force required to generate the joint acceleration trajectory you specify, given the gravity and external force that act on the arm.
error out contains error information. This output provides standard error out functionality.

Log in to get a better experience