Kinova® KINOVA KORTEX™ is the common software platform behind all of the products in the Gen3 family (Gen3 and Gen3 lite). It unifies the inner workings of the various robots and their related external tools, like the API.
https://www.kinovarobotics.com/product/gen3-robots
ROS2 KINOVA KORTEX™ is the official ROS2 package to interact with KINOVA KORTEX™ and its related products. It is built upon the KINOVA KORTEX™ API, documentation for which can be found in the GitHub Kortex repository.
| ROS 2 Distro | Humble | Jazzy |
|---|---|---|
| Branch | humble | main |
| Build Status |
|
|
| Release Status | Stable (binary available — may lag behind source) | Stable (source only) |
Note: There are several CI jobs checking against future upstream changes see detailed build status for a full list of CI jobs and for more information.
Note: Gazebo classic support was kept on the humble branch of this repository
-
Install ROS 2.
For this branch, ROS2 Humble has to be installed on Ubuntu 22.04.
Stable LTS Release: Install ROS2 Humble
After installing ROS2, source the setup.bash, which will set the
$ROS_DISTROenvironment variable. -
Install this package from binary
sudo apt install ros-$ROS_DISTRO-kortex-bringup -
Optional: install MoveIt Configuration and Cyclone DDS
If you have a 7dof arm:
sudo apt install ros-$ROS_DISTRO-kinova-gen3-7dof-robotiq-2f-85-moveit-configIf you have a 6dof arm:
sudo apt install ros-$ROS_DISTRO-kinova-gen3-6dof-robotiq-2f-85-moveit-configIf you plan to use MoveIt, it is recommended to install and use Cyclone DDS.
sudo apt install ros-$ROS_DISTRO-rmw-cyclonedds-cpp export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp -
Go to Usage section
Note: It is recommended to use a released binary version of this package and apt install it. If you want the latest version of this repository for testing latest fixes check out testing with pre-released binaries: https://docs.ros.org/en/rolling/Installation/Testing.html
If the bug fix you need isn't in a released version or If you want to build this repository from source or contribute back to the repository read on.
-
Make sure that
colcon, its extensions, andvcsare installed:sudo apt install python3-colcon-common-extensions python3-vcstool -
Create a new ROS2 workspace:
export COLCON_WS=~/workspace/ros2_kortex_ws mkdir -p $COLCON_WS/src -
Pull relevant packages:
cd $COLCON_WS git clone -b humble --single-branch https://github.com/Kinovarobotics/ros2_kortex.git src/ros2_kortex vcs import src --skip-existing --input src/ros2_kortex/ros2_kortex.$ROS_DISTRO.repos vcs import src --skip-existing --input src/ros2_kortex/ros2_kortex-not-released.$ROS_DISTRO.reposIf you plan on simulating the robot with ignition or gazebo, first install the simulator using the following commands:
sudo apt-get update && sudo apt-get install wget
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
sudo apt-get update && sudo apt-get install ignition-fortress
Then make sure to pull the additional simulation packages. If you're on ROS2 Humble, run:
vcs import src --skip-existing --input src/ros2_kortex/simulation.humble.repos
otherwise
vcs import --skip-existing --input src/ros2_kortex/simulation.repos
If you plan on using MoveIt, you must make sure that you have it already installed either from binaries or by building it from source.
If you plan on simulating the Gen3 7Dof robot mounted on the Husky mobile robot from clearpath, make sure to pull the additional related packages. On ROS2 Humble, run
vcs import src --skip-existing --input src/ros2_kortex/clearpath.repos
-
Install dependencies, compile, and source the workspace:
rosdep install --ignore-src --from-paths src -y -r colcon build --cmake-args -DCMAKE_BUILD_TYPE=ReleaseBy default, colcon will use as much resources as possible to build the ROS2 workspace. This can temporarily freeze or even crash your machine. You can limit the number of threads used to avoid this issue, we found a good tradeoff between build time and resource utilisation by setting it to 3 :
colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release --parallel-workers 3 -
Source the previously built workspace using the following command:
echo 'source ~/workspace/ros2_kortex_ws/install/setup.bash' >> ~/.bashrc
Please note, at this time there are two known issues you with simulation
- Gazebo + Mimic Joints for the Robotiq Gripper
- Protobuf version mismatch
A pull request has been made to gz_ros2_control which is how this repository was tested in simulation. The pull request won't be merged as the fix should be done upstream in gz-sim. Once a fix is available ros2_robotiq_gripper will be re-released and an update should fix any workarounds.
In the meantime if you need simulation checkout the upstream pull request link:
- Upstream Issue: gazebosim/gz-sim#1684
- Upstream Pull Request: ros-controls/gz_ros2_control#86
- Tracking Issue: PickNikRobotics/ros2_robotiq_gripper#7
Due to mismatched protobuf version that ships system and used by Gazebo simulator compiling twice may be required. You will only run into this if you have certain other gazebo related code in your workspace while compiling this repository. If errors are encounter you must clean your workspace and run colcon build in two steps:
- build everything except kortex related packages
- build the packages that where skipped
sudo apt install python3-colcon-clean # if you don't have colcon-clean installed already
colcon clean workspace -y
colcon build --packages-skip-regex '.*kortex.*' '.*gen3.*'
colcon build --packages-select-regex '.*kortex.*' '.*gen3.*'
To launch and view any of the robot's URDF run:
ros2 launch kortex_description view_robot.launch.pyThe accepted arguments are:
-
robot_type: Your robot model. Possible values are eithergen3orgen3_lite, the default isgen3. -
gripper: Gripper to use. Possible values for the Gen3 are eitherrobotiq_2f_85orrobotiq_2f_140. For the Gen3 Lite, the only option isgen3_lite_2f. Default value is an empty string, which will display the arm without a gripper. -
dof: Degrees of freedom of the arm. Possible values for the Gen3 are either6or7. For the Gen3 Lite, the only option is6. Default value is7.
The gen3.launch.py launch file is designed to be used for Gen3 arms. The typical use case to bringup and visualize the 7 DoF Kinova Gen3 robot arm (default) with mock hardware on Rviz:
ros2 launch kortex_bringup gen3.launch.py \
robot_ip:=yyy.yyy.yyy.yyy \
use_fake_hardware:=trueAlternatively, for a physical robot:
ros2 launch kortex_bringup gen3.launch.py \
robot_ip:=192.168.1.10You can specify the following arguments if you wish to change your arm configuration:
-
robot_type: Your robot model. Default value (and only one) isgen3. -
gripper: Gripper to use. Possible values for the Gen3 are eitherrobotiq_2f_85,robotiq_2f_140or"". Default is"". An empty string will not initialise any gripper. -
gripper_joint_name: Name of the controlled joint of the gripper attached to the arm. Default value isrobotiq_85_left_knuckle_joint. -
use_internal_bus_gripper_comm: Use internal bus for gripper communication. Default value istrue. -
gripper_max_velocity: Max velocity for gripper commands. Default value is100.0. -
gripper_max_force: Max force for gripper commands. Default value is100.0. -
dof: Degrees of freedom of the arm. Possible values are either6or7.Default value is7. -
robot_ip: IP address by which the robot can be reached. No default is specified, this is a required argument. All arms are shipped with address192.168.1.10, but if you have reassigned your physical arm's robot IP address, then you will need to assign that ip address. -
use_fake_hardware: Start robot with fake hardware mirroring command to its states. Default value isfalse. -
fake_sensor_commands: Enable fake command interfaces for sensors used for simple simulations. Used only if 'use_fake_hardware' parameter is true. Default value isfalse. -
robot_controller: Robot controller to start. Possible values aretwist_controllerandjoint_trajectory_controller.Default value isjoint_trajectory_controller. -
controllers_file: Ros 2 control configuration file to use. Default value isros2_controllers.yaml -
launch_rviz: Start an Rviz window to visualize the robot. Default value istrue.
The gen3_lite.launch.py launch file is designed to be used for Gen3 Lite arms. The typical use case to bringup the robot arm with mock hardware:
ros2 launch kortex_bringup gen3_lite.launch.py \
robot_ip:=yyy.yyy.yyy.yyy \
use_fake_hardware:=trueAlternatively, if you wish to use the physical robot:
ros2 launch kortex_bringup gen3_lite.launch.py \
robot_ip:=192.168.1.10 \You can specify the following arguments if you wish to change your arm configuration:
-
robot_type: Your robot model. Default value (and only one) isgen3_lite. -
gripper: Gripper to use. Default value (and only one) isgen3_lite_2f. -
gripper_joint_name: Name of the controlled joint of the gripper attached to the arm. Default value (and only one) isright_finger_bottom_joint. -
use_internal_bus_gripper_comm: Use internal bus for gripper communication. Default value istrue. -
gripper_max_velocity: Max velocity for gripper commands. Default value is100.0. -
gripper_max_force: Max force for gripper commands. Default value is100.0. -
robot_ip: IP address by which the robot can be reached. No default is specified, this is a required argument. All arms are shipped with address192.168.1.10, but if you have reassigned your physical arm's robot IP address, then you will need to assign that ip address. If you're using an USB to Ethernet interface to connect your robot to your machine instead of USB via RNDIS, the ip address will be192.168.2.10. -
use_fake_hardware: Start robot with fake hardware mirroring command to its states. Default value isfalse. -
fake_sensor_commands: Enable fake command interfaces for sensors used for simple simulations. Used only if 'use_fake_hardware' parameter is true. Default value isfalse. -
robot_controller: Robot controller to start. Possible values aretwist_controllerandjoint_trajectory_controller.Default value isjoint_trajectory_controller. -
controllers_file: Ros 2 control configuration file to use. Default value isros2_controllers.yaml -
description_file: URDF/XACRO description file with the robot. Default value isgen3_lite_gen3_lite_2f.xacro. -
launch_rviz: Start an Rviz window to visualize the robot. Default value istrue.
The kortex_sim_control.launch.py launch file is designed to simulate all of our arm models, you just need to specify your configuration through the arguments. By default, the Gen3 7 dof configuration is used :
ros2 launch kortex_bringup kortex_sim_control.launch.py \
use_sim_time:=true \
launch_rviz:=falsesim_ignition: Use Ignition for simulation. Default value istrue.sim_gazebo: Use Gazebo Classic for simulation. Default value isfalse.robot_type: Your robot model. Possible values are eithergen3orgen3_lite.Default isgen3.robot_name: Name you would like your robot to have. Default value isgen3.dof: Degrees of freedom of the arm. Possible values are either6or7.Default value is7.vision: Use arm mounted realsens. Possible values are eithertrueorfalse. Default value isfalse. This option does not generate simulated images, it only loads up the robot's URDF that includes the vision link.robot_controller: Robot joint controller to start. Default value isjoint_trajectory_controller.robot_pos_controller: Robot position controller to start. Default value istwist_controller.robot_hand_controller: Robot gripper controller to start. Default value isrobotiq_gripper_controller.controllers_file: Ros 2 control configuration file to use. Default value isros2_controllers.yamldescription_package: Description package with robot URDF/XACRO files. Default value iskortex_description.description_file: URDF/XACRO description file with the robot. Default value iskinova.urdf.xacro.prefix: Prefix of the joint names, useful for multi-robot setup. If changed, then also joint names in the controllers' configuration have to be updated. Default value is""(none).use_sim_time: Use simulated clock. Default value istrue.gripper: Gripper to use. Possible values for the Gen3 are:robotiq_2f_85,robotiq_2f_140,""andgen3_lite_2fand the default value is""which will not initialise any gripper.
To generate motion plans and execute them with virtual arm hardware:
- For a 6 DoF Kinova Gen3 arm, run the following:
ros2 launch kinova_gen3_6dof_robotiq_2f_85_moveit_config robot.launch.py \
robot_ip:=yyy.yyy.yyy.yyy \
use_fake_hardware:=true- For a 7 DoF Kinova Gen3 arm, run the following:
ros2 launch kinova_gen3_7dof_robotiq_2f_85_moveit_config robot.launch.py \
robot_ip:=yyy.yyy.yyy.yyy \
use_fake_hardware:=trueTo generate motion plans and execute them with real-life hardware:
- For a 6 DoF Kinova Gen3 arm with default IP address, run the following:
ros2 launch kinova_gen3_6dof_robotiq_2f_85_moveit_config robot.launch.py \
robot_ip:=192.168.1.10- For a 7 DoF Kinova Gen3 arm with default IP address, run the following:
ros2 launch kinova_gen3_7dof_robotiq_2f_85_moveit_config robot.launch.py \
robot_ip:=192.168.1.10- For a Gen3-Lite arm with default IP address and connected through USB, run the following:
ros2 launch kinova_gen3_lite_moveit_config robot.launch.py \
robot_ip:=192.168.2.10To generate motion plans and execute them in simulation, make sure to first start the simulated robot with the command at the simulation section, then:
- For a 6 DoF Kinova Gen3 arm, run the following:
ros2 launch kinova_gen3_6dof_robotiq_2f_85_moveit_config sim.launch.py \
use_sim_time:=true- For a 7 DoF Kinova Gen3 arm, run the following:
ros2 launch kinova_gen3_7dof_robotiq_2f_85_moveit_config sim.launch.py \
use_sim_time:=true- For a Gen3-Lite arm, run the following:
ros2 launch kinova_gen3_lite_moveit_config sim.launch.py \
use_sim_time:=trueYou can command the arm by publishing Joint Trajectory messages directly to the joint trajectory controller with joint positions are in radians:
ros2 topic pub /joint_trajectory_controller/joint_trajectory trajectory_msgs/JointTrajectory "{
joint_names: [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6, joint_7],
points: [
{ positions: [0, 0, 0, 0, 0, 0, 0], time_from_start: { sec: 10 } },
]
}" -1Depending on your robot type and its DoF, you will need to adapt the joint_names and positions properties accordingly. For the Gen3 Lite arm, the integrated gripper is considered as a joint, so to command it, it must be included in the joint_names array. (0.0=open, 1.0=close):
ros2 topic pub /joint_trajectory_controller/joint_trajectory trajectory_msgs/JointTrajectory "{
joint_names: [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6, right_finger_bottom_joint],
points: [
{ positions: [0, 0, 0, 0, 0, 0, 1], time_from_start: { sec: 10 } },
]
}" -1You can also command the arm using Twist messages. Before doing so, you must active the twist_controller and deactivate the joint_trajectory_controller:
ros2 service call /controller_manager/switch_controller controller_manager_msgs/srv/SwitchController "{
activate_controllers: [twist_controller],
deactivate_controllers: [joint_trajectory_controller],
strictness: 1,
activate_asap: true,
}"Note: the required interface for the twist_controller does not currently exist in the gazebo or mock hardware simulation setups. So the twist_controller is currently only functional on Kinova hardware.
Once the twist_controller is activated, You can publish Twist messages on the /twist_controller/commands topic to command the arm.
For example, you can jog the arm using Teleop Twist Keyboard with the following command:
WARNING: you are responsible for collision checking, including self collisions when in this mode.
ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args --remap /cmd_vel:=/twist_controller/commandsIf you wish to use the joint_trajectory_controller again to command the arm using JointTrajectory messages, run the following:
ros2 service call /controller_manager/switch_controller controller_manager_msgs/srv/SwitchController "{
activate_controllers: [joint_trajectory_controller],
deactivate_controllers: [twist_controller],
strictness: 1,
activate_asap: true,
}"The Robotiq 2f 85 (or 2f 140) Gripper will be available on the Action topic:
/robotiq_gripper_controller/gripper_cmdYou can test the gripper by calling the Action server with the following command and setting the desired position of the gripper (0.1=open, 0.7=close)
ros2 action send_goal /robotiq_gripper_controller/gripper_cmd control_msgs/action/GripperCommand "{command:{position: 0.0, max_effort: 100.0}}"In order to access the Kinova Vision module's depth and color streams for the camera-equipped Gen3 arm models, please refer to the following github repository for detailed instructions: ros2_kortex_vision
The following is a description of the packages included in this repository.
This package contains the URDF (Unified Robot Description Format), STL and configuration files for the Kortex-compatible robots. For more details, please consult the README from the package subdirectory.
This package implements a ROS node that allows communication between a node and a Kinova Gen3 or Gen3 lite robot. For more details, please consult the README from the package subdirectory.
This metapackage contains the auto-generated MoveIt! files to use the Kinova Gen3 and Gen3 lite arms with the MoveIt! motion planning framework. For more details, please consult the README from the package subdirectory.
-
Make sure to connect each robotic arm via an Ethernet connection, and assign each arm to a different IP subnet (for example, one at 192.168.1.10 and the other at 192.168.2.10).
-
Start the dual control launch file using the following command:
ros2 launch kortex_bringup gen3_dual.launch.py robot_ip_1:=192.168.1.10 robot_ip_2:=192.168.2.10
You can specify the following arguments if you wish to change your arms configurations:
-
robot_ip_1: IP address by which the first robot can be reached. The default is empty, this is a required argument. All arms are shipped with address192.168.1.10by default, but if you have reassigned your physical arm's robot IP address, then you will need to assign that ip address. -
robot_ip_2: IP address by which the second robot can be reached. The default is empty, this is a required argument. All arms are shipped with address192.168.1.10by default, but if you have reassigned your physical arm's robot IP address, then you will need to assign that ip address. -
gripper_1: Gripper to use with the first arm. Possible values for the Gen3 are eitherrobotiq_2f_85,robotiq_2f_140or"". Default is"". An empty string will not initialise any gripper. -
gripper_2: Gripper to use with the second arm. Possible values for the Gen3 are eitherrobotiq_2f_85,robotiq_2f_140or"". Default is"". An empty string will not initialise any gripper. -
dof_1: Degrees of freedom of the first arm. Possible values are either6or7.Default value is7. -
dof_2: Degrees of freedom of the first arm. Possible values are either6or7.Default value is7.
- Use the following command to control the first arm's joints positions:
6DoF
ros2 topic pub /arm_1_/joint_trajectory_controller/joint_trajectory trajectory_msgs/JointTrajectory "{
joint_names: [arm_1_joint_1, arm_1_joint_2, arm_1_joint_3, arm_1_joint_4, arm_1_joint_5, arm_1_joint_6],
points: [
{ positions: [0, 0, 0, 0, 0, 0], time_from_start: { sec: 10 } },
]
}" -1
7DoF
ros2 topic pub /arm_1_/joint_trajectory_controller/joint_trajectory trajectory_msgs/JointTrajectory "{
joint_names: [arm_1_joint_1, arm_1_joint_2, arm_1_joint_3, arm_1_joint_4, arm_1_joint_5, arm_1_joint_6, arm_1_joint_7],
points: [
{ positions: [0, 0, 0, 0, 0, 0, 0], time_from_start: { sec: 10 } },
]
}" -1
- Use the following command to control the second arm's joints positions:
6DoF
ros2 topic pub /arm_2_/joint_trajectory_controller/joint_trajectory trajectory_msgs/JointTrajectory "{
joint_names: [arm_2_joint_1, arm_2_joint_2, arm_2_joint_3, arm_2_joint_4, arm_2_joint_5, arm_2_joint_6],
points: [
{ positions: [0, 0, 0, 0, 0, 0], time_from_start: { sec: 10 } },
]
}" -1
7DoF
ros2 topic pub /arm_2_/joint_trajectory_controller/joint_trajectory trajectory_msgs/JointTrajectory "{
joint_names: [arm_2_joint_1, arm_2_joint_2, arm_2_joint_3, arm_2_joint_4, arm_2_joint_5, arm_2_joint_6, arm_2_joint_7],
points: [
{ positions: [0, 0, 0, 0, 0, 0, 0], time_from_start: { sec: 10 } },
]
}" -1
