Name | abb-motion-program-exec JSON |
Version |
0.7.4
JSON |
| download |
home_page | None |
Summary | Python package to execute motion commands on ABB robots and log results |
upload_time | 2024-10-25 20:20:05 |
maintainer | None |
docs_url | None |
author | None |
requires_python | >=3.6 |
license | Apache-2.0 |
keywords |
|
VCS |
 |
bugtrack_url |
|
requirements |
No requirements were recorded.
|
Travis-CI |
No Travis.
|
coveralls test coverage |
No coveralls.
|
# abb_motion_program_exec
[](https://github.com/rpiRobotics/abb_motion_program_exec)
[](https://pypi.org/project/abb-motion-program-exec/)
`abb_motion_program_exec` provides a simple way to download and run a sequence of
`MoveAbsJ`, `MoveJ`, `MoveL`, `MoveC`, and `WaitTime` commands on
an ABB IRC5 robot controller. This program is intended to be a proof of
concept for more sophisticated controller interfaces. Multi-move control of two robots is also
supported. Externally Guided Motion (EGM) is also supported for joint target, pose target, and path correction modes.
Documentation can be found at: https://abb-motion-program-exec.readthedocs.io/
## Installation
`abb-motion-program-exec` is avaliable on PyPi.
```
pip install abb-motion-program-exec
```
Begin by installing the software for the robot controller. This software can be
installed manually by copying files to the robot controller and importing configuration files.
* See [robot_setup_manual.md](docs/robot_setup_manual.md) for setup instructions.
* See [robot_multimove_setup_manual.md](docs/robot_multimove_setup_manual.md) for ABB Multi-Move
setup to control two robots. See later sections of this doc for more information on Multi-Move.
This contains the robot-side code, that reads
and executes the contents of `motion_program.bin`. `motion_program.bin`
contains the sequence of instructions to run, encoded in binary
format for fast interpretation.
**Only one instance of a Robot Studio virtual controller can be run at a time.** Only
instances of Robot Studio can be run at a time running a single virtual controller. This is due to
the controller using TCP port 80 on the local computer to accept REST commands from Python. If
more than one controller is started, TCP port 80 will already be in use and can cause unpredictable
behavior. Restart the computer if connections cannot be made from Python to the controller. Multiple
real robots can be used concurrently since they will each have a unique IP address to bind port 80.
### Python 3.6 Linux Install (Ubuntu Bionic)
Older versions of Python are not supported by the currently available protobuf package. Use the apt version instead.
```
sudo apt install python3-virtualenv python3-protobuf python3-numpy python3-wheel python3-setuptools
python3 -m pip install --user abb-motion-program-exec
```
## Usage
**The robot must be in "Auto" mode for this driver to operate. A non-descriptive error code will be
returned if attempting to execute a motion program in manual mode.**
Once the `abb_motion_program_exec.mod` has been loaded on the controller,
the Python module can be used to command motion sequences. The class
`MotionProgram` contains is used to build the sequence of motions. It has
the following commands of interest:
* `MoveAbsJ(to_joint_pos: jointtarget, speed: speeddata, zone: zonedata)` - Move the
robot to a specified joint waypoint.
* `MoveJ(to_point: robtarget, speed: speeddata, zone: zonedata)` - Move the
robot to the specified Cartesian target using joint interpolation.
* `MoveL(to_point: robtarget, speed: speeddata, zone: zonedata)` - Move
the robot to the specified Cartesian target using linear interpolation.
* `MoveC(cir_point: robtarget, to_point: robtarget, speed: speeddata, zone: zonedata)` -
Move the robot to the specified Cartesian target circularly using an intermediate
waypoint.
* `WaitTime(t: float)` - Wait a specified time in seconds.
Calling each of these functions adds the command to the sequence.
The constructor for `MotionProgram` optionally takes a `tool` parameter.
This parameter is expected to be type `tooldata` and will be passed
to each of the move commands. Because the tool is expected to be a
`PERS` type by the ABB software, it can't be modified for each
motion command without a significant performance penalty.
```python
my_motion_program = MotionProgram(tool=my_tool)
```
The following types are defined as subclasses of `NamedTuple`:
```python
class speeddata(NamedTuple):
v_tcp: float
v_ori: float
v_leax: float
v_reax: float
class zonedata(NamedTuple):
finep: bool
pzone_tcp: float
pzone_ori: float
pzone_eax: float
zone_ori: float
zone_leax: float
zone_reax: float
class jointtarget(NamedTuple):
robax: np.ndarray # shape=(6,)
extax: np.ndarray # shape=(6,)
class pose(NamedTuple):
trans: np.ndarray # [x,y,z]
rot: np.ndarray # [qw,qx,qy,qz]
class confdata(NamedTuple):
cf1: float
cf4: float
cf6: float
cfx: float
class robtarget(NamedTuple):
trans: np.ndarray # [x,y,z]
rot: np.ndarray # [qw,qx,qy,qz]
robconf: confdata #
extax: np.ndarray # shape=(6,)
class loaddata(NamedTuple):
mass: float
cog: np.ndarray # shape=(3,)
aom: np.ndarray # shape=(4,)
ix: float
iy: float
iz: float
class tooldata(NamedTuple):
robhold: bool
tframe: pose
tload : loaddata
```
See the ABB Robotics manual "Technical reference manual RAPID
Instructions, Functions and Data types" for more details on these data
types. Note that `pos`, `orient`, `robjoint`, and `extjoint` are
implemented using numpy arrays or lists.
The following standard `speeddata` are available in the module:
`v5`, `v10`, `v20`, `v30`, `v40`, `v50`, `v60`, `v80`, `v100`,
`v200`, `v300`, `v400`, `v500`, `v600`, `v800`, `v1000`, `v1500`,
`v2000`, `v2500`, `v3000`, `v4000`, `v5000`, `v6000`, `v7000`,
`vmax`.
The following standard `zonedata` are available in the module:
`fine`, `z0`, `z1`, `z5`, `z10`, `z15`, `z20`, `z30`, `z40`,
`z50`, `z60`, `z80`, `z100`, `z150`, `z200`.
The following `tooldata` are available in the module: `tool0`
Once the program is complete, it can be executed on the robot using
`MotionProgramExecClient`. The constructor is by default:
```
mp_client = MotionProgramClient(base_url='http://127.0.0.1:80', username='Default User', password='robotics')
```
The `base_url`, `username`, and `password` should be adjusted to the actual robot. The
client using ABB Web Services. `base_url` must be set to the IP address of the
robot, or using `localhost` if using the simulator.
Once the client is constructed, it can be used to execute the program:
```python
log_results = mp_client.execute_motion_program(mp)
```
`log_results` is a tuple containing the results of the motion:
```python
class MotionProgramResultLog(NamedTuple):
timestamp: str
column_headers: List[str]
data: np.array
```
`timestamp` is a string timestamp for the data. `column_headers` is a list of strings containing the labels of the
columns of data. `data` contains a float32 numpy 2D array of the data, with each row being a sample.
For a single robot, the data has the following columns:
* `timestamp` - The time of the row. This is time from the startup of the logger task in seconds.
Subtract the initial time from all samples to get a 0 start time for the program.
* `cmd_num` - The currently executing command number. Use `get_program_rapid()` to print out
the program with command numbers annotated.
* `J1` - Joint 1 position in degrees
* `J2` - Joint 2 position in degrees
* `J3` - Joint 3 position in degrees
* `J4` - Joint 4 position in degrees
* `J5` - Joint 5 position in degrees
* `J6` - Joint 6 position in degrees
The field `column_headers` contains a list of the column headers.
## Python module installation
The `abb_motion_program_exec` module is available on PyPI and can be installed using pip:
```
pip install abb_motion_program_exec
```
For development, use of a `virtualenv` is recommended. Use editable install with the virtualenv:
```
pip install -e .
```
## Externally Guided Motion (EGM)
See [egm.md](docs/egm.md) for instructions on using EGM.
## Example
```python
import abb_motion_program_exec as abb
j1 = abb.jointtarget([10,20,30,40,50,60],[0]*6)
j2 = abb.jointtarget([-10,15,35,10,95,-95],[0]*6)
j3 = abb.jointtarget([15,-5,25,83,-84,85],[0]*6)
my_tool = abb.tooldata(True,abb.pose([0,0,0.1],[1,0,0,0]),abb.loaddata(0.001,[0,0,0.001],[1,0,0,0],0,0,0))
mp = abb.MotionProgram(tool=my_tool)
mp.MoveAbsJ(j1,abb.v1000,abb.fine)
mp.MoveAbsJ(j2,abb.v5000,abb.fine)
mp.MoveAbsJ(j3,abb.v500,abb.fine)
mp.MoveAbsJ(j2,abb.v5000,abb.z50)
mp.MoveAbsJ(j3,abb.v500,abb.z200)
mp.MoveAbsJ(j2,abb.v5000,abb.fine)
mp.WaitTime(1)
r1 = abb.robtarget([350., -100., 600.], [ 0.0868241, -0.0868241, 0.9924039, 0.0075961 ], abb.confdata(-1,0,-1,0),[0]*6)
r2 = abb.robtarget([370., 120., 620. ], [ 0.0868241, 0.0868241, 0.9924039, -0.0075961], abb.confdata(0,-1,0,0),[0]*6)
r3 = abb.robtarget([400., -200., 500.], [0.7071068, 0., 0.7071068, 0.], abb.confdata( -1., -3., 2., 0.),[0]*6)
r4 = abb.robtarget([400., 0., 580.], [0.7071068, 0., 0.7071068, 0.], abb.confdata(0., -3., 2., 0.), [0]*6)
r5 = abb.robtarget([400., 200., 500.], [0.7071068, 0., 0.7071068, 0.], abb.confdata(0., -2., 1., 0.),[0]*6)
mp.MoveJ(r1,abb.v500,abb.fine)
mp.MoveJ(r2,abb.v400,abb.fine)
mp.MoveJ(r1,abb.v500,abb.z100)
mp.MoveJ(r2,abb.v400,abb.z100)
mp.MoveJ(r1,abb.v500,abb.fine)
mp.WaitTime(1.5)
mp.MoveJ(r3,abb.v5000,abb.fine)
mp.MoveL(r4,abb.v200,abb.fine)
mp.MoveL(r3,abb.v200,abb.fine)
mp.MoveL(r4,abb.v1000,abb.z100)
mp.MoveL(r3,abb.v1000,abb.z100)
mp.MoveL(r4,abb.v1000,abb.fine)
mp.WaitTime(2.5)
mp.MoveJ(r3,abb.v5000,abb.fine)
mp.MoveC(r4,r5,abb.v200,abb.z10)
mp.MoveC(r4,r3,abb.v50,abb.fine)
# Print out RAPID module of motion program for debugging
print(mp.get_program_rapid())
# Execute the motion program on the robot
# Change base_url to the robot IP address
client = abb.MotionProgramExecClient(base_url="http://127.0.0.1:80")
log_results = client.execute_motion_program(mp)
# log_results.data is a numpy array
import matplotlib.pyplot as plt
fig, ax1 = plt.subplots()
lns1 = ax1.plot(log_results.data[:,0], log_results.data[:,2:])
ax1.set_xlabel("Time (s)")
ax1.set_ylabel("Joint angle (deg)")
ax2 = ax1.twinx()
lns2 = ax2.plot(log_results.data[:,0], log_results.data[:,1], '-k')
ax2.set_ylabel("Command number")
ax2.set_yticks(range(-1,int(max(log_results.data[:,1]))+1))
ax1.legend(lns1 + lns2, log_results.column_headers[2:] + ["cmdnum"])
ax1.set_title("Joint motion")
plt.show()
```
## Multi-Move Robot Example
Two robots can be controlled using ABB Multi-Move. See
[robot_multimove_setup_manual.md](docs/robot_multimove_setup_manual.md) for setup instructions.
They must have exactly the same number of motion commands. The commands
are passed with the `\ID` parameter corresponding to the command number. `SyncMoveOn` is activated
to cause the robots to move in sync. The `execute_multimove_motion_program()` function
of `MotionProgramExecClient` is used to send multi-move programs to the robot.
```python
import abb_motion_program_exec as abb
# Fill motion program for T_ROB1
t1 = abb.robtarget([575,-200,1280],[0,-.707,0,.707],abb.confdata(0,0,-1,1),[0]*6)
t2 = abb.robtarget([575,200,1480],[0,-.707,0,.707],abb.confdata(-1,-1,0,1),[0]*6)
t3 = abb.robtarget([575,0,1280],[0,-.707,0,.707],abb.confdata(-1,-1,0,1),[0]*6)
my_tool = abb.tooldata(True,abb.pose([0,0,0.1],[1,0,0,0]),abb.loaddata(0.001,[0,0,0.001],[1,0,0,0],0,0,0))
mp = abb.MotionProgram(tool=my_tool)
mp.SyncMoveOn()
mp.MoveAbsJ(abb.jointtarget([5,-20,30,27,-11,-27],[0]*6),abb.v1000,abb.fine)
mp.MoveL(t1,abb.v1000,abb.fine)
mp.MoveJ(t2,abb.v5000,abb.fine)
mp.MoveL(t3,abb.v500,abb.fine)
mp.WaitTime(1)
mp.MoveL(t1,abb.v5000,abb.z50)
mp.MoveJ(t2,abb.v500,abb.z200)
mp.MoveL(t3,abb.v5000,abb.fine)
# Fill motion program for T_ROB2. Both programs must have
# same number of commands
t1_2 = abb.robtarget([250,-200,1280],[.707,0,.707,0],abb.confdata(-1,-1,0,1),[0]*6)
t2_2 = abb.robtarget([250,200,1480],[.707,0,.707,0],abb.confdata(0,0,-1,1),[0]*6)
t3_2 = abb.robtarget([250,0,1280],[.707,0,.707,0],abb.confdata(0,0,0,1),[0]*6)
my_tool2 = abb.tooldata(True,abb.pose([0,0,0.5],[1,0,0,0]),abb.loaddata(0.1,[0,0,0.1],[1,0,0,0],0,0,0))
mp2 = abb.MotionProgram(tool=my_tool2)
mp2.SyncMoveOn()
mp2.MoveAbsJ(abb.jointtarget([1,1,40,2,-40,-2],[0]*6),abb.v1000,abb.fine)
mp2.MoveJ(t1_2,abb.v1000,abb.fine)
mp2.MoveL(t2_2,abb.v5000,abb.fine)
mp2.MoveL(t3_2,abb.v500,abb.fine)
mp2.WaitTime(1)
mp2.MoveL(t1_2,abb.v5000,abb.z50)
mp2.MoveL(t2_2,abb.v500,abb.z200)
mp2.MoveL(t3_2,abb.v5000,abb.fine)
# Execute the motion program on the robot
# Change base_url to the robot IP address
client = abb.MotionProgramExecClient(base_url="http://127.0.0.1:80")
# Execute both motion programs simultaneously
log_results = client.execute_multimove_motion_program([mp,mp2])
# log_results.data is a numpy array
import matplotlib.pyplot as plt
fig, ax1 = plt.subplots()
lns1 = ax1.plot(log_results.data[:,0], log_results.data[:,2:8])
ax1.set_xlabel("Time (s)")
ax1.set_ylabel("Joint angle (deg)")
ax2 = ax1.twinx()
lns2 = ax2.plot(log_results.data[:,0], log_results.data[:,1], '-k')
ax2.set_ylabel("Command number")
ax2.set_yticks(range(-1,int(max(log_results.data[:,1]))+1))
ax1.legend(lns1 + lns2, log_results.column_headers[2:8] + ["cmdnum"])
ax1.set_title("Robot 1 joint motion")
fig, ax1 = plt.subplots()
lns1 = ax1.plot(log_results.data[:,0], log_results.data[:,8:])
ax1.set_xlabel("Time (s)")
ax1.set_ylabel("Joint angle (deg)")
ax2 = ax1.twinx()
lns2 = ax2.plot(log_results.data[:,0], log_results.data[:,1], '-k')
ax2.set_ylabel("Command number")
ax2.set_yticks(range(-1,int(max(log_results.data[:,1]))+1))
ax1.legend(lns1 + lns2, log_results.column_headers[8:] + ["cmdnum"])
ax1.set_title("Robot 2 joint motion")
plt.show()
```
Multi-Move example using relative work object:
```python
# Multi-Move example using relative robot end effector poses
import abb_motion_program_exec as abb
# Fill motion program for T_ROB1
# Hold constant relative position for this example
t1 = abb.robtarget([0,0,-200],[1,0,0,0],abb.confdata(0,0,1,1),[0]*6)
t2 = t1
t3 = t1
my_tool = abb.tooldata(True,abb.pose([0,0,0],[1,0,0,0]),abb.loaddata(0.001,[0,0,0.001],[1,0,0,0],0,0,0))
my_wobj = abb.wobjdata(False,False,"ROB_2",abb.pose([0,0,0],[1,0,0,0]),abb.pose([0,0,0],[0,0,1,0]))
mp = abb.MotionProgram(tool=my_tool,wobj=my_wobj)
mp.SyncMoveOn()
mp.MoveAbsJ(abb.jointtarget([5,-20,30,27,-11,172],[0]*6),abb.v1000,abb.fine)
mp.WaitTime(0.1)
mp.MoveJ(t1,abb.v1000,abb.fine)
mp.MoveJ(t1,abb.v1000,abb.fine)
mp.MoveL(t1,abb.v1000,abb.fine)
# Fill motion program for T_ROB2. Both programs must have
# same number of commands
t1_2 = abb.robtarget([250,-200,1280],[.707,0,.707,0],abb.confdata(-1,-1,0,1),[0]*6)
t2_2 = abb.robtarget([250,200,1480],[.707,0,.707,0],abb.confdata(0,0,-1,1),[0]*6)
t3_2 = abb.robtarget([250,0,1280],[.707,0,.707,0],abb.confdata(0,0,0,1),[0]*6)
my_tool2 = abb.tooldata(True,abb.pose([0,0,0.5],[1,0,0,0]),abb.loaddata(0.1,[0,0,0.1],[1,0,0,0],0,0,0))
mp2 = abb.MotionProgram(tool=my_tool2)
mp2.SyncMoveOn()
mp2.MoveAbsJ(abb.jointtarget([1,1,40,2,-40,-2],[0]*6),abb.v1000,abb.fine)
mp2.WaitTime(0.1)
mp2.MoveL(t1_2,abb.v1000,abb.fine)
mp2.MoveL(t2_2,abb.v5000,abb.fine)
mp2.MoveL(t3_2,abb.v500,abb.fine)
# Execute the motion program on the robot
# Change base_url to the robot IP address
client = abb.MotionProgramExecClient(base_url="http://127.0.0.1:80")
# Execute both motion programs simultaneously
log_results = client.execute_multimove_motion_program([mp,mp2])
# log_results.data is a numpy array
import matplotlib.pyplot as plt
fig, ax1 = plt.subplots()
lns1 = ax1.plot(log_results.data[:,0], log_results.data[:,2:8])
ax1.set_xlabel("Time (s)")
ax1.set_ylabel("Joint angle (deg)")
ax2 = ax1.twinx()
lns2 = ax2.plot(log_results.data[:,0], log_results.data[:,1], '-k')
ax2.set_ylabel("Command number")
ax2.set_yticks(range(-1,int(max(log_results.data[:,1]))+1))
ax1.legend(lns1 + lns2, log_results.column_headers[2:8] + ["cmdnum"])
ax1.set_title("Robot 1 joint motion")
fig, ax1 = plt.subplots()
lns1 = ax1.plot(log_results.data[:,0], log_results.data[:,8:])
ax1.set_xlabel("Time (s)")
ax1.set_ylabel("Joint angle (deg)")
ax2 = ax1.twinx()
lns2 = ax2.plot(log_results.data[:,0], log_results.data[:,1], '-k')
ax2.set_ylabel("Command number")
ax2.set_yticks(range(-1,int(max(log_results.data[:,1]))+1))
ax1.legend(lns1 + lns2, log_results.column_headers[8:] + ["cmdnum"])
ax1.set_title("Robot 2 joint motion")
plt.show()
```
## Robot Raconteur Service
A Robot Raconteur service is available to allow a client to execute multi-move programs. The service
uses a standards track service definition `experimental.robotics.motion_program` that will provide interoperability
between multiple robot types. Due to the differences in the robot commands between controller implementations there
may be slight differences in the commands between robots, but in general the commands are very similar.
When installing the module, include the `robotraconteur` option to get the required dependencies:
```bash
python -m pip install abb-motion-program-exec[robotraconteur]
```
Start the service, specifying a robot info file:
```
abb-motion-program-exec-robotraconteur --mp-robot-info-file=config/abb_multimove_motion_program_robot_default_config.yml
```
Optionally start using a module if the entrypoint does not work:
```
python -m abb_motion_program_exec.robotraconteur --mp-robot-info-file=config/abb_multimove_motion_program_robot_default_config.yml
```
The following options are supported:
* `--mp-robot-info-file=` - The info file that specifies information about the robot
* `--mp-robot-base-url=` - The connection URL for Robot Web Services on the robot. Defaults to `http://127.0.0.1:80`
for use with Robot Studio virtual controllers. Set `127.0.0.1` to the WAN IP address of the robot.
* `--mp-robot-username=` - The robot controller username. Defaults to "Default User"
* `--mp-robot-password=` - The robot controller password. Defaults to "robotics"
Examples for a single robot and multi-move robots are in the `examples/robotraconteur` directory. The motion
programs make heavy use of `varvalue` types to allow for flexibility in the motion program contents.
The Python type `RR.VarValue` is used to represent the `varvalue` type. See the Robot Raconteur Python documentation
for more inforamtion on how `RR.VarValue` works and why it is necessary.
### Connection Info
* URL: `rr+tcp://localhost:59843?service=mp_robot`
* Node Name: `experimental.robotics.motion_program`
* Device Name: `abb_robot`
* Service Name: `mp_robot`
* Root Object Type: `experimental.robotics.motion_program.MotionProgramRobot`
## License
Apache 2.0 License, Copyright 2022 Wason Technology, LLC, Rensselaer Polytechnic Institute
## Acknowledgment
This work was supported in part by Subaward No. ARM-TEC-21-02-F19 from the Advanced Robotics for Manufacturing ("ARM") Institute under Agreement Number W911NF-17-3-0004 sponsored by the Office of the Secretary of Defense. ARM Project Management was provided by Christopher Adams. The views and conclusions contained in this document are those of the authors and should not be interpreted as representing the official policies, either expressed or implied, of either ARM or the Office of the Secretary of Defense of the U.S. Government. The U.S. Government is authorized to reproduce and distribute reprints for Government purposes, notwithstanding any copyright notation herein.
This work was supported in part by the New York State Empire State Development Division of Science, Technology and Innovation (NYSTAR) under contract C160142.
 
Raw data
{
"_id": null,
"home_page": null,
"name": "abb-motion-program-exec",
"maintainer": null,
"docs_url": null,
"requires_python": ">=3.6",
"maintainer_email": null,
"keywords": null,
"author": null,
"author_email": "John Wason <wason@wasontech.com>",
"download_url": "https://files.pythonhosted.org/packages/a7/e6/b93cfa2413ea9a5d0408e83673d01f62da7e3250c54be6deb0381a89addd/abb_motion_program_exec-0.7.4.tar.gz",
"platform": null,
"description": "# abb_motion_program_exec\r\n\r\n[](https://github.com/rpiRobotics/abb_motion_program_exec)\r\n[](https://pypi.org/project/abb-motion-program-exec/)\r\n\r\n`abb_motion_program_exec` provides a simple way to download and run a sequence of\r\n`MoveAbsJ`, `MoveJ`, `MoveL`, `MoveC`, and `WaitTime` commands on\r\nan ABB IRC5 robot controller. This program is intended to be a proof of\r\nconcept for more sophisticated controller interfaces. Multi-move control of two robots is also\r\nsupported. Externally Guided Motion (EGM) is also supported for joint target, pose target, and path correction modes.\r\n\r\nDocumentation can be found at: https://abb-motion-program-exec.readthedocs.io/\r\n\r\n## Installation\r\n\r\n`abb-motion-program-exec` is avaliable on PyPi.\r\n\r\n```\r\npip install abb-motion-program-exec\r\n```\r\n\r\nBegin by installing the software for the robot controller. This software can be\r\ninstalled manually by copying files to the robot controller and importing configuration files.\r\n\r\n* See [robot_setup_manual.md](docs/robot_setup_manual.md) for setup instructions.\r\n* See [robot_multimove_setup_manual.md](docs/robot_multimove_setup_manual.md) for ABB Multi-Move\r\n setup to control two robots. See later sections of this doc for more information on Multi-Move.\r\n\r\nThis contains the robot-side code, that reads\r\nand executes the contents of `motion_program.bin`. `motion_program.bin`\r\ncontains the sequence of instructions to run, encoded in binary\r\nformat for fast interpretation.\r\n\r\n**Only one instance of a Robot Studio virtual controller can be run at a time.** Only\r\ninstances of Robot Studio can be run at a time running a single virtual controller. This is due to\r\nthe controller using TCP port 80 on the local computer to accept REST commands from Python. If\r\nmore than one controller is started, TCP port 80 will already be in use and can cause unpredictable\r\nbehavior. Restart the computer if connections cannot be made from Python to the controller. Multiple\r\nreal robots can be used concurrently since they will each have a unique IP address to bind port 80.\r\n\r\n### Python 3.6 Linux Install (Ubuntu Bionic)\r\n\r\nOlder versions of Python are not supported by the currently available protobuf package. Use the apt version instead.\r\n\r\n```\r\nsudo apt install python3-virtualenv python3-protobuf python3-numpy python3-wheel python3-setuptools\r\npython3 -m pip install --user abb-motion-program-exec\r\n```\r\n\r\n## Usage\r\n\r\n**The robot must be in \"Auto\" mode for this driver to operate. A non-descriptive error code will be\r\nreturned if attempting to execute a motion program in manual mode.**\r\n\r\nOnce the `abb_motion_program_exec.mod` has been loaded on the controller,\r\nthe Python module can be used to command motion sequences. The class\r\n`MotionProgram` contains is used to build the sequence of motions. It has\r\nthe following commands of interest:\r\n\r\n* `MoveAbsJ(to_joint_pos: jointtarget, speed: speeddata, zone: zonedata)` - Move the\r\n robot to a specified joint waypoint.\r\n* `MoveJ(to_point: robtarget, speed: speeddata, zone: zonedata)` - Move the\r\n robot to the specified Cartesian target using joint interpolation.\r\n* `MoveL(to_point: robtarget, speed: speeddata, zone: zonedata)` - Move\r\n the robot to the specified Cartesian target using linear interpolation.\r\n* `MoveC(cir_point: robtarget, to_point: robtarget, speed: speeddata, zone: zonedata)` -\r\n Move the robot to the specified Cartesian target circularly using an intermediate\r\n waypoint.\r\n* `WaitTime(t: float)` - Wait a specified time in seconds.\r\n\r\nCalling each of these functions adds the command to the sequence.\r\n\r\nThe constructor for `MotionProgram` optionally takes a `tool` parameter.\r\nThis parameter is expected to be type `tooldata` and will be passed\r\nto each of the move commands. Because the tool is expected to be a\r\n`PERS` type by the ABB software, it can't be modified for each\r\nmotion command without a significant performance penalty.\r\n\r\n```python\r\nmy_motion_program = MotionProgram(tool=my_tool)\r\n```\r\n\r\nThe following types are defined as subclasses of `NamedTuple`:\r\n\r\n```python\r\nclass speeddata(NamedTuple):\r\n v_tcp: float\r\n v_ori: float\r\n v_leax: float\r\n v_reax: float\r\n\r\nclass zonedata(NamedTuple):\r\n finep: bool\r\n pzone_tcp: float\r\n pzone_ori: float\r\n pzone_eax: float\r\n zone_ori: float\r\n zone_leax: float\r\n zone_reax: float\r\n\r\nclass jointtarget(NamedTuple):\r\n robax: np.ndarray # shape=(6,)\r\n extax: np.ndarray # shape=(6,)\r\n\r\nclass pose(NamedTuple):\r\n trans: np.ndarray # [x,y,z]\r\n rot: np.ndarray # [qw,qx,qy,qz]\r\n\r\nclass confdata(NamedTuple):\r\n cf1: float\r\n cf4: float\r\n cf6: float\r\n cfx: float\r\n\r\nclass robtarget(NamedTuple):\r\n trans: np.ndarray # [x,y,z]\r\n rot: np.ndarray # [qw,qx,qy,qz]\r\n robconf: confdata # \r\n extax: np.ndarray # shape=(6,)\r\n\r\nclass loaddata(NamedTuple):\r\n mass: float\r\n cog: np.ndarray # shape=(3,)\r\n aom: np.ndarray # shape=(4,)\r\n ix: float\r\n iy: float\r\n iz: float\r\n\r\nclass tooldata(NamedTuple):\r\n robhold: bool\r\n tframe: pose\r\n tload : loaddata\r\n\r\n```\r\n\r\nSee the ABB Robotics manual \"Technical reference manual RAPID \r\nInstructions, Functions and Data types\" for more details on these data\r\ntypes. Note that `pos`, `orient`, `robjoint`, and `extjoint` are\r\nimplemented using numpy arrays or lists.\r\n\r\nThe following standard `speeddata` are available in the module:\r\n`v5`, `v10`, `v20`, `v30`, `v40`, `v50`, `v60`, `v80`, `v100`,\r\n`v200`, `v300`, `v400`, `v500`, `v600`, `v800`, `v1000`, `v1500`,\r\n`v2000`, `v2500`, `v3000`, `v4000`, `v5000`, `v6000`, `v7000`,\r\n`vmax`.\r\n\r\nThe following standard `zonedata` are available in the module:\r\n`fine`, `z0`, `z1`, `z5`, `z10`, `z15`, `z20`, `z30`, `z40`,\r\n`z50`, `z60`, `z80`, `z100`, `z150`, `z200`.\r\n\r\nThe following `tooldata` are available in the module: `tool0`\r\n\r\nOnce the program is complete, it can be executed on the robot using\r\n`MotionProgramExecClient`. The constructor is by default:\r\n\r\n```\r\nmp_client = MotionProgramClient(base_url='http://127.0.0.1:80', username='Default User', password='robotics')\r\n```\r\n\r\nThe `base_url`, `username`, and `password` should be adjusted to the actual robot. The\r\nclient using ABB Web Services. `base_url` must be set to the IP address of the\r\nrobot, or using `localhost` if using the simulator.\r\n\r\nOnce the client is constructed, it can be used to execute the program:\r\n\r\n```python\r\nlog_results = mp_client.execute_motion_program(mp)\r\n```\r\n\r\n`log_results` is a tuple containing the results of the motion:\r\n\r\n```python\r\nclass MotionProgramResultLog(NamedTuple):\r\n timestamp: str\r\n column_headers: List[str]\r\n data: np.array\r\n```\r\n\r\n`timestamp` is a string timestamp for the data. `column_headers` is a list of strings containing the labels of the\r\ncolumns of data. `data` contains a float32 numpy 2D array of the data, with each row being a sample.\r\n\r\nFor a single robot, the data has the following columns:\r\n\r\n* `timestamp` - The time of the row. This is time from the startup of the logger task in seconds.\r\n Subtract the initial time from all samples to get a 0 start time for the program.\r\n* `cmd_num` - The currently executing command number. Use `get_program_rapid()` to print out\r\n the program with command numbers annotated.\r\n* `J1` - Joint 1 position in degrees\r\n* `J2` - Joint 2 position in degrees\r\n* `J3` - Joint 3 position in degrees\r\n* `J4` - Joint 4 position in degrees\r\n* `J5` - Joint 5 position in degrees\r\n* `J6` - Joint 6 position in degrees\r\n\r\nThe field `column_headers` contains a list of the column headers.\r\n\r\n## Python module installation\r\n\r\nThe `abb_motion_program_exec` module is available on PyPI and can be installed using pip:\r\n\r\n```\r\npip install abb_motion_program_exec\r\n```\r\n\r\nFor development, use of a `virtualenv` is recommended. Use editable install with the virtualenv:\r\n\r\n```\r\npip install -e .\r\n```\r\n\r\n## Externally Guided Motion (EGM)\r\n\r\nSee [egm.md](docs/egm.md) for instructions on using EGM.\r\n\r\n## Example\r\n\r\n```python\r\nimport abb_motion_program_exec as abb\r\n\r\nj1 = abb.jointtarget([10,20,30,40,50,60],[0]*6)\r\nj2 = abb.jointtarget([-10,15,35,10,95,-95],[0]*6)\r\nj3 = abb.jointtarget([15,-5,25,83,-84,85],[0]*6)\r\n\r\nmy_tool = abb.tooldata(True,abb.pose([0,0,0.1],[1,0,0,0]),abb.loaddata(0.001,[0,0,0.001],[1,0,0,0],0,0,0)) \r\n\r\nmp = abb.MotionProgram(tool=my_tool)\r\nmp.MoveAbsJ(j1,abb.v1000,abb.fine)\r\nmp.MoveAbsJ(j2,abb.v5000,abb.fine)\r\nmp.MoveAbsJ(j3,abb.v500,abb.fine)\r\nmp.MoveAbsJ(j2,abb.v5000,abb.z50)\r\nmp.MoveAbsJ(j3,abb.v500,abb.z200)\r\nmp.MoveAbsJ(j2,abb.v5000,abb.fine)\r\nmp.WaitTime(1)\r\n\r\nr1 = abb.robtarget([350., -100., 600.], [ 0.0868241, -0.0868241, 0.9924039, 0.0075961 ], abb.confdata(-1,0,-1,0),[0]*6)\r\nr2 = abb.robtarget([370., 120., 620. ], [ 0.0868241, 0.0868241, 0.9924039, -0.0075961], abb.confdata(0,-1,0,0),[0]*6)\r\n\r\nr3 = abb.robtarget([400., -200., 500.], [0.7071068, 0., 0.7071068, 0.], abb.confdata( -1., -3., 2., 0.),[0]*6)\r\nr4 = abb.robtarget([400., 0., 580.], [0.7071068, 0., 0.7071068, 0.], abb.confdata(0., -3., 2., 0.), [0]*6)\r\nr5 = abb.robtarget([400., 200., 500.], [0.7071068, 0., 0.7071068, 0.], abb.confdata(0., -2., 1., 0.),[0]*6)\r\n\r\nmp.MoveJ(r1,abb.v500,abb.fine)\r\nmp.MoveJ(r2,abb.v400,abb.fine)\r\nmp.MoveJ(r1,abb.v500,abb.z100)\r\nmp.MoveJ(r2,abb.v400,abb.z100)\r\nmp.MoveJ(r1,abb.v500,abb.fine)\r\nmp.WaitTime(1.5)\r\n\r\nmp.MoveJ(r3,abb.v5000,abb.fine)\r\nmp.MoveL(r4,abb.v200,abb.fine)\r\nmp.MoveL(r3,abb.v200,abb.fine)\r\nmp.MoveL(r4,abb.v1000,abb.z100)\r\nmp.MoveL(r3,abb.v1000,abb.z100)\r\nmp.MoveL(r4,abb.v1000,abb.fine)\r\nmp.WaitTime(2.5)\r\n\r\nmp.MoveJ(r3,abb.v5000,abb.fine)\r\n\r\nmp.MoveC(r4,r5,abb.v200,abb.z10)\r\nmp.MoveC(r4,r3,abb.v50,abb.fine)\r\n\r\n# Print out RAPID module of motion program for debugging\r\nprint(mp.get_program_rapid())\r\n\r\n# Execute the motion program on the robot\r\n# Change base_url to the robot IP address\r\nclient = abb.MotionProgramExecClient(base_url=\"http://127.0.0.1:80\")\r\nlog_results = client.execute_motion_program(mp)\r\n\r\n# log_results.data is a numpy array\r\nimport matplotlib.pyplot as plt\r\nfig, ax1 = plt.subplots()\r\nlns1 = ax1.plot(log_results.data[:,0], log_results.data[:,2:])\r\nax1.set_xlabel(\"Time (s)\")\r\nax1.set_ylabel(\"Joint angle (deg)\")\r\nax2 = ax1.twinx()\r\nlns2 = ax2.plot(log_results.data[:,0], log_results.data[:,1], '-k')\r\nax2.set_ylabel(\"Command number\")\r\nax2.set_yticks(range(-1,int(max(log_results.data[:,1]))+1))\r\nax1.legend(lns1 + lns2, log_results.column_headers[2:] + [\"cmdnum\"])\r\nax1.set_title(\"Joint motion\")\r\nplt.show()\r\n\r\n```\r\n\r\n\r\n## Multi-Move Robot Example\r\n\r\nTwo robots can be controlled using ABB Multi-Move. See \r\n[robot_multimove_setup_manual.md](docs/robot_multimove_setup_manual.md) for setup instructions.\r\n\r\nThey must have exactly the same number of motion commands. The commands\r\nare passed with the `\\ID` parameter corresponding to the command number. `SyncMoveOn` is activated\r\nto cause the robots to move in sync. The `execute_multimove_motion_program()` function\r\nof `MotionProgramExecClient` is used to send multi-move programs to the robot.\r\n\r\n```python\r\nimport abb_motion_program_exec as abb\r\n\r\n# Fill motion program for T_ROB1\r\nt1 = abb.robtarget([575,-200,1280],[0,-.707,0,.707],abb.confdata(0,0,-1,1),[0]*6)\r\nt2 = abb.robtarget([575,200,1480],[0,-.707,0,.707],abb.confdata(-1,-1,0,1),[0]*6)\r\nt3 = abb.robtarget([575,0,1280],[0,-.707,0,.707],abb.confdata(-1,-1,0,1),[0]*6)\r\n\r\nmy_tool = abb.tooldata(True,abb.pose([0,0,0.1],[1,0,0,0]),abb.loaddata(0.001,[0,0,0.001],[1,0,0,0],0,0,0)) \r\n\r\nmp = abb.MotionProgram(tool=my_tool)\r\nmp.SyncMoveOn()\r\nmp.MoveAbsJ(abb.jointtarget([5,-20,30,27,-11,-27],[0]*6),abb.v1000,abb.fine)\r\nmp.MoveL(t1,abb.v1000,abb.fine)\r\nmp.MoveJ(t2,abb.v5000,abb.fine)\r\nmp.MoveL(t3,abb.v500,abb.fine)\r\nmp.WaitTime(1)\r\nmp.MoveL(t1,abb.v5000,abb.z50)\r\nmp.MoveJ(t2,abb.v500,abb.z200)\r\nmp.MoveL(t3,abb.v5000,abb.fine)\r\n\r\n# Fill motion program for T_ROB2. Both programs must have\r\n# same number of commands\r\nt1_2 = abb.robtarget([250,-200,1280],[.707,0,.707,0],abb.confdata(-1,-1,0,1),[0]*6)\r\nt2_2 = abb.robtarget([250,200,1480],[.707,0,.707,0],abb.confdata(0,0,-1,1),[0]*6)\r\nt3_2 = abb.robtarget([250,0,1280],[.707,0,.707,0],abb.confdata(0,0,0,1),[0]*6)\r\n\r\nmy_tool2 = abb.tooldata(True,abb.pose([0,0,0.5],[1,0,0,0]),abb.loaddata(0.1,[0,0,0.1],[1,0,0,0],0,0,0)) \r\n\r\nmp2 = abb.MotionProgram(tool=my_tool2)\r\nmp2.SyncMoveOn()\r\nmp2.MoveAbsJ(abb.jointtarget([1,1,40,2,-40,-2],[0]*6),abb.v1000,abb.fine)\r\nmp2.MoveJ(t1_2,abb.v1000,abb.fine)\r\nmp2.MoveL(t2_2,abb.v5000,abb.fine)\r\nmp2.MoveL(t3_2,abb.v500,abb.fine)\r\nmp2.WaitTime(1)\r\nmp2.MoveL(t1_2,abb.v5000,abb.z50)\r\nmp2.MoveL(t2_2,abb.v500,abb.z200)\r\nmp2.MoveL(t3_2,abb.v5000,abb.fine)\r\n\r\n\r\n# Execute the motion program on the robot\r\n# Change base_url to the robot IP address\r\nclient = abb.MotionProgramExecClient(base_url=\"http://127.0.0.1:80\")\r\n\r\n# Execute both motion programs simultaneously\r\nlog_results = client.execute_multimove_motion_program([mp,mp2])\r\n\r\n# log_results.data is a numpy array\r\nimport matplotlib.pyplot as plt\r\nfig, ax1 = plt.subplots()\r\nlns1 = ax1.plot(log_results.data[:,0], log_results.data[:,2:8])\r\nax1.set_xlabel(\"Time (s)\")\r\nax1.set_ylabel(\"Joint angle (deg)\")\r\nax2 = ax1.twinx()\r\nlns2 = ax2.plot(log_results.data[:,0], log_results.data[:,1], '-k')\r\nax2.set_ylabel(\"Command number\")\r\nax2.set_yticks(range(-1,int(max(log_results.data[:,1]))+1))\r\nax1.legend(lns1 + lns2, log_results.column_headers[2:8] + [\"cmdnum\"])\r\nax1.set_title(\"Robot 1 joint motion\")\r\nfig, ax1 = plt.subplots()\r\nlns1 = ax1.plot(log_results.data[:,0], log_results.data[:,8:])\r\nax1.set_xlabel(\"Time (s)\")\r\nax1.set_ylabel(\"Joint angle (deg)\")\r\nax2 = ax1.twinx()\r\nlns2 = ax2.plot(log_results.data[:,0], log_results.data[:,1], '-k')\r\nax2.set_ylabel(\"Command number\")\r\nax2.set_yticks(range(-1,int(max(log_results.data[:,1]))+1))\r\nax1.legend(lns1 + lns2, log_results.column_headers[8:] + [\"cmdnum\"])\r\nax1.set_title(\"Robot 2 joint motion\")\r\nplt.show()\r\n```\r\n\r\nMulti-Move example using relative work object:\r\n\r\n```python\r\n# Multi-Move example using relative robot end effector poses\r\n\r\nimport abb_motion_program_exec as abb\r\n\r\n\r\n# Fill motion program for T_ROB1\r\n\r\n# Hold constant relative position for this example\r\nt1 = abb.robtarget([0,0,-200],[1,0,0,0],abb.confdata(0,0,1,1),[0]*6)\r\nt2 = t1\r\nt3 = t1\r\n\r\n\r\nmy_tool = abb.tooldata(True,abb.pose([0,0,0],[1,0,0,0]),abb.loaddata(0.001,[0,0,0.001],[1,0,0,0],0,0,0))\r\nmy_wobj = abb.wobjdata(False,False,\"ROB_2\",abb.pose([0,0,0],[1,0,0,0]),abb.pose([0,0,0],[0,0,1,0]))\r\n\r\nmp = abb.MotionProgram(tool=my_tool,wobj=my_wobj)\r\nmp.SyncMoveOn()\r\nmp.MoveAbsJ(abb.jointtarget([5,-20,30,27,-11,172],[0]*6),abb.v1000,abb.fine)\r\nmp.WaitTime(0.1)\r\nmp.MoveJ(t1,abb.v1000,abb.fine)\r\nmp.MoveJ(t1,abb.v1000,abb.fine)\r\nmp.MoveL(t1,abb.v1000,abb.fine)\r\n\r\n# Fill motion program for T_ROB2. Both programs must have\r\n# same number of commands\r\nt1_2 = abb.robtarget([250,-200,1280],[.707,0,.707,0],abb.confdata(-1,-1,0,1),[0]*6)\r\nt2_2 = abb.robtarget([250,200,1480],[.707,0,.707,0],abb.confdata(0,0,-1,1),[0]*6)\r\nt3_2 = abb.robtarget([250,0,1280],[.707,0,.707,0],abb.confdata(0,0,0,1),[0]*6)\r\n\r\nmy_tool2 = abb.tooldata(True,abb.pose([0,0,0.5],[1,0,0,0]),abb.loaddata(0.1,[0,0,0.1],[1,0,0,0],0,0,0)) \r\n\r\nmp2 = abb.MotionProgram(tool=my_tool2)\r\nmp2.SyncMoveOn()\r\nmp2.MoveAbsJ(abb.jointtarget([1,1,40,2,-40,-2],[0]*6),abb.v1000,abb.fine)\r\nmp2.WaitTime(0.1)\r\nmp2.MoveL(t1_2,abb.v1000,abb.fine)\r\nmp2.MoveL(t2_2,abb.v5000,abb.fine)\r\nmp2.MoveL(t3_2,abb.v500,abb.fine)\r\n\r\n# Execute the motion program on the robot\r\n# Change base_url to the robot IP address\r\nclient = abb.MotionProgramExecClient(base_url=\"http://127.0.0.1:80\")\r\n\r\n# Execute both motion programs simultaneously\r\nlog_results = client.execute_multimove_motion_program([mp,mp2])\r\n\r\n# log_results.data is a numpy array\r\nimport matplotlib.pyplot as plt\r\nfig, ax1 = plt.subplots()\r\nlns1 = ax1.plot(log_results.data[:,0], log_results.data[:,2:8])\r\nax1.set_xlabel(\"Time (s)\")\r\nax1.set_ylabel(\"Joint angle (deg)\")\r\nax2 = ax1.twinx()\r\nlns2 = ax2.plot(log_results.data[:,0], log_results.data[:,1], '-k')\r\nax2.set_ylabel(\"Command number\")\r\nax2.set_yticks(range(-1,int(max(log_results.data[:,1]))+1))\r\nax1.legend(lns1 + lns2, log_results.column_headers[2:8] + [\"cmdnum\"])\r\nax1.set_title(\"Robot 1 joint motion\")\r\nfig, ax1 = plt.subplots()\r\nlns1 = ax1.plot(log_results.data[:,0], log_results.data[:,8:])\r\nax1.set_xlabel(\"Time (s)\")\r\nax1.set_ylabel(\"Joint angle (deg)\")\r\nax2 = ax1.twinx()\r\nlns2 = ax2.plot(log_results.data[:,0], log_results.data[:,1], '-k')\r\nax2.set_ylabel(\"Command number\")\r\nax2.set_yticks(range(-1,int(max(log_results.data[:,1]))+1))\r\nax1.legend(lns1 + lns2, log_results.column_headers[8:] + [\"cmdnum\"])\r\nax1.set_title(\"Robot 2 joint motion\")\r\nplt.show()\r\n\r\n```\r\n\r\n## Robot Raconteur Service\r\n\r\nA Robot Raconteur service is available to allow a client to execute multi-move programs. The service\r\nuses a standards track service definition `experimental.robotics.motion_program` that will provide interoperability\r\nbetween multiple robot types. Due to the differences in the robot commands between controller implementations there \r\nmay be slight differences in the commands between robots, but in general the commands are very similar.\r\n\r\nWhen installing the module, include the `robotraconteur` option to get the required dependencies:\r\n\r\n```bash\r\npython -m pip install abb-motion-program-exec[robotraconteur]\r\n```\r\n\r\nStart the service, specifying a robot info file:\r\n\r\n```\r\nabb-motion-program-exec-robotraconteur --mp-robot-info-file=config/abb_multimove_motion_program_robot_default_config.yml\r\n```\r\n\r\nOptionally start using a module if the entrypoint does not work:\r\n\r\n```\r\npython -m abb_motion_program_exec.robotraconteur --mp-robot-info-file=config/abb_multimove_motion_program_robot_default_config.yml\r\n```\r\n\r\nThe following options are supported:\r\n\r\n* `--mp-robot-info-file=` - The info file that specifies information about the robot\r\n* `--mp-robot-base-url=` - The connection URL for Robot Web Services on the robot. Defaults to `http://127.0.0.1:80`\r\n for use with Robot Studio virtual controllers. Set `127.0.0.1` to the WAN IP address of the robot.\r\n* `--mp-robot-username=` - The robot controller username. Defaults to \"Default User\"\r\n* `--mp-robot-password=` - The robot controller password. Defaults to \"robotics\"\r\n\r\nExamples for a single robot and multi-move robots are in the `examples/robotraconteur` directory. The motion\r\nprograms make heavy use of `varvalue` types to allow for flexibility in the motion program contents.\r\nThe Python type `RR.VarValue` is used to represent the `varvalue` type. See the Robot Raconteur Python documentation\r\nfor more inforamtion on how `RR.VarValue` works and why it is necessary.\r\n\r\n### Connection Info\r\n\r\n* URL: `rr+tcp://localhost:59843?service=mp_robot`\r\n* Node Name: `experimental.robotics.motion_program`\r\n* Device Name: `abb_robot`\r\n* Service Name: `mp_robot`\r\n* Root Object Type: `experimental.robotics.motion_program.MotionProgramRobot`\r\n\r\n## License\r\n\r\nApache 2.0 License, Copyright 2022 Wason Technology, LLC, Rensselaer Polytechnic Institute\r\n\r\n## Acknowledgment\r\n\r\nThis work was supported in part by Subaward No. ARM-TEC-21-02-F19 from the Advanced Robotics for Manufacturing (\"ARM\") Institute under Agreement Number W911NF-17-3-0004 sponsored by the Office of the Secretary of Defense. ARM Project Management was provided by Christopher Adams. The views and conclusions contained in this document are those of the authors and should not be interpreted as representing the official policies, either expressed or implied, of either ARM or the Office of the Secretary of Defense of the U.S. Government. The U.S. Government is authorized to reproduce and distribute reprints for Government purposes, notwithstanding any copyright notation herein.\r\n\r\nThis work was supported in part by the New York State Empire State Development Division of Science, Technology and Innovation (NYSTAR) under contract C160142. \r\n\r\n \r\n",
"bugtrack_url": null,
"license": "Apache-2.0",
"summary": "Python package to execute motion commands on ABB robots and log results",
"version": "0.7.4",
"project_urls": {
"documentation": "https://abb-motion-program-exec.readthedocs.io/en/latest/",
"homepage": "https://github.com/rpiRobotics/abb_motion_program_exec",
"repository": "https://github.com/rpiRobotics/abb_motion_program_exec"
},
"split_keywords": [],
"urls": [
{
"comment_text": "",
"digests": {
"blake2b_256": "2db56dc53b34e6d3e85c1c569ed09377e8474a4e0a16554a2b87c4e3b2811557",
"md5": "aee6ad5b41b3691ed4cbf2859096df53",
"sha256": "022555430b9eb3ad37ed5269684bec20f20fb9058a9892ad862abf373f089eaf"
},
"downloads": -1,
"filename": "abb_motion_program_exec-0.7.4-py3-none-any.whl",
"has_sig": false,
"md5_digest": "aee6ad5b41b3691ed4cbf2859096df53",
"packagetype": "bdist_wheel",
"python_version": "py3",
"requires_python": ">=3.6",
"size": 41199,
"upload_time": "2024-10-25T20:20:04",
"upload_time_iso_8601": "2024-10-25T20:20:04.689587Z",
"url": "https://files.pythonhosted.org/packages/2d/b5/6dc53b34e6d3e85c1c569ed09377e8474a4e0a16554a2b87c4e3b2811557/abb_motion_program_exec-0.7.4-py3-none-any.whl",
"yanked": false,
"yanked_reason": null
},
{
"comment_text": "",
"digests": {
"blake2b_256": "a7e6b93cfa2413ea9a5d0408e83673d01f62da7e3250c54be6deb0381a89addd",
"md5": "d9ff8d07c25b53d04ea91b9287419764",
"sha256": "941f6fc2b78dfda1c81737535d21e4be0eaade92572e250a18bbf5c45a46cc80"
},
"downloads": -1,
"filename": "abb_motion_program_exec-0.7.4.tar.gz",
"has_sig": false,
"md5_digest": "d9ff8d07c25b53d04ea91b9287419764",
"packagetype": "sdist",
"python_version": "source",
"requires_python": ">=3.6",
"size": 36971,
"upload_time": "2024-10-25T20:20:05",
"upload_time_iso_8601": "2024-10-25T20:20:05.983391Z",
"url": "https://files.pythonhosted.org/packages/a7/e6/b93cfa2413ea9a5d0408e83673d01f62da7e3250c54be6deb0381a89addd/abb_motion_program_exec-0.7.4.tar.gz",
"yanked": false,
"yanked_reason": null
}
],
"upload_time": "2024-10-25 20:20:05",
"github": true,
"gitlab": false,
"bitbucket": false,
"codeberg": false,
"github_user": "rpiRobotics",
"github_project": "abb_motion_program_exec",
"travis_ci": false,
"coveralls": false,
"github_actions": false,
"lcname": "abb-motion-program-exec"
}