AS: redame updated
This commit is contained in:
parent
ff8d5ee281
commit
161bb068df
31
README.md
31
README.md
@ -3,7 +3,7 @@
|
|||||||
|
|
||||||
## Description
|
## Description
|
||||||
|
|
||||||
This repository provides an interface that connects OSC with ROS 2. It allows coltroling robotic manipulators using OSC messages.
|
This repository provides an interface that connects OSC with ROS 2. It allows controlling robotic manipulators using OSC messages.
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
@ -28,13 +28,13 @@ Run the test container:
|
|||||||
docker run --rm hello-world
|
docker run --rm hello-world
|
||||||
```
|
```
|
||||||
|
|
||||||
In this repository there are three folders, two of them are docker containers. The first docker container to be installed will be the [`URSim`](./URSim) docker container. A docker container consists of a file describing what the operating system of the docker container looks like (and from which docker container it is derived). Our URSim docker container is derived from the latest [`e-series`](https://hub.docker.com/r/universalrobots/ursim_e-series) URSim container. The only modification added to it is the installtion of the [`external-control`](https://github.com/UniversalRobots/Universal_Robots_ExternalControl_URCap) urcaps. All this is stated in [`URSim/Dockerfile`](./URSim/Dockerfile).
|
In this repository there are three folders, two of them are Docker containers. The first Docker container to be installed will be the [`URSim`](./URSim) Docker container. A Docker container consists of a file describing what the operating system of the Docker container looks like (and from which Docker container it is derived). Our URSim Docker container is derived from the latest [`e-series`](https://hub.docker.com/r/universalrobots/ursim_e-series) URSim container. The only modification added to it is the installation of the [`external-control`](https://github.com/UniversalRobots/Universal_Robots_ExternalControl_URCap) urcaps. All this is stated in [`URSim/Dockerfile`](./URSim/Dockerfile).
|
||||||
|
|
||||||
The Second docker container in this repository is the [`ROS2_humble`](./ROS2_humble) container. From its name it contains the ROS2 operating system and environment. Its [`Dockerfile`](./ROS2_humble/Dockerfile) is also relatively simple. It iterates over the [`ros-humble-desktop-full`](https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver) container by installing the [`ros-humble-ur`](https://hub.docker.com/r/osrf/ros/tags?name=humble-desktop-full) package as well as other utilities for network scanning ([`nmap`](https://nmap.org/)), text editing ([`neovim`](https://neovim.io/)) and terminal multiplexing ([`tmux`](https://github.com/tmux/tmux/wiki)).
|
The second Docker container in this repository is the [`ROS 2_Humble`](./ROS 2_Humble) container. From its name it contains the ROS 2 operating system and environment. Its [`Dockerfile`](./ROS 2_Humble/Dockerfile) is also relatively simple. It iterates over the [`ros-humble-desktop-full`](https://github.com/UniversalRobots/Universal_Robots_ROS 2_Driver) container by installing the [`ros-humble-ur`](https://hub.docker.com/r/osrf/ros/tags?name=humble-desktop-full) package as well as other utilities for network scanning ([`nmap`](https://nmap.org/)), text editing ([`neovim`](https://neovim.io/)) and terminal multiplexing ([`tmux`](https://github.com/tmux/tmux/wiki)).
|
||||||
|
|
||||||
# Usage
|
# Starting the Docker containers
|
||||||
|
|
||||||
To start using these docker containers together a bridge network must be established first.
|
To start using these Docker containers together a bridge network must be established first.
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
docker network create ros_ursim # The name of the network is `ros_ursim`
|
docker network create ros_ursim # The name of the network is `ros_ursim`
|
||||||
@ -50,10 +50,10 @@ docker build -t ursim:latest URSim
|
|||||||
|
|
||||||
This command builds the container defined in [`URSim/Dockerfile`](./URSim/Dockerfile) with the `ursim:latest` tag, so that we can easily run it later.
|
This command builds the container defined in [`URSim/Dockerfile`](./URSim/Dockerfile) with the `ursim:latest` tag, so that we can easily run it later.
|
||||||
|
|
||||||
The same can be done for the ROS2_humble container
|
The same can be done for the ROS 2_Humble container
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
docker build -t ros2_humble:latest ROS2_humble
|
docker build -t ros2_humble:latest ROS 2_Humble
|
||||||
```
|
```
|
||||||
|
|
||||||
After all the containers are successfully built and the bridge network is established we can now start both containers. On one terminal run the following command to start the URSim container
|
After all the containers are successfully built and the bridge network is established we can now start both containers. On one terminal run the following command to start the URSim container
|
||||||
@ -124,8 +124,9 @@ Finally, we can run ROS2 scripts to control the robot. For example
|
|||||||
```
|
```
|
||||||
ros2 launch ur_robot_driver test_scaled_joint_trajectory_controller.launch.py
|
ros2 launch ur_robot_driver test_scaled_joint_trajectory_controller.launch.py
|
||||||
```
|
```
|
||||||
|
|
||||||
If everything worked, this should either move the robot or complain about it being in a strange position.
|
If everything worked, this should either move the robot or complain about it being in a strange position.
|
||||||
|
|
||||||
|
|
||||||
---
|
---
|
||||||
## Installation Instructions for the Interface
|
## Installation Instructions for the Interface
|
||||||
|
|
||||||
@ -218,15 +219,22 @@ The interace asks for workspace and end-effector limits only if a URDF was provi
|
|||||||
|
|
||||||
Now you can also add joint limits. If you have a URDF provided the current joint limits will be shown. You can enter new joint limits if you want. For the ur10e at the Ligeti Center it is helpfull to set the joint limits of
|
Now you can also add joint limits. If you have a URDF provided the current joint limits will be shown. You can enter new joint limits if you want. For the ur10e at the Ligeti Center it is helpfull to set the joint limits of
|
||||||
|
|
||||||
|
## Refresh Rate
|
||||||
|
|
||||||
|
Enter the refreshrate. This is the rate at which the interface will check for new OSC commands and executes them.
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
|
# Usage
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
## Supported OSC Commands
|
## Supported OSC Commands
|
||||||
|
|
||||||
| Address | Data Format | Description |
|
| Address | Data Format | Description |
|
||||||
|-------------------------------|-----------------------------------------------------------|----------------------------------------|
|
|-------------------------------|-----------------------------------------------------------|----------------------------------------|
|
||||||
| `/joint_positions` | `[q1, ..., qN]` or `[q1, ..., qN, duration]` | Move all joints |
|
| `/joint_positions` | `[q1, ..., qN]` or `[q1, ..., qN, duration]` | Move all joints |
|
||||||
| `/joint_positions/{joint}` | `q1` or `[q1, duration]` | Set one joint only |
|
| `/joint_position/{joint}` | `q1` or `[q1, duration]` | Set one joint only |
|
||||||
| `/tcp_coordinates` | `[x, y, z, roll, pitch, yaw]` or with duration | Move to Cartesian pose |
|
| `/tcp_coordinates` | `[x, y, z, roll, pitch, yaw]` or with duration | Move to Cartesian pose |
|
||||||
| `/joint_trajectory` | `[[q1,...], [q2,...], ...]` | Follow a joint-space trajectory |
|
| `/joint_trajectory` | `[[q1,...], [q2,...], ...]` | Follow a joint-space trajectory |
|
||||||
| `/cartesian_trajectory` | `[[x1,...], [x2,...], ...]` | Follow a Cartesian-space trajectory |
|
| `/cartesian_trajectory` | `[[x1,...], [x2,...], ...]` | Follow a Cartesian-space trajectory |
|
||||||
@ -236,11 +244,10 @@ Now you can also add joint limits. If you have a URDF provided the current joint
|
|||||||
|
|
||||||
## Example Usage
|
## Example Usage
|
||||||
|
|
||||||
An example patch in puredata is provided that allows the user to control a 6-DOF robot with sliders via OSC.
|
An example patch in puredata is provided that allows control of a 6-DOF robot with sliders via OSC.
|
||||||
|
|
||||||
---
|
---
|
||||||
|
|
||||||
[^1]: [What is Docker?](https://docs.docker.com/get-started/)
|
[^1]: [What is Docker?](https://docs.docker.com/get-started/)
|
||||||
[^2]: [WSL2 & Docker Networking](https://stackoverflow.com/questions/65426891)
|
[^2]: [WSL2 & Docker Networking](https://stackoverflow.com/questions/65426891)
|
||||||
[^3]: [USB Device in Docker](https://stackoverflow.com/questions/46467295)
|
[^3]: [Cisco VPN and WSL2](https://github.com/Microsoft/WSL/issues/4277)
|
||||||
[^4]: [Cisco VPN and WSL2](https://github.com/Microsoft/WSL/issues/4277)
|
|
@ -349,10 +349,12 @@ class OSC_ROS2_interface(Node):
|
|||||||
"""Handles incoming OSC messages for joint positions."""
|
"""Handles incoming OSC messages for joint positions."""
|
||||||
try:
|
try:
|
||||||
joint_name = address.split("/")[-1]
|
joint_name = address.split("/")[-1]
|
||||||
|
|
||||||
if joint_name in self.joint_names:
|
if joint_name in self.joint_names:
|
||||||
if len(args) == 1:
|
if len(args) == 1:
|
||||||
position = float(args[0])
|
position = float(args[0])
|
||||||
index = self.joint_names.index(joint_name)
|
index = self.joint_names.index(joint_name)
|
||||||
|
if self.robot:
|
||||||
if position < self.robot.qlim[0][index]:
|
if position < self.robot.qlim[0][index]:
|
||||||
position = self.robot.qlim[0][index]
|
position = self.robot.qlim[0][index]
|
||||||
self.get_logger().warn(
|
self.get_logger().warn(
|
||||||
@ -363,6 +365,17 @@ class OSC_ROS2_interface(Node):
|
|||||||
self.get_logger().warn(
|
self.get_logger().warn(
|
||||||
f"joint_position_handler: Joint '{joint_name}' position {position} is out of bounds. Using {self.robot.qlim[1][index]}."
|
f"joint_position_handler: Joint '{joint_name}' position {position} is out of bounds. Using {self.robot.qlim[1][index]}."
|
||||||
)
|
)
|
||||||
|
else:
|
||||||
|
if self.joint_lim[0][index] is not None and position < self.joint_lim[0][index]:
|
||||||
|
position = self.joint_lim[0][index]
|
||||||
|
self.get_logger().warn(
|
||||||
|
f"joint_position_handler: Joint '{joint_name}' position {position} is out of bounds. Using {self.joint_lim[0][index]}."
|
||||||
|
)
|
||||||
|
elif self.joint_lim[1][index] is not None and position > self.joint_lim[1][index]:
|
||||||
|
position = self.joint_lim[1][index]
|
||||||
|
self.get_logger().warn(
|
||||||
|
f"joint_position_handler: Joint '{joint_name}' position {position} is out of bounds. Using {self.joint_lim[1][index]}."
|
||||||
|
)
|
||||||
desired_joint_positions = self.current_joint_positions
|
desired_joint_positions = self.current_joint_positions
|
||||||
desired_joint_positions[index] = position
|
desired_joint_positions[index] = position
|
||||||
self.desired = ["joint_positions"] + desired_joint_positions
|
self.desired = ["joint_positions"] + desired_joint_positions
|
||||||
@ -371,6 +384,7 @@ class OSC_ROS2_interface(Node):
|
|||||||
position = float(args[0])
|
position = float(args[0])
|
||||||
duration = float(args[1])
|
duration = float(args[1])
|
||||||
index = self.joint_names.index(joint_name)
|
index = self.joint_names.index(joint_name)
|
||||||
|
if self.robot:
|
||||||
if position < self.robot.qlim[0][index]:
|
if position < self.robot.qlim[0][index]:
|
||||||
position = self.robot.qlim[0][index]
|
position = self.robot.qlim[0][index]
|
||||||
self.get_logger().warn(
|
self.get_logger().warn(
|
||||||
@ -381,6 +395,17 @@ class OSC_ROS2_interface(Node):
|
|||||||
self.get_logger().warn(
|
self.get_logger().warn(
|
||||||
f"joint_position_handler: Joint '{joint_name}' position {position} is out of bounds. Using {self.robot.qlim[1][index]}."
|
f"joint_position_handler: Joint '{joint_name}' position {position} is out of bounds. Using {self.robot.qlim[1][index]}."
|
||||||
)
|
)
|
||||||
|
else:
|
||||||
|
if self.joint_lim[0][index] is not None and position < self.joint_lim[0][index]:
|
||||||
|
position = self.joint_lim[0][index]
|
||||||
|
self.get_logger().warn(
|
||||||
|
f"joint_position_handler: Joint '{joint_name}' position {position} is out of bounds. Using {self.joint_lim[0][index]}."
|
||||||
|
)
|
||||||
|
elif self.joint_lim[1][index] is not None and position > self.joint_lim[1][index]:
|
||||||
|
position = self.joint_lim[1][index]
|
||||||
|
self.get_logger().warn(
|
||||||
|
f"joint_position_handler: Joint '{joint_name}' position {position} is out of bounds. Using {self.joint_lim[1][index]}."
|
||||||
|
)
|
||||||
desired_joint_positions = self.current_joint_positions
|
desired_joint_positions = self.current_joint_positions
|
||||||
desired_joint_positions[index] = position
|
desired_joint_positions[index] = position
|
||||||
self.desired = ["joint_positions"] + desired_joint_positions + [duration]
|
self.desired = ["joint_positions"] + desired_joint_positions + [duration]
|
||||||
@ -413,6 +438,7 @@ class OSC_ROS2_interface(Node):
|
|||||||
return
|
return
|
||||||
|
|
||||||
# Check if joint positions exceed limits
|
# Check if joint positions exceed limits
|
||||||
|
if self.robot:
|
||||||
for i, position in enumerate(desired_joint_positions[:len(self.joint_names)]): # Exclude duration if present
|
for i, position in enumerate(desired_joint_positions[:len(self.joint_names)]): # Exclude duration if present
|
||||||
if position < self.robot.qlim[0][i]:
|
if position < self.robot.qlim[0][i]:
|
||||||
desired_joint_positions[i] = self.robot.qlim[0][i]
|
desired_joint_positions[i] = self.robot.qlim[0][i]
|
||||||
@ -424,6 +450,18 @@ class OSC_ROS2_interface(Node):
|
|||||||
self.get_logger().warn(
|
self.get_logger().warn(
|
||||||
f"joint_positions_handler: Joint '{self.joint_names[i]}' position {position} is out of bounds. Using {self.robot.qlim[1][i]}."
|
f"joint_positions_handler: Joint '{self.joint_names[i]}' position {position} is out of bounds. Using {self.robot.qlim[1][i]}."
|
||||||
)
|
)
|
||||||
|
else:
|
||||||
|
for i, position in enumerate(desired_joint_positions[:len(self.joint_names)]):
|
||||||
|
if self.joint_lim[0][i] is not None and position < self.joint_lim[0][i]:
|
||||||
|
desired_joint_positions[i] = self.joint_lim[0][i]
|
||||||
|
self.get_logger().warn(
|
||||||
|
f"joint_positions_handler: Joint '{self.joint_names[i]}' position {position} is out of bounds. Using {self.joint_lim[0][i]}."
|
||||||
|
)
|
||||||
|
elif self.joint_lim[1][i] is not None and position > self.joint_lim[1][i]:
|
||||||
|
desired_joint_positions[i] = self.joint_lim[1][i]
|
||||||
|
self.get_logger().warn(
|
||||||
|
f"joint_positions_handler: Joint '{self.joint_names[i]}' position {position} is out of bounds. Using {self.joint_lim[1][i]}."
|
||||||
|
)
|
||||||
|
|
||||||
self.desired = ["joint_positions"] + desired_joint_positions
|
self.desired = ["joint_positions"] + desired_joint_positions
|
||||||
self.new = True
|
self.new = True
|
||||||
|
Loading…
Reference in New Issue
Block a user