Skip to content

Commit

Permalink
migrated run single script to use the test interface
Browse files Browse the repository at this point in the history
  • Loading branch information
cbteeple committed Mar 9, 2022
1 parent 2af3a35 commit f3fca35
Show file tree
Hide file tree
Showing 16 changed files with 218 additions and 286 deletions.
11 changes: 8 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,13 @@ This ROS package and associated GUI make use of the 6-axis force/torque sensor o


## Installation
1. Clone this package to the `src` folder of your catkin workspace
2. In the root folder of your workspace, install dependencies:
1. Set up your robot arm for use with the [Universal_Robots_ROS_Driver](https://github.com/UniversalRobots/Universal_Robots_ROS_Driver).
- Clone the package to the **src** folder of your catkin workspace
- Follow instructions in the [ur_robot_driver/doc](https://github.com/UniversalRobots/Universal_Robots_ROS_Driver/tree/master/ur_robot_driver/doc) folder. to set up the URCap on the robot
2. Clone this package (armstron) to the **src** folder of your catkin workspace
3. In the root folder of your workspace, install dependencies:
- `rosdep install --from-paths src --ignore-src -r -y`
3. Navigate to the armstron package folder and install a few extra non-ROS python requirements:
4. Navigate to the armstron package folder and install a few extra non-ROS python requirements:
- `cd src/armstron/armstron`
- `pip install -r requirements.txt`
5. Navigate back to the workspace folder, and build your workspace (`catkin_make`)
Expand All @@ -22,6 +25,7 @@ This ROS package and associated GUI make use of the 6-axis force/torque sensor o
### Use the Armstron test server
1. Start the test server: `roslaunch armstron bringup_testing.launch`
2. Start a test by publishing a goal message to the `/armstron/goal` topic

```bash
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"
Expand All @@ -30,6 +34,7 @@ This ROS package and associated GUI make use of the 6-axis force/torque sensor o
### Start the GUI
1. Start the test server: `roslaunch armstron bringup_testing.launch`
2. Start the Armstron GUI:

```bash
rosrun armstron gui.py
```
Expand Down
1 change: 0 additions & 1 deletion armstron/config/test_profiles/ceti_force_hold.yaml
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@

type: 'sequence'
params:
preload:
Expand Down
1 change: 0 additions & 1 deletion armstron/config/test_profiles/ceti_pull_test.yaml
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@

type: 'sequence'
params:
preload:
Expand Down
1 change: 0 additions & 1 deletion armstron/config/test_profiles/ceti_pull_test_diag.yaml
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@

type: 'sequence'
params:
preload:
Expand Down
9 changes: 9 additions & 0 deletions armstron/launch/bringup_testing.launch
Original file line number Diff line number Diff line change
Expand Up @@ -11,4 +11,13 @@
<param name="debug" type="bool" value="$(arg debug)"/>
<param name="action_name" type="str" value="$(arg action_name)" />
</node>


<!-- Start the plotting interface -->
<node name="armstron_plot"
pkg="rqt_multiplot"
type="rqt_multiplot"
respawn="false"
args="--force-discover --multiplot-config $(find armstron)/config/rqt_multiplot.xml --multiplot-run-all" />

</launch>
171 changes: 19 additions & 152 deletions armstron/scripts/run_single_test.py
Original file line number Diff line number Diff line change
@@ -1,165 +1,32 @@
#!/usr/bin/env python
import time
#import roslib; roslib.load_manifest('ur_driver')
import rospy
import rospkg
import actionlib
import yaml
import json
import ast
import os
import sys
import copy

import armstron.msg as msg
from armstron.srv import Balance, Estop
from armstron.test_interface import TestRunner

filepath_config = os.path.join(rospkg.RosPack().get_path('armstron'), 'config')

class TestRunner():
'''
A ROS Action server to run single tests.
Parameters
----------
name : str
Name of the Action Server
'''

def __init__(self, name):

self.DEBUG = rospy.get_param(rospy.get_name()+"/DEBUG",False)
self._action_name = rospy.get_param(rospy.get_name()+"/action_name",name)
self.config_file = rospy.get_param(rospy.get_name()+"/config_file",None)
self.save_file = rospy.get_param(rospy.get_name()+"/save_file",None)
self.config_path = os.path.join(filepath_config,'test_profiles')
self.config = self._get_config(os.path.join(self.config_path, self.config_file))

# Make an action client
self._test_client = actionlib.SimpleActionClient(self._action_name, msg.RunTestAction)
self._test_client.wait_for_server()

# Make a service proxy for the estop service


def _get_config(self, filename):
'''
Load a testing profile (config)
Parameters
----------
filename : str or Path
Filename to load config from
Returns
-------
config : dict
The test config
'''
with open(filename, 'r') as f:
config=yaml.safe_load(f)
return config


def run_test(self):
'''
Run a test and wait for the result
Returns
-------
result : ActionResult
The result of the test.
'''
# Balance at start
balance = self.config['balance'].lower()
if balance!="":
if 'pose' in balance:
self.balance('pose')
if 'ft' in balance:
self.balance('ft')

# Build the goal message to send
goal = msg.RunTestGoal()
goal.command = self.config['type']
goal.params = json.dumps(self.config['params'])
goal.filename = self.save_file

# Tell the test server to run the test.
self._test_client.send_goal(goal)

# Wait for the server to finish performing the test.
self._test_client.wait_for_result()

# Return the result
return self._test_client.get_result()


def estop(self):
'''
Perform an Emergency Stop
'''
# Send estop service call
self._call_service(self._action_name+'/estop',Estop)


def balance(self, type):
'''
Balance either the load or F/T sensor
Parameters
----------
type : str
The type of balance to perform. Must be either
``pose`` or ``ft``
'''
# Send estop service call
self._call_service(self._action_name+'/balance',Balance, type = str(type))


def _call_service(self, name, service_type, **fargs):
'''
Call a service and handle the result
Parameters
----------
name : str
Name of the service to call
service_type : ROS srv
ROS service class (must be correct for the service name you are calling)
**args : Any
Arguments to pass to the service
Returns
-------
response : ROS srv response
The response from the service. Returns ``None`` if the service
call was unsuccessful.
'''
rospy.wait_for_service(name)
try:
fun = rospy.ServiceProxy(name, service_type)
resp1 = fun(**fargs)
return resp1
except rospy.ServiceException as e:
print("Service call failed: %s"%e)
return None


def shutdown(self):
'''
Shut down the node gracefully
'''
pass



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()))
sender = TestRunner(rospy.get_name())
sender.run_test()
print("V_INST TEST RUNNER: Ready!")

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:
Expand Down
24 changes: 24 additions & 0 deletions armstron/src/armstron/test_interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
import copy

import armstron.msg as msg
from armstron.utils import load_yaml
from armstron.srv import Balance, Estop

class TestRunner():
Expand All @@ -34,16 +35,39 @@ def __init__(self, name, debug=False):
self._test_client.wait_for_server()


def load_profile(self, filename):
'''
Load the config profile from a file
Parameters
----------
filename : str
Filename to load
'''
profile = load_yaml(filename)
self.set_profile(profile)


def set_profile(self, profile):
'''
Set the config profile
Parameters
----------
profile : dict
Testing profile to use
'''
self.config = profile


def set_savefile(self, save_file):
'''
Set the filename to save
Parameters
----------
save_file : str
Filename to save data to
'''
self.save_file = save_file

Expand Down
8 changes: 1 addition & 7 deletions docs/description.rst
Original file line number Diff line number Diff line change
Expand Up @@ -24,13 +24,7 @@ The Armstron package allows you to This ROS package and associated GUI make use

Install
=======
1. Clone this package to the `src` folder of your catkin workspace
2. In the root folder of your workspace, install dependencies:
- ``rosdep install --from-paths src --ignore-src -r -y``
3. Navigate to the armstron package folder and install a few extra non-ROS python requirements:
- ``cd src/armstron/armstron``
- ``pip install -r requirements.txt``
5. Navigate back to the workspace folder, and build your workspace (``catkin_make``)
Follow instructions in the :ref:`Quickstart Guide <quickstart>`.



Expand Down
Loading

0 comments on commit f3fca35

Please sign in to comment.