Armstron¶

The Armstron package allows you to This ROS package and associated GUI make use of the 6-axis force/torque sensor on the Universal Robot e-series to apply complex loads to things. We can essentially perform tests similar to an Instron Uniaxial Testing machine, but in all axes.
Table of Contents
Quickstart Guide¶
(from “ README.md ” in github repo)
Armstron¶
This ROS package and associated GUI make use of the 6-axis force/torque sensor on the Universal Robot e-series to apply complex loads to things. We can essentially perform tests similar to an Instron Uniaxial Testing machine, but in all axes.
Installation¶
Set up your robot arm for use with the Universal_Robots_ROS_Driver.
Clone the package to the src folder of your catkin workspace
Follow instructions in the ur_robot_driver/doc folder.
Be sure to create a calibration package for your robot per these instructions. In this example, we have created a package called “_ur_usercalibration” with a dedicated launch file “_bringuparmando.launch” where the IP address of the robot is set.
Set up this package
Clone this package (armstron) to the src folder of your catkin workspace
In the root folder of your workspace, install dependencies:
rosdep install --from-paths src --ignore-src -r -y
Navigate to the armstron package folder and install a few extra non-ROS python requirements:
cd src/armstron/armstron
pip install -r requirements.txt
Navigate back to the workspace folder, and build your workspace (
catkin_make
)
Set up the runfile (so you can run Armstron as though it is a regular application)
Navigate to the armstron top level folder:
cd src/armstron
Generate the run files
sudo bash armstron/bash/generate_desktop.sh [ROBOT PACKAGE] [ROBOT LAUNCH FILE]
For example:
sudo bash armstron/bash/generate_desktop.sh ur_user_calibration bringup_armando.launch
Now you can run Armstron with one click by going to your application menu (Super + A) and choosing “Armstron”.
Usage¶
Bringup the robot¶
(Teach Pendant) Turn on the robot, get into manual mode, then load the “EXTERNAL_CONTROL.urp” program.
(Teach Pendant) Start the robot (tap the small red dot on the bottom left corner)
Start Armstron¶
(Host Computer) Choose “Armstron” from your application menu (Super + A).
This starts communication with the robot arm, starts the Armstron test server, and starts the Armstron GUI.
Use the GUI to load/build test profiles, set data save locations, and run tests.
Advanced Usage¶
Since everything is modular, you can run each part of the Armstron software stack as independent ROS processes. This is useful for debugging purposes
Bringup the robot¶
(Teach Pendant) Turn on the robot, get into manual mode, then load the “EXTERNAL_CONTROL.urp” program.
(Teach Pendant) Start the robot (tap the small red dot on the bottom left corner)
(Host Computer) (new terminal):
roslaunch ur_user_calibration bringup_armando.launch
(Teach Pendant) Run the “EXTERNAL_CONTROL.urp” program.
Use the Armstron test server¶
Start the test server (new terminal):
roslaunch armstron bringup_testing.launch
Start a test (new terminal):
roslaunch armstron run_test.launch config:="ceti_pull_test.yaml" save:="~/vinst_data/testing_launch.csv"
roslaunch armstron run_test.launch config:="ceti_force_hold.yaml" save:="~/vinst_data/testing_launch.csv"
Start the GUI¶
Start the test server (new terminal):
roslaunch armstron bringup_testing.launch
Start the Armstron GUI (new terminal):
rosrun armstron gui.py
Useful commands for debugging¶
Show the controller manager:
rosrun rqt_controller_manager rqt_controller_manager
Enable sending of single messages
rqt
Go to Plugins >> Topics >> Message Publisher
Examples¶
Some basic examples of how armstron can be used will be include here. You can find them in the armstron/launch folder in the github repo.
Run a Test¶
Lets walk through the manual way to build and run a test.
Contents:
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:
type (
str
): The type of profile. For now, the only valid value is “sequence”params (
dict
): A set of parameterspreload (
list
): A list of actions to perform during the “preload” phasetest (
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:
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:
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¶
Bringup the robot
(Teach Pendant) Turn on the robot, get into _manual_ mode, then load the “EXTERNAL_CONTROL.urp” program.
(Host Computer) In a new terminal:
roslaunch ur_user_calibration bringup_armando.launch
(Teach Pendant) Run the “EXTERNAL_CONTROL.urp” program.
Start the Armstron test server (this waits for tests to be started, and handles balancing and estop commands)
In a new terminal, start the test server:
roslaunch armstron bringup_testing.launch
Start a test (for example, ceti_pull_test.yaml), and save data in the Documents folder (~/Documents/vinst_data/test.csv)
In a new terminal, run:
roslaunch armstron run_test.launch config:="ceti_pull_test.yaml" save:="~/Documents/vinst_data/test.csv"
Note
If you want to run more tests, just keep repeating step 3. 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.
More Details¶
When running the test, the launch file you are calling takes care of routing parameters to the correct script:
<?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:
#!/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()
Use the GUI¶
rosrun armstron gui.py
Note
GUI instructions Coming soon.
API Reference¶
Each page contains details and full API reference for all the classes that can be accessed outside the armstron package.
These are located in the src/armstron
folder.
For an explanation of how to use all of it together, see Quickstart Guide.
Test Interface¶
Run and manage tests. This class can be imported into other ROS packages to enable control of tests. This interface is used in the backend of the GUI.
-
class
test_interface.
TestRunner
(name, debug=False)¶ A ROS Action server to run single tests.
- Parameters
name (str) – Name of the Action Server
-
balance
(type)¶ Balance either the load or F/T sensor
- Parameters
type (str) – The type of balance to perform. Must be either
pose
orft
-
estop
()¶ Perform an Emergency Stop
-
get_test_status
()¶ Get the current state of the test
- Returns
state – The current state of the test
- Return type
ActionFeedback
-
load_profile
(filename)¶ Load the config profile from a file
- Parameters
filename (str) – Filename to load
-
run_test
(wait_for_finish=True)¶ Run a test and wait for the result
- Parameters
wait_for_finish (bool) – Wait for the test to finish
- Returns
result – The result of the test.
- Return type
ActionResult
-
set_profile
(profile)¶ Set the config profile
- Parameters
profile (dict) – Testing profile to use
-
set_savefile
(save_file)¶ Set the filename to save
- Parameters
save_file (str) – Filename to save data to
-
shutdown
()¶ Shut down the node gracefully
Hardware Interface¶
Robot Controller¶
Control the robot’s motion and get data. This interface relies on the Universal_Robots_ROS_Driver package to control UR robots using the builtin ROS controllers.
-
class
hardware_interface.
RobotController
(robot_name='', debug=False)¶ Hardware interface that can control a robot via ROS controllers
- Parameters
robot_name (str) – Name of the robot. This name must match the prefix of the robot’s controller topics
debug (bool) – Turn on debugging print statements
-
balance_ft
()¶ Zero the internal F/T offsets
-
balance_pose
()¶ Zero the internal pose offsets
-
get_offsets
()¶ Get the internal F/T and Pose offsets
- Returns
offsets – Offset dict with “force”, “torque”, “position”, and “orientation” keys
- Return type
dict
-
get_twist
(linear, angular)¶ Build a twist message from vectors
- Parameters
linear (list) – The linear twist components [x,y,z]
angular (list) – The angular twist components [x,y,z]
- Returns
twist – The resulting twist message
- Return type
geometry_msgs/Twist
-
load_controller
(controller)¶ Load a ROS controller
- Parameters
controller (str) – Name of the controller to load
- Returns
response – Service response from the controller manager
- Return type
str
-
set_controller
(controller)¶ Set which ROS controller is started, and stop all others
- Parameters
controller (str) – Name of the controller to start
- Returns
response – Service response from the controller manager
- Return type
str
-
set_offsets
(offsets)¶ Set the internal F/T and Pose offsets
- Parameters
offsets (dict) – Offset dict with “force”, “torque”, “position”, and “orientation” keys
-
switch_controller
(start_controllers, stop_controllers, strictness=1, start_asap=False, timeout=0)¶ Switch ROS controllers
- Parameters
start_controllers (list) – Names of the controllers to start
stop_controllers (list) – Names of the controllers to stop
strictness (int) – Strictness of controller switching
start_asap (bool) – Decide whether controllers should be started immediately
timeout (int) – Timeout (in seconds)
- Returns
response – Service response from the controller manager
- Return type
str
-
unload_controller
(controller)¶ Unload a ROS controller
- Parameters
controller (str) – Name of the controller to unload
- Returns
response – Service response from the controller manager
- Return type
str
-
update_tool_pose
(data)¶ Update the internal value of the tool pose. Saves a copy of the cartesian position (in m) and euler angle orientation (in rad). The pose is then balanced via offsets. The balanced wrench is published in the
/tf_balanced
topic.- Parameters
data (tf2_msgs/TFMessage) – Wrench message
-
update_wrench
(data)¶ Update the internal value of the wrench. The wrench is converted from the tool frame to the world frame, then balanced via offsets. The balanced wrench is published in the
/wrench_balanced
topic.- Parameters
data (geometry_msgs/Wrench) – Wrench message
Data Logger¶
Log data to syncronized files. Given a filename and a map of topics (see armstron/config/data_to_save.yaml), log data from ROS topics to CSV files.
-
class
hardware_interface.
DataLogger
(filename, config, overwrite=False)¶ Log data to csv files.
- Parameters
filename (str) – Filename to save to. Note: files will be saved with suffixes corresponding to the name of the data being saved
config (dict) – Configuration, including the topic map
- Raises
ValueError – If the topic_map is invalid
-
pause
()¶ Pause logging.
-
resume
()¶ Resume logging.
-
shutdown
()¶ Shutdown gracefully.
-
start
()¶ Start logging data.
-
stop
()¶ Stop logging data.
Install¶
Follow instructions in the Quickstart Guide.
Explore the Examples¶
Check out the Examples, or run any of the launch files in the armstron/launch
folder.
Links¶
Documentation: Read the Docs
Source code: Github
Contact¶
If you have questions, or if you’ve done something interesting with this package, get in touch with Clark Teeple, or the Harvard Microrobotics Lab!
If you find a problem or want something added to the library, open an issue on Github.
Used In…¶
Armstron will enable many future works!