Run a Test Manually

Lets walk through the manual way to build and run a test.

Build a Test Profile

Test profiles are defined in YAML files inside the armstron/config/test_profiles folder.

Profile Structure

Test profiles must be structured in a specific way:

  1. type (str): The type of profile. For now, the only valid value is “sequence

  2. params (dict): A set of parameters

    1. preload (list): A list of actions to perform during the “preload” phase

    2. test (list): A list of actions to perform during the “test” phase

Testing Actions

Actions can be either “jog”, “pose” or “balance”.

Jog steps have motion parameters (how the arm moves) and stop conditions (when the arm should stop moving):

jog: # jog motions about the end effector (TCP of the robot)
    linear: [X, Y, Z]          # [mm/sec]
    angular: [X, Y, Z]         # [rad/sec]
stop_conditions:
    max_time: [TIME]           # [sec]
    max_force_x: [FORCE]       # [N], options: min/max, and x/y/z
    max_torque_x: [TORQUE]     # [Nm], options: min/max, and x/y/z
    max_position_x: [POSITION] # [m], options: min/max, and x/y/z
    max_orientation_x: [ORI]   # [rad], options: min/max, and x/y/z

Pose steps move the arm to a specific pose over a given time:

pose: # pose of the end effector (TCP of the robot)
    position: [X, Y, Z]          # [m]
    orientation: [X, Y, Z]         # [degrees (euler angles)]
stop_conditions:
    max_time: [TIME]           # [sec]
    max_force_x: [FORCE]       # [N], options: min/max, and x/y/z
    max_torque_x: [TORQUE]     # [Nm], options: min/max, and x/y/z
    max_position_x: [POSITION] # [m], options: min/max, and x/y/z
    max_orientation_x: [ORI]   # [rad], options: min/max, and x/y/z

Balancing steps can balance (zero) either the pose or the F/T sensor readings:

balance: [TYPE]   # options: 'pose' and 'ft'

Note: Omit (or comment out) stop_conditions if you do not want to use them.

Examples

Here is an example of a simple testing profile:

ceti_pull_test.yaml

type: 'sequence'
params:
  preload:
    # Step 0: Balance the pose
    - balance: 'pose'

    # Step 1: Preload
    - jog: 
        linear: [0, 0, -0.003] # [mm/sec]
        angular: [0.0, 0, 0]    # [rad/sec]
      stop_conditions:
        min_force_z: -60 # [N]

  test:
    # Step 1: Preload
    - jog:
        linear: [0.00, 0.0, 0.001] # [mm/sec]
        angular: [0.0, 0.0, 0.0]   # [rad/sec]
      stop_conditions:
        max_position_z: 0.02 # [m]

Here is an example of a more complex, multi-step testing profile:

ceti_force_hold.yaml

type: 'sequence'
params:
  preload:
    # Step 0: Balance the pose
    - balance: 'pose'

    # Step 1: Move slowly down until 60 N are applied
    - jog: 
        linear: [0, 0, -0.001] # [mm/sec]
        angular: [0.0, 0, 0]    # [rad/sec]
      stop_conditions:
          min_force_z: -60 # [N]

    # Step 2: Hold for 5 seconds
    - jog:
        linear: [0.00, 0.0, 0.000] # [mm/sec]
        angular: [0.0, 0.0, 0.0]   # [rad/sec]
      stop_conditions:
        max_time: 5 #[sec]

  test:
    # Step 1: Move slowly in Z until 10 N are applied or we've moved 50mm
    - jog:
        linear: [0.00, 0.0, 0.0005] # [mm/sec]
        angular: [0.0, 0.0, 0.0]   # [rad/sec]
      stop_conditions:
        max_force_x: 20 # [N]
        max_force_y: 20 # [N]
        max_force_z: 10 # [N]
        #max_position_z: 0.020 # [m]

    # Step 2: Hold for 10 seconds
    - jog:
        linear: [0.00, 0.0, 0.000] # [mm/sec]
        angular: [0.0, 0.0, 0.0]   # [rad/sec]
      stop_conditions:
        max_time: 10 #[sec]

    # Step 3: Pull suction cup off
    - jog:
        linear: [0.00, 0.0, 0.0005] # [mm/sec]
        angular: [0.0, 0.0, 0.0]   # [rad/sec]
      stop_conditions:
        max_position_z: 0.05 #[m]

Run a Test

Running a test is just a matter of running one terminal command (after you start the rest of the system up) with the profile you want to use, and the filename to save data.

Testing Procedure

  1. Bringup the robot

    1. (Teach Pendant) Turn on the robot, get into _manual_ mode, then load the “EXTERNAL_CONTROL.urp” program.

    2. (Host Computer) In a new terminal: roslaunch ur_user_calibration bringup_armando.launch

  2. Start the Armstron test server (this waits for tests to be started, and handles balancing and estop commands)

    1. In a new terminal, start the test server: roslaunch armstron bringup_testing.launch

  3. Start a test (for example, ceti_pull_test.yaml), and save data in the Documents folder (~/Documents/armstron_data/test.csv)

    1. (Teach Pendant) Move the arm around manually to set things up.

    2. (Teach Pendant) Once you are ready to test, run the “EXTERNAL_CONTROL.urp” program. (press “play” in the bottom bar)

    3. (Host Computer) In a new terminal, run:

roslaunch armstron run_test.launch config:="ceti_pull_test.yaml" save:="~/Documents/armstron_data/test.csv"

Note

Savefile names are auto-incremented to prevent overwriting of data, so you can keep sending the same filename (and thus the same terminal command) over and over to keep repeating the same test procedure

Important

Don’t forget to run the “EXTERNAL_CONTROL.urp” program before running tests! It’s easy to forget, so let this note serve as a reminder.

More Details

When running the test, the launch file you are calling takes care of routing parameters to the correct script:

run_test.launch

<?xml version="1.0"?>
<launch>
	<!-- Get arguements  -->
	<arg name="config" doc="Filename of the test config" />
	<arg name="save" doc="Filename of data to save" />
	<arg name="debug" default="False" doc="Whether debug is on" />
	<arg name="action_name" default="armstron" doc="Name of the action server" />


	<!-- start the run node and pass it all of the parameters -->
    <node name="armstron_runner_node" pkg="armstron" type="run_single_test.py" respawn="false"
    	output="screen">
		<param name="debug" type="bool" value="$(arg debug)"/>
		<param name="action_name" type="str" value="$(arg action_name)" />
		<param name="config_file" type="str" value="$(arg config)" />
		<param name="save_file" type="str" value="$(arg save)" />
		
    </node>
</launch>

This launch file invokes a ros node that creates a TestRunner object:

run_single_test.py

#!/usr/bin/env python
import rospy
import rospkg
import os

from armstron.test_interface import TestRunner

filepath_config = os.path.join(rospkg.RosPack().get_path('armstron'), 'config')  
   
if __name__ == '__main__':
    try:
        rospy.init_node('v_inst_test_runner', disable_signals=True)
        print("V_INST TEST RUNNER: Node Initiatilized (%s)"%(rospy.get_name()))

        debug = rospy.get_param(rospy.get_name()+"/DEBUG",False)
        action_name = rospy.get_param(rospy.get_name()+"/action_name",None)
        config_file = rospy.get_param(rospy.get_name()+"/config_file",None)
        save_file = rospy.get_param(rospy.get_name()+"/save_file",None)

        config_path = os.path.join(filepath_config,'test_profiles',config_file)

        # Set settings
        sender = TestRunner(action_name, debug=debug)
        sender.load_profile(config_path)
        sender.set_savefile(save_file)

        print("V_INST TEST RUNNER: Running Test")
        sender.run_test(wait_for_finish=True)
        print("V_INST TEST RUNNER: Finished!")
        sender.shutdown()

    except KeyboardInterrupt:
        print("V_INST TEST RUNNER: Shutting Down")
        sender.estop()
        sender.shutdown()

    except rospy.ROSInterruptException:
        print("V_INST TEST RUNNER: Shutting Down")
        sender.estop()
        sender.shutdown()