Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion .devcontainer/Dockerfile
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
FROM ros:humble
FROM ros:jazzy

# Add vscode user with same UID and GID as your host system
# (modified from https://code.visualstudio.com/remote/advancedcontainers/add-nonroot-user#_creating-a-nonroot-user)
Expand Down
2 changes: 1 addition & 1 deletion .devcontainer/devcontainer.json
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
{
"name": "Omron Arm humble",
"name": "Omron Arm Jazzy",
"dockerFile": "Dockerfile",
"remoteUser": "ubuntu",
"containerEnv": {
Expand Down
51 changes: 51 additions & 0 deletions .github/workflows/compile.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
name: Compile Check

on:
workflow_dispatch:

push:
branches:
- main
- develop

pull_request:
branches:
- main
- develop

concurrency:
group: ${{ github.workflow }}-${{ github.ref }}
cancel-in-progress: true

jobs:
build:
runs-on: ubuntu-24.04

steps:
- name: Check out repository
uses: actions/checkout@v4

- name: Set up ROS 2 Jazzy
uses: ros-tooling/setup-ros@v0.7
with:
required-ros-distributions: jazzy

- name: Install system tooling
run: |
sudo apt-get update
sudo apt-get install -y python3-colcon-common-extensions python3-rosdep

- name: Initialize rosdep
run: |
sudo rosdep init || true
rosdep update

- name: Install package dependencies
run: |
rosdep install --from-paths . --ignore-src --rosdistro jazzy -r -y

- name: Build workspace
shell: bash
run: |
source /opt/ros/jazzy/setup.bash
colcon build --event-handlers console_direct+
16 changes: 11 additions & 5 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,10 +1,16 @@
# Omron ARM package
# TMR ROS2 package

To view the original Readme.md [click here](./docs/README.md)

This package is a combination of documentation from [OmronAPAC/Omron_TM_ROS2](https://github.com/OmronAPAC/Omron_TM_ROS2) and functionality of [TechmanRobotInc/tmr_ros2](https://github.com/TechmanRobotInc/tmr_ros2)

View [Developer's Guide](https://github.com/CollaborativeRoboticsLab/omron_arm/blob/humble/docs/DeveloperGuide.adoc).
View [Developer's Guide](https://github.com/CollaborativeRoboticsLab/tmr_ros2/blob/humble/docs/DeveloperGuide.adoc).

| Branch | ROS2 Version | Compile |
|--------|--------------|---------|
| main | Jazzy | [![main](https://github.com/CollaborativeRoboticsLab/tmr_ros2/actions/workflows/compile.yml/badge.svg?branch=main)](https://github.com/CollaborativeRoboticsLab/tmr_ros2/actions/workflows/compile.yml?query=branch%3Amain) |
| develop | Jazzy | [![develop](https://github.com/CollaborativeRoboticsLab/tmr_ros2/actions/workflows/compile.yml/badge.svg?branch=develop)](https://github.com/CollaborativeRoboticsLab/tmr_ros2/actions/workflows/compile.yml?query=branch%3Adevelop) |
| humble | Humble | [![humble](https://github.com/CollaborativeRoboticsLab/tmr_ros2/actions/workflows/compile.yml/badge.svg?branch=humble)](https://github.com/CollaborativeRoboticsLab/tmr_ros2/actions/workflows/compile.yml?query=branch%3Ahumble) |

## Setup

Expand All @@ -23,7 +29,7 @@ sudo apt install ros-humble-moveit ros-humble-controller-manager ros-humble-join
Clone the repositories into the `src` folder by

```sh
git clone https://github.com/CollaborativeRoboticsLab/omron_arm.git
git clone https://github.com/CollaborativeRoboticsLab/tmr_ros2.git
```

Build by
Expand All @@ -37,9 +43,9 @@ colcon build

### Initialization

1. [Startup TMFLow software with a listener node](https://github.com/CollaborativeRoboticsLab/omron_arm/blob/humble/docs/README.md#-tmflow-listen-node-setup)
1. [Startup TMFLow software with a listener node](https://github.com/CollaborativeRoboticsLab/tmr_ros2/blob/humble/docs/README.md#-tmflow-listen-node-setup)

2. [Establish Remote connection to TM Robot](https://github.com/CollaborativeRoboticsLab/omron_arm/blob/humble/docs/README.md#-remote-connection-to-tm-robot)
2. [Establish Remote connection to TM Robot](https://github.com/CollaborativeRoboticsLab/tmr_ros2/blob/humble/docs/README.md#-remote-connection-to-tm-robot)

3. Once the robot starts up, it needs to have the listner node loaded (via TMFlow) and should be in the auto mode. On the arm it needs to flash blue and red, while on the pendent a blue light should appear near letter A.

Expand Down
16 changes: 9 additions & 7 deletions tm_moveit/tm12_moveit_config/config/chomp_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,10 +1,12 @@
planning_plugin: chomp_interface/CHOMPPlanner
request_adapters: >-
default_planner_request_adapters/AddTimeParameterization
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
planning_plugins:
- chomp_interface/CHOMPPlanner
request_adapters:
- default_planning_request_adapters/ValidateWorkspaceBounds
- default_planning_request_adapters/CheckStartStateBounds
- default_planning_request_adapters/CheckStartStateCollision
response_adapters:
- default_planning_response_adapters/AddTimeOptimalParameterization
- default_planning_response_adapters/ValidateSolution
start_state_max_bounds_error: 0.1
planning_time_limit: 10.0
max_iterations: 200
Expand Down
24 changes: 12 additions & 12 deletions tm_moveit/tm12_moveit_config/config/joint_limits.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -11,30 +11,30 @@ joint_limits:
joint_1:
has_velocity_limits: true
max_velocity: 2.0943951023931953
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 2.0943951023931953
joint_2:
has_velocity_limits: true
max_velocity: 2.0943951023931953
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 2.0943951023931953
joint_3:
has_velocity_limits: true
max_velocity: 3.1415926535897931
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 3.1415926535897931
joint_4:
has_velocity_limits: true
max_velocity: 3.1415926535897931
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 3.1415926535897931
joint_5:
has_velocity_limits: true
max_velocity: 3.1415926535897931
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 3.1415926535897931
joint_6:
has_velocity_limits: true
max_velocity: 3.1415926535897931
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 3.1415926535897931
19 changes: 11 additions & 8 deletions tm_moveit/tm12_moveit_config/config/ompl_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,11 +1,14 @@
planning_plugin: ompl_interface/OMPLPlanner
request_adapters: >-
default_planner_request_adapters/AddTimeOptimalParameterization
default_planner_request_adapters/ResolveConstraintFrames
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
planning_plugins:
- ompl_interface/OMPLPlanner
request_adapters:
- default_planning_request_adapters/ResolveConstraintFrames
- default_planning_request_adapters/ValidateWorkspaceBounds
- default_planning_request_adapters/CheckStartStateBounds
- default_planning_request_adapters/CheckStartStateCollision
response_adapters:
- default_planning_response_adapters/AddTimeOptimalParameterization
- default_planning_response_adapters/ValidateSolution
- default_planning_response_adapters/DisplayMotionPath
start_state_max_bounds_error: 0.1
planner_configs:
SBLkConfigDefault:
Expand Down
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
planning_plugin: pilz_industrial_motion_planner/CommandPlanner
request_adapters: >-
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
planning_plugins:
- pilz_industrial_motion_planner/CommandPlanner
request_adapters:
- default_planning_request_adapters/ValidateWorkspaceBounds
- default_planning_request_adapters/CheckStartStateBounds
- default_planning_request_adapters/CheckStartStateCollision
default_planner_config: PTP
capabilities: >-
pilz_industrial_motion_planner/MoveGroupSequenceAction
pilz_industrial_motion_planner/MoveGroupSequenceService
capabilities: pilz_industrial_motion_planner/MoveGroupSequenceAction pilz_industrial_motion_planner/MoveGroupSequenceService
16 changes: 9 additions & 7 deletions tm_moveit/tm12x_moveit_config/config/chomp_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,10 +1,12 @@
planning_plugin: chomp_interface/CHOMPPlanner
request_adapters: >-
default_planner_request_adapters/AddTimeParameterization
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
planning_plugins:
- chomp_interface/CHOMPPlanner
request_adapters:
- default_planning_request_adapters/ValidateWorkspaceBounds
- default_planning_request_adapters/CheckStartStateBounds
- default_planning_request_adapters/CheckStartStateCollision
response_adapters:
- default_planning_response_adapters/AddTimeOptimalParameterization
- default_planning_response_adapters/ValidateSolution
start_state_max_bounds_error: 0.1
planning_time_limit: 10.0
max_iterations: 200
Expand Down
24 changes: 12 additions & 12 deletions tm_moveit/tm12x_moveit_config/config/joint_limits.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -11,30 +11,30 @@ joint_limits:
joint_1:
has_velocity_limits: true
max_velocity: 2.0943951023931953
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 2.0943951023931953
joint_2:
has_velocity_limits: true
max_velocity: 2.0943951023931953
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 2.0943951023931953
joint_3:
has_velocity_limits: true
max_velocity: 3.1415926535897931
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 3.1415926535897931
joint_4:
has_velocity_limits: true
max_velocity: 3.1415926535897931
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 3.1415926535897931
joint_5:
has_velocity_limits: true
max_velocity: 3.1415926535897931
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 3.1415926535897931
joint_6:
has_velocity_limits: true
max_velocity: 3.1415926535897931
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 3.1415926535897931
19 changes: 11 additions & 8 deletions tm_moveit/tm12x_moveit_config/config/ompl_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,11 +1,14 @@
planning_plugin: ompl_interface/OMPLPlanner
request_adapters: >-
default_planner_request_adapters/AddTimeOptimalParameterization
default_planner_request_adapters/ResolveConstraintFrames
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
planning_plugins:
- ompl_interface/OMPLPlanner
request_adapters:
- default_planning_request_adapters/ResolveConstraintFrames
- default_planning_request_adapters/ValidateWorkspaceBounds
- default_planning_request_adapters/CheckStartStateBounds
- default_planning_request_adapters/CheckStartStateCollision
response_adapters:
- default_planning_response_adapters/AddTimeOptimalParameterization
- default_planning_response_adapters/ValidateSolution
- default_planning_response_adapters/DisplayMotionPath
start_state_max_bounds_error: 0.1
planner_configs:
SBLkConfigDefault:
Expand Down
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
planning_plugin: pilz_industrial_motion_planner/CommandPlanner
request_adapters: >-
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
planning_plugins:
- pilz_industrial_motion_planner/CommandPlanner
request_adapters:
- default_planning_request_adapters/ValidateWorkspaceBounds
- default_planning_request_adapters/CheckStartStateBounds
- default_planning_request_adapters/CheckStartStateCollision
default_planner_config: PTP
capabilities: >-
pilz_industrial_motion_planner/MoveGroupSequenceAction
pilz_industrial_motion_planner/MoveGroupSequenceService
capabilities: pilz_industrial_motion_planner/MoveGroupSequenceAction pilz_industrial_motion_planner/MoveGroupSequenceService
16 changes: 9 additions & 7 deletions tm_moveit/tm14_moveit_config/config/chomp_planning.yaml
Original file line number Diff line number Diff line change
@@ -1,10 +1,12 @@
planning_plugin: chomp_interface/CHOMPPlanner
request_adapters: >-
default_planner_request_adapters/AddTimeParameterization
default_planner_request_adapters/FixWorkspaceBounds
default_planner_request_adapters/FixStartStateBounds
default_planner_request_adapters/FixStartStateCollision
default_planner_request_adapters/FixStartStatePathConstraints
planning_plugins:
- chomp_interface/CHOMPPlanner
request_adapters:
- default_planning_request_adapters/ValidateWorkspaceBounds
- default_planning_request_adapters/CheckStartStateBounds
- default_planning_request_adapters/CheckStartStateCollision
response_adapters:
- default_planning_response_adapters/AddTimeOptimalParameterization
- default_planning_response_adapters/ValidateSolution
start_state_max_bounds_error: 0.1
planning_time_limit: 10.0
max_iterations: 200
Expand Down
24 changes: 12 additions & 12 deletions tm_moveit/tm14_moveit_config/config/joint_limits.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -11,30 +11,30 @@ joint_limits:
joint_1:
has_velocity_limits: true
max_velocity: 2.0943951023931953
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 2.0943951023931953
joint_2:
has_velocity_limits: true
max_velocity: 2.0943951023931953
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 2.0943951023931953
joint_3:
has_velocity_limits: true
max_velocity: 3.1415926535897931
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 3.1415926535897931
joint_4:
has_velocity_limits: true
max_velocity: 2.6179938779914944
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 2.6179938779914944
joint_5:
has_velocity_limits: true
max_velocity: 2.6179938779914944
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 2.6179938779914944
joint_6:
has_velocity_limits: true
max_velocity: 3.1415926535897931
has_acceleration_limits: false
max_acceleration: 0
has_acceleration_limits: true
max_acceleration: 3.1415926535897931
Loading
Loading