5
$\begingroup$

I am working on a 6 DOF robotic arm(industrial manipulator). I have the basic structural specs (dimensions, weights etc) for the links and joints with me.

Basically, I want to simulate both static torque(Due to the weight of the arm) and dynamic torque(due to the accelerating joint's motion) Torque that the joints will need to bear for a given set of motions.

I have looked on the web and found tools like the ROS-MoveIt Visualiser, Gazebo, V-REP which let me visually see a robotic arm and simulate the position logic and external factors like collisions etc. But I have been unable to simulate/calculate dynamic torque values from these tools.

Ideally, I'd want to define a fixed motion of the end effector(i.e. move the robot between 2 positions) and measure the Torque(both static and dynamic) during that particular move.

These torque values are essential for selecting the optimum motors and gearboxes for my design and payload.

$\endgroup$

4 Answers 4

4
$\begingroup$

The dynamics of robotic arms are fairly complex, especially when there are more than three joints to consider. The problem is that the movement of each joint moves all the links beyond it, which can induce torques at other joints. You have to consider how the movement of all links affects each individual joint.

There is software that can automatically compute the dynamics based on the geometry you provide (MATLAB + SimMechanics comes to mind, although that is an expensive option). I don't have any knowledge of free simulators, but I'm sure they exist. You may have to search around to see what simulator is right for your application.

Another option is to program your own simulation. The mathematics behind the dynamics of serial link robots are covered in many different textbooks. In order to do this part from scratch you would need to be familiar with using matrices, plus some understanding of differential equations. I can give some of the basics here, to give you an idea of what you would have to program.

You can calculate the torque required to move a serial-link robotic arm using the following nonlinear matrix equation:

$\boldsymbol{\tau} = \boldsymbol{M}(\boldsymbol{q})\ddot{\boldsymbol{q}} + \boldsymbol{C}(\boldsymbol{q},\dot{\boldsymbol{q}})\dot{\boldsymbol{q}} + \boldsymbol{G}(\boldsymbol{q})$

where

$\boldsymbol{\tau}$ is the (6x1) vector of joint torques

$\boldsymbol{q}$ is a (6x1) vector of joint angles

$\dot{\boldsymbol{q}}, \ddot{\boldsymbol{q}}$ are the (6x1) joint angular velocity vector and joint angular acceleration vector, respectively

$\boldsymbol{M}(\boldsymbol{q})$ is the (6x6) inertia matrix of the robot, which is a function of the joint angles

$\boldsymbol{C}(\boldsymbol{q},\dot{\boldsymbol{q}})$ is the (6x6) centrifugal and Coriolis effect matrix, which is a function of the joint angles and angular velocities

$\boldsymbol{G}(\boldsymbol{q})$ is the (6x1) gravitational torque vector, which is a function of joint position

Notice that this equation includes both the dynamic and static loads on each joint. If you set the joint angular velocity and acceleration to zero, you would have the static equation by itself.

You may be able to find expressions for the $M$, $C$, and $G$ matrices online, but you can also try to derive them for your application using the Euler-Lagrange method.

So, the steps you would have to take are:

  1. Derive the dynamic matrices associated with your application.
  2. Derive the equations that convert the motion (position, velocity, acceleration) of the end-effector to the motion of the joints (the inverse kinematics).
  3. Write a program that
    • Converts an end-effector trajectory to a set of joint trajectories (position, velocity, and acceleration).
    • Computes the required torque using the dynamic equation for each point along that trajectory.

This is all possible (in fact I have done this myself for a 3 DOF manipulator) but it might be too much work for an enthusiast.

$\endgroup$
1
  • $\begingroup$ Please notice the $C$ matrix in @BarbalatsDilemma's answer. Unlike in the question, where you call out dynamic torque to be due to accelerating the robot's joints, you also need to account for the torque required just to compensate for Coriolis and centrifugal forces. For some motion profiles these values exceed the other torque requirements. $\endgroup$
    – SteveO
    Jul 11, 2016 at 19:07
3
$\begingroup$

I think you may be going about this problem wrong. If you find a simulator that reports joint torques, then what? Are you going to iterate through every possible start and end location?

You should only need to evaluate the worst-case motion. Worst case static torque would be with the arm straight out carrying maximum load, and worst case dynamic torque would probably be whatever the largest range of motion would be while fighting gravity.

Evaluate the worst-case scenarios (not necessarily the same for each joint, by the way!) and you're done.

$\endgroup$
1
$\begingroup$

In order to simulate dynamics you need a multi-body dynamics simulation software. Matlab-Simulink has SimMechanics toolbox to do this, but many CAD software used to carry out the mechanical design of the robot can aolso do the simulation. SolidWorks for example has a simulation component calld Simulation.

If you are interested in wiring the dynamic equations and calculating the torques you can use the iterative newton-euler method.

$\endgroup$
1
  • 1
    $\begingroup$ SimMechanics is now called Simscape Multibody, fyi. $\endgroup$
    – Chuck
    Jul 11, 2016 at 18:18
1
$\begingroup$

OpenRave is another good library that will calculate dynamic torques. Use the ComputeInverseDynamics function. Here is a python example:

robot.SetDOFValues(dofvalues)
robot.SetDOFVelocities(dofvelocities)
torques = robot.ComputeInverseDynamics(dofaccelerations)

or

torqueconfiguration, torquecoriolis, torquegravity = robot.ComputeInverseDynamics(dofaccelerations,None,returncomponents=True)
$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge that you have read and understand our privacy policy and code of conduct.

Not the answer you're looking for? Browse other questions tagged or ask your own question.