Add ros2 support for franka fr3
This commit is contained in:
parent
daae81f4a7
commit
7acec08749
58 changed files with 3189 additions and 5 deletions
5
.gitignore
vendored
5
.gitignore
vendored
|
@ -27,3 +27,8 @@ outputs/*
|
||||||
# vim
|
# vim
|
||||||
*.swp
|
*.swp
|
||||||
MUJOCO_LOG.TXT
|
MUJOCO_LOG.TXT
|
||||||
|
|
||||||
|
#ros
|
||||||
|
ros2/build/
|
||||||
|
ros2/install/
|
||||||
|
ros2/log/
|
24
README.md
24
README.md
|
@ -34,6 +34,10 @@ We have provided an entry point into the docker container
|
||||||
python scripts/launch.py
|
python scripts/launch.py
|
||||||
```
|
```
|
||||||
|
|
||||||
|
## Use with ROS 2
|
||||||
|
|
||||||
|
> **Note:** GELLO also supports ROS 2 humble for the Franka FR3 robot. For more details, see the [ROS 2-specific README](ros2/README.md) located in the `ros2` directory.
|
||||||
|
|
||||||
# GELLO configuration setup (PLEASE READ)
|
# GELLO configuration setup (PLEASE READ)
|
||||||
Now that you have downloaded the code, there is some additional preparation work to properly configure the Dynamixels and GELLO.
|
Now that you have downloaded the code, there is some additional preparation work to properly configure the Dynamixels and GELLO.
|
||||||
These instructions will guide you on how to update the motor ids of the Dynamixels and then how to extract the joint offsets to configure your GELLO.
|
These instructions will guide you on how to update the motor ids of the Dynamixels and then how to extract the joint offsets to configure your GELLO.
|
||||||
|
@ -56,13 +60,14 @@ Dynamixels have a symmetric 4 hole pattern which means there the joint offset is
|
||||||
The `GelloAgent` class accepts a `DynamixelRobotConfig` (found in `gello/agents/gello_agent.py`). The Dynamixel config specifies the parameters you need to find to operate your GELLO. Look at the documentation for more details.
|
The `GelloAgent` class accepts a `DynamixelRobotConfig` (found in `gello/agents/gello_agent.py`). The Dynamixel config specifies the parameters you need to find to operate your GELLO. Look at the documentation for more details.
|
||||||
|
|
||||||
We have created a simple script to automatically detect the joint offset:
|
We have created a simple script to automatically detect the joint offset:
|
||||||
* set GELLO into a known configuration, where you know what the corresponding joint angles should be. For example, we set out GELLO in this configuration, where we know the desired ground truth joints. (0, -90, 90, -90, -90, 0)
|
* set GELLO into a known configuration, where you know what the corresponding joint angles should be. For example, we set our GELLO for the UR and Franka FR3 in this configuration, where we know the desired ground truth joints (0, -90, 90, -90, -90, 0), or (0, 0, 0, -90, 0, 90 , 0) respectively.
|
||||||
<p align="center">
|
<p align="center">
|
||||||
<img src="imgs/gello_matching_joints.jpg" width="45%"/>
|
<img src="imgs/gello_matching_joints.jpg" width="29%"/>
|
||||||
<img src="imgs/robot_known_configuration.jpg" width="45%"/>
|
<img src="imgs/robot_known_configuration.jpg" width="29%"/>
|
||||||
|
<img src="imgs/fr3_gello_calib_pose.jpeg" width="31%"/>
|
||||||
</p>
|
</p>
|
||||||
|
|
||||||
* run
|
* For the UR run
|
||||||
```
|
```
|
||||||
python scripts/gello_get_offset.py \
|
python scripts/gello_get_offset.py \
|
||||||
--start-joints 0 -1.57 1.57 -1.57 -1.57 0 \ # in radians
|
--start-joints 0 -1.57 1.57 -1.57 -1.57 0 \ # in radians
|
||||||
|
@ -70,13 +75,22 @@ python scripts/gello_get_offset.py \
|
||||||
--port /dev/serial/by-id/usb-FTDI_USB__-__Serial_Converter_FT7WBG6
|
--port /dev/serial/by-id/usb-FTDI_USB__-__Serial_Converter_FT7WBG6
|
||||||
# replace values with your own
|
# replace values with your own
|
||||||
```
|
```
|
||||||
|
* For the Franka FR3 run
|
||||||
|
```
|
||||||
|
python scripts/gello_get_offset.py \
|
||||||
|
--start-joints 0 0 0 -1.57 0 1.57 0 \ # in radians
|
||||||
|
--joint-signs 1 1 1 1 1 -1 1 \
|
||||||
|
--port /dev/serial/by-id/usb-FTDI_USB__-__Serial_Converter_FT7WBG6
|
||||||
|
# replace values with your own
|
||||||
|
```
|
||||||
* Use the known starting joints for `start-joints`.
|
* Use the known starting joints for `start-joints`.
|
||||||
* Use the `joint-signs` for your own robot (see below).
|
* Depending on the mechanical setup of your GELLO, the joint signs can flip, so you need to specify them for each axis.
|
||||||
* Use your serial port for `port`. You can find the port id of your U2D2 Dynamixel device by running `ls /dev/serial/by-id` and looking for the path that starts with `usb-FTDI_USB__-__Serial_Converter` (on Ubuntu). On Mac, look in /dev/ and the device that starts with `cu.usbserial`
|
* Use your serial port for `port`. You can find the port id of your U2D2 Dynamixel device by running `ls /dev/serial/by-id` and looking for the path that starts with `usb-FTDI_USB__-__Serial_Converter` (on Ubuntu). On Mac, look in /dev/ and the device that starts with `cu.usbserial`
|
||||||
|
|
||||||
`joint-signs` for each robot type:
|
`joint-signs` for each robot type:
|
||||||
* UR: `1 1 -1 1 1 1`
|
* UR: `1 1 -1 1 1 1`
|
||||||
* Panda: `1 -1 1 1 1 -1 1`
|
* Panda: `1 -1 1 1 1 -1 1`
|
||||||
|
* FR3: `1 1 1 1 1 -1 1`
|
||||||
* xArm: `1 1 1 1 1 1 1`
|
* xArm: `1 1 1 1 1 1 1`
|
||||||
|
|
||||||
The script prints out a list of joint offsets. Go to `gello/agents/gello_agent.py` and add a DynamixelRobotConfig to the PORT_CONFIG_MAP. You are now ready to run your GELLO!
|
The script prints out a list of joint offsets. Go to `gello/agents/gello_agent.py` and add a DynamixelRobotConfig to the PORT_CONFIG_MAP. You are now ready to run your GELLO!
|
||||||
|
|
BIN
imgs/fr3_gello_calib_pose.jpeg
Normal file
BIN
imgs/fr3_gello_calib_pose.jpeg
Normal file
Binary file not shown.
After Width: | Height: | Size: 182 KiB |
4
ros2/.clang-format
Normal file
4
ros2/.clang-format
Normal file
|
@ -0,0 +1,4 @@
|
||||||
|
BasedOnStyle: Chromium
|
||||||
|
Standard: c++20
|
||||||
|
SortIncludes: true
|
||||||
|
ColumnLimit: 100
|
120
ros2/.clang-tidy
Normal file
120
ros2/.clang-tidy
Normal file
|
@ -0,0 +1,120 @@
|
||||||
|
Checks: "-*,
|
||||||
|
bugprone-argument-comment,
|
||||||
|
bugprone-assert-side-effect,
|
||||||
|
bugprone-bool-pointer-implicit-conversion,
|
||||||
|
bugprone-dangling-handle,
|
||||||
|
bugprone-forward-declaration-namespace,
|
||||||
|
bugprone-inaccurate-erase,
|
||||||
|
bugprone-string-constructor,
|
||||||
|
bugprone-string-integer-assignment,
|
||||||
|
bugprone-undefined-memory-manipulation,
|
||||||
|
bugprone-unique-ptr-array-mismatch,
|
||||||
|
bugprone-unused-raii,
|
||||||
|
bugprone-use-after-move,
|
||||||
|
bugprone-virtual-near-miss,
|
||||||
|
google-build-explicit-make-pair,
|
||||||
|
google-default-arguments,
|
||||||
|
google-explicit-constructor,
|
||||||
|
google-objc-avoid-nsobject-new,
|
||||||
|
google-upgrade-googletest-case,
|
||||||
|
misc-misleading-identifier,
|
||||||
|
misc-homoglyph,
|
||||||
|
modernize-avoid-bind,
|
||||||
|
modernize-concat-nested-namespaces,
|
||||||
|
modernize-loop-convert,
|
||||||
|
modernize-make-shared,
|
||||||
|
modernize-make-unique,
|
||||||
|
modernize-redundant-void-arg,
|
||||||
|
modernize-replace-random-shuffle,
|
||||||
|
modernize-shrink-to-fit,
|
||||||
|
modernize-use-bool-literals,
|
||||||
|
modernize-use-default-member-init,
|
||||||
|
modernize-use-emplace,
|
||||||
|
modernize-use-equals-default,
|
||||||
|
modernize-use-equals-delete,
|
||||||
|
modernize-use-noexcept,
|
||||||
|
modernize-use-nullptr,
|
||||||
|
modernize-use-override,
|
||||||
|
modernize-use-transparent-functors,
|
||||||
|
readability-redundant-member-init"
|
||||||
|
CheckOptions:
|
||||||
|
- key: bugprone-assert-side-effect.AssertMacros
|
||||||
|
value: assert,DCHECK
|
||||||
|
- key: bugprone-dangling-handle.HandleClasses
|
||||||
|
value: ::std::basic_string_view;::std::span;::absl::string_view;::base::BasicStringPiece;::base::span
|
||||||
|
- key: bugprone-string-constructor.StringNames
|
||||||
|
value: ::std::basic_string;::std::basic_string_view;::base::BasicStringPiece;::absl::string_view
|
||||||
|
- key: modernize-use-default-member-init.UseAssignment
|
||||||
|
value: 1
|
||||||
|
# crbug.com/1342136, crbug.com/1343915: At times, this check makes
|
||||||
|
# suggestions that break builds. Safe mode allows us to sidestep that.
|
||||||
|
- key: modernize-use-transparent-functors.SafeMode
|
||||||
|
value: 1
|
||||||
|
# This relaxes modernize-use-emplace in some cases; we might want to make it
|
||||||
|
# more aggressive in the future. See discussion on
|
||||||
|
# https://groups.google.com/a/chromium.org/g/cxx/c/noMMTNYiM0w .
|
||||||
|
- key: modernize-use-emplace.IgnoreImplicitConstructors
|
||||||
|
value: 1
|
||||||
|
# Use of `std::ranges::reverse_view` is inconsistent with
|
||||||
|
# Chromium style. Recommend `base::Reversed` instead.
|
||||||
|
- key: modernize-loop-convert.MakeReverseRangeFunction
|
||||||
|
value: base::Reversed
|
||||||
|
- key: modernize-loop-convert.MakeReverseRangeHeader
|
||||||
|
value: base/containers/adapters.h
|
||||||
|
# Classes, structs, ...
|
||||||
|
- key: readability-identifier-naming.NamespaceCase
|
||||||
|
value: lower_case
|
||||||
|
- key: readability-identifier-naming.ClassCase
|
||||||
|
value: CamelCase
|
||||||
|
- key: readability-identifier-naming.StructCase
|
||||||
|
value: CamelCase
|
||||||
|
- key: readability-identifier-naming.EnumCase
|
||||||
|
value: CamelCase
|
||||||
|
- key: readability-identifier-naming.UnionCase
|
||||||
|
value: CamelCase
|
||||||
|
- key: readability-identifier-naming.TypedefCase
|
||||||
|
value: CamelCase
|
||||||
|
|
||||||
|
# Variables, member variables, ...
|
||||||
|
- key: readability-identifier-naming.ParameterCase
|
||||||
|
value: lower_case
|
||||||
|
- key: readability-identifier-naming.VariableCase
|
||||||
|
value: lower_case
|
||||||
|
- key: readability-identifier-naming.MemberCase
|
||||||
|
value: lower_case
|
||||||
|
- key: readability-identifier-naming.PublicMemberCase
|
||||||
|
value: lower_case
|
||||||
|
- key: readability-identifier-naming.ProtectedMemberCase
|
||||||
|
value: lower_case
|
||||||
|
- key: readability-identifier-naming.PrivateMemberCase
|
||||||
|
value: lower_case
|
||||||
|
- key: readability-identifier-naming.PrivateMemberSuffix
|
||||||
|
value: _
|
||||||
|
|
||||||
|
# Functions, methods, ...
|
||||||
|
- key: readability-identifier-naming.FunctionCase
|
||||||
|
value: camelBack
|
||||||
|
- key: readability-identifier-naming.MethodCase
|
||||||
|
value: camelBack
|
||||||
|
|
||||||
|
# Constants
|
||||||
|
- key: readability-identifier-naming.ConstantPrefix
|
||||||
|
value: k
|
||||||
|
- key: readability-identifier-naming.ConstantCase
|
||||||
|
value: CamelCase
|
||||||
|
- key: readability-identifier-naming.ConstantMemberPrefix
|
||||||
|
value: ''
|
||||||
|
- key: readability-identifier-naming.ConstantMemberCase
|
||||||
|
value: lower_case
|
||||||
|
- key: readability-identifier-naming.ConstantParameterPrefix
|
||||||
|
value: ''
|
||||||
|
- key: readability-identifier-naming.ConstantParameterCase
|
||||||
|
value: lower_case
|
||||||
|
- key: readability-identifier-naming.LocalConstantParameterPrefix
|
||||||
|
value: ''
|
||||||
|
- key: readability-identifier-naming.LocalConstantCase
|
||||||
|
value: lower_case
|
||||||
|
- key: readability-identifier-naming.ConstexprVariablePrefix
|
||||||
|
value: k
|
||||||
|
- key: readability-identifier-naming.ConstexprVariableCase
|
||||||
|
value: CamelCase
|
91
ros2/.devcontainer/Dockerfile
Normal file
91
ros2/.devcontainer/Dockerfile
Normal file
|
@ -0,0 +1,91 @@
|
||||||
|
FROM ros:humble-ros-base
|
||||||
|
# Add home directory for user root
|
||||||
|
RUN mkdir -p /home/root && chown root:root /home/root
|
||||||
|
|
||||||
|
RUN apt update && apt install -y \
|
||||||
|
# Install libfranka build depencencies
|
||||||
|
build-essential \
|
||||||
|
cmake \
|
||||||
|
git \
|
||||||
|
libeigen3-dev \
|
||||||
|
libfmt-dev \
|
||||||
|
libpoco-dev \
|
||||||
|
# Install ros packages
|
||||||
|
libignition-gazebo6-dev \
|
||||||
|
libignition-plugin-dev \
|
||||||
|
ros-humble-ament-cmake-clang-format \
|
||||||
|
ros-humble-ament-cmake-clang-tidy \
|
||||||
|
ros-humble-backward-ros \
|
||||||
|
ros-humble-control-msgs \
|
||||||
|
ros-humble-controller-interface \
|
||||||
|
ros-humble-controller-manager \
|
||||||
|
ros-humble-generate-parameter-library \
|
||||||
|
ros-humble-hardware-interface \
|
||||||
|
ros-humble-hardware-interface-testing \
|
||||||
|
ros-humble-joint-state-broadcaster \
|
||||||
|
ros-humble-joint-state-publisher \
|
||||||
|
ros-humble-joint-state-publisher-gui \
|
||||||
|
ros-humble-joint-trajectory-controller \
|
||||||
|
ros-humble-moveit-kinematics \
|
||||||
|
ros-humble-moveit-planners-ompl \
|
||||||
|
ros-humble-moveit-ros-move-group \
|
||||||
|
ros-humble-moveit-ros-visualization \
|
||||||
|
ros-humble-moveit-simple-controller-manager \
|
||||||
|
ros-humble-pinocchio \
|
||||||
|
ros-humble-realtime-tools \
|
||||||
|
ros-humble-ros2-control-test-assets \
|
||||||
|
ros-humble-ros2-controllers \
|
||||||
|
ros-humble-ros2controlcli \
|
||||||
|
ros-humble-rviz2 \
|
||||||
|
ros-humble-sdformat-urdf \
|
||||||
|
ros-humble-xacro \
|
||||||
|
# Install python3 packages
|
||||||
|
python3-colcon-common-extensions\
|
||||||
|
python3-colcon-mixin \
|
||||||
|
python3-pip \
|
||||||
|
&& rm -rf /var/lib/apt/lists/* \
|
||||||
|
&& pip3 install -U dynamixel_sdk \
|
||||||
|
tyro \
|
||||||
|
vcstool \
|
||||||
|
black
|
||||||
|
|
||||||
|
|
||||||
|
# Install libfranka
|
||||||
|
ARG LIBFRANKA_VERSION=0.15.0
|
||||||
|
RUN /bin/bash -c "source /opt/ros/humble/setup.bash && \
|
||||||
|
git clone --recursive https://github.com/frankaemika/libfranka --branch ${LIBFRANKA_VERSION} \
|
||||||
|
&& cd libfranka \
|
||||||
|
&& mkdir build \
|
||||||
|
&& cd build \
|
||||||
|
&& cmake -DCMAKE_BUILD_TYPE=Release -DBUILD_TESTS=OFF .. \
|
||||||
|
&& cmake --build . -j $(nproc) \
|
||||||
|
&& cpack -G DEB \
|
||||||
|
&& dpkg -i libfranka*.deb \
|
||||||
|
&& cd ../../ && rm -r libfranka"
|
||||||
|
# Install franka_ros2
|
||||||
|
ARG FRANKA_ROS2_VERSION=v1.0.0
|
||||||
|
ARG FRANKA_DESCRIPTION_VERSION=0.4.0
|
||||||
|
RUN /bin/bash -c 'source /opt/ros/humble/setup.bash && \
|
||||||
|
mkdir -p /tmp/franka_ros2 && cd /tmp/franka_ros2 && \
|
||||||
|
git clone --recursive https://github.com/frankaemika/franka_ros2.git --branch ${FRANKA_ROS2_VERSION} && \
|
||||||
|
git clone --recursive https://github.com/frankaemika/franka_description.git --branch ${FRANKA_DESCRIPTION_VERSION} &&\
|
||||||
|
colcon build --install-base /opt/ros/humble/franka --cmake-args -DCMAKE_BUILD_TYPE=Release -DBUILD_TESTING=off && \
|
||||||
|
cd .. &&\
|
||||||
|
rm -rf /tmp/franka_ros2 && \
|
||||||
|
echo "source /opt/ros/humble/franka/setup.bash" >> ~/.bashrc &&\
|
||||||
|
echo "source /opt/ros/humble/franka/setup.sh" >> ~/.profile'
|
||||||
|
|
||||||
|
|
||||||
|
# Install robotiq gripper
|
||||||
|
ARG ROS2_ROBOTIQ_GRIPPER_COMMIT_HASH="2ff85455d4b9f973c4b0bab1ce95fb09367f0d26"
|
||||||
|
RUN /bin/bash -c "source /opt/ros/humble/setup.bash && \
|
||||||
|
mkdir tmp_build && \
|
||||||
|
cd tmp_build && \
|
||||||
|
git clone https://github.com/PickNikRobotics/ros2_robotiq_gripper.git && \
|
||||||
|
cd ros2_robotiq_gripper && git checkout ${ROS2_ROBOTIQ_GRIPPER_COMMIT_HASH} && cd .. && \
|
||||||
|
sed -i 's/kGripperMaxSpeed = 0.150;/kGripperMaxSpeed = 1.0;/g' ros2_robotiq_gripper/robotiq_driver/src/hardware_interface.cpp && \
|
||||||
|
vcs import . --input ros2_robotiq_gripper/ros2_robotiq_gripper.humble.repos && \
|
||||||
|
colcon build --install-base /opt/ros/humble/franka --cmake-args -DCMAKE_BUILD_TYPE=Release && \
|
||||||
|
cd .. && \
|
||||||
|
rm -rf tmp_build && \
|
||||||
|
rm -rf /var/lib/apt/lists/*"
|
41
ros2/.devcontainer/devcontainer.json
Normal file
41
ros2/.devcontainer/devcontainer.json
Normal file
|
@ -0,0 +1,41 @@
|
||||||
|
{
|
||||||
|
"name": "gello-ros2",
|
||||||
|
"dockerComposeFile": "docker-compose.yml",
|
||||||
|
"service": "gello-ros2",
|
||||||
|
"overrideCommand": true,
|
||||||
|
"customizations": {
|
||||||
|
"vscode": {
|
||||||
|
"extensions": [
|
||||||
|
"ms-python.python",
|
||||||
|
"charliermarsh.ruff",
|
||||||
|
"ms-vscode.cpptools-extension-pack",
|
||||||
|
"ms-iot.vscode-ros",
|
||||||
|
"smilerobotics.urdf",
|
||||||
|
"redhat.vscode-xml",
|
||||||
|
"tamasfe.even-better-toml",
|
||||||
|
"timonwong.shellcheck",
|
||||||
|
"yzhang.markdown-all-in-one",
|
||||||
|
"GitHub.copilot-chat",
|
||||||
|
"xaver.clang-format"
|
||||||
|
],
|
||||||
|
"settings": {
|
||||||
|
"files.associations": {
|
||||||
|
"*.rviz": "yaml",
|
||||||
|
"*.srdf": "xml",
|
||||||
|
"*.urdf": "xml",
|
||||||
|
"*.xacro": "xml"
|
||||||
|
},
|
||||||
|
"terminal.integrated.defaultProfile.linux": "bash",
|
||||||
|
"terminal.integrated.profiles.linux": {
|
||||||
|
"bash": {
|
||||||
|
"path": "/bin/bash"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"terminal.integrated.cwd": "/workspace"
|
||||||
|
}
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"workspaceFolder": "/workspace/",
|
||||||
|
"shutdownAction": "stopCompose",
|
||||||
|
"postCreateCommand": "echo \"source /workspace/install/setup.bash \">> ~/.bashrc"
|
||||||
|
}
|
15
ros2/.devcontainer/docker-compose.yml
Normal file
15
ros2/.devcontainer/docker-compose.yml
Normal file
|
@ -0,0 +1,15 @@
|
||||||
|
services:
|
||||||
|
gello-ros2:
|
||||||
|
build: .
|
||||||
|
privileged: true
|
||||||
|
restart: no
|
||||||
|
network_mode: host
|
||||||
|
volumes:
|
||||||
|
- ../:/workspace
|
||||||
|
- ../../gello/dynamixel/driver.py:/workspace/src/franka_gello_state_publisher/franka_gello_state_publisher/driver.py
|
||||||
|
- /dev/serial/by-id:/dev/serial/by-id
|
||||||
|
# GELLO Calibration Files
|
||||||
|
- ../../scripts/gello_get_offset.py:/workspace/gello_get_offset.py
|
||||||
|
- ../../gello/dynamixel:/workspace/gello/dynamixel
|
||||||
|
# Python flake8 config
|
||||||
|
- ../../.flake8:/workspace/.flake8
|
1
ros2/.gitignore
vendored
Normal file
1
ros2/.gitignore
vendored
Normal file
|
@ -0,0 +1 @@
|
||||||
|
.vscode/
|
153
ros2/README.md
Normal file
153
ros2/README.md
Normal file
|
@ -0,0 +1,153 @@
|
||||||
|
# GELLO ROS 2 humble integration
|
||||||
|
|
||||||
|
This folder contains all required ROS 2 packages for using GELLO.
|
||||||
|
|
||||||
|
## Packages
|
||||||
|
|
||||||
|
### 1. `franka_fr3_arm_controllers`
|
||||||
|
This package provides a Joint Impedance controller for the Franka FR3. It subscribes to the GELLO joint states and sends torque commands to the robot.
|
||||||
|
|
||||||
|
#### Key Features:
|
||||||
|
- Implements a `JointImpedanceController` for controlling the robot's torques.
|
||||||
|
- Subscribes to `/gello/joint_states` topic for the GELLO joint states.
|
||||||
|
|
||||||
|
#### Launch Files:
|
||||||
|
- **`franka.launch.py`**: Launches the Franka robot ros interfaces.
|
||||||
|
- **`franka_fr3_arm_controllers.launch.py`**: Launches the Joint Impedance controller.
|
||||||
|
|
||||||
|
### 2. `franka_gello_state_publisher`
|
||||||
|
This package provides a ROS 2 node that reads input from the GELLO and publishes it as `sensor_msgs/msg/JointState` messages.
|
||||||
|
|
||||||
|
#### Key Features:
|
||||||
|
- Publishes GELLO state to the `/gello/joint_states` topic.
|
||||||
|
|
||||||
|
#### Launch Files:
|
||||||
|
- **`main.launch.py`**: Launches the GELLO publisher node.
|
||||||
|
|
||||||
|
### 3. `franka_gripper_manager`
|
||||||
|
This package provides a ROS 2 node for managing the gripper connected to the Franka robot. Supported grippers are either the `Franka Hand` or the `Robotiq 2F-85`. It allows sending commands to control the gripper's width and perform homing actions.
|
||||||
|
|
||||||
|
#### Key Features:
|
||||||
|
- Subscribes to `/gripper_client/target_gripper_width_percent` for gripper width commands.
|
||||||
|
- Supports homing and move actions for the gripper.
|
||||||
|
|
||||||
|
#### Launch Files:
|
||||||
|
- **`franka_gripper_client.launch.py`**: Launches the gripper manager node for the `Franka Hand`.
|
||||||
|
- **`robotiq_gripper_controller_client.launch.py`**: Launches the gripper manager node for the `Robotiq 2F-85`.
|
||||||
|
|
||||||
|
## VS-Code Dev-Container
|
||||||
|
|
||||||
|
We recommend working inside the provided VS-Code Dev-Container for a seamless development experience. Dev-Containers allow you to use a consistent environment with all necessary dependencies pre-installed. For more information, refer to the [VS-Code Dev-Containers documentation](https://code.visualstudio.com/docs/devcontainers/containers).
|
||||||
|
|
||||||
|
If you choose not to use the Dev-Container, you will need to manually install the dependencies listed in the `Dockerfile` located in the `.devcontainer` folder.
|
||||||
|
|
||||||
|
## Build and Test
|
||||||
|
|
||||||
|
### Building the Project
|
||||||
|
|
||||||
|
To build the project, use the following `colcon` command with CMake arguments, required for clang-tidy:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
colcon build --cmake-args -DCMAKE_EXPORT_COMPILE_COMMANDS=ON -DCHECK_TIDY=ON
|
||||||
|
```
|
||||||
|
|
||||||
|
### Testing the Project
|
||||||
|
|
||||||
|
The packages come with a set of tests, which can be executed using the following command:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
colcon test
|
||||||
|
```
|
||||||
|
|
||||||
|
## Getting Started
|
||||||
|
|
||||||
|
### 1. **Run the GELLO Publisher**
|
||||||
|
#### Step 1: Determine your GELLO USB ID
|
||||||
|
|
||||||
|
To proceed, you need to know the USB ID of your GELLO device. This can be determined by running:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
ls /dev/serial/by-id
|
||||||
|
```
|
||||||
|
|
||||||
|
Example output:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
usb-FTDI_USB__-__Serial_Converter_FT7WBG6
|
||||||
|
```
|
||||||
|
|
||||||
|
In this case, the `GELLO_USB_ID` would be `/dev/serial/by-id/usb-FTDI_USB__-__Serial_Converter_FT7WBG6`.
|
||||||
|
|
||||||
|
#### Step 2: Configure your GELLO
|
||||||
|
|
||||||
|
If not done already, follow the instructions of the `Create the GELLO configuration and determining joint ID's` section in the main README.md. Use the provided script to configure the GELLO for Franka FR3:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
python3 gello_get_offset.py \
|
||||||
|
--start-joints 0 0 0 -1.57 0 1.57 0 \
|
||||||
|
--joint-signs 1 1 1 1 1 -1 1 \
|
||||||
|
--port /dev/serial/by-id/<GELLO_USB_ID>
|
||||||
|
```
|
||||||
|
|
||||||
|
To apply your configuration:
|
||||||
|
- Update the `/workspace/src/franka_gello_state_publisher/config/gello_config.yaml` file.
|
||||||
|
- Rebuild the project to ensure the updated configuration is applied:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
colcon build
|
||||||
|
```
|
||||||
|
|
||||||
|
#### Step 3: Launch the GELLO publisher:
|
||||||
|
Launch the GELLO publisher node with the appropriate `com_port` parameter:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
ros2 launch franka_gello_state_publisher main.launch.py com_port:=/dev/serial/by-id/<GELLO_USB_ID>
|
||||||
|
```
|
||||||
|
|
||||||
|
### 2. **Launch the Joint Impedance Controller**
|
||||||
|
|
||||||
|
Launch the controller to send torque commands to the Franka robot:
|
||||||
|
```bash
|
||||||
|
ros2 launch franka_fr3_arm_controllers franka_fr3_arm_controllers.launch.py robot_ip:=<robot-ip> load_gripper:=<true_or_false>
|
||||||
|
```
|
||||||
|
|
||||||
|
- `robot_ip:` Replace `<robot-ip>` with the IP address of your Franka robot.
|
||||||
|
- `load_gripper`: A boolean parameter (true or false) that specifies whether to load the Franka Hand:
|
||||||
|
- Set load_gripper:=true if you are using the Franka Hand.
|
||||||
|
- Set load_gripper:=false if you are not using the Franka Hand.
|
||||||
|
|
||||||
|
### 3. **Launch the Gripper Manager**
|
||||||
|
|
||||||
|
To control the gripper, use the appropriate launch file based on the gripper type:
|
||||||
|
|
||||||
|
- **For the Franka Hand**:
|
||||||
|
```bash
|
||||||
|
ros2 launch franka_gripper_manager franka_gripper_client.launch.py
|
||||||
|
```
|
||||||
|
|
||||||
|
- **For the Robotiq 2F-85**:
|
||||||
|
```bash
|
||||||
|
ros2 launch franka_gripper_manager robotiq_gripper_controller_client.launch.py com_port:=<ROBOTIQ_USB_ID>
|
||||||
|
```
|
||||||
|
|
||||||
|
The `ROBOTIQ_USB_ID` can be determined by `ls /dev/serial/by-id`.
|
||||||
|
|
||||||
|
|
||||||
|
## Troubleshooting
|
||||||
|
|
||||||
|
### SerialException(msg.errno, "could not open port {}: {}".format(self._port, msg))
|
||||||
|
|
||||||
|
The open com port could not be opened. Possible reasons are:
|
||||||
|
- Wrongly specified, the full path is required, such as: `/dev/serial/by-id/usb-FTDI_***`
|
||||||
|
- The device was plugged in after the docker container started, re-open the container
|
||||||
|
|
||||||
|
### libfranka: Incompatible library version (server version: X, library version: Y).
|
||||||
|
|
||||||
|
The libfranka version and robot system version are not compatible. More information can be found [here](https://frankaemika.github.io/docs/compatibility.html).
|
||||||
|
Fix this by correcting the `LIBFRANKA_VERSION=0.15.0` in the [Dockerfile](./.devcontainer/Dockerfile) and update the `FRANKA_ROS2_VERSION` and `FRANKA_DESCRIPTION_VERSION` accordingly.
|
||||||
|
|
||||||
|
|
||||||
|
## Acknowledgements
|
||||||
|
The source code for the Robotiq gripper control is based on
|
||||||
|
[ros2_robotiq_gripper](https://github.com/PickNikRobotics/ros2_robotiq_gripper.git), licensed under the BSD 3-Clause license.
|
||||||
|
|
3
ros2/pyproject.toml
Normal file
3
ros2/pyproject.toml
Normal file
|
@ -0,0 +1,3 @@
|
||||||
|
[tool.black]
|
||||||
|
line-length = 99
|
||||||
|
skip-string-normalization = false
|
133
ros2/src/franka_fr3_arm_controllers/CMakeLists.txt
Normal file
133
ros2/src/franka_fr3_arm_controllers/CMakeLists.txt
Normal file
|
@ -0,0 +1,133 @@
|
||||||
|
cmake_minimum_required(VERSION 3.5)
|
||||||
|
project(franka_fr3_arm_controllers)
|
||||||
|
|
||||||
|
# Default to C++17
|
||||||
|
if(NOT CMAKE_CXX_STANDARD)
|
||||||
|
set(CMAKE_CXX_STANDARD 17)
|
||||||
|
set(CMAKE_CXX_STANDARD_REQUIRED ON)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if(NOT CMAKE_BUILD_TYPE)
|
||||||
|
set(CMAKE_BUILD_TYPE "Debug" CACHE STRING "Build type (default is Debug)" FORCE)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
|
||||||
|
add_compile_options(-Wall -Wextra -Wpedantic)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if(CMAKE_BUILD_TYPE STREQUAL "Debug")
|
||||||
|
if(CMAKE_CXX_COMPILER_ID MATCHES "GNU|Clang")
|
||||||
|
add_compile_options(--coverage -O0 -g)
|
||||||
|
add_link_options(--coverage)
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
option(CHECK_TIDY "Adds clang-tidy tests" OFF)
|
||||||
|
|
||||||
|
# find dependencies
|
||||||
|
find_package(ament_cmake REQUIRED)
|
||||||
|
find_package(rclcpp REQUIRED)
|
||||||
|
find_package(controller_interface REQUIRED)
|
||||||
|
find_package(pluginlib REQUIRED)
|
||||||
|
find_package(rclcpp_lifecycle REQUIRED)
|
||||||
|
find_package(hardware_interface REQUIRED)
|
||||||
|
find_package(franka_msgs REQUIRED)
|
||||||
|
find_package(Eigen3 REQUIRED)
|
||||||
|
find_package(franka_semantic_components REQUIRED)
|
||||||
|
find_package(moveit_core REQUIRED)
|
||||||
|
find_package(moveit_msgs REQUIRED)
|
||||||
|
|
||||||
|
add_library(
|
||||||
|
${PROJECT_NAME}
|
||||||
|
SHARED
|
||||||
|
src/joint_impedance_controller.cpp
|
||||||
|
src/motion_generator.cpp)
|
||||||
|
target_include_directories(
|
||||||
|
${PROJECT_NAME}
|
||||||
|
PUBLIC
|
||||||
|
include
|
||||||
|
${EIGEN3_INCLUDE_DIRS}
|
||||||
|
)
|
||||||
|
ament_target_dependencies(
|
||||||
|
${PROJECT_NAME}
|
||||||
|
controller_interface
|
||||||
|
hardware_interface
|
||||||
|
pluginlib
|
||||||
|
rclcpp
|
||||||
|
rclcpp_lifecycle
|
||||||
|
franka_semantic_components
|
||||||
|
moveit_core
|
||||||
|
moveit_msgs
|
||||||
|
)
|
||||||
|
|
||||||
|
pluginlib_export_plugin_description_file(
|
||||||
|
controller_interface franka_fr3_arm_controllers.xml)
|
||||||
|
|
||||||
|
install(
|
||||||
|
TARGETS
|
||||||
|
${PROJECT_NAME}
|
||||||
|
RUNTIME DESTINATION bin
|
||||||
|
ARCHIVE DESTINATION lib
|
||||||
|
LIBRARY DESTINATION lib
|
||||||
|
)
|
||||||
|
|
||||||
|
install(
|
||||||
|
DIRECTORY include/
|
||||||
|
DESTINATION include
|
||||||
|
)
|
||||||
|
|
||||||
|
install(
|
||||||
|
DIRECTORY config launch
|
||||||
|
DESTINATION share/${PROJECT_NAME}
|
||||||
|
)
|
||||||
|
|
||||||
|
ament_export_include_directories(
|
||||||
|
include
|
||||||
|
)
|
||||||
|
ament_export_libraries(
|
||||||
|
${PROJECT_NAME}
|
||||||
|
)
|
||||||
|
ament_export_dependencies(
|
||||||
|
controller_interface
|
||||||
|
pluginlib
|
||||||
|
rclcpp
|
||||||
|
rclcpp_lifecycle
|
||||||
|
hardware_interface
|
||||||
|
moveit_core
|
||||||
|
)
|
||||||
|
|
||||||
|
if(BUILD_TESTING)
|
||||||
|
find_package(ament_cmake_gtest REQUIRED)
|
||||||
|
find_package(ament_cmake_clang_format REQUIRED)
|
||||||
|
find_package(ament_cmake_copyright REQUIRED)
|
||||||
|
find_package(ament_cmake_cppcheck REQUIRED)
|
||||||
|
find_package(ament_cmake_lint_cmake REQUIRED)
|
||||||
|
find_package(ament_cmake_xmllint REQUIRED)
|
||||||
|
|
||||||
|
set(CPP_DIRECTORIES src include test)
|
||||||
|
|
||||||
|
ament_cppcheck(${CPP_DIRECTORIES})
|
||||||
|
ament_lint_cmake(CMakeLists.txt)
|
||||||
|
ament_xmllint()
|
||||||
|
ament_clang_format(CONFIG_FILE /workspace/.clang-format ${CPP_DIRECTORIES})
|
||||||
|
ament_copyright(${CPP_DIRECTORIES} package.xml)
|
||||||
|
|
||||||
|
ament_add_gtest(
|
||||||
|
test_joint_impedance_controller
|
||||||
|
test/test_joint_impedance_controller.cpp
|
||||||
|
test/invalid_configuration_test.cpp
|
||||||
|
test/setup_test.cpp
|
||||||
|
)
|
||||||
|
if(TARGET test_joint_impedance_controller)
|
||||||
|
target_link_libraries(test_joint_impedance_controller ${PROJECT_NAME})
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if(CHECK_TIDY)
|
||||||
|
find_package(ament_cmake_clang_tidy REQUIRED)
|
||||||
|
set(ament_cmake_clang_tidy_CONFIG_FILE /workspace/.clang-tidy)
|
||||||
|
ament_clang_tidy(${CMAKE_BINARY_DIR})
|
||||||
|
endif()
|
||||||
|
|
||||||
|
|
||||||
|
ament_package()
|
202
ros2/src/franka_fr3_arm_controllers/LICENSE
Normal file
202
ros2/src/franka_fr3_arm_controllers/LICENSE
Normal file
|
@ -0,0 +1,202 @@
|
||||||
|
|
||||||
|
Apache License
|
||||||
|
Version 2.0, January 2004
|
||||||
|
http://www.apache.org/licenses/
|
||||||
|
|
||||||
|
TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
|
||||||
|
|
||||||
|
1. Definitions.
|
||||||
|
|
||||||
|
"License" shall mean the terms and conditions for use, reproduction,
|
||||||
|
and distribution as defined by Sections 1 through 9 of this document.
|
||||||
|
|
||||||
|
"Licensor" shall mean the copyright owner or entity authorized by
|
||||||
|
the copyright owner that is granting the License.
|
||||||
|
|
||||||
|
"Legal Entity" shall mean the union of the acting entity and all
|
||||||
|
other entities that control, are controlled by, or are under common
|
||||||
|
control with that entity. For the purposes of this definition,
|
||||||
|
"control" means (i) the power, direct or indirect, to cause the
|
||||||
|
direction or management of such entity, whether by contract or
|
||||||
|
otherwise, or (ii) ownership of fifty percent (50%) or more of the
|
||||||
|
outstanding shares, or (iii) beneficial ownership of such entity.
|
||||||
|
|
||||||
|
"You" (or "Your") shall mean an individual or Legal Entity
|
||||||
|
exercising permissions granted by this License.
|
||||||
|
|
||||||
|
"Source" form shall mean the preferred form for making modifications,
|
||||||
|
including but not limited to software source code, documentation
|
||||||
|
source, and configuration files.
|
||||||
|
|
||||||
|
"Object" form shall mean any form resulting from mechanical
|
||||||
|
transformation or translation of a Source form, including but
|
||||||
|
not limited to compiled object code, generated documentation,
|
||||||
|
and conversions to other media types.
|
||||||
|
|
||||||
|
"Work" shall mean the work of authorship, whether in Source or
|
||||||
|
Object form, made available under the License, as indicated by a
|
||||||
|
copyright notice that is included in or attached to the work
|
||||||
|
(an example is provided in the Appendix below).
|
||||||
|
|
||||||
|
"Derivative Works" shall mean any work, whether in Source or Object
|
||||||
|
form, that is based on (or derived from) the Work and for which the
|
||||||
|
editorial revisions, annotations, elaborations, or other modifications
|
||||||
|
represent, as a whole, an original work of authorship. For the purposes
|
||||||
|
of this License, Derivative Works shall not include works that remain
|
||||||
|
separable from, or merely link (or bind by name) to the interfaces of,
|
||||||
|
the Work and Derivative Works thereof.
|
||||||
|
|
||||||
|
"Contribution" shall mean any work of authorship, including
|
||||||
|
the original version of the Work and any modifications or additions
|
||||||
|
to that Work or Derivative Works thereof, that is intentionally
|
||||||
|
submitted to Licensor for inclusion in the Work by the copyright owner
|
||||||
|
or by an individual or Legal Entity authorized to submit on behalf of
|
||||||
|
the copyright owner. For the purposes of this definition, "submitted"
|
||||||
|
means any form of electronic, verbal, or written communication sent
|
||||||
|
to the Licensor or its representatives, including but not limited to
|
||||||
|
communication on electronic mailing lists, source code control systems,
|
||||||
|
and issue tracking systems that are managed by, or on behalf of, the
|
||||||
|
Licensor for the purpose of discussing and improving the Work, but
|
||||||
|
excluding communication that is conspicuously marked or otherwise
|
||||||
|
designated in writing by the copyright owner as "Not a Contribution."
|
||||||
|
|
||||||
|
"Contributor" shall mean Licensor and any individual or Legal Entity
|
||||||
|
on behalf of whom a Contribution has been received by Licensor and
|
||||||
|
subsequently incorporated within the Work.
|
||||||
|
|
||||||
|
2. Grant of Copyright License. Subject to the terms and conditions of
|
||||||
|
this License, each Contributor hereby grants to You a perpetual,
|
||||||
|
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
|
||||||
|
copyright license to reproduce, prepare Derivative Works of,
|
||||||
|
publicly display, publicly perform, sublicense, and distribute the
|
||||||
|
Work and such Derivative Works in Source or Object form.
|
||||||
|
|
||||||
|
3. Grant of Patent License. Subject to the terms and conditions of
|
||||||
|
this License, each Contributor hereby grants to You a perpetual,
|
||||||
|
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
|
||||||
|
(except as stated in this section) patent license to make, have made,
|
||||||
|
use, offer to sell, sell, import, and otherwise transfer the Work,
|
||||||
|
where such license applies only to those patent claims licensable
|
||||||
|
by such Contributor that are necessarily infringed by their
|
||||||
|
Contribution(s) alone or by combination of their Contribution(s)
|
||||||
|
with the Work to which such Contribution(s) was submitted. If You
|
||||||
|
institute patent litigation against any entity (including a
|
||||||
|
cross-claim or counterclaim in a lawsuit) alleging that the Work
|
||||||
|
or a Contribution incorporated within the Work constitutes direct
|
||||||
|
or contributory patent infringement, then any patent licenses
|
||||||
|
granted to You under this License for that Work shall terminate
|
||||||
|
as of the date such litigation is filed.
|
||||||
|
|
||||||
|
4. Redistribution. You may reproduce and distribute copies of the
|
||||||
|
Work or Derivative Works thereof in any medium, with or without
|
||||||
|
modifications, and in Source or Object form, provided that You
|
||||||
|
meet the following conditions:
|
||||||
|
|
||||||
|
(a) You must give any other recipients of the Work or
|
||||||
|
Derivative Works a copy of this License; and
|
||||||
|
|
||||||
|
(b) You must cause any modified files to carry prominent notices
|
||||||
|
stating that You changed the files; and
|
||||||
|
|
||||||
|
(c) You must retain, in the Source form of any Derivative Works
|
||||||
|
that You distribute, all copyright, patent, trademark, and
|
||||||
|
attribution notices from the Source form of the Work,
|
||||||
|
excluding those notices that do not pertain to any part of
|
||||||
|
the Derivative Works; and
|
||||||
|
|
||||||
|
(d) If the Work includes a "NOTICE" text file as part of its
|
||||||
|
distribution, then any Derivative Works that You distribute must
|
||||||
|
include a readable copy of the attribution notices contained
|
||||||
|
within such NOTICE file, excluding those notices that do not
|
||||||
|
pertain to any part of the Derivative Works, in at least one
|
||||||
|
of the following places: within a NOTICE text file distributed
|
||||||
|
as part of the Derivative Works; within the Source form or
|
||||||
|
documentation, if provided along with the Derivative Works; or,
|
||||||
|
within a display generated by the Derivative Works, if and
|
||||||
|
wherever such third-party notices normally appear. The contents
|
||||||
|
of the NOTICE file are for informational purposes only and
|
||||||
|
do not modify the License. You may add Your own attribution
|
||||||
|
notices within Derivative Works that You distribute, alongside
|
||||||
|
or as an addendum to the NOTICE text from the Work, provided
|
||||||
|
that such additional attribution notices cannot be construed
|
||||||
|
as modifying the License.
|
||||||
|
|
||||||
|
You may add Your own copyright statement to Your modifications and
|
||||||
|
may provide additional or different license terms and conditions
|
||||||
|
for use, reproduction, or distribution of Your modifications, or
|
||||||
|
for any such Derivative Works as a whole, provided Your use,
|
||||||
|
reproduction, and distribution of the Work otherwise complies with
|
||||||
|
the conditions stated in this License.
|
||||||
|
|
||||||
|
5. Submission of Contributions. Unless You explicitly state otherwise,
|
||||||
|
any Contribution intentionally submitted for inclusion in the Work
|
||||||
|
by You to the Licensor shall be under the terms and conditions of
|
||||||
|
this License, without any additional terms or conditions.
|
||||||
|
Notwithstanding the above, nothing herein shall supersede or modify
|
||||||
|
the terms of any separate license agreement you may have executed
|
||||||
|
with Licensor regarding such Contributions.
|
||||||
|
|
||||||
|
6. Trademarks. This License does not grant permission to use the trade
|
||||||
|
names, trademarks, service marks, or product names of the Licensor,
|
||||||
|
except as required for reasonable and customary use in describing the
|
||||||
|
origin of the Work and reproducing the content of the NOTICE file.
|
||||||
|
|
||||||
|
7. Disclaimer of Warranty. Unless required by applicable law or
|
||||||
|
agreed to in writing, Licensor provides the Work (and each
|
||||||
|
Contributor provides its Contributions) on an "AS IS" BASIS,
|
||||||
|
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
|
||||||
|
implied, including, without limitation, any warranties or conditions
|
||||||
|
of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
|
||||||
|
PARTICULAR PURPOSE. You are solely responsible for determining the
|
||||||
|
appropriateness of using or redistributing the Work and assume any
|
||||||
|
risks associated with Your exercise of permissions under this License.
|
||||||
|
|
||||||
|
8. Limitation of Liability. In no event and under no legal theory,
|
||||||
|
whether in tort (including negligence), contract, or otherwise,
|
||||||
|
unless required by applicable law (such as deliberate and grossly
|
||||||
|
negligent acts) or agreed to in writing, shall any Contributor be
|
||||||
|
liable to You for damages, including any direct, indirect, special,
|
||||||
|
incidental, or consequential damages of any character arising as a
|
||||||
|
result of this License or out of the use or inability to use the
|
||||||
|
Work (including but not limited to damages for loss of goodwill,
|
||||||
|
work stoppage, computer failure or malfunction, or any and all
|
||||||
|
other commercial damages or losses), even if such Contributor
|
||||||
|
has been advised of the possibility of such damages.
|
||||||
|
|
||||||
|
9. Accepting Warranty or Additional Liability. While redistributing
|
||||||
|
the Work or Derivative Works thereof, You may choose to offer,
|
||||||
|
and charge a fee for, acceptance of support, warranty, indemnity,
|
||||||
|
or other liability obligations and/or rights consistent with this
|
||||||
|
License. However, in accepting such obligations, You may act only
|
||||||
|
on Your own behalf and on Your sole responsibility, not on behalf
|
||||||
|
of any other Contributor, and only if You agree to indemnify,
|
||||||
|
defend, and hold each Contributor harmless for any liability
|
||||||
|
incurred by, or claims asserted against, such Contributor by reason
|
||||||
|
of your accepting any such warranty or additional liability.
|
||||||
|
|
||||||
|
END OF TERMS AND CONDITIONS
|
||||||
|
|
||||||
|
APPENDIX: How to apply the Apache License to your work.
|
||||||
|
|
||||||
|
To apply the Apache License to your work, attach the following
|
||||||
|
boilerplate notice, with the fields enclosed by brackets "[]"
|
||||||
|
replaced with your own identifying information. (Don't include
|
||||||
|
the brackets!) The text should be enclosed in the appropriate
|
||||||
|
comment syntax for the file format. We also recommend that a
|
||||||
|
file or class name and description of purpose be included on the
|
||||||
|
same "printed page" as the copyright notice for easier
|
||||||
|
identification within third-party archives.
|
||||||
|
|
||||||
|
Copyright [yyyy] [name of copyright owner]
|
||||||
|
|
||||||
|
Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
you may not use this file except in compliance with the License.
|
||||||
|
You may obtain a copy of the License at
|
||||||
|
|
||||||
|
http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
|
||||||
|
Unless required by applicable law or agreed to in writing, software
|
||||||
|
distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
See the License for the specific language governing permissions and
|
||||||
|
limitations under the License.
|
14
ros2/src/franka_fr3_arm_controllers/NOTICE
Normal file
14
ros2/src/franka_fr3_arm_controllers/NOTICE
Normal file
|
@ -0,0 +1,14 @@
|
||||||
|
franka_fr3_arm_controllers
|
||||||
|
Copyright 2025 Franka Robotics GmbH
|
||||||
|
|
||||||
|
Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
you may not use this file except in compliance with the License.
|
||||||
|
You may obtain a copy of the License at
|
||||||
|
|
||||||
|
http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
|
||||||
|
Unless required by applicable law or agreed to in writing, software
|
||||||
|
distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
See the License for the specific language governing permissions and
|
||||||
|
limitations under the License.
|
32
ros2/src/franka_fr3_arm_controllers/config/controllers.yaml
Normal file
32
ros2/src/franka_fr3_arm_controllers/config/controllers.yaml
Normal file
|
@ -0,0 +1,32 @@
|
||||||
|
controller_manager:
|
||||||
|
ros__parameters:
|
||||||
|
update_rate: 1000 # Hz
|
||||||
|
|
||||||
|
joint_impedance_controller:
|
||||||
|
type: franka_fr3_arm_controllers/JointImpedanceController
|
||||||
|
|
||||||
|
joint_state_broadcaster:
|
||||||
|
type: joint_state_broadcaster/JointStateBroadcaster
|
||||||
|
|
||||||
|
franka_robot_state_broadcaster:
|
||||||
|
type: franka_robot_state_broadcaster/FrankaRobotStateBroadcaster
|
||||||
|
|
||||||
|
joint_impedance_controller:
|
||||||
|
ros__parameters:
|
||||||
|
k_alpha: 0.99
|
||||||
|
k_gains:
|
||||||
|
- 240.0
|
||||||
|
- 240.0
|
||||||
|
- 240.0
|
||||||
|
- 240.0
|
||||||
|
- 100.0
|
||||||
|
- 60.0
|
||||||
|
- 20.0
|
||||||
|
d_gains:
|
||||||
|
- 20.0
|
||||||
|
- 20.0
|
||||||
|
- 20.0
|
||||||
|
- 10.0
|
||||||
|
- 10.0
|
||||||
|
- 10.0
|
||||||
|
- 5.0
|
|
@ -0,0 +1,9 @@
|
||||||
|
<library path="franka_fr3_arm_controllers">
|
||||||
|
<class name="franka_fr3_arm_controllers/JointImpedanceController"
|
||||||
|
type="franka_fr3_arm_controllers::JointImpedanceController"
|
||||||
|
base_class_type="controller_interface::ControllerInterface">
|
||||||
|
<description>
|
||||||
|
The JointImpedanceController single arm controller for gello
|
||||||
|
</description>
|
||||||
|
</class>
|
||||||
|
</library>
|
|
@ -0,0 +1,70 @@
|
||||||
|
// Copyright (c) 2025 Franka Robotics GmbH
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <Eigen/Eigen>
|
||||||
|
#include <controller_interface/controller_interface.hpp>
|
||||||
|
#include <rclcpp/rclcpp.hpp>
|
||||||
|
#include <sensor_msgs/msg/joint_state.hpp>
|
||||||
|
#include <string>
|
||||||
|
#include "franka_fr3_arm_controllers/motion_generator.hpp"
|
||||||
|
|
||||||
|
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
|
||||||
|
|
||||||
|
namespace franka_fr3_arm_controllers {
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Controller to move the robot to a desired joint position.
|
||||||
|
*/
|
||||||
|
class JointImpedanceController : public controller_interface::ControllerInterface {
|
||||||
|
public:
|
||||||
|
using Vector7d = Eigen::Matrix<double, 7, 1>;
|
||||||
|
[[nodiscard]] controller_interface::InterfaceConfiguration command_interface_configuration()
|
||||||
|
const override;
|
||||||
|
[[nodiscard]] controller_interface::InterfaceConfiguration state_interface_configuration()
|
||||||
|
const override;
|
||||||
|
controller_interface::return_type update(const rclcpp::Time& time,
|
||||||
|
const rclcpp::Duration& period) override;
|
||||||
|
CallbackReturn on_init() override;
|
||||||
|
CallbackReturn on_configure(const rclcpp_lifecycle::State& previous_state) override;
|
||||||
|
CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) override;
|
||||||
|
|
||||||
|
private:
|
||||||
|
std::string arm_id_;
|
||||||
|
std::string robot_description_;
|
||||||
|
const int num_joints = 7;
|
||||||
|
Vector7d q_;
|
||||||
|
Vector7d dq_;
|
||||||
|
Vector7d dq_filtered_;
|
||||||
|
Vector7d k_gains_;
|
||||||
|
Vector7d d_gains_;
|
||||||
|
double k_alpha_;
|
||||||
|
bool move_to_start_position_finished_{false};
|
||||||
|
rclcpp::Time start_time_;
|
||||||
|
std::unique_ptr<MotionGenerator> motion_generator_;
|
||||||
|
rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr joint_state_subscriber_ = nullptr;
|
||||||
|
bool gello_position_values_valid_ = false;
|
||||||
|
std::array<double, 7> gello_position_values_{0, 0, 0, 0, 0, 0, 0};
|
||||||
|
rclcpp::Time last_joint_state_time_;
|
||||||
|
|
||||||
|
Vector7d calculateTauDGains_(const Vector7d& q_goal);
|
||||||
|
bool validateGains_(const std::vector<double>& gains, const std::string& gains_name);
|
||||||
|
void initializeMotionGenerator_();
|
||||||
|
void updateJointStates_();
|
||||||
|
void validateGelloPositions_(const sensor_msgs::msg::JointState& msg);
|
||||||
|
void jointStateCallback_(const sensor_msgs::msg::JointState msg);
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace franka_fr3_arm_controllers
|
|
@ -0,0 +1,73 @@
|
||||||
|
// Copyright (c) 2023 Franka Robotics GmbH
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <array>
|
||||||
|
#include <utility>
|
||||||
|
|
||||||
|
#include <Eigen/Core>
|
||||||
|
#include <rclcpp/duration.hpp>
|
||||||
|
/**
|
||||||
|
* An example showing how to generate a joint pose motion to a goal position. Adapted from:
|
||||||
|
* Wisama Khalil and Etienne Dombre. 2002. Modeling, Identification and Control of Robots
|
||||||
|
* (Kogan Page Science Paper edition).
|
||||||
|
*/
|
||||||
|
class MotionGenerator {
|
||||||
|
public:
|
||||||
|
using Vector7d = Eigen::Matrix<double, 7, 1>;
|
||||||
|
/**
|
||||||
|
* Creates a new MotionGenerator instance for a target q.
|
||||||
|
*
|
||||||
|
* @param[in] speed_factor General speed factor in range (0, 1].
|
||||||
|
* @param[in] q_start Start joint positions.
|
||||||
|
* @param[in] q_goal Target joint positions.
|
||||||
|
*/
|
||||||
|
MotionGenerator(double speed_factor, const Vector7d& q_start, const Vector7d& q_goal);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Sends joint position calculations
|
||||||
|
*
|
||||||
|
* @param[in] robot_state Current state of the robot.
|
||||||
|
* @param[in] trajectory_time Amount of time, that has passed since the start of the trajectory.
|
||||||
|
*
|
||||||
|
* @return Joint positions to use inside a control loop and a boolean indicating whether the
|
||||||
|
* motion is finished.
|
||||||
|
*/
|
||||||
|
std::pair<Vector7d, bool> getDesiredJointPositions(const rclcpp::Duration& trajectory_time);
|
||||||
|
|
||||||
|
private:
|
||||||
|
using Vector7i = Eigen::Matrix<int, 7, 1>;
|
||||||
|
|
||||||
|
bool calculateDesiredValues(double time, Vector7d* delta_q_d) const;
|
||||||
|
void calculateSynchronizedValues();
|
||||||
|
|
||||||
|
static constexpr double kDeltaQMotionFinished = 1e-6;
|
||||||
|
static const int kJoints = 7;
|
||||||
|
|
||||||
|
Vector7d q_start_;
|
||||||
|
Vector7d delta_q_;
|
||||||
|
|
||||||
|
Vector7d dq_max_sync_;
|
||||||
|
Vector7d t_1_sync_;
|
||||||
|
Vector7d t_2_sync_;
|
||||||
|
Vector7d t_f_sync_;
|
||||||
|
Vector7d q_1_;
|
||||||
|
|
||||||
|
double time_ = 0.0;
|
||||||
|
|
||||||
|
Vector7d dq_max_ = (Vector7d() << 2.0, 2.0, 2.0, 2.0, 2.5, 2.5, 2.5).finished(); // in m/s
|
||||||
|
Vector7d ddq_max_start_ = (Vector7d() << 5, 5, 5, 5, 5, 5, 5).finished(); // in m/s^2
|
||||||
|
Vector7d ddq_max_goal_ = (Vector7d() << 5, 5, 5, 5, 5, 5, 5).finished(); // in m/s^2
|
||||||
|
};
|
182
ros2/src/franka_fr3_arm_controllers/launch/franka.launch.py
Normal file
182
ros2/src/franka_fr3_arm_controllers/launch/franka.launch.py
Normal file
|
@ -0,0 +1,182 @@
|
||||||
|
# Copyright (c) 2024 Franka Robotics GmbH
|
||||||
|
#
|
||||||
|
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
# you may not use this file except in compliance with the License.
|
||||||
|
# You may obtain a copy of the License at
|
||||||
|
#
|
||||||
|
# http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
#
|
||||||
|
# Unless required by applicable law or agreed to in writing, software
|
||||||
|
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
# See the License for the specific language governing permissions and
|
||||||
|
# limitations under the License.
|
||||||
|
|
||||||
|
|
||||||
|
import os
|
||||||
|
|
||||||
|
from ament_index_python.packages import get_package_share_directory
|
||||||
|
from launch import LaunchContext, LaunchDescription
|
||||||
|
from launch.actions import (
|
||||||
|
DeclareLaunchArgument,
|
||||||
|
IncludeLaunchDescription,
|
||||||
|
OpaqueFunction,
|
||||||
|
Shutdown
|
||||||
|
)
|
||||||
|
from launch.conditions import IfCondition, UnlessCondition
|
||||||
|
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||||
|
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
from launch_ros.substitutions import FindPackageShare
|
||||||
|
|
||||||
|
import xacro
|
||||||
|
|
||||||
|
|
||||||
|
def robot_description_dependent_nodes_spawner(
|
||||||
|
context: LaunchContext,
|
||||||
|
robot_ip,
|
||||||
|
arm_id,
|
||||||
|
use_fake_hardware,
|
||||||
|
fake_sensor_commands,
|
||||||
|
load_gripper):
|
||||||
|
|
||||||
|
robot_ip_str = context.perform_substitution(robot_ip)
|
||||||
|
arm_id_str = context.perform_substitution(arm_id)
|
||||||
|
use_fake_hardware_str = context.perform_substitution(use_fake_hardware)
|
||||||
|
fake_sensor_commands_str = context.perform_substitution(
|
||||||
|
fake_sensor_commands)
|
||||||
|
load_gripper_str = context.perform_substitution(load_gripper)
|
||||||
|
|
||||||
|
franka_xacro_filepath = os.path.join(get_package_share_directory(
|
||||||
|
'franka_description'), 'robots', arm_id_str, arm_id_str+'.urdf.xacro')
|
||||||
|
robot_description = xacro.process_file(franka_xacro_filepath,
|
||||||
|
mappings={
|
||||||
|
'ros2_control': 'true',
|
||||||
|
'arm_id': arm_id_str,
|
||||||
|
'robot_ip': robot_ip_str,
|
||||||
|
'hand': load_gripper_str,
|
||||||
|
'use_fake_hardware': use_fake_hardware_str,
|
||||||
|
'fake_sensor_commands': fake_sensor_commands_str,
|
||||||
|
}).toprettyxml(indent=' ')
|
||||||
|
|
||||||
|
franka_controllers = PathJoinSubstitution(
|
||||||
|
[FindPackageShare('franka_fr3_arm_controllers'), 'config', 'controllers.yaml'])
|
||||||
|
|
||||||
|
return [
|
||||||
|
Node(
|
||||||
|
package='robot_state_publisher',
|
||||||
|
executable='robot_state_publisher',
|
||||||
|
name='robot_state_publisher',
|
||||||
|
output='screen',
|
||||||
|
parameters=[{'robot_description': robot_description}],
|
||||||
|
),
|
||||||
|
Node(
|
||||||
|
package='controller_manager',
|
||||||
|
executable='ros2_control_node',
|
||||||
|
parameters=[franka_controllers,
|
||||||
|
{'robot_description': robot_description},
|
||||||
|
{'arm_id': arm_id},
|
||||||
|
{'load_gripper': load_gripper},
|
||||||
|
],
|
||||||
|
remappings=[('joint_states', 'franka/joint_states')],
|
||||||
|
output={
|
||||||
|
'stdout': 'screen',
|
||||||
|
'stderr': 'screen',
|
||||||
|
},
|
||||||
|
on_exit=Shutdown(),
|
||||||
|
)]
|
||||||
|
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
arm_id_parameter_name = 'arm_id'
|
||||||
|
robot_ip_parameter_name = 'robot_ip'
|
||||||
|
load_gripper_parameter_name = 'load_gripper'
|
||||||
|
use_fake_hardware_parameter_name = 'use_fake_hardware'
|
||||||
|
fake_sensor_commands_parameter_name = 'fake_sensor_commands'
|
||||||
|
use_rviz_parameter_name = 'use_rviz'
|
||||||
|
|
||||||
|
arm_id = LaunchConfiguration(arm_id_parameter_name)
|
||||||
|
robot_ip = LaunchConfiguration(robot_ip_parameter_name)
|
||||||
|
load_gripper = LaunchConfiguration(load_gripper_parameter_name)
|
||||||
|
use_fake_hardware = LaunchConfiguration(use_fake_hardware_parameter_name)
|
||||||
|
fake_sensor_commands = LaunchConfiguration(
|
||||||
|
fake_sensor_commands_parameter_name)
|
||||||
|
use_rviz = LaunchConfiguration(use_rviz_parameter_name)
|
||||||
|
|
||||||
|
rviz_file = os.path.join(get_package_share_directory('franka_description'), 'rviz',
|
||||||
|
'visualize_franka.rviz')
|
||||||
|
|
||||||
|
robot_description_dependent_nodes_spawner_opaque_function = OpaqueFunction(
|
||||||
|
function=robot_description_dependent_nodes_spawner,
|
||||||
|
args=[
|
||||||
|
robot_ip,
|
||||||
|
arm_id,
|
||||||
|
use_fake_hardware,
|
||||||
|
fake_sensor_commands,
|
||||||
|
load_gripper])
|
||||||
|
|
||||||
|
launch_description = LaunchDescription([
|
||||||
|
DeclareLaunchArgument(
|
||||||
|
robot_ip_parameter_name,
|
||||||
|
description='Hostname or IP address of the robot.'),
|
||||||
|
DeclareLaunchArgument(
|
||||||
|
arm_id_parameter_name,
|
||||||
|
description='ID of the type of arm used. Supported values: fer, fr3, fp3'),
|
||||||
|
DeclareLaunchArgument(
|
||||||
|
use_rviz_parameter_name,
|
||||||
|
default_value='false',
|
||||||
|
description='Visualize the robot in Rviz'),
|
||||||
|
DeclareLaunchArgument(
|
||||||
|
use_fake_hardware_parameter_name,
|
||||||
|
default_value='false',
|
||||||
|
description='Use fake hardware'),
|
||||||
|
DeclareLaunchArgument(
|
||||||
|
fake_sensor_commands_parameter_name,
|
||||||
|
default_value='false',
|
||||||
|
description='Fake sensor commands. Only valid when "{}" is true'.format(
|
||||||
|
use_fake_hardware_parameter_name)),
|
||||||
|
DeclareLaunchArgument(
|
||||||
|
load_gripper_parameter_name,
|
||||||
|
default_value='true',
|
||||||
|
description='Use Franka Gripper as an end-effector, otherwise, the robot is loaded '
|
||||||
|
'without an end-effector.'),
|
||||||
|
Node(
|
||||||
|
package='joint_state_publisher',
|
||||||
|
executable='joint_state_publisher',
|
||||||
|
name='joint_state_publisher',
|
||||||
|
parameters=[
|
||||||
|
{'source_list': ['franka/joint_states', 'franka_gripper/joint_states'],
|
||||||
|
'rate': 30}],
|
||||||
|
),
|
||||||
|
robot_description_dependent_nodes_spawner_opaque_function,
|
||||||
|
Node(
|
||||||
|
package='controller_manager',
|
||||||
|
executable='spawner',
|
||||||
|
arguments=['joint_state_broadcaster'],
|
||||||
|
output='screen',
|
||||||
|
),
|
||||||
|
Node(
|
||||||
|
package='controller_manager',
|
||||||
|
executable='spawner',
|
||||||
|
arguments=['franka_robot_state_broadcaster'],
|
||||||
|
parameters=[{'arm_id': arm_id}],
|
||||||
|
output='screen',
|
||||||
|
condition=UnlessCondition(use_fake_hardware),
|
||||||
|
),
|
||||||
|
IncludeLaunchDescription(
|
||||||
|
PythonLaunchDescriptionSource([PathJoinSubstitution(
|
||||||
|
[FindPackageShare('franka_gripper'), 'launch', 'gripper.launch.py'])]),
|
||||||
|
launch_arguments={robot_ip_parameter_name: robot_ip,
|
||||||
|
use_fake_hardware_parameter_name: use_fake_hardware}.items(),
|
||||||
|
condition=IfCondition(load_gripper)
|
||||||
|
),
|
||||||
|
Node(package='rviz2',
|
||||||
|
executable='rviz2',
|
||||||
|
name='rviz2',
|
||||||
|
arguments=['--display-config', rviz_file],
|
||||||
|
condition=IfCondition(use_rviz)
|
||||||
|
)
|
||||||
|
|
||||||
|
])
|
||||||
|
|
||||||
|
return launch_description
|
|
@ -0,0 +1,85 @@
|
||||||
|
# Copyright (c) 2024 Franka Robotics GmbH
|
||||||
|
#
|
||||||
|
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
# you may not use this file except in compliance with the License.
|
||||||
|
# You may obtain a copy of the License at
|
||||||
|
#
|
||||||
|
# http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
#
|
||||||
|
# Unless required by applicable law or agreed to in writing, software
|
||||||
|
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
# See the License for the specific language governing permissions and
|
||||||
|
# limitations under the License.
|
||||||
|
|
||||||
|
|
||||||
|
from launch import LaunchDescription
|
||||||
|
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
|
||||||
|
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||||
|
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
from launch_ros.substitutions import FindPackageShare
|
||||||
|
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
robot_ip_parameter_name = 'robot_ip'
|
||||||
|
arm_id_parameter_name = 'arm_id'
|
||||||
|
load_gripper_parameter_name = 'load_gripper'
|
||||||
|
use_fake_hardware_parameter_name = 'use_fake_hardware'
|
||||||
|
fake_sensor_commands_parameter_name = 'fake_sensor_commands'
|
||||||
|
use_rviz_parameter_name = 'use_rviz'
|
||||||
|
|
||||||
|
robot_ip = LaunchConfiguration(robot_ip_parameter_name)
|
||||||
|
arm_id = LaunchConfiguration(arm_id_parameter_name)
|
||||||
|
load_gripper = LaunchConfiguration(load_gripper_parameter_name)
|
||||||
|
use_fake_hardware = LaunchConfiguration(use_fake_hardware_parameter_name)
|
||||||
|
fake_sensor_commands = LaunchConfiguration(
|
||||||
|
fake_sensor_commands_parameter_name)
|
||||||
|
use_rviz = LaunchConfiguration(use_rviz_parameter_name)
|
||||||
|
|
||||||
|
return LaunchDescription([
|
||||||
|
DeclareLaunchArgument(
|
||||||
|
robot_ip_parameter_name,
|
||||||
|
description='Hostname or IP address of the robot.'),
|
||||||
|
DeclareLaunchArgument(
|
||||||
|
arm_id_parameter_name,
|
||||||
|
default_value='fr3',
|
||||||
|
description='ID of the type of arm used. Supported values: fer, fr3, fp3'),
|
||||||
|
DeclareLaunchArgument(
|
||||||
|
use_rviz_parameter_name,
|
||||||
|
default_value='false',
|
||||||
|
description='Visualize the robot in Rviz'),
|
||||||
|
DeclareLaunchArgument(
|
||||||
|
use_fake_hardware_parameter_name,
|
||||||
|
default_value='false',
|
||||||
|
description='Use fake hardware'),
|
||||||
|
DeclareLaunchArgument(
|
||||||
|
fake_sensor_commands_parameter_name,
|
||||||
|
default_value='false',
|
||||||
|
description="Fake sensor commands. Only valid when '{}' is true".format(
|
||||||
|
use_fake_hardware_parameter_name)),
|
||||||
|
DeclareLaunchArgument(
|
||||||
|
load_gripper_parameter_name,
|
||||||
|
default_value='false',
|
||||||
|
description='Use Franka Gripper as an end-effector, otherwise, the robot is loaded '
|
||||||
|
'without an end-effector.'),
|
||||||
|
|
||||||
|
IncludeLaunchDescription(
|
||||||
|
PythonLaunchDescriptionSource([PathJoinSubstitution(
|
||||||
|
[FindPackageShare('franka_fr3_arm_controllers'), 'launch', 'franka.launch.py'])]),
|
||||||
|
launch_arguments={robot_ip_parameter_name: robot_ip,
|
||||||
|
arm_id_parameter_name: arm_id,
|
||||||
|
load_gripper_parameter_name: load_gripper,
|
||||||
|
use_fake_hardware_parameter_name: use_fake_hardware,
|
||||||
|
fake_sensor_commands_parameter_name: fake_sensor_commands,
|
||||||
|
use_rviz_parameter_name: use_rviz
|
||||||
|
}.items(),
|
||||||
|
),
|
||||||
|
|
||||||
|
Node(
|
||||||
|
package='controller_manager',
|
||||||
|
executable='spawner',
|
||||||
|
arguments=['joint_impedance_controller'],
|
||||||
|
output='screen',
|
||||||
|
),
|
||||||
|
])
|
36
ros2/src/franka_fr3_arm_controllers/package.xml
Normal file
36
ros2/src/franka_fr3_arm_controllers/package.xml
Normal file
|
@ -0,0 +1,36 @@
|
||||||
|
<?xml version="1.0"?>
|
||||||
|
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||||
|
<package format="3">
|
||||||
|
<name>franka_fr3_arm_controllers</name>
|
||||||
|
<version>0.1.0</version>
|
||||||
|
<description>Single arm controller for gello</description>
|
||||||
|
<maintainer email="support@franka.de">Franka Robotics GmbH</maintainer>
|
||||||
|
<license>Apache 2.0</license>
|
||||||
|
|
||||||
|
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||||
|
|
||||||
|
<depend>rclcpp</depend>
|
||||||
|
<depend>controller_interface</depend>
|
||||||
|
<depend>pluginlib</depend>
|
||||||
|
<depend>rclcpp_lifecycle</depend>
|
||||||
|
<depend>franka_msgs</depend>
|
||||||
|
<depend>franka_semantic_components</depend>
|
||||||
|
|
||||||
|
|
||||||
|
<test_depend>ament_cmake_clang_format</test_depend>
|
||||||
|
<test_depend>ament_cmake_copyright</test_depend>
|
||||||
|
<test_depend>ament_cmake_cppcheck</test_depend>
|
||||||
|
<test_depend>ament_cmake_flake8</test_depend>
|
||||||
|
<test_depend>ament_cmake_lint_cmake</test_depend>
|
||||||
|
<test_depend>ament_cmake_pep257</test_depend>
|
||||||
|
<test_depend>ament_cmake_xmllint</test_depend>
|
||||||
|
<test_depend>ament_cmake_gmock</test_depend>
|
||||||
|
<test_depend>ament_cmake_clang_tidy</test_depend>
|
||||||
|
<test_depend>controller_manager</test_depend>
|
||||||
|
<test_depend>ros2_control_test_assets</test_depend>
|
||||||
|
|
||||||
|
|
||||||
|
<export>
|
||||||
|
<build_type>ament_cmake</build_type>
|
||||||
|
</export>
|
||||||
|
</package>
|
|
@ -0,0 +1,242 @@
|
||||||
|
// Copyright (c) 2025 Franka Robotics GmbH
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#include <franka_fr3_arm_controllers/joint_impedance_controller.hpp>
|
||||||
|
|
||||||
|
#include <Eigen/Eigen>
|
||||||
|
#include <cassert>
|
||||||
|
#include <cmath>
|
||||||
|
#include <exception>
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
using std::placeholders::_1;
|
||||||
|
|
||||||
|
namespace franka_fr3_arm_controllers {
|
||||||
|
|
||||||
|
controller_interface::InterfaceConfiguration
|
||||||
|
JointImpedanceController::command_interface_configuration() const {
|
||||||
|
controller_interface::InterfaceConfiguration config;
|
||||||
|
config.type = controller_interface::interface_configuration_type::INDIVIDUAL;
|
||||||
|
|
||||||
|
for (int i = 1; i <= num_joints; ++i) {
|
||||||
|
config.names.push_back(arm_id_ + "_joint" + std::to_string(i) + "/effort");
|
||||||
|
}
|
||||||
|
return config;
|
||||||
|
}
|
||||||
|
|
||||||
|
controller_interface::InterfaceConfiguration
|
||||||
|
JointImpedanceController::state_interface_configuration() const {
|
||||||
|
controller_interface::InterfaceConfiguration config;
|
||||||
|
config.type = controller_interface::interface_configuration_type::INDIVIDUAL;
|
||||||
|
for (int i = 1; i <= num_joints; ++i) {
|
||||||
|
config.names.push_back(arm_id_ + "_joint" + std::to_string(i) + "/position");
|
||||||
|
config.names.push_back(arm_id_ + "_joint" + std::to_string(i) + "/velocity");
|
||||||
|
}
|
||||||
|
return config;
|
||||||
|
}
|
||||||
|
|
||||||
|
controller_interface::return_type JointImpedanceController::update(
|
||||||
|
const rclcpp::Time& /*time*/,
|
||||||
|
const rclcpp::Duration& /*period*/) {
|
||||||
|
updateJointStates_();
|
||||||
|
Vector7d q_goal;
|
||||||
|
Vector7d tau_d_calculated;
|
||||||
|
|
||||||
|
if (!move_to_start_position_finished_) {
|
||||||
|
auto trajectory_time = this->get_node()->now() - start_time_;
|
||||||
|
auto motion_generator_output = motion_generator_->getDesiredJointPositions(trajectory_time);
|
||||||
|
move_to_start_position_finished_ = motion_generator_output.second;
|
||||||
|
|
||||||
|
q_goal = motion_generator_output.first;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (move_to_start_position_finished_) {
|
||||||
|
if (!gello_position_values_valid_) {
|
||||||
|
RCLCPP_FATAL(get_node()->get_logger(), "Timeout: No valid joint states received from Gello");
|
||||||
|
rclcpp::shutdown(); // Exit the node permanently
|
||||||
|
}
|
||||||
|
for (int i = 0; i < num_joints; ++i) {
|
||||||
|
q_goal(i) = gello_position_values_[i];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
tau_d_calculated = calculateTauDGains_(q_goal);
|
||||||
|
|
||||||
|
for (int i = 0; i < num_joints; ++i) {
|
||||||
|
command_interfaces_[i].set_value(tau_d_calculated(i));
|
||||||
|
}
|
||||||
|
|
||||||
|
return controller_interface::return_type::OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void JointImpedanceController::jointStateCallback_(const sensor_msgs::msg::JointState msg) {
|
||||||
|
if (last_joint_state_time_.seconds() == 0.0) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (msg.position.size() < gello_position_values_.size()) {
|
||||||
|
RCLCPP_WARN(get_node()->get_logger(),
|
||||||
|
"Received joint state size is smaller than expected size.");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
std::copy(msg.position.begin(), msg.position.begin() + gello_position_values_.size(),
|
||||||
|
gello_position_values_.begin());
|
||||||
|
|
||||||
|
validateGelloPositions_(msg);
|
||||||
|
last_joint_state_time_ = msg.header.stamp;
|
||||||
|
}
|
||||||
|
|
||||||
|
CallbackReturn JointImpedanceController::on_init() {
|
||||||
|
try {
|
||||||
|
auto_declare<std::string>("arm_id", "");
|
||||||
|
auto_declare<std::vector<double>>("k_gains", {});
|
||||||
|
auto_declare<std::vector<double>>("d_gains", {});
|
||||||
|
} catch (const std::exception& e) {
|
||||||
|
fprintf(stderr, "Exception thrown during init stage with message: %s \n", e.what());
|
||||||
|
return CallbackReturn::ERROR;
|
||||||
|
}
|
||||||
|
return CallbackReturn::SUCCESS;
|
||||||
|
}
|
||||||
|
|
||||||
|
CallbackReturn JointImpedanceController::on_configure(
|
||||||
|
const rclcpp_lifecycle::State& /*previous_state*/) {
|
||||||
|
arm_id_ = get_node()->get_parameter("arm_id").as_string();
|
||||||
|
auto k_gains = get_node()->get_parameter("k_gains").as_double_array();
|
||||||
|
auto d_gains = get_node()->get_parameter("d_gains").as_double_array();
|
||||||
|
auto k_alpha = get_node()->get_parameter("k_alpha").as_double();
|
||||||
|
|
||||||
|
if (!validateGains_(k_gains, "k_gains") || !validateGains_(d_gains, "d_gains")) {
|
||||||
|
return CallbackReturn::FAILURE;
|
||||||
|
}
|
||||||
|
|
||||||
|
for (int i = 0; i < num_joints; ++i) {
|
||||||
|
d_gains_(i) = d_gains.at(i);
|
||||||
|
k_gains_(i) = k_gains.at(i);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (k_alpha < 0.0 || k_alpha > 1.0) {
|
||||||
|
RCLCPP_FATAL(get_node()->get_logger(), "k_alpha should be in the range [0, 1]");
|
||||||
|
return CallbackReturn::FAILURE;
|
||||||
|
}
|
||||||
|
|
||||||
|
k_alpha_ = k_alpha;
|
||||||
|
|
||||||
|
dq_filtered_.setZero();
|
||||||
|
|
||||||
|
auto parameters_client =
|
||||||
|
std::make_shared<rclcpp::AsyncParametersClient>(get_node(), "/robot_state_publisher");
|
||||||
|
parameters_client->wait_for_service();
|
||||||
|
|
||||||
|
auto future = parameters_client->get_parameters({"robot_description"});
|
||||||
|
auto result = future.get();
|
||||||
|
if (!result.empty()) {
|
||||||
|
robot_description_ = result[0].value_to_string();
|
||||||
|
} else {
|
||||||
|
RCLCPP_ERROR(get_node()->get_logger(), "Failed to get robot_description parameter.");
|
||||||
|
}
|
||||||
|
|
||||||
|
joint_state_subscriber_ = get_node()->create_subscription<sensor_msgs::msg::JointState>(
|
||||||
|
"/gello/joint_states", 1,
|
||||||
|
[this](const sensor_msgs::msg::JointState& msg) { jointStateCallback_(msg); });
|
||||||
|
|
||||||
|
return CallbackReturn::SUCCESS;
|
||||||
|
}
|
||||||
|
|
||||||
|
CallbackReturn JointImpedanceController::on_activate(
|
||||||
|
const rclcpp_lifecycle::State& /*previous_state*/) {
|
||||||
|
initializeMotionGenerator_();
|
||||||
|
|
||||||
|
dq_filtered_.setZero();
|
||||||
|
start_time_ = this->get_node()->now();
|
||||||
|
|
||||||
|
return CallbackReturn::SUCCESS;
|
||||||
|
}
|
||||||
|
|
||||||
|
auto JointImpedanceController::calculateTauDGains_(const Vector7d& q_goal) -> Vector7d {
|
||||||
|
dq_filtered_ = (1 - k_alpha_) * dq_filtered_ + k_alpha_ * dq_;
|
||||||
|
Vector7d tau_d_calculated;
|
||||||
|
tau_d_calculated = k_gains_.cwiseProduct(q_goal - q_) + d_gains_.cwiseProduct(-dq_filtered_);
|
||||||
|
|
||||||
|
return tau_d_calculated;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool JointImpedanceController::validateGains_(const std::vector<double>& gains,
|
||||||
|
const std::string& gains_name) {
|
||||||
|
if (gains.empty()) {
|
||||||
|
RCLCPP_FATAL(get_node()->get_logger(), "%s parameter not set", gains_name.c_str());
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gains.size() != static_cast<uint>(num_joints)) {
|
||||||
|
RCLCPP_FATAL(get_node()->get_logger(), "%s should be of size %d but is of size %ld",
|
||||||
|
gains_name.c_str(), num_joints, gains.size());
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void JointImpedanceController::validateGelloPositions_(const sensor_msgs::msg::JointState& msg) {
|
||||||
|
const double max_time_diff = 0.5;
|
||||||
|
auto current_time = get_node()->now();
|
||||||
|
auto time_since_last_joint_state = (current_time - last_joint_state_time_).seconds();
|
||||||
|
auto time_since_msg_stamp = (current_time - msg.header.stamp).seconds();
|
||||||
|
gello_position_values_valid_ =
|
||||||
|
(time_since_last_joint_state < max_time_diff && time_since_msg_stamp < max_time_diff);
|
||||||
|
if (!gello_position_values_valid_) {
|
||||||
|
RCLCPP_WARN(get_node()->get_logger(),
|
||||||
|
"Gello position values are not valid. Time since last joint state: %f // Time "
|
||||||
|
"since message stamp: %f",
|
||||||
|
time_since_last_joint_state, time_since_msg_stamp);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void JointImpedanceController::updateJointStates_() {
|
||||||
|
for (auto i = 0; i < num_joints; ++i) {
|
||||||
|
const auto& position_interface = state_interfaces_.at(2 * i);
|
||||||
|
const auto& velocity_interface = state_interfaces_.at(2 * i + 1);
|
||||||
|
|
||||||
|
assert(position_interface.get_interface_name() == "position");
|
||||||
|
assert(velocity_interface.get_interface_name() == "velocity");
|
||||||
|
|
||||||
|
q_(i) = position_interface.get_value();
|
||||||
|
dq_(i) = velocity_interface.get_value();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void JointImpedanceController::initializeMotionGenerator_() {
|
||||||
|
last_joint_state_time_ = get_node()->now();
|
||||||
|
while (!gello_position_values_valid_) {
|
||||||
|
RCLCPP_WARN(get_node()->get_logger(), "Waiting for valid joint states...");
|
||||||
|
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
|
||||||
|
last_joint_state_time_ = get_node()->now();
|
||||||
|
}
|
||||||
|
|
||||||
|
Vector7d q_goal;
|
||||||
|
updateJointStates_();
|
||||||
|
for (int i = 0; i < num_joints; ++i) {
|
||||||
|
q_goal(i) = gello_position_values_[i];
|
||||||
|
}
|
||||||
|
RCLCPP_INFO(get_node()->get_logger(), "q_goal of motion generator: [%f, %f, %f, %f, %f, %f, %f]",
|
||||||
|
q_goal(0), q_goal(1), q_goal(2), q_goal(3), q_goal(4), q_goal(5), q_goal(6));
|
||||||
|
|
||||||
|
const double motion_generator_speed_factor = 0.2;
|
||||||
|
motion_generator_ = std::make_unique<MotionGenerator>(motion_generator_speed_factor, q_, q_goal);
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace franka_fr3_arm_controllers
|
||||||
|
#include "pluginlib/class_list_macros.hpp"
|
||||||
|
// NOLINTNEXTLINE
|
||||||
|
PLUGINLIB_EXPORT_CLASS(franka_fr3_arm_controllers::JointImpedanceController,
|
||||||
|
controller_interface::ControllerInterface)
|
127
ros2/src/franka_fr3_arm_controllers/src/motion_generator.cpp
Normal file
127
ros2/src/franka_fr3_arm_controllers/src/motion_generator.cpp
Normal file
|
@ -0,0 +1,127 @@
|
||||||
|
// Copyright (c) 2023 Franka Robotics GmbH
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#include <franka_fr3_arm_controllers/motion_generator.hpp>
|
||||||
|
|
||||||
|
#include <algorithm>
|
||||||
|
#include <array>
|
||||||
|
#include <cassert>
|
||||||
|
#include <cmath>
|
||||||
|
#include <utility>
|
||||||
|
|
||||||
|
#include <Eigen/Core>
|
||||||
|
|
||||||
|
MotionGenerator::MotionGenerator(double speed_factor,
|
||||||
|
const Vector7d& q_start,
|
||||||
|
const Vector7d& q_goal)
|
||||||
|
: q_start_(q_start) {
|
||||||
|
assert(speed_factor > 0);
|
||||||
|
assert(speed_factor <= 1);
|
||||||
|
delta_q_ = q_goal - q_start;
|
||||||
|
dq_max_ *= speed_factor;
|
||||||
|
ddq_max_start_ *= speed_factor;
|
||||||
|
ddq_max_goal_ *= speed_factor;
|
||||||
|
calculateSynchronizedValues();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool MotionGenerator::calculateDesiredValues(double time, Vector7d* delta_q_d) const {
|
||||||
|
Vector7i sign_delta_q;
|
||||||
|
sign_delta_q << delta_q_.cwiseSign().cast<int>();
|
||||||
|
Vector7d t_d = t_2_sync_ - t_1_sync_;
|
||||||
|
Vector7d delta_t_2_sync = t_f_sync_ - t_2_sync_;
|
||||||
|
std::array<bool, kJoints> joint_motion_finished{};
|
||||||
|
|
||||||
|
for (auto i = 0; i < kJoints; i++) {
|
||||||
|
if (std::abs(delta_q_[i]) < kDeltaQMotionFinished) {
|
||||||
|
(*delta_q_d)[i] = 0;
|
||||||
|
joint_motion_finished.at(i) = true;
|
||||||
|
} else {
|
||||||
|
if (time < t_1_sync_[i]) {
|
||||||
|
(*delta_q_d)[i] = -1.0 / std::pow(t_1_sync_[i], 3.0) * dq_max_sync_[i] * sign_delta_q[i] *
|
||||||
|
(0.5 * time - t_1_sync_[i]) * std::pow(time, 3.0);
|
||||||
|
} else if (time >= t_1_sync_[i] && time < t_2_sync_[i]) {
|
||||||
|
(*delta_q_d)[i] = q_1_[i] + (time - t_1_sync_[i]) * dq_max_sync_[i] * sign_delta_q[i];
|
||||||
|
} else if (time >= t_2_sync_[i] && time < t_f_sync_[i]) {
|
||||||
|
(*delta_q_d)[i] =
|
||||||
|
delta_q_[i] +
|
||||||
|
0.5 *
|
||||||
|
(1.0 / std::pow(delta_t_2_sync[i], 3.0) *
|
||||||
|
(time - t_1_sync_[i] - 2.0 * delta_t_2_sync[i] - t_d[i]) *
|
||||||
|
std::pow((time - t_1_sync_[i] - t_d[i]), 3.0) +
|
||||||
|
(2.0 * time - 2.0 * t_1_sync_[i] - delta_t_2_sync[i] - 2.0 * t_d[i])) *
|
||||||
|
dq_max_sync_[i] * sign_delta_q[i];
|
||||||
|
} else {
|
||||||
|
(*delta_q_d)[i] = delta_q_[i];
|
||||||
|
joint_motion_finished.at(i) = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return std::all_of(joint_motion_finished.cbegin(), joint_motion_finished.cend(),
|
||||||
|
[](bool each_joint_finished) { return each_joint_finished; });
|
||||||
|
}
|
||||||
|
|
||||||
|
void MotionGenerator::calculateSynchronizedValues() {
|
||||||
|
Vector7d dq_max_reach(dq_max_);
|
||||||
|
Vector7d t_f = Vector7d::Zero();
|
||||||
|
Vector7d delta_t_2 = Vector7d::Zero();
|
||||||
|
Vector7d t_1 = Vector7d::Zero();
|
||||||
|
Vector7d delta_t_2_sync = Vector7d::Zero();
|
||||||
|
Vector7i sign_delta_q;
|
||||||
|
sign_delta_q << delta_q_.cwiseSign().cast<int>();
|
||||||
|
|
||||||
|
for (auto i = 0; i < kJoints; i++) {
|
||||||
|
if (std::abs(delta_q_[i]) > kDeltaQMotionFinished) {
|
||||||
|
if (std::abs(delta_q_[i]) < (3.0 / 4.0 * (std::pow(dq_max_[i], 2.0) / ddq_max_start_[i]) +
|
||||||
|
3.0 / 4.0 * (std::pow(dq_max_[i], 2.0) / ddq_max_goal_[i]))) {
|
||||||
|
dq_max_reach[i] = std::sqrt(4.0 / 3.0 * delta_q_[i] * sign_delta_q[i] *
|
||||||
|
(ddq_max_start_[i] * ddq_max_goal_[i]) /
|
||||||
|
(ddq_max_start_[i] + ddq_max_goal_[i]));
|
||||||
|
}
|
||||||
|
t_1[i] = 1.5 * dq_max_reach[i] / ddq_max_start_[i];
|
||||||
|
delta_t_2[i] = 1.5 * dq_max_reach[i] / ddq_max_goal_[i];
|
||||||
|
t_f[i] = t_1[i] / 2.0 + delta_t_2[i] / 2.0 + std::abs(delta_q_[i]) / dq_max_reach[i];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
double max_t_f = t_f.maxCoeff();
|
||||||
|
for (auto i = 0; i < kJoints; i++) {
|
||||||
|
if (std::abs(delta_q_[i]) > kDeltaQMotionFinished) {
|
||||||
|
double param_a = 1.5 / 2.0 * (ddq_max_goal_[i] + ddq_max_start_[i]);
|
||||||
|
double param_b = -1.0 * max_t_f * ddq_max_goal_[i] * ddq_max_start_[i];
|
||||||
|
double param_c = std::abs(delta_q_[i]) * ddq_max_goal_[i] * ddq_max_start_[i];
|
||||||
|
double delta = param_b * param_b - 4.0 * param_a * param_c;
|
||||||
|
if (delta < 0.0) {
|
||||||
|
delta = 0.0;
|
||||||
|
}
|
||||||
|
dq_max_sync_[i] = (-1.0 * param_b - std::sqrt(delta)) / (2.0 * param_a);
|
||||||
|
t_1_sync_[i] = 1.5 * dq_max_sync_[i] / ddq_max_start_[i];
|
||||||
|
delta_t_2_sync[i] = 1.5 * dq_max_sync_[i] / ddq_max_goal_[i];
|
||||||
|
t_f_sync_[i] =
|
||||||
|
(t_1_sync_)[i] / 2.0 + delta_t_2_sync[i] / 2.0 + std::abs(delta_q_[i] / dq_max_sync_[i]);
|
||||||
|
t_2_sync_[i] = (t_f_sync_)[i] - delta_t_2_sync[i];
|
||||||
|
q_1_[i] = (dq_max_sync_)[i] * sign_delta_q[i] * (0.5 * (t_1_sync_)[i]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
std::pair<MotionGenerator::Vector7d, bool> MotionGenerator::getDesiredJointPositions(
|
||||||
|
const rclcpp::Duration& trajectory_time) {
|
||||||
|
time_ = trajectory_time.seconds();
|
||||||
|
|
||||||
|
Vector7d delta_q_d;
|
||||||
|
bool motion_finished = calculateDesiredValues(time_, &delta_q_d);
|
||||||
|
|
||||||
|
std::array<double, kJoints> joint_positions{};
|
||||||
|
Eigen::VectorXd::Map(joint_positions.data(), kJoints) = (q_start_ + delta_q_d);
|
||||||
|
return std::make_pair(q_start_ + delta_q_d, motion_finished);
|
||||||
|
}
|
|
@ -0,0 +1,48 @@
|
||||||
|
// Copyright (c) 2025 Franka Robotics GmbH
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <rclcpp/rclcpp.hpp>
|
||||||
|
#include <sensor_msgs/msg/joint_state.hpp>
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @class MockGelloJointStatePublisher
|
||||||
|
* @brief A mock joint state publisher node replacing the gello publisher for testing purposes.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
class MockGelloJointStatePublisher : public rclcpp::Node {
|
||||||
|
public:
|
||||||
|
MockGelloJointStatePublisher() : Node("joint_state_publisher_node") {
|
||||||
|
publisher_ = this->create_publisher<sensor_msgs::msg::JointState>("/gello/joint_states", 3);
|
||||||
|
timer_ =
|
||||||
|
this->create_wall_timer(std::chrono::milliseconds(100),
|
||||||
|
std::bind(&MockGelloJointStatePublisher::publishJointState_, this));
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
void publishJointState_() {
|
||||||
|
auto message = sensor_msgs::msg::JointState();
|
||||||
|
message.header.stamp = this->now();
|
||||||
|
message.name = {"joint1", "joint2", "joint3", "joint4", "joint5", "joint6", "joint7", "joint8"};
|
||||||
|
message.position = {1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0};
|
||||||
|
message.velocity = {0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1};
|
||||||
|
message.effort = {0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01};
|
||||||
|
|
||||||
|
publisher_->publish(message);
|
||||||
|
}
|
||||||
|
|
||||||
|
rclcpp::Publisher<sensor_msgs::msg::JointState>::SharedPtr publisher_;
|
||||||
|
rclcpp::TimerBase::SharedPtr timer_;
|
||||||
|
};
|
|
@ -0,0 +1,29 @@
|
||||||
|
// Copyright (c) 2025 Franka Robotics GmbH
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <rclcpp/rclcpp.hpp>
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @class MockRobotParameterServer
|
||||||
|
* @brief A mock parameter server node replacing the robot parameter server for testing purposes.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
class MockRobotParameterServer : public rclcpp::Node {
|
||||||
|
public:
|
||||||
|
MockRobotParameterServer() : Node("robot_state_publisher") {
|
||||||
|
this->declare_parameter("robot_description", std::string("<robot>...</robot>"));
|
||||||
|
}
|
||||||
|
};
|
|
@ -0,0 +1,81 @@
|
||||||
|
// Copyright (c) 2025 Franka Robotics GmbH
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <gtest/gtest.h>
|
||||||
|
#include <rclcpp/rclcpp.hpp>
|
||||||
|
#include <sensor_msgs/msg/joint_state.hpp>
|
||||||
|
#include "franka_fr3_arm_controllers/joint_impedance_controller.hpp"
|
||||||
|
#include "hardware_interface/types/hardware_interface_type_values.hpp"
|
||||||
|
#include "mocks/mock_joint_state_publisher.hpp"
|
||||||
|
#include "mocks/mock_parameter_server.hpp"
|
||||||
|
|
||||||
|
using hardware_interface::CommandInterface;
|
||||||
|
using hardware_interface::HW_IF_EFFORT;
|
||||||
|
using hardware_interface::HW_IF_POSITION;
|
||||||
|
using hardware_interface::HW_IF_VELOCITY;
|
||||||
|
using hardware_interface::LoanedCommandInterface;
|
||||||
|
using hardware_interface::LoanedStateInterface;
|
||||||
|
using hardware_interface::StateInterface;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Test fixture for the JointImpedanceController
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
class JointImpedanceControllerTest : public ::testing::Test {
|
||||||
|
public:
|
||||||
|
JointImpedanceControllerTest();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void SetUp() override;
|
||||||
|
void TearDown() override;
|
||||||
|
void startExecutorThread();
|
||||||
|
void stopExecutorThread();
|
||||||
|
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn startController();
|
||||||
|
void setRobotPosition(const std::vector<double>& positions);
|
||||||
|
void setValidControllerParameters();
|
||||||
|
|
||||||
|
std::shared_ptr<franka_fr3_arm_controllers::JointImpedanceController> controller_;
|
||||||
|
std::shared_ptr<MockRobotParameterServer> mock_parameter_server_;
|
||||||
|
std::shared_ptr<MockGelloJointStatePublisher> mock_joint_state_publisher_;
|
||||||
|
std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> executor_;
|
||||||
|
std::thread executor_thread_;
|
||||||
|
std::condition_variable cv_executor_thread_;
|
||||||
|
std::mutex cv_mut_executor_thread_;
|
||||||
|
bool done_;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Current state of the "robot"
|
||||||
|
*/
|
||||||
|
static constexpr size_t num_joints = 7;
|
||||||
|
static constexpr std::array<double, num_joints> kInitialJointCommands = {1.0, 1.0, 1.0, 1.0,
|
||||||
|
1.0, 1.0, 1.0};
|
||||||
|
static constexpr std::array<double, num_joints> kInitialPositionStates = {1.0, 1.0, 1.0, 1.0,
|
||||||
|
1.0, 1.0, 1.0};
|
||||||
|
static constexpr std::array<double, num_joints> kInitialVelocityStates = {1.0, 1.0, 1.0, 1.0,
|
||||||
|
1.0, 1.0, 1.0};
|
||||||
|
|
||||||
|
const std::array<std::string, num_joints> joint_names_ = {
|
||||||
|
"fr3_joint1", "fr3_joint2", "fr3_joint3", "fr3_joint4",
|
||||||
|
"fr3_joint5", "fr3_joint6", "fr3_joint7"};
|
||||||
|
|
||||||
|
std::vector<double> joint_commands_{kInitialJointCommands.begin(), kInitialJointCommands.end()};
|
||||||
|
std::vector<double> position_states_{kInitialPositionStates.begin(),
|
||||||
|
kInitialPositionStates.end()};
|
||||||
|
std::vector<double> velocity_states_{kInitialVelocityStates.begin(),
|
||||||
|
kInitialVelocityStates.end()};
|
||||||
|
std::vector<CommandInterface> command_interfaces_;
|
||||||
|
std::vector<StateInterface> state_interfaces_;
|
||||||
|
};
|
|
@ -0,0 +1,44 @@
|
||||||
|
// Copyright (c) 2025 Franka Robotics GmbH
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#include "include/test_joint_impedance_controller.hpp"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Test fixture for the JointImpedanceController
|
||||||
|
*/
|
||||||
|
class InvalidConfigurationTest : public JointImpedanceControllerTest,
|
||||||
|
public ::testing::WithParamInterface<rclcpp::Parameter> {};
|
||||||
|
|
||||||
|
TEST_P(InvalidConfigurationTest, TestInvalidConfiguration) {
|
||||||
|
auto parameter_invalid_configuration = GetParam();
|
||||||
|
controller_->get_node()->set_parameters({parameter_invalid_configuration});
|
||||||
|
controller_->on_init();
|
||||||
|
rclcpp_lifecycle::State state;
|
||||||
|
|
||||||
|
EXPECT_EQ(controller_->on_configure(state), CallbackReturn::FAILURE);
|
||||||
|
}
|
||||||
|
|
||||||
|
INSTANTIATE_TEST_SUITE_P(
|
||||||
|
InvalidConfigurations,
|
||||||
|
InvalidConfigurationTest,
|
||||||
|
::testing::Values(rclcpp::Parameter("k_gains",
|
||||||
|
std::vector<double>{1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0,
|
||||||
|
1.0}), // exceeding number of joints
|
||||||
|
rclcpp::Parameter("d_gains",
|
||||||
|
std::vector<double>{1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0,
|
||||||
|
1.0}), // exceeding number of joints
|
||||||
|
rclcpp::Parameter("k_gains", std::vector<double>{}), // empty
|
||||||
|
rclcpp::Parameter("d_gains", std::vector<double>{}), // empty
|
||||||
|
rclcpp::Parameter("k_alpha", double(-1.0)), // out of range (<0)
|
||||||
|
rclcpp::Parameter("k_alpha", double(2.0)))); // out of range (>1)
|
119
ros2/src/franka_fr3_arm_controllers/test/setup_test.cpp
Normal file
119
ros2/src/franka_fr3_arm_controllers/test/setup_test.cpp
Normal file
|
@ -0,0 +1,119 @@
|
||||||
|
// Copyright (c) 2025 Franka Robotics GmbH
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#include "include/test_joint_impedance_controller.hpp"
|
||||||
|
|
||||||
|
TEST_F(JointImpedanceControllerTest, TestInitialization) {
|
||||||
|
EXPECT_EQ(controller_->on_init(), CallbackReturn::SUCCESS);
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(JointImpedanceControllerTest, TestValidConfiguration) {
|
||||||
|
controller_->on_init();
|
||||||
|
rclcpp_lifecycle::State state;
|
||||||
|
|
||||||
|
EXPECT_EQ(controller_->on_configure(state), CallbackReturn::SUCCESS);
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(JointImpedanceControllerTest, TestActivate) {
|
||||||
|
EXPECT_EQ(startController(), CallbackReturn::SUCCESS);
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(JointImpedanceControllerTest, TestUpdateMotionGeneratorOnly) {
|
||||||
|
static const std::vector<double> kInitialRobotPosition = {0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1};
|
||||||
|
static constexpr double kExpectedValue = -0.05;
|
||||||
|
static constexpr double kTolerance = 1e-6;
|
||||||
|
|
||||||
|
setRobotPosition(kInitialRobotPosition);
|
||||||
|
startController();
|
||||||
|
|
||||||
|
rclcpp::Time time;
|
||||||
|
rclcpp::Duration period = rclcpp::Duration::from_seconds(1.0);
|
||||||
|
EXPECT_EQ(controller_->update(time, period), controller_interface::return_type::OK);
|
||||||
|
|
||||||
|
for (size_t i = 0; i < joint_commands_.size(); ++i) {
|
||||||
|
EXPECT_NEAR(joint_commands_[i], kExpectedValue, kTolerance);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(JointImpedanceControllerTest, TestUpdateMotionGeneratorAndGelloPositionValues) {
|
||||||
|
static const std::vector<double> kInitialRobotPosition = {1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0};
|
||||||
|
static constexpr double kExpectedValue = -0.05;
|
||||||
|
static constexpr double kTolerance = 1e-6;
|
||||||
|
|
||||||
|
setRobotPosition(kInitialRobotPosition);
|
||||||
|
startController();
|
||||||
|
|
||||||
|
rclcpp::Time time;
|
||||||
|
rclcpp::Duration period = rclcpp::Duration::from_seconds(1.0);
|
||||||
|
EXPECT_EQ(controller_->update(time, period), controller_interface::return_type::OK);
|
||||||
|
|
||||||
|
for (size_t i = 0; i < joint_commands_.size(); ++i) {
|
||||||
|
EXPECT_NEAR(joint_commands_[i], kExpectedValue, kTolerance);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(JointImpedanceControllerTest, TestUpdateGelloPositionValuesOnly) {
|
||||||
|
static const std::vector<double> kInitialRobotPosition = {1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0};
|
||||||
|
static constexpr double kExpectedValue = -0.075;
|
||||||
|
static constexpr double kTolerance = 1e-6;
|
||||||
|
|
||||||
|
setRobotPosition(kInitialRobotPosition);
|
||||||
|
startController();
|
||||||
|
|
||||||
|
rclcpp::Time time;
|
||||||
|
rclcpp::Duration period = rclcpp::Duration::from_seconds(1.0);
|
||||||
|
EXPECT_EQ(controller_->update(time, period), controller_interface::return_type::OK);
|
||||||
|
period = rclcpp::Duration::from_seconds(1.1);
|
||||||
|
EXPECT_EQ(controller_->update(time, period), controller_interface::return_type::OK);
|
||||||
|
|
||||||
|
for (size_t i = 0; i < joint_commands_.size(); ++i) {
|
||||||
|
EXPECT_NEAR(joint_commands_[i], kExpectedValue, kTolerance);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(JointImpedanceControllerTest, TestUpdateInvalidGelloPositionValues) {
|
||||||
|
GTEST_SKIP() << "Skipping this test because yet not implemented";
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Description: Modify mock_joint_state_publisher.hpp (Fake Gello), to be reconfigured to publish
|
||||||
|
* invalid joint states (invalid / old timestamp).
|
||||||
|
*/
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(JointImpedanceControllerTest, TestCommandInterfaceConfiguration) {
|
||||||
|
controller_->on_init();
|
||||||
|
rclcpp_lifecycle::State state;
|
||||||
|
controller_->on_configure(state);
|
||||||
|
|
||||||
|
auto config = controller_->command_interface_configuration();
|
||||||
|
EXPECT_EQ(config.type, controller_interface::interface_configuration_type::INDIVIDUAL);
|
||||||
|
ASSERT_EQ(config.names.size(), command_interfaces_.size());
|
||||||
|
for (size_t i = 0; i < command_interfaces_.size(); i++) {
|
||||||
|
EXPECT_EQ(config.names[i], joint_names_[i] + "/" + HW_IF_EFFORT);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(JointImpedanceControllerTest, TestStateInterfaceConfiguration) {
|
||||||
|
controller_->on_init();
|
||||||
|
rclcpp_lifecycle::State state;
|
||||||
|
controller_->on_configure(state);
|
||||||
|
|
||||||
|
auto config = controller_->state_interface_configuration();
|
||||||
|
EXPECT_EQ(config.type, controller_interface::interface_configuration_type::INDIVIDUAL);
|
||||||
|
ASSERT_EQ(config.names.size(), state_interfaces_.size());
|
||||||
|
for (size_t i = 0; i < joint_names_.size(); ++i) {
|
||||||
|
EXPECT_EQ(config.names[2 * i], joint_names_[i] + "/" + HW_IF_POSITION);
|
||||||
|
EXPECT_EQ(config.names[2 * i + 1], joint_names_[i] + "/" + HW_IF_VELOCITY);
|
||||||
|
}
|
||||||
|
}
|
|
@ -0,0 +1,113 @@
|
||||||
|
// Copyright (c) 2025 Franka Robotics GmbH
|
||||||
|
//
|
||||||
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
// you may not use this file except in compliance with the License.
|
||||||
|
// You may obtain a copy of the License at
|
||||||
|
//
|
||||||
|
// http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
//
|
||||||
|
// Unless required by applicable law or agreed to in writing, software
|
||||||
|
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
// See the License for the specific language governing permissions and
|
||||||
|
// limitations under the License.
|
||||||
|
|
||||||
|
#include "include/test_joint_impedance_controller.hpp"
|
||||||
|
|
||||||
|
JointImpedanceControllerTest::JointImpedanceControllerTest() : done_(false) {
|
||||||
|
for (size_t i = 0; i < joint_names_.size(); ++i) {
|
||||||
|
command_interfaces_.emplace_back(joint_names_[i], HW_IF_EFFORT, &joint_commands_[i]);
|
||||||
|
state_interfaces_.emplace_back(joint_names_[i], HW_IF_POSITION, &position_states_[i]);
|
||||||
|
state_interfaces_.emplace_back(joint_names_[i], HW_IF_VELOCITY, &velocity_states_[i]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void JointImpedanceControllerTest::SetUp() {
|
||||||
|
rclcpp::init(0, nullptr);
|
||||||
|
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
|
||||||
|
|
||||||
|
controller_ = std::make_shared<franka_fr3_arm_controllers::JointImpedanceController>();
|
||||||
|
controller_->init("single_arm_controller_test");
|
||||||
|
|
||||||
|
mock_parameter_server_ = std::make_shared<MockRobotParameterServer>();
|
||||||
|
mock_joint_state_publisher_ = std::make_shared<MockGelloJointStatePublisher>();
|
||||||
|
|
||||||
|
executor_->add_node(controller_->get_node()->get_node_base_interface());
|
||||||
|
executor_->add_node(mock_parameter_server_);
|
||||||
|
executor_->add_node(mock_joint_state_publisher_);
|
||||||
|
|
||||||
|
std::vector<LoanedCommandInterface> loaned_command_interfaces;
|
||||||
|
loaned_command_interfaces.reserve(command_interfaces_.size());
|
||||||
|
for (auto& command_interface : command_interfaces_) {
|
||||||
|
loaned_command_interfaces.emplace_back(command_interface);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<LoanedStateInterface> loaned_state_interfaces;
|
||||||
|
loaned_state_interfaces.reserve(state_interfaces_.size());
|
||||||
|
for (auto& state_interface : state_interfaces_) {
|
||||||
|
loaned_state_interfaces.emplace_back(state_interface);
|
||||||
|
}
|
||||||
|
|
||||||
|
controller_->assign_interfaces(std::move(loaned_command_interfaces),
|
||||||
|
std::move(loaned_state_interfaces));
|
||||||
|
|
||||||
|
setValidControllerParameters();
|
||||||
|
|
||||||
|
startExecutorThread();
|
||||||
|
}
|
||||||
|
|
||||||
|
void JointImpedanceControllerTest::TearDown() {
|
||||||
|
stopExecutorThread();
|
||||||
|
|
||||||
|
executor_->remove_node(controller_->get_node()->get_node_base_interface());
|
||||||
|
executor_->remove_node(mock_joint_state_publisher_);
|
||||||
|
executor_->remove_node(mock_parameter_server_);
|
||||||
|
|
||||||
|
rclcpp::shutdown();
|
||||||
|
}
|
||||||
|
|
||||||
|
void JointImpedanceControllerTest::startExecutorThread() {
|
||||||
|
done_ = false;
|
||||||
|
executor_thread_ = std::thread([this]() {
|
||||||
|
std::unique_lock<std::mutex> lock(cv_mut_executor_thread_);
|
||||||
|
while (!done_) {
|
||||||
|
executor_->spin_some();
|
||||||
|
cv_executor_thread_.wait_for(lock, std::chrono::milliseconds(10));
|
||||||
|
}
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
void JointImpedanceControllerTest::stopExecutorThread() {
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> lock(cv_mut_executor_thread_);
|
||||||
|
done_ = true;
|
||||||
|
}
|
||||||
|
cv_executor_thread_.notify_all();
|
||||||
|
if (executor_thread_.joinable()) {
|
||||||
|
executor_thread_.join();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
|
||||||
|
JointImpedanceControllerTest::startController() {
|
||||||
|
controller_->on_init();
|
||||||
|
rclcpp_lifecycle::State state;
|
||||||
|
controller_->on_configure(state);
|
||||||
|
return controller_->on_activate(state);
|
||||||
|
}
|
||||||
|
|
||||||
|
void JointImpedanceControllerTest::setRobotPosition(const std::vector<double>& positions) {
|
||||||
|
for (size_t i = 0; i < positions.size(); ++i) {
|
||||||
|
position_states_[i] = positions[i];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void JointImpedanceControllerTest::setValidControllerParameters() {
|
||||||
|
static const std::string kArmId = "fr3";
|
||||||
|
static const std::vector<double> kKGains = {1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0};
|
||||||
|
static const std::vector<double> kDGains = {0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1};
|
||||||
|
static constexpr double kKAlpha = 0.5;
|
||||||
|
|
||||||
|
controller_->get_node()->set_parameters(
|
||||||
|
{{"arm_id", kArmId}, {"k_gains", kKGains}, {"d_gains", kDGains}, {"k_alpha", kKAlpha}});
|
||||||
|
}
|
22
ros2/src/franka_gello_state_publisher/LICENSE
Normal file
22
ros2/src/franka_gello_state_publisher/LICENSE
Normal file
|
@ -0,0 +1,22 @@
|
||||||
|
MIT License
|
||||||
|
|
||||||
|
Original Copyright (c) 2023 Philipp Wu
|
||||||
|
Modified Copyright (c) 2025 Franka Robotics GmbH
|
||||||
|
|
||||||
|
Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
of this software and associated documentation files (the "Software"), to deal
|
||||||
|
in the Software without restriction, including without limitation the rights
|
||||||
|
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
copies of the Software, and to permit persons to whom the Software is
|
||||||
|
furnished to do so, subject to the following conditions:
|
||||||
|
|
||||||
|
The above copyright notice and this permission notice shall be included in all
|
||||||
|
copies or substantial portions of the Software.
|
||||||
|
|
||||||
|
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||||
|
SOFTWARE.
|
|
@ -0,0 +1,7 @@
|
||||||
|
usb-FTDI_USB__-__Serial_Converter_FT94EVW4-if00-port0:
|
||||||
|
side: "sample-config"
|
||||||
|
num_joints: 7
|
||||||
|
joint_signs: [1, 1, 1, 1, 1, -1, 1]
|
||||||
|
gripper: true
|
||||||
|
best_offsets: [6.283, 4.712, 3.142, 3.142, 3.142, 3.142, 4.712]
|
||||||
|
gripper_range_rad: [2.77856, 3.50931]
|
|
@ -0,0 +1,132 @@
|
||||||
|
import os
|
||||||
|
import glob
|
||||||
|
from typing import Tuple
|
||||||
|
import rclpy
|
||||||
|
from rclpy.node import Node
|
||||||
|
import numpy as np
|
||||||
|
|
||||||
|
try:
|
||||||
|
from franka_gello_state_publisher.driver import DynamixelDriver
|
||||||
|
except ImportError:
|
||||||
|
from driver import DynamixelDriver
|
||||||
|
from sensor_msgs.msg import JointState
|
||||||
|
from std_msgs.msg import Float32
|
||||||
|
import yaml
|
||||||
|
from ament_index_python.packages import get_package_share_directory
|
||||||
|
|
||||||
|
|
||||||
|
class GelloPublisher(Node):
|
||||||
|
def __init__(self):
|
||||||
|
super().__init__("gello_publisher")
|
||||||
|
|
||||||
|
default_com_port = self.determine_default_com_port()
|
||||||
|
self.declare_parameter("com_port", default_com_port)
|
||||||
|
self.com_port = self.get_parameter("com_port").get_parameter_value().string_value
|
||||||
|
self.port = self.com_port.split("/")[-1]
|
||||||
|
"""The port that GELLO is connected to."""
|
||||||
|
|
||||||
|
config_path = os.path.join(
|
||||||
|
get_package_share_directory("franka_gello_state_publisher"),
|
||||||
|
"config",
|
||||||
|
"gello_config.yaml",
|
||||||
|
)
|
||||||
|
self.get_values_from_config(config_path)
|
||||||
|
|
||||||
|
self.robot_joint_publisher = self.create_publisher(JointState, "/gello/joint_states", 10)
|
||||||
|
self.gripper_joint_publisher = self.create_publisher(
|
||||||
|
Float32, "/gripper_client/target_gripper_width_percent", 10
|
||||||
|
)
|
||||||
|
|
||||||
|
self.timer = self.create_timer(1 / 25, self.publish_joint_jog)
|
||||||
|
|
||||||
|
self.joint_names = [
|
||||||
|
"fr3_joint1",
|
||||||
|
"fr3_joint2",
|
||||||
|
"fr3_joint3",
|
||||||
|
"fr3_joint4",
|
||||||
|
"fr3_joint5",
|
||||||
|
"fr3_joint6",
|
||||||
|
"fr3_joint7",
|
||||||
|
]
|
||||||
|
|
||||||
|
def determine_default_com_port(self) -> str:
|
||||||
|
matches = glob.glob("/dev/serial/by-id/usb-FTDI_USB__-__Serial_Converter*")
|
||||||
|
if matches:
|
||||||
|
self.get_logger().info(f"Auto-detected com_ports: {matches}")
|
||||||
|
return matches[0]
|
||||||
|
else:
|
||||||
|
self.get_logger().warn("No com_ports detected. Please specify the com_port manually.")
|
||||||
|
return "INVALID_COM_PORT"
|
||||||
|
|
||||||
|
def get_values_from_config(self, config_file: str):
|
||||||
|
with open(config_file, "r") as file:
|
||||||
|
config = yaml.safe_load(file)
|
||||||
|
|
||||||
|
self.num_robot_joints: int = config[self.port]["num_joints"]
|
||||||
|
"""The number of joints in the robot."""
|
||||||
|
|
||||||
|
self.joint_signs: Tuple[float, ...] = config[self.port]["joint_signs"]
|
||||||
|
"""Depending on how the motor is mounted on the Gello, its rotation direction can be reversed."""
|
||||||
|
|
||||||
|
self.gripper: bool = config[self.port]["gripper"]
|
||||||
|
"""Whether or not the gripper is attached."""
|
||||||
|
|
||||||
|
joint_ids = list(range(1, self.num_joints + 1))
|
||||||
|
self.driver = DynamixelDriver(joint_ids, port=self.com_port, baudrate=57600)
|
||||||
|
"""The driver for the Dynamixel motors."""
|
||||||
|
|
||||||
|
self.best_offsets = np.array(config[self.port]["best_offsets"])
|
||||||
|
"""The best offsets for the joints."""
|
||||||
|
|
||||||
|
self.gripper_range_rad: Tuple[float, float] = config[self.port]["gripper_range_rad"]
|
||||||
|
"""The range of the gripper in radians."""
|
||||||
|
|
||||||
|
self.__post_init__()
|
||||||
|
|
||||||
|
def __post_init__(self):
|
||||||
|
assert len(self.joint_signs) == self.num_robot_joints
|
||||||
|
for idx, j in enumerate(self.joint_signs):
|
||||||
|
assert j == -1 or j == 1, f"Joint idx: {idx} should be -1 or 1, but got {j}."
|
||||||
|
|
||||||
|
@property
|
||||||
|
def num_joints(self) -> int:
|
||||||
|
extra_joints = 1 if self.gripper else 0
|
||||||
|
return self.num_robot_joints + extra_joints
|
||||||
|
|
||||||
|
def publish_joint_jog(self):
|
||||||
|
current_joints = self.driver.get_joints()
|
||||||
|
current_robot_joints = current_joints[: self.num_robot_joints]
|
||||||
|
current_joints_corrected = (current_robot_joints - self.best_offsets) * self.joint_signs
|
||||||
|
|
||||||
|
robot_joint_states = JointState()
|
||||||
|
robot_joint_states.header.stamp = self.get_clock().now().to_msg()
|
||||||
|
robot_joint_states.name = self.joint_names
|
||||||
|
robot_joint_states.header.frame_id = "fr3_link0"
|
||||||
|
robot_joint_states.position = [float(joint) for joint in current_joints_corrected]
|
||||||
|
|
||||||
|
gripper_joint_states = Float32()
|
||||||
|
if self.gripper:
|
||||||
|
gripper_position = current_joints[-1]
|
||||||
|
gripper_joint_states.data = self.gripper_readout_to_percent(gripper_position)
|
||||||
|
else:
|
||||||
|
gripper_joint_states.position = 0.0
|
||||||
|
self.robot_joint_publisher.publish(robot_joint_states)
|
||||||
|
self.gripper_joint_publisher.publish(gripper_joint_states)
|
||||||
|
|
||||||
|
def gripper_readout_to_percent(self, gripper_position: float) -> float:
|
||||||
|
gripper_percent = (gripper_position - self.gripper_range_rad[0]) / (
|
||||||
|
self.gripper_range_rad[1] - self.gripper_range_rad[0]
|
||||||
|
)
|
||||||
|
return max(0.0, min(1.0, gripper_percent))
|
||||||
|
|
||||||
|
|
||||||
|
def main(args=None):
|
||||||
|
rclpy.init(args=args)
|
||||||
|
gello_publisher = GelloPublisher()
|
||||||
|
rclpy.spin(gello_publisher)
|
||||||
|
gello_publisher.destroy_node()
|
||||||
|
rclpy.shutdown()
|
||||||
|
|
||||||
|
|
||||||
|
if __name__ == "__main__":
|
||||||
|
main()
|
22
ros2/src/franka_gello_state_publisher/launch/main.launch.py
Executable file
22
ros2/src/franka_gello_state_publisher/launch/main.launch.py
Executable file
|
@ -0,0 +1,22 @@
|
||||||
|
from launch import LaunchDescription
|
||||||
|
from launch.actions import DeclareLaunchArgument
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
from launch.substitutions import LaunchConfiguration
|
||||||
|
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
args = []
|
||||||
|
args.append(
|
||||||
|
DeclareLaunchArgument(name="com_port", default_value=None, description="Default COM port")
|
||||||
|
)
|
||||||
|
nodes = [
|
||||||
|
Node(
|
||||||
|
package="franka_gello_state_publisher",
|
||||||
|
executable="gello_publisher",
|
||||||
|
name="gello_publisher",
|
||||||
|
output="screen",
|
||||||
|
parameters=[{"com_port": LaunchConfiguration("com_port")}],
|
||||||
|
),
|
||||||
|
]
|
||||||
|
|
||||||
|
return LaunchDescription(args + nodes)
|
24
ros2/src/franka_gello_state_publisher/package.xml
Normal file
24
ros2/src/franka_gello_state_publisher/package.xml
Normal file
|
@ -0,0 +1,24 @@
|
||||||
|
<?xml version="1.0"?>
|
||||||
|
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||||
|
<package format="3">
|
||||||
|
<name>franka_gello_state_publisher</name>
|
||||||
|
<version>0.1.0</version>
|
||||||
|
<description>Publisher of joint states of gello</description>
|
||||||
|
<maintainer email="support@franka.de">Franka Robotics GmbH</maintainer>
|
||||||
|
<license>MIT</license>
|
||||||
|
|
||||||
|
<depend>rclpy</depend>
|
||||||
|
<depend>std_msgs</depend>
|
||||||
|
<depend>sensor_msgs</depend>
|
||||||
|
<depend>control_msgs</depend>
|
||||||
|
<depend>geometry_msgs</depend>
|
||||||
|
|
||||||
|
<test_depend>ament_copyright</test_depend>
|
||||||
|
<test_depend>ament_flake8</test_depend>
|
||||||
|
<test_depend>ament_pep257</test_depend>
|
||||||
|
<test_depend>python3-pytest</test_depend>
|
||||||
|
|
||||||
|
<export>
|
||||||
|
<build_type>ament_python</build_type>
|
||||||
|
</export>
|
||||||
|
</package>
|
4
ros2/src/franka_gello_state_publisher/setup.cfg
Normal file
4
ros2/src/franka_gello_state_publisher/setup.cfg
Normal file
|
@ -0,0 +1,4 @@
|
||||||
|
[develop]
|
||||||
|
script_dir=$base/lib/franka_gello_state_publisher
|
||||||
|
[install]
|
||||||
|
install_scripts=$base/lib/franka_gello_state_publisher
|
26
ros2/src/franka_gello_state_publisher/setup.py
Normal file
26
ros2/src/franka_gello_state_publisher/setup.py
Normal file
|
@ -0,0 +1,26 @@
|
||||||
|
from setuptools import find_packages, setup
|
||||||
|
import glob
|
||||||
|
|
||||||
|
package_name = "franka_gello_state_publisher"
|
||||||
|
|
||||||
|
setup(
|
||||||
|
name=package_name,
|
||||||
|
version="0.1.0",
|
||||||
|
packages=find_packages(exclude=["test"]),
|
||||||
|
data_files=[
|
||||||
|
("share/ament_index/resource_index/packages", ["resource/" + package_name]),
|
||||||
|
("share/" + package_name, ["package.xml"]),
|
||||||
|
("share/" + package_name + "/config", glob.glob("config/*.yaml")),
|
||||||
|
("share/" + package_name + "/launch", ["launch/main.launch.py"]),
|
||||||
|
],
|
||||||
|
install_requires=["setuptools", "dynamixel_sdk"],
|
||||||
|
zip_safe=True,
|
||||||
|
maintainer="Franka Robotics GmbH",
|
||||||
|
maintainer_email="support@franka.de",
|
||||||
|
description="Publishes the state of the GELLO teleoperation device.",
|
||||||
|
license="MIT",
|
||||||
|
tests_require=["pytest"],
|
||||||
|
entry_points={
|
||||||
|
"console_scripts": ["gello_publisher = franka_gello_state_publisher.gello_publisher:main"],
|
||||||
|
},
|
||||||
|
)
|
25
ros2/src/franka_gello_state_publisher/test/test_copyright.py
Normal file
25
ros2/src/franka_gello_state_publisher/test/test_copyright.py
Normal file
|
@ -0,0 +1,25 @@
|
||||||
|
# Copyright 2015 Open Source Robotics Foundation, Inc.
|
||||||
|
#
|
||||||
|
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
# you may not use this file except in compliance with the License.
|
||||||
|
# You may obtain a copy of the License at
|
||||||
|
#
|
||||||
|
# http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
#
|
||||||
|
# Unless required by applicable law or agreed to in writing, software
|
||||||
|
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
# See the License for the specific language governing permissions and
|
||||||
|
# limitations under the License.
|
||||||
|
|
||||||
|
from ament_copyright.main import main
|
||||||
|
import pytest
|
||||||
|
|
||||||
|
|
||||||
|
# Remove the `skip` decorator once the source file(s) have a copyright header
|
||||||
|
@pytest.mark.skip(reason="No copyright header has been placed in the generated source file.")
|
||||||
|
@pytest.mark.copyright
|
||||||
|
@pytest.mark.linter
|
||||||
|
def test_copyright():
|
||||||
|
rc = main(argv=[".", "test"])
|
||||||
|
assert rc == 0, "Found errors"
|
33
ros2/src/franka_gello_state_publisher/test/test_flake8.py
Normal file
33
ros2/src/franka_gello_state_publisher/test/test_flake8.py
Normal file
|
@ -0,0 +1,33 @@
|
||||||
|
# Copyright 2017 Open Source Robotics Foundation, Inc.
|
||||||
|
#
|
||||||
|
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
# you may not use this file except in compliance with the License.
|
||||||
|
# You may obtain a copy of the License at
|
||||||
|
#
|
||||||
|
# http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
#
|
||||||
|
# Unless required by applicable law or agreed to in writing, software
|
||||||
|
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
# See the License for the specific language governing permissions and
|
||||||
|
# limitations under the License.
|
||||||
|
|
||||||
|
from ament_flake8.main import main_with_errors
|
||||||
|
import pytest
|
||||||
|
from pathlib import Path
|
||||||
|
|
||||||
|
|
||||||
|
@pytest.mark.flake8
|
||||||
|
@pytest.mark.linter
|
||||||
|
def test_flake8():
|
||||||
|
config_path = Path(__file__).resolve().parents[3] / ".flake8"
|
||||||
|
excluded_file = Path(__file__).resolve().parents[1] / "franka_gello_state_publisher/driver.py"
|
||||||
|
print(excluded_file)
|
||||||
|
rc, errors = main_with_errors(
|
||||||
|
argv=["--config", str(config_path), "--exclude", str(excluded_file)]
|
||||||
|
)
|
||||||
|
assert rc == 0, "Found %d code style errors / warnings:\n" % len(errors) + "\n".join(errors)
|
||||||
|
|
||||||
|
|
||||||
|
if __name__ == "__main__":
|
||||||
|
test_flake8()
|
25
ros2/src/franka_gello_state_publisher/test/test_pep257.py
Normal file
25
ros2/src/franka_gello_state_publisher/test/test_pep257.py
Normal file
|
@ -0,0 +1,25 @@
|
||||||
|
# Copyright 2015 Open Source Robotics Foundation, Inc.
|
||||||
|
#
|
||||||
|
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
# you may not use this file except in compliance with the License.
|
||||||
|
# You may obtain a copy of the License at
|
||||||
|
#
|
||||||
|
# http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
#
|
||||||
|
# Unless required by applicable law or agreed to in writing, software
|
||||||
|
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
# See the License for the specific language governing permissions and
|
||||||
|
# limitations under the License.
|
||||||
|
|
||||||
|
from ament_pep257.main import main
|
||||||
|
import pytest
|
||||||
|
from pathlib import Path
|
||||||
|
|
||||||
|
|
||||||
|
@pytest.mark.linter
|
||||||
|
@pytest.mark.pep257
|
||||||
|
def test_pep257():
|
||||||
|
excluded_file = Path(__file__).resolve().parents[1] / "franka_gello_state_publisher/driver.py"
|
||||||
|
rc = main(argv=[".", "test", "--exclude", str(excluded_file)])
|
||||||
|
assert rc == 0, "Found code style errors / warnings"
|
202
ros2/src/franka_gripper_manager/LICENSE
Normal file
202
ros2/src/franka_gripper_manager/LICENSE
Normal file
|
@ -0,0 +1,202 @@
|
||||||
|
|
||||||
|
Apache License
|
||||||
|
Version 2.0, January 2004
|
||||||
|
http://www.apache.org/licenses/
|
||||||
|
|
||||||
|
TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
|
||||||
|
|
||||||
|
1. Definitions.
|
||||||
|
|
||||||
|
"License" shall mean the terms and conditions for use, reproduction,
|
||||||
|
and distribution as defined by Sections 1 through 9 of this document.
|
||||||
|
|
||||||
|
"Licensor" shall mean the copyright owner or entity authorized by
|
||||||
|
the copyright owner that is granting the License.
|
||||||
|
|
||||||
|
"Legal Entity" shall mean the union of the acting entity and all
|
||||||
|
other entities that control, are controlled by, or are under common
|
||||||
|
control with that entity. For the purposes of this definition,
|
||||||
|
"control" means (i) the power, direct or indirect, to cause the
|
||||||
|
direction or management of such entity, whether by contract or
|
||||||
|
otherwise, or (ii) ownership of fifty percent (50%) or more of the
|
||||||
|
outstanding shares, or (iii) beneficial ownership of such entity.
|
||||||
|
|
||||||
|
"You" (or "Your") shall mean an individual or Legal Entity
|
||||||
|
exercising permissions granted by this License.
|
||||||
|
|
||||||
|
"Source" form shall mean the preferred form for making modifications,
|
||||||
|
including but not limited to software source code, documentation
|
||||||
|
source, and configuration files.
|
||||||
|
|
||||||
|
"Object" form shall mean any form resulting from mechanical
|
||||||
|
transformation or translation of a Source form, including but
|
||||||
|
not limited to compiled object code, generated documentation,
|
||||||
|
and conversions to other media types.
|
||||||
|
|
||||||
|
"Work" shall mean the work of authorship, whether in Source or
|
||||||
|
Object form, made available under the License, as indicated by a
|
||||||
|
copyright notice that is included in or attached to the work
|
||||||
|
(an example is provided in the Appendix below).
|
||||||
|
|
||||||
|
"Derivative Works" shall mean any work, whether in Source or Object
|
||||||
|
form, that is based on (or derived from) the Work and for which the
|
||||||
|
editorial revisions, annotations, elaborations, or other modifications
|
||||||
|
represent, as a whole, an original work of authorship. For the purposes
|
||||||
|
of this License, Derivative Works shall not include works that remain
|
||||||
|
separable from, or merely link (or bind by name) to the interfaces of,
|
||||||
|
the Work and Derivative Works thereof.
|
||||||
|
|
||||||
|
"Contribution" shall mean any work of authorship, including
|
||||||
|
the original version of the Work and any modifications or additions
|
||||||
|
to that Work or Derivative Works thereof, that is intentionally
|
||||||
|
submitted to Licensor for inclusion in the Work by the copyright owner
|
||||||
|
or by an individual or Legal Entity authorized to submit on behalf of
|
||||||
|
the copyright owner. For the purposes of this definition, "submitted"
|
||||||
|
means any form of electronic, verbal, or written communication sent
|
||||||
|
to the Licensor or its representatives, including but not limited to
|
||||||
|
communication on electronic mailing lists, source code control systems,
|
||||||
|
and issue tracking systems that are managed by, or on behalf of, the
|
||||||
|
Licensor for the purpose of discussing and improving the Work, but
|
||||||
|
excluding communication that is conspicuously marked or otherwise
|
||||||
|
designated in writing by the copyright owner as "Not a Contribution."
|
||||||
|
|
||||||
|
"Contributor" shall mean Licensor and any individual or Legal Entity
|
||||||
|
on behalf of whom a Contribution has been received by Licensor and
|
||||||
|
subsequently incorporated within the Work.
|
||||||
|
|
||||||
|
2. Grant of Copyright License. Subject to the terms and conditions of
|
||||||
|
this License, each Contributor hereby grants to You a perpetual,
|
||||||
|
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
|
||||||
|
copyright license to reproduce, prepare Derivative Works of,
|
||||||
|
publicly display, publicly perform, sublicense, and distribute the
|
||||||
|
Work and such Derivative Works in Source or Object form.
|
||||||
|
|
||||||
|
3. Grant of Patent License. Subject to the terms and conditions of
|
||||||
|
this License, each Contributor hereby grants to You a perpetual,
|
||||||
|
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
|
||||||
|
(except as stated in this section) patent license to make, have made,
|
||||||
|
use, offer to sell, sell, import, and otherwise transfer the Work,
|
||||||
|
where such license applies only to those patent claims licensable
|
||||||
|
by such Contributor that are necessarily infringed by their
|
||||||
|
Contribution(s) alone or by combination of their Contribution(s)
|
||||||
|
with the Work to which such Contribution(s) was submitted. If You
|
||||||
|
institute patent litigation against any entity (including a
|
||||||
|
cross-claim or counterclaim in a lawsuit) alleging that the Work
|
||||||
|
or a Contribution incorporated within the Work constitutes direct
|
||||||
|
or contributory patent infringement, then any patent licenses
|
||||||
|
granted to You under this License for that Work shall terminate
|
||||||
|
as of the date such litigation is filed.
|
||||||
|
|
||||||
|
4. Redistribution. You may reproduce and distribute copies of the
|
||||||
|
Work or Derivative Works thereof in any medium, with or without
|
||||||
|
modifications, and in Source or Object form, provided that You
|
||||||
|
meet the following conditions:
|
||||||
|
|
||||||
|
(a) You must give any other recipients of the Work or
|
||||||
|
Derivative Works a copy of this License; and
|
||||||
|
|
||||||
|
(b) You must cause any modified files to carry prominent notices
|
||||||
|
stating that You changed the files; and
|
||||||
|
|
||||||
|
(c) You must retain, in the Source form of any Derivative Works
|
||||||
|
that You distribute, all copyright, patent, trademark, and
|
||||||
|
attribution notices from the Source form of the Work,
|
||||||
|
excluding those notices that do not pertain to any part of
|
||||||
|
the Derivative Works; and
|
||||||
|
|
||||||
|
(d) If the Work includes a "NOTICE" text file as part of its
|
||||||
|
distribution, then any Derivative Works that You distribute must
|
||||||
|
include a readable copy of the attribution notices contained
|
||||||
|
within such NOTICE file, excluding those notices that do not
|
||||||
|
pertain to any part of the Derivative Works, in at least one
|
||||||
|
of the following places: within a NOTICE text file distributed
|
||||||
|
as part of the Derivative Works; within the Source form or
|
||||||
|
documentation, if provided along with the Derivative Works; or,
|
||||||
|
within a display generated by the Derivative Works, if and
|
||||||
|
wherever such third-party notices normally appear. The contents
|
||||||
|
of the NOTICE file are for informational purposes only and
|
||||||
|
do not modify the License. You may add Your own attribution
|
||||||
|
notices within Derivative Works that You distribute, alongside
|
||||||
|
or as an addendum to the NOTICE text from the Work, provided
|
||||||
|
that such additional attribution notices cannot be construed
|
||||||
|
as modifying the License.
|
||||||
|
|
||||||
|
You may add Your own copyright statement to Your modifications and
|
||||||
|
may provide additional or different license terms and conditions
|
||||||
|
for use, reproduction, or distribution of Your modifications, or
|
||||||
|
for any such Derivative Works as a whole, provided Your use,
|
||||||
|
reproduction, and distribution of the Work otherwise complies with
|
||||||
|
the conditions stated in this License.
|
||||||
|
|
||||||
|
5. Submission of Contributions. Unless You explicitly state otherwise,
|
||||||
|
any Contribution intentionally submitted for inclusion in the Work
|
||||||
|
by You to the Licensor shall be under the terms and conditions of
|
||||||
|
this License, without any additional terms or conditions.
|
||||||
|
Notwithstanding the above, nothing herein shall supersede or modify
|
||||||
|
the terms of any separate license agreement you may have executed
|
||||||
|
with Licensor regarding such Contributions.
|
||||||
|
|
||||||
|
6. Trademarks. This License does not grant permission to use the trade
|
||||||
|
names, trademarks, service marks, or product names of the Licensor,
|
||||||
|
except as required for reasonable and customary use in describing the
|
||||||
|
origin of the Work and reproducing the content of the NOTICE file.
|
||||||
|
|
||||||
|
7. Disclaimer of Warranty. Unless required by applicable law or
|
||||||
|
agreed to in writing, Licensor provides the Work (and each
|
||||||
|
Contributor provides its Contributions) on an "AS IS" BASIS,
|
||||||
|
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
|
||||||
|
implied, including, without limitation, any warranties or conditions
|
||||||
|
of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
|
||||||
|
PARTICULAR PURPOSE. You are solely responsible for determining the
|
||||||
|
appropriateness of using or redistributing the Work and assume any
|
||||||
|
risks associated with Your exercise of permissions under this License.
|
||||||
|
|
||||||
|
8. Limitation of Liability. In no event and under no legal theory,
|
||||||
|
whether in tort (including negligence), contract, or otherwise,
|
||||||
|
unless required by applicable law (such as deliberate and grossly
|
||||||
|
negligent acts) or agreed to in writing, shall any Contributor be
|
||||||
|
liable to You for damages, including any direct, indirect, special,
|
||||||
|
incidental, or consequential damages of any character arising as a
|
||||||
|
result of this License or out of the use or inability to use the
|
||||||
|
Work (including but not limited to damages for loss of goodwill,
|
||||||
|
work stoppage, computer failure or malfunction, or any and all
|
||||||
|
other commercial damages or losses), even if such Contributor
|
||||||
|
has been advised of the possibility of such damages.
|
||||||
|
|
||||||
|
9. Accepting Warranty or Additional Liability. While redistributing
|
||||||
|
the Work or Derivative Works thereof, You may choose to offer,
|
||||||
|
and charge a fee for, acceptance of support, warranty, indemnity,
|
||||||
|
or other liability obligations and/or rights consistent with this
|
||||||
|
License. However, in accepting such obligations, You may act only
|
||||||
|
on Your own behalf and on Your sole responsibility, not on behalf
|
||||||
|
of any other Contributor, and only if You agree to indemnify,
|
||||||
|
defend, and hold each Contributor harmless for any liability
|
||||||
|
incurred by, or claims asserted against, such Contributor by reason
|
||||||
|
of your accepting any such warranty or additional liability.
|
||||||
|
|
||||||
|
END OF TERMS AND CONDITIONS
|
||||||
|
|
||||||
|
APPENDIX: How to apply the Apache License to your work.
|
||||||
|
|
||||||
|
To apply the Apache License to your work, attach the following
|
||||||
|
boilerplate notice, with the fields enclosed by brackets "[]"
|
||||||
|
replaced with your own identifying information. (Don't include
|
||||||
|
the brackets!) The text should be enclosed in the appropriate
|
||||||
|
comment syntax for the file format. We also recommend that a
|
||||||
|
file or class name and description of purpose be included on the
|
||||||
|
same "printed page" as the copyright notice for easier
|
||||||
|
identification within third-party archives.
|
||||||
|
|
||||||
|
Copyright [yyyy] [name of copyright owner]
|
||||||
|
|
||||||
|
Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
you may not use this file except in compliance with the License.
|
||||||
|
You may obtain a copy of the License at
|
||||||
|
|
||||||
|
http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
|
||||||
|
Unless required by applicable law or agreed to in writing, software
|
||||||
|
distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
See the License for the specific language governing permissions and
|
||||||
|
limitations under the License.
|
15
ros2/src/franka_gripper_manager/NOTICE
Normal file
15
ros2/src/franka_gripper_manager/NOTICE
Normal file
|
@ -0,0 +1,15 @@
|
||||||
|
franka_gripper_manager
|
||||||
|
|
||||||
|
Copyright 2025 Franka Robotics GmbH
|
||||||
|
|
||||||
|
Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
you may not use this file except in compliance with the License.
|
||||||
|
You may obtain a copy of the License at
|
||||||
|
|
||||||
|
http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
|
||||||
|
Unless required by applicable law or agreed to in writing, software
|
||||||
|
distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
See the License for the specific language governing permissions and
|
||||||
|
limitations under the License.
|
|
@ -0,0 +1,20 @@
|
||||||
|
robotiq/controller_manager:
|
||||||
|
ros__parameters:
|
||||||
|
update_rate: 500 # Hz
|
||||||
|
joint_state_broadcaster:
|
||||||
|
type: joint_state_broadcaster/JointStateBroadcaster
|
||||||
|
robotiq_gripper_controller:
|
||||||
|
type: position_controllers/GripperActionController
|
||||||
|
robotiq_activation_controller:
|
||||||
|
type: robotiq_controllers/RobotiqActivationController
|
||||||
|
|
||||||
|
robotiq/robotiq_gripper_controller:
|
||||||
|
ros__parameters:
|
||||||
|
default: true
|
||||||
|
joint: robotiq_85_left_knuckle_joint
|
||||||
|
use_effort_interface: true
|
||||||
|
use_speed_interface: true
|
||||||
|
|
||||||
|
robotiq/robotiq_activation_controller:
|
||||||
|
ros__parameters:
|
||||||
|
default: true
|
|
@ -0,0 +1,151 @@
|
||||||
|
import rclpy
|
||||||
|
import time
|
||||||
|
from rclpy.node import Node
|
||||||
|
from franka_msgs.action import Move
|
||||||
|
from franka_msgs.action import Homing
|
||||||
|
from sensor_msgs.msg import JointState
|
||||||
|
from rclpy.action import ActionClient
|
||||||
|
from std_msgs.msg import Float32
|
||||||
|
|
||||||
|
DEFAULT_MOVE_ACTION_TOPIC = "/fr3_gripper/move"
|
||||||
|
DEFAULT_HOMING_ACTION_TOPIC = "/fr3_gripper/homing"
|
||||||
|
DEFAULT_JOINT_STATES_TOPIC = "/fr3_gripper/joint_states"
|
||||||
|
DEFAULT_GRIPPER_COMMAND_TOPIC = "/gripper_client/target_gripper_width_percent"
|
||||||
|
|
||||||
|
|
||||||
|
class GripperClient(Node):
|
||||||
|
def __init__(self):
|
||||||
|
super().__init__("gripper_client")
|
||||||
|
|
||||||
|
self.declare_parameter("move_action_topic", DEFAULT_MOVE_ACTION_TOPIC)
|
||||||
|
self.declare_parameter("homing_action_topic", DEFAULT_HOMING_ACTION_TOPIC)
|
||||||
|
self.declare_parameter("gripper_command_topic", DEFAULT_GRIPPER_COMMAND_TOPIC)
|
||||||
|
self.declare_parameter("joint_states_topic", DEFAULT_JOINT_STATES_TOPIC)
|
||||||
|
|
||||||
|
move_action_topic = (
|
||||||
|
self.get_parameter("move_action_topic").get_parameter_value().string_value
|
||||||
|
)
|
||||||
|
homing_action_topic = (
|
||||||
|
self.get_parameter("homing_action_topic").get_parameter_value().string_value
|
||||||
|
)
|
||||||
|
gripper_command_topic = (
|
||||||
|
self.get_parameter("gripper_command_topic").get_parameter_value().string_value
|
||||||
|
)
|
||||||
|
joint_states_topic = (
|
||||||
|
self.get_parameter("joint_states_topic").get_parameter_value().string_value
|
||||||
|
)
|
||||||
|
|
||||||
|
self._ACTION_SERVER_TIMEOUT = 10.0
|
||||||
|
self._MIN_GRIPPER_WIDTH_PERCENT = 0.0
|
||||||
|
self._MAX_GRIPPER_WIDTH_PERCENT = 1.0
|
||||||
|
self._gripper_command_transmitted = True
|
||||||
|
self._max_width = 0.0
|
||||||
|
self._last_gripper_command = self._max_width * self._MAX_GRIPPER_WIDTH_PERCENT
|
||||||
|
|
||||||
|
self.get_logger().info("Initializing gripper client...")
|
||||||
|
self._home_gripper(homing_action_topic)
|
||||||
|
self._get_max_gripper_width(joint_states_topic)
|
||||||
|
|
||||||
|
self.get_logger().info("Subscribing to gripper commands...")
|
||||||
|
self._gripper_command_subscription = self.create_subscription(
|
||||||
|
Float32, gripper_command_topic, self._gripper_command_callback, 10
|
||||||
|
)
|
||||||
|
self._action_client = ActionClient(self, Move, move_action_topic)
|
||||||
|
|
||||||
|
self.get_logger().info("Waiting for gripper move action server...")
|
||||||
|
if not self._action_client.wait_for_server(timeout_sec=self._ACTION_SERVER_TIMEOUT):
|
||||||
|
raise RuntimeError(
|
||||||
|
f"Move action server not available after {self._ACTION_SERVER_TIMEOUT} seconds!"
|
||||||
|
)
|
||||||
|
|
||||||
|
self.get_logger().info("Gripper client initialized!")
|
||||||
|
|
||||||
|
def _home_gripper(self, homing_action_topic: str) -> None:
|
||||||
|
self.get_logger().info("Starting gripper homing...")
|
||||||
|
homing_client = ActionClient(self, Homing, homing_action_topic)
|
||||||
|
|
||||||
|
self.get_logger().info(f"Waiting for homing action server {homing_action_topic}...")
|
||||||
|
if not homing_client.wait_for_server(timeout_sec=self._ACTION_SERVER_TIMEOUT):
|
||||||
|
raise RuntimeError(
|
||||||
|
f"Homing action server not available after {self._ACTION_SERVER_TIMEOUT} seconds!"
|
||||||
|
)
|
||||||
|
|
||||||
|
self.get_logger().info("Homing action server found!")
|
||||||
|
goal_msg = Homing.Goal()
|
||||||
|
future = homing_client.send_goal_async(goal_msg)
|
||||||
|
rclpy.spin_until_future_complete(self, future)
|
||||||
|
|
||||||
|
goal_handle = future.result()
|
||||||
|
if not goal_handle.accepted:
|
||||||
|
raise RuntimeError("Homing action rejected!")
|
||||||
|
|
||||||
|
result_future = goal_handle.get_result_async()
|
||||||
|
rclpy.spin_until_future_complete(self, result_future)
|
||||||
|
result = result_future.result()
|
||||||
|
time.sleep(2)
|
||||||
|
|
||||||
|
if result.result.success:
|
||||||
|
self.get_logger().info("Gripper homing successful!")
|
||||||
|
else:
|
||||||
|
raise RuntimeError("Gripper homing failed!")
|
||||||
|
|
||||||
|
def _get_max_gripper_width(self, joint_states_topic: str) -> None:
|
||||||
|
self.get_logger().info("Readout maximum gripper width...")
|
||||||
|
future = rclpy.task.Future()
|
||||||
|
|
||||||
|
def joint_state_callback(msg):
|
||||||
|
_INDEX_FINGER_LEFT = 0
|
||||||
|
self._max_width = 2 * msg.position[_INDEX_FINGER_LEFT]
|
||||||
|
self.get_logger().info(f"Maximum gripper width determined: {self._max_width}")
|
||||||
|
future.set_result(True)
|
||||||
|
|
||||||
|
self.get_logger().info(f"Subscribing to {joint_states_topic}...")
|
||||||
|
gripper_subscription = self.create_subscription(
|
||||||
|
JointState, joint_states_topic, joint_state_callback, 10
|
||||||
|
)
|
||||||
|
|
||||||
|
self.get_logger().info(f"Waiting for {joint_states_topic}...")
|
||||||
|
rclpy.spin_until_future_complete(self, future)
|
||||||
|
|
||||||
|
self.get_logger().info(f"Unsubscribing from {joint_states_topic}")
|
||||||
|
self.destroy_subscription(gripper_subscription)
|
||||||
|
|
||||||
|
def _gripper_command_callback(self, msg: Float32) -> None:
|
||||||
|
new_open_width_percent = msg.data
|
||||||
|
new_open_width = self._max_width * new_open_width_percent
|
||||||
|
if self._gripper_command_transmitted and new_open_width != self._last_gripper_command:
|
||||||
|
self._send_gripper_command(new_open_width)
|
||||||
|
self._last_gripper_command = new_open_width
|
||||||
|
self._gripper_command_transmitted = False
|
||||||
|
|
||||||
|
def _send_gripper_command(self, gripper_position: float) -> None:
|
||||||
|
goal_msg = Move.Goal()
|
||||||
|
goal_msg.width = gripper_position
|
||||||
|
goal_msg.speed = 1.0
|
||||||
|
self._future = self._action_client.send_goal_async(goal_msg)
|
||||||
|
self._future.add_done_callback(self._gripper_response_callback)
|
||||||
|
|
||||||
|
def _gripper_response_callback(self, future: rclpy.task.Future) -> None:
|
||||||
|
goal_handle = future.result()
|
||||||
|
|
||||||
|
if not goal_handle.accepted:
|
||||||
|
raise RuntimeError(f"Goal rejected with status: {goal_handle.status}")
|
||||||
|
|
||||||
|
self._get_result_future = goal_handle.get_result_async()
|
||||||
|
self._get_result_future.add_done_callback(self._get_result_callback)
|
||||||
|
|
||||||
|
def _get_result_callback(self, future: rclpy.task.Future) -> None:
|
||||||
|
result = future.result().result
|
||||||
|
self.get_logger().info("Result: {0}".format(result))
|
||||||
|
self._gripper_command_transmitted = True
|
||||||
|
|
||||||
|
|
||||||
|
def main(args=None):
|
||||||
|
rclpy.init(args=args)
|
||||||
|
gripper_client = GripperClient()
|
||||||
|
rclpy.spin(gripper_client)
|
||||||
|
rclpy.shutdown()
|
||||||
|
|
||||||
|
|
||||||
|
if __name__ == "__main__":
|
||||||
|
main()
|
|
@ -0,0 +1,58 @@
|
||||||
|
import rclpy
|
||||||
|
from rclpy.node import Node
|
||||||
|
from control_msgs.action import GripperCommand
|
||||||
|
from rclpy.action import ActionClient
|
||||||
|
from std_msgs.msg import Float32
|
||||||
|
|
||||||
|
DEFAULT_GRIPPER_COMMAND_TOPIC = "/gripper_client/target_gripper_width_percent"
|
||||||
|
DEFAULT_MOVE_ACTION_TOPIC = "/robotiq/robotiq_gripper_controller/gripper_cmd"
|
||||||
|
|
||||||
|
|
||||||
|
class RobotiqGripperClient(Node):
|
||||||
|
def __init__(self):
|
||||||
|
super().__init__("robotiq_gripper_client")
|
||||||
|
self.get_logger().info("Starting Robotiq Gripper Client")
|
||||||
|
self.gripper_state_callback = self.create_subscription(
|
||||||
|
Float32, DEFAULT_GRIPPER_COMMAND_TOPIC, self.gripper_state_callback, 10
|
||||||
|
)
|
||||||
|
self.action_client = ActionClient(self, GripperCommand, DEFAULT_MOVE_ACTION_TOPIC)
|
||||||
|
self.action_client.wait_for_server()
|
||||||
|
self.last_width = -1.0
|
||||||
|
self.get_logger().info("Gripper action server is up and running")
|
||||||
|
|
||||||
|
def gripper_state_callback(self, msg):
|
||||||
|
gripper_target_position = msg.data
|
||||||
|
if abs(gripper_target_position - self.last_width) < 0.02:
|
||||||
|
return
|
||||||
|
self.send_gripper_command(gripper_target_position)
|
||||||
|
|
||||||
|
def send_gripper_command(self, gripper_position):
|
||||||
|
self.last_width = gripper_position
|
||||||
|
goal_msg = GripperCommand.Goal()
|
||||||
|
goal_msg.command.position = 1 - gripper_position # Convert to 0-1 range
|
||||||
|
goal_msg.command.max_effort = 1.0
|
||||||
|
self.future = self.action_client.send_goal_async(goal_msg)
|
||||||
|
self.future.add_done_callback(self.gripper_response_callback)
|
||||||
|
|
||||||
|
def gripper_response_callback(self, future):
|
||||||
|
goal_handle = future.result()
|
||||||
|
if not goal_handle.accepted:
|
||||||
|
raise RuntimeError(f"Goal rejected with status: {goal_handle.status}")
|
||||||
|
|
||||||
|
self._get_result_future = goal_handle.get_result_async()
|
||||||
|
self._get_result_future.add_done_callback(self.get_result_callback)
|
||||||
|
|
||||||
|
def get_result_callback(self, future):
|
||||||
|
result = future.result().result
|
||||||
|
self.get_logger().info("Result: {0}".format(result))
|
||||||
|
|
||||||
|
|
||||||
|
def main(args=None):
|
||||||
|
rclpy.init(args=args)
|
||||||
|
gripper_client = RobotiqGripperClient()
|
||||||
|
rclpy.spin(gripper_client)
|
||||||
|
rclpy.shutdown()
|
||||||
|
|
||||||
|
|
||||||
|
if __name__ == "__main__":
|
||||||
|
main()
|
|
@ -0,0 +1,15 @@
|
||||||
|
from launch import LaunchDescription
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
return LaunchDescription(
|
||||||
|
[
|
||||||
|
Node(
|
||||||
|
package="franka_gripper_manager",
|
||||||
|
executable="franka_gripper_client",
|
||||||
|
arguments=["franka_gripper_client"],
|
||||||
|
output="screen",
|
||||||
|
),
|
||||||
|
]
|
||||||
|
)
|
|
@ -0,0 +1,174 @@
|
||||||
|
# Copyright (c) 2022 PickNik, Inc.
|
||||||
|
#
|
||||||
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
# modification, are permitted provided that the following conditions are met:
|
||||||
|
#
|
||||||
|
# * Redistributions of source code must retain the above copyright
|
||||||
|
# notice, this list of conditions and the following disclaimer.
|
||||||
|
#
|
||||||
|
# * Redistributions in binary form must reproduce the above copyright
|
||||||
|
# notice, this list of conditions and the following disclaimer in the
|
||||||
|
# documentation and/or other materials provided with the distribution.
|
||||||
|
#
|
||||||
|
# * Neither the name of the {copyright_holder} nor the names of its
|
||||||
|
# contributors may be used to endorse or promote products derived from
|
||||||
|
# this software without specific prior written permission.
|
||||||
|
#
|
||||||
|
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||||
|
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||||
|
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||||
|
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
|
||||||
|
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
||||||
|
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
||||||
|
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
||||||
|
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
||||||
|
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||||
|
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
# POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
|
||||||
|
import launch
|
||||||
|
from launch.substitutions import (
|
||||||
|
Command,
|
||||||
|
FindExecutable,
|
||||||
|
LaunchConfiguration,
|
||||||
|
PathJoinSubstitution,
|
||||||
|
)
|
||||||
|
from launch.conditions import IfCondition
|
||||||
|
import launch_ros
|
||||||
|
import os
|
||||||
|
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
description_pkg_share = launch_ros.substitutions.FindPackageShare(
|
||||||
|
package="robotiq_description"
|
||||||
|
).find("robotiq_description")
|
||||||
|
default_rviz_config_path = os.path.join(description_pkg_share, "rviz", "view_urdf.rviz")
|
||||||
|
|
||||||
|
gripper_pkg_share = launch_ros.substitutions.FindPackageShare(
|
||||||
|
package="franka_gripper_manager"
|
||||||
|
).find("franka_gripper_manager")
|
||||||
|
default_model_path = os.path.join(
|
||||||
|
gripper_pkg_share, "urdf", "robotiq_2f_85_gripper.urdf.xacro"
|
||||||
|
)
|
||||||
|
|
||||||
|
args = []
|
||||||
|
args.append(
|
||||||
|
launch.actions.DeclareLaunchArgument(
|
||||||
|
name="model",
|
||||||
|
default_value=default_model_path,
|
||||||
|
description="Absolute path to gripper URDF file",
|
||||||
|
)
|
||||||
|
)
|
||||||
|
args.append(
|
||||||
|
launch.actions.DeclareLaunchArgument(
|
||||||
|
name="rvizconfig",
|
||||||
|
default_value=default_rviz_config_path,
|
||||||
|
description="Absolute path to rviz config file",
|
||||||
|
)
|
||||||
|
)
|
||||||
|
args.append(
|
||||||
|
launch.actions.DeclareLaunchArgument(
|
||||||
|
name="launch_rviz", default_value="false", description="Launch RViz?"
|
||||||
|
)
|
||||||
|
)
|
||||||
|
args.append(
|
||||||
|
launch.actions.DeclareLaunchArgument(name="com_port", description="Default COM port")
|
||||||
|
)
|
||||||
|
|
||||||
|
robot_description_content = Command(
|
||||||
|
[
|
||||||
|
PathJoinSubstitution([FindExecutable(name="xacro")]),
|
||||||
|
" ",
|
||||||
|
LaunchConfiguration("model"),
|
||||||
|
" ",
|
||||||
|
"use_fake_hardware:=false",
|
||||||
|
" ",
|
||||||
|
"com_port:=",
|
||||||
|
LaunchConfiguration("com_port"),
|
||||||
|
]
|
||||||
|
)
|
||||||
|
robot_description_param = {
|
||||||
|
"robot_description": launch_ros.parameter_descriptions.ParameterValue(
|
||||||
|
robot_description_content, value_type=str
|
||||||
|
)
|
||||||
|
}
|
||||||
|
|
||||||
|
update_rate_config_file = PathJoinSubstitution(
|
||||||
|
[
|
||||||
|
description_pkg_share,
|
||||||
|
"config",
|
||||||
|
"robotiq_update_rate.yaml",
|
||||||
|
]
|
||||||
|
)
|
||||||
|
|
||||||
|
controllers_file = "robotiq_controllers.yaml"
|
||||||
|
initial_joint_controllers = PathJoinSubstitution(
|
||||||
|
[gripper_pkg_share, "config", controllers_file]
|
||||||
|
)
|
||||||
|
|
||||||
|
control_node = launch_ros.actions.Node(
|
||||||
|
package="controller_manager",
|
||||||
|
executable="ros2_control_node",
|
||||||
|
namespace="robotiq",
|
||||||
|
parameters=[
|
||||||
|
robot_description_param,
|
||||||
|
update_rate_config_file,
|
||||||
|
initial_joint_controllers,
|
||||||
|
],
|
||||||
|
)
|
||||||
|
|
||||||
|
robot_state_publisher_node = launch_ros.actions.Node(
|
||||||
|
package="robot_state_publisher",
|
||||||
|
executable="robot_state_publisher",
|
||||||
|
parameters=[robot_description_param],
|
||||||
|
)
|
||||||
|
|
||||||
|
rviz_node = launch_ros.actions.Node(
|
||||||
|
package="rviz2",
|
||||||
|
executable="rviz2",
|
||||||
|
name="rviz2",
|
||||||
|
output="log",
|
||||||
|
arguments=["-d", LaunchConfiguration("rvizconfig")],
|
||||||
|
condition=IfCondition(LaunchConfiguration("launch_rviz")),
|
||||||
|
)
|
||||||
|
|
||||||
|
joint_state_broadcaster_spawner = launch_ros.actions.Node(
|
||||||
|
package="controller_manager",
|
||||||
|
executable="spawner",
|
||||||
|
arguments=[
|
||||||
|
"joint_state_broadcaster",
|
||||||
|
"--controller-manager",
|
||||||
|
"robotiq/controller_manager",
|
||||||
|
],
|
||||||
|
)
|
||||||
|
|
||||||
|
robotiq_gripper_controller_spawner = launch_ros.actions.Node(
|
||||||
|
package="controller_manager",
|
||||||
|
executable="spawner",
|
||||||
|
arguments=["robotiq_gripper_controller", "-c", "robotiq/controller_manager"],
|
||||||
|
)
|
||||||
|
|
||||||
|
robotiq_activation_controller_spawner = launch_ros.actions.Node(
|
||||||
|
package="controller_manager",
|
||||||
|
executable="spawner",
|
||||||
|
arguments=["robotiq_activation_controller", "-c", "robotiq/controller_manager"],
|
||||||
|
)
|
||||||
|
|
||||||
|
robotiq_gripper_client = launch_ros.actions.Node(
|
||||||
|
package="franka_gripper_manager",
|
||||||
|
executable="robotiq_gripper_client",
|
||||||
|
name="robotiq_gripper_client",
|
||||||
|
output="screen",
|
||||||
|
)
|
||||||
|
|
||||||
|
nodes = [
|
||||||
|
control_node,
|
||||||
|
robot_state_publisher_node,
|
||||||
|
joint_state_broadcaster_spawner,
|
||||||
|
robotiq_gripper_controller_spawner,
|
||||||
|
robotiq_activation_controller_spawner,
|
||||||
|
rviz_node,
|
||||||
|
robotiq_gripper_client,
|
||||||
|
]
|
||||||
|
|
||||||
|
return launch.LaunchDescription(args + nodes)
|
20
ros2/src/franka_gripper_manager/package.xml
Normal file
20
ros2/src/franka_gripper_manager/package.xml
Normal file
|
@ -0,0 +1,20 @@
|
||||||
|
<?xml version="1.0"?>
|
||||||
|
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||||
|
<package format="3">
|
||||||
|
<name>franka_gripper_manager</name>
|
||||||
|
<version>0.0.0</version>
|
||||||
|
<description>Provisioning of gripper clients for gello</description>
|
||||||
|
<maintainer email="support@franka.de">Franka Robotics GmbH</maintainer>
|
||||||
|
<license>Apache 2.0</license>
|
||||||
|
<depend>ros2-robotiq-gripper</depend>
|
||||||
|
<depend>sensor-msgs</depend>
|
||||||
|
<depend>rclpy</depend>
|
||||||
|
|
||||||
|
<test_depend>ament_copyright</test_depend>
|
||||||
|
<test_depend>ament_flake8</test_depend>
|
||||||
|
<test_depend>ament_pep257</test_depend>
|
||||||
|
<test_depend>python3-pytest</test_depend>
|
||||||
|
<export>
|
||||||
|
<build_type>ament_python</build_type>
|
||||||
|
</export>
|
||||||
|
</package>
|
4
ros2/src/franka_gripper_manager/setup.cfg
Normal file
4
ros2/src/franka_gripper_manager/setup.cfg
Normal file
|
@ -0,0 +1,4 @@
|
||||||
|
[develop]
|
||||||
|
script_dir=$base/lib/franka_gripper_manager
|
||||||
|
[install]
|
||||||
|
install_scripts=$base/lib/franka_gripper_manager
|
31
ros2/src/franka_gripper_manager/setup.py
Normal file
31
ros2/src/franka_gripper_manager/setup.py
Normal file
|
@ -0,0 +1,31 @@
|
||||||
|
from setuptools import find_packages, setup
|
||||||
|
import glob
|
||||||
|
|
||||||
|
package_name = "franka_gripper_manager"
|
||||||
|
|
||||||
|
setup(
|
||||||
|
name=package_name,
|
||||||
|
version="0.1.0",
|
||||||
|
packages=find_packages(exclude=["test"]),
|
||||||
|
data_files=[
|
||||||
|
("share/ament_index/resource_index/packages", ["resource/" + package_name]),
|
||||||
|
("share/" + package_name, ["package.xml"]),
|
||||||
|
("share/" + package_name + "/config", glob.glob("config/*.yaml")),
|
||||||
|
("share/" + package_name + "/launch", glob.glob("launch/*.launch.py")),
|
||||||
|
("share/" + package_name + "/urdf", glob.glob("urdf/*.urdf.xacro")),
|
||||||
|
],
|
||||||
|
include_package_data=True,
|
||||||
|
install_requires=["setuptools"],
|
||||||
|
zip_safe=True,
|
||||||
|
maintainer="Franka Robotics GmbH",
|
||||||
|
maintainer_email="support@franka.de",
|
||||||
|
description="Manages the grippers of the robot.",
|
||||||
|
license="Apache 2.0",
|
||||||
|
tests_require=["pytest"],
|
||||||
|
entry_points={
|
||||||
|
"console_scripts": [
|
||||||
|
"franka_gripper_client = franka_gripper_manager.franka_gripper_client:main",
|
||||||
|
"robotiq_gripper_client = franka_gripper_manager.robotiq_gripper_client:main",
|
||||||
|
],
|
||||||
|
},
|
||||||
|
)
|
25
ros2/src/franka_gripper_manager/test/test_copyright.py
Normal file
25
ros2/src/franka_gripper_manager/test/test_copyright.py
Normal file
|
@ -0,0 +1,25 @@
|
||||||
|
# Copyright 2015 Open Source Robotics Foundation, Inc.
|
||||||
|
#
|
||||||
|
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
# you may not use this file except in compliance with the License.
|
||||||
|
# You may obtain a copy of the License at
|
||||||
|
#
|
||||||
|
# http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
#
|
||||||
|
# Unless required by applicable law or agreed to in writing, software
|
||||||
|
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
# See the License for the specific language governing permissions and
|
||||||
|
# limitations under the License.
|
||||||
|
|
||||||
|
from ament_copyright.main import main
|
||||||
|
import pytest
|
||||||
|
|
||||||
|
|
||||||
|
# Remove the `skip` decorator once the source file(s) have a copyright header
|
||||||
|
@pytest.mark.skip(reason="No copyright header has been placed in the generated source file.")
|
||||||
|
@pytest.mark.copyright
|
||||||
|
@pytest.mark.linter
|
||||||
|
def test_copyright():
|
||||||
|
rc = main(argv=[".", "test"])
|
||||||
|
assert rc == 0, "Found errors"
|
25
ros2/src/franka_gripper_manager/test/test_flake8.py
Normal file
25
ros2/src/franka_gripper_manager/test/test_flake8.py
Normal file
|
@ -0,0 +1,25 @@
|
||||||
|
# Copyright 2017 Open Source Robotics Foundation, Inc.
|
||||||
|
#
|
||||||
|
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
# you may not use this file except in compliance with the License.
|
||||||
|
# You may obtain a copy of the License at
|
||||||
|
#
|
||||||
|
# http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
#
|
||||||
|
# Unless required by applicable law or agreed to in writing, software
|
||||||
|
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
# See the License for the specific language governing permissions and
|
||||||
|
# limitations under the License.
|
||||||
|
|
||||||
|
from ament_flake8.main import main_with_errors
|
||||||
|
import pytest
|
||||||
|
from pathlib import Path
|
||||||
|
|
||||||
|
|
||||||
|
@pytest.mark.flake8
|
||||||
|
@pytest.mark.linter
|
||||||
|
def test_flake8():
|
||||||
|
config_path = Path(__file__).resolve().parents[3] / ".flake8"
|
||||||
|
rc, errors = main_with_errors(argv=["--config", str(config_path)])
|
||||||
|
assert rc == 0, "Found %d code style errors / warnings:\n" % len(errors) + "\n".join(errors)
|
23
ros2/src/franka_gripper_manager/test/test_pep257.py
Normal file
23
ros2/src/franka_gripper_manager/test/test_pep257.py
Normal file
|
@ -0,0 +1,23 @@
|
||||||
|
# Copyright 2015 Open Source Robotics Foundation, Inc.
|
||||||
|
#
|
||||||
|
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
# you may not use this file except in compliance with the License.
|
||||||
|
# You may obtain a copy of the License at
|
||||||
|
#
|
||||||
|
# http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
#
|
||||||
|
# Unless required by applicable law or agreed to in writing, software
|
||||||
|
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
# See the License for the specific language governing permissions and
|
||||||
|
# limitations under the License.
|
||||||
|
|
||||||
|
from ament_pep257.main import main
|
||||||
|
import pytest
|
||||||
|
|
||||||
|
|
||||||
|
@pytest.mark.linter
|
||||||
|
@pytest.mark.pep257
|
||||||
|
def test_pep257():
|
||||||
|
rc = main(argv=[".", "test"])
|
||||||
|
assert rc == 0, "Found code style errors / warnings"
|
|
@ -0,0 +1,15 @@
|
||||||
|
<?xml version="1.0"?>
|
||||||
|
<!-- Based on ros2_robotiq_gripper/robotiq_description/urdf/robotiq_2f_85_gripper.urdf.xacro, added arg com_port-->
|
||||||
|
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="robotiq_gripper">
|
||||||
|
<!-- parameters -->
|
||||||
|
<xacro:arg name="use_fake_hardware" default="true" />
|
||||||
|
<xacro:arg name="com_port" default="/dev/ttyUSB0" />
|
||||||
|
|
||||||
|
<!-- Import macros -->
|
||||||
|
<xacro:include filename="$(find robotiq_description)/urdf/robotiq_2f_85_macro.urdf.xacro" />
|
||||||
|
|
||||||
|
<link name="world" />
|
||||||
|
<xacro:robotiq_gripper name="RobotiqGripperHardwareInterface" prefix="" parent="world" use_fake_hardware="$(arg use_fake_hardware)" com_port="$(arg com_port)">
|
||||||
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
|
</xacro:robotiq_gripper>
|
||||||
|
</robot>
|
Loading…
Add table
Add a link
Reference in a new issue