(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Improving ROS-Industrial motion on an Industrial Robot (Implementation Notes)

Description: This tutorial gives some background information and hint/tips/tricks to achieve faster and smoother motion when using ROS-Industrial

Tutorial Level: ADVANCED

Overview

This goal of this tutorial is to provide background information on industrial robot motion and explain motion related issues that arise when using ROS-Industrial. There are several tips/tricks to improving motion in general on an industrial robotic platform. This tutorial aims to describe the tradeoffs that are a result of improving certain motion parameters. This tutorial is written from a general point of view. Every robot/controller is different, it's up to the user to experiment and find the right set of motion tweaks that meet their needs.

Background

Industrial Robot Motion Limitations

In general,most industrial robot platforms employ some sort of look-ahead logic when it comes to motion. By looking ahead to upcoming motion commonds, the robot controller can smooth trajectories between commands. The amount of look ahead varies by robot and can include aspects such as move distance or speed, but in the simplest terms can be thought of as a fixed number of moves. The benefit of look ahead is smooth, desirable, motion. A side effect of look ahead is that the robot controller assumes the last look ahead point will be the last executed motion. This means that the robot is always prepared to stop at the last look ahead point and therefore limits it's speed appropriately. For sparse waypoints (as is the case for traditional robot waypoints), this works well. However, for dense waypoints (as is traditionally generated from ROS), the resulting motion is much slower than desired because the controller is assuming a motion stop is very close (Note: this assumes a fixed look ahead based on number of waypoints). While we don't know all the details of different vendor look-ahead functions, the behavior seems to indicate a fixed number of look ahead moves.

Improving Motion

Improving motion can depend on your particular application. In general there is a tradoff between accuracy of path and speed of path (Note: repeatability is different from accuracy, repeatability of robot motion (same waypoints) is extremely high in almost all cases). Some applications require a robot follow the desired path as closely as possible(high accuracy), but as a result must limit the speed of motion. The opposite is also true, high speed paths will not have high path accuracy. Keep this in mind when considering possible tweaks to "improving" motion.

Default ROS-Industrial Motion

By default, the motion that is generated with a standard ROS-Industrial arm navigation package and driver is slow, but accurate (i.e. tries to achieve waypoints with a minimal ammount of error). The main reason for this is to protect users from damaging equipment or injuring themselves when using ROS-Industrial for the first time and to follow, as closely as possible, the desired trajectory planned within ROS.

Increasing Motion Accuracy

As discussed, by default ROS-Industrial motion is pretty accurate, but there are some simple changes that can be made to increase accuracy (at the expense of motion speed/smoothess).

  • Increase waypoint density - The motion between points is typically planned on the robot controller using joint interpolated motion. This means that the motion in between points, although possible predictable, may not be accurate.
  • Decrease waypoint zone on robot controller - By tightening this zone/smoothness tolerance, the path accuracy can be improved.

Increasing Motion Speed/Smoothness

The process to increase motion speed is the opposite of increasing motion accuracy (as might be expected).

  • Decrease waypoint density - The effect of this on the controller side is that the robot doesn't prepare for near term stop and follows the desired velocity. The motion between way-points is executed using controller specific interpolated motion and therefore is unpredictable. ROS assumes higher order spline intermolation (in joint space) between points. If the controller uses similar interpolation, then the robot trajectory can match the ROS expecation. However, this should not be relied upon.
  • Increase waypoint zone on robot controller - Loosening the zone/smoothness tolerance, the path speed and smoothness can be improved. Any reduction in path accuracy is generally small and this can be done safely (even for dense trajectories).

Motion Zone Parameters

In most robot drivers, the motion command is given in the native robot language. Every motion command has some sort of zone/smoothness parameter that describes how close the robot. These parameters vary in all sorts of way, but ultimatley they have some affect on how closely the robot tries to achieve the desired waypoint. Decreasing the zone increases accuracy, but reduces path speed and smoothness. Increasing the zone decreases accuracy, but increases path speed and smoothness. The following sections outline in how and where to adjust the zone parameters. NOTE: The info is provided in a somewhat generic manor so that users can find the right location in each driver if and when the robot driver changes.

Fanuc Robot Driver

The fanuc robot consists of two parts. A KAREL program manages communications, and a TPE (teach pendant) program commands motion. Data received in KAREL, including the motion zone parameter (currently hard coded) is mapped via common registers to the TPE. As of the Groovy release, the zone parameter can be found in ros_relay.kl

<ros_relay.kl>
<snip>
CONST
        LOG_PFIX     = 'RREL '  -- 

        MOTION_TAG   =  4       -- which server tag to use

        MOVE_PREG    =  1       -- position register to use with ros_movesm
        MOVE_SPD_REG =  1       -- integer registers to use with ros_movesm
        MOVE_CNT_REG =  2       -- 

        MOVE_SPEED   = 20       -- speed to use with ros_movesm (percentage of maximum)
        MOVE_CNT     = 80       -- CNT value to use with ros_movesm
<snip>

The MOVE_CNT constant can be adjusted between 0 and 100, with 0 being a full stop at each waypoint (i.e. exact) and 100 being continuous motion (i.e. somewhere close). The physical meaning of MOVE_CNT is the percent of desired velocity required at each waypoint. The larger the velocity, the harder to reach the desired point. The MOVE_CNT value is communicated to the TPE program via shared register and used for the commanded motion in ros_movesm.ls

<ros_movesm.ls>
<snip>
 10:  !Signal busy ;
  11:  F[2]=(ON) ;
  12:   ;
  13:  !Copy it to temp p-reg ;
  14:  PR[2]=PR[1]    ;
  15:   ;
  16:  !Not busy ;
  17:  F[1]=(OFF) ;
  18:  F[2]=(OFF) ;
  19:   ;
  20:  !Perform actual move ;
  21:J PR[2] R[1]% CNT R[2]    ;
  22:   ;
  23:  !Repeat ;
  24:  JMP LBL[1] ;
<snip>

ABB Robot Driver

All motion related control for the ABB driver happens in a single RAPID file, ROS_motion.mod. The zone parameter is stored in the DEFAULT_CORNER_DIST variable. The variable represents a stop data structure. Several standard stop data structures are already defined in rapid (ex. z10). The physical meaning of the standard stop data structures is a cartesian radius (z10 = 10mm radius) around the target point in which the motion smoothing can occur. These standards values range from z0 to z100. A value of z0 will cause motion to stop at each point. Values greater than z100 don't seem to have an appreciable effect.

<ROS_motion.mod>
<snip>
LOCAL CONST zonedata DEFAULT_CORNER_DIST := z10;
LOCAL VAR ROS_joint_trajectory_pt trajectory{MAX_TRAJ_LENGTH};
LOCAL VAR num trajectory_size := 0;
LOCAL VAR intnum intr_new_trajectory;
<snip>



<snip>
! execute all points in this trajectory
        IF (trajectory_size > 0) THEN
            FOR current_index FROM 1 TO trajectory_size DO
                target.robax := trajectory{current_index}.joint_pos;

                skip_move := (current_index = 1) AND is_near(target.robax, 0.1);

                stop_mode := DEFAULT_CORNER_DIST;  ! assume we're smoothing between points
                IF (current_index = trajectory_size) stop_mode := fine;  ! stop at path end

                ! Execute move command
                IF (NOT skip_move)
                    MoveAbsJ target, move_speed, \T:=trajectory{current_index}.duration, stop_mode, tool0;
            ENDFOR

            trajectory_size := 0;  ! trajectory done
        ENDIF
<snip>

Motoman Robot Driver

DX100 Driver (Groovy Release)

The motion zone for the Motoman driver is stored within the PVARQ20VV.JBI job file. Each of the 20 buffered move commands has an associated zone. The zone varies from 0-10 (I think). The physical meaning of the zone is uncertain, but the greater the zone number, the more smoothing occurs. Zone values greater than 10 don't seem to show an appreciable difference.

<PVARQ20VV.JBI>
<snip>
CALL JOB:BUFFER_INIT
*LABEL
CALL JOB:BUFFER_WAIT
MOVJ P000 VJ=I000 PL=3
CALL JOB:BUFFER_WAIT
MOVJ P001 VJ=I001 PL=3
CALL JOB:BUFFER_WAIT
MOVJ P002 VJ=I002 PL=3
CALL JOB:BUFFER_WAIT
MOVJ P003 VJ=I003 PL=3
<snip>

Motoman Driver (Hydro)

The Motoman driver as of the Hydro release supports both the DX and FS100 controllers. Motion limitations that occurred in earlier versions of the driver have been overcome. The Motoman driver accurately follows any trajectory at the desired speed regardless of the density. For more information see the motoman driver

Wiki: Industrial/Tutorials/Improving_Motion_on_an_Industrial_Robot (last edited 2016-03-14 16:05:27 by IanMcMahon)