Skip to content

Commit

Permalink
Merge pull request #49 from SalvoVirga/development
Browse files Browse the repository at this point in the history
iiwa_stack 1.2
  • Loading branch information
SalvoVirga authored Feb 1, 2017
2 parents 94670d7 + cc94334 commit 943299a
Show file tree
Hide file tree
Showing 59 changed files with 2,685 additions and 1,447 deletions.
15 changes: 15 additions & 0 deletions CHANGELOG.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,20 @@
# IIWA_STACK Changelog

## Version 1.2.0 (release date: 01.02.2016)

#### New
* `An approximation of the inertia parameters was added to the URDF of the iiwa7.`
* `Commanding in joint velocity available.`
* `Added a service to get the time left to reach the commanded destination and topic that publishes when the destination is reached.`
* `Moved the feature to change the joing velocity and acceleration to its own service.`
* `Refactored the code in iiwa_ros, now it provides wrappers for all the state/command messages and the service calls.`
* `Tested and workin on ROS Kinetic`

#### Bug Fixes
* `The online change of the joint velocity now works properly`
* `Got rid of minor compiler warning`
* `Got rid of the errors and most of the warning from Rviz and MoveIn in Kinect, some are left but they clash with Indigo atm.`

## Version 1.1.0 (release date: 26.08.2016)

Completely refactoring of the Java applications led to various improvements in terms of performance.
Expand Down
2 changes: 1 addition & 1 deletion LICENSE.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
Most of the files were drastically modified, but the original authors inspired our work.
For everything else :

Copyright (c) 2016, Salvatore Virga - [email protected], Marco Esposito - [email protected]
Copyright (c) 2016-2017, Salvatore Virga - [email protected], Marco Esposito - [email protected]
Technische Universität München
Chair for Computer Aided Medical Procedures and Augmented Reality
Fakultät für Informatik / I16, Boltzmannstraße 3, 85748 Garching bei München, Germany
Expand Down
78 changes: 25 additions & 53 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,58 +1,42 @@
## IIWA STACK
ROS indigo metapackage that contains ROS packages to work with the KUKA LBR IIWA R800/R820 (7/14 Kg).
ROS Indigo/Kinetic metapackage for the KUKA LBR IIWA R800/R820 (7/14 Kg).

**Current version : v-1.1.0 for Sunrise 1.11**
**Current version : v-1.2.0 for Sunrise 1.11**
[Using a previous version of Sunrise?](https://github.com/SalvoVirga/iiwa_stack/wiki/FAQ#which-version-of-sunriseossunrise-workbench-is-supported)

[![Build Status](https://travis-ci.org/SalvoVirga/iiwa_stack.svg?branch=master)](https://travis-ci.org/SalvoVirga/iiwa_stack)
___
### Features
- rosjava node running on the robot as a Sunrise RoboticApplication: supports ROS parameters, topics, services, actions
- SmartServo integration
- default: position control (joint or cartesian)
- joint or cartesian impedance control reconfigurable through a ROS service
- Sunrise tool can be attached to the flange in order to consider its mass for impedance control
- monitor mode with gravity compensation, enabled through SmartPad keys
- optional autonomous publication of joint_states topic
- NTP synchronization if server is running on ROS master
- Native ROSJava nodes running on the robot as a Sunrise RoboticApplication: supports ROS parameters, topics, services, etc.
- Integration of KUKA's SmartServo motions:
- joint position, joint velocity and cartesian position control via simple ROS messages.
- online configuration of JointImpedance, CartesianImpedance, DesiredForce and Sine(Force)Pattern via ROS service.
- online configuration of joint velocity and acceleration via ROS service.
- updates on the time left to reach the commanded destination via ROS service.
- The Sunrise tool to use can be selected via a ROS parameter.
- Gravity compensation by setting the appropriate JointImpedance values.
- NTP synchronization with a server running on the ROS master
- full MoveIt! integration
- Gazebo support

There are two RoboticApplications included in our software stack:
- ROSMonitor does not perform any motion, but it constantly publishes the current
state of the robot. This is suitable for procedures in the native teaching mode
or in the custom-made gravity compensation mode.
- ROSSmartServo allows to use the Sunrise SmartServo control modes to move the robot.
The motion is fully reconfigurable at runtime, allowing to switch from any control
strategy to any other, and to change the respective parameters at runtime through a
ROS service.

Both applications look for ROS parameters at startup, including the ID of the Sunrise
tool to attach to the flange. The IP of the robot is automatically discovered, while
the ROS master IP should be set in the configuration file included in the project.

The communication with the robot is implemented through ROS topics: a rosjava node
runs in the context of a Sunrise application on the robot cabinet, which in turn
performs a SmartServo motion. This approach allows great flexibility, as we can
use a ROS service to reconfigure the ServoMotion at runtime (e.g. stiffness of
certain joints or around cartesian axes). Even if not real-time, we never incurred
in any communication problems on our setup: the TCP topics could scale up to 4 KHz
without compromising the ordering of the received packets. However, we also plan
to offer FRI as a drop-in replacement for ROS-topic communication as soon as it is stable.

The state of the robot is published through a set of topics, and optionally through
the joint_states topic for compatibility with the robot_state_publisher even when
not using MoveIt!. The timestamps are correct if an NTP server runs on the ROS master,
such that the system can also be used for latency-sensitive application.

The impedance control can be configured with respect to the stiffness and damping
for each joint, or for each and about each direction in the cartesian space. It is
possible to switch the control mode at runtime safely.
___
### Usage
__The features and usage of the stack are described in depth on its [WIKI][8].__
We **_strongly_** suggest to have a look at the wiki to have a better understanding of the code, both for its use and its extension.
Do you have problems? First, please check the [**FAQs**](https://github.com/SalvoVirga/iiwa_stack/wiki/FAQ). Issues or emails are always welcome.
Do you have problems? First, please check the [**FAQs**](https://github.com/SalvoVirga/iiwa_stack/wiki/FAQ). Issues or emails are always welcome!

___
### Citation

If you use iiwa_stack for reseach, you could cite the following work. It is the first publication where it is used.

@article{hennersperger2016towards,
title={Towards MRI-based Autonomous Robotic US Acquisitions: A First Feasibility Study},
author={Hennersperger, Christoph and Fuerst, Bernhard and Virga, Salvatore and Zettinig, Oliver and Frisch, Benjamin and Neff, Thomas and Navab, Nassir},
journal={IEEE transactions on medical imaging},
year={2016},
publisher={IEEE}
}

___
### Acknowledgements
Expand All @@ -62,18 +46,6 @@ This repository takes inspiration from the work of :
- _Robert Krug_ and his [IIWA URDF and Gazebo package][7]

Most of the original files were completely refactored though.
___
### Overview
This packages contained in this repository are :
- __iiwa__ : the ROS metapackage
- __iiwa_control__: contains the joint and trajectory controllers used by MoveIt! and Gazebo.
- __iiwa_description__: URDF for both KUKA LBR IIWA R800 and R820.
- __iiwa_gazebo__: launch files to run a Gazebo simulation.
- __iiwa_hw__: implements the ROS hardware interface and the communication interface with the real robot (using iiwa_ros).
- __iiwa_moveit__: a MoveIt! configuration for controlling the robot (either a Gazebo simulation or a real one).
- __iiwa_msgs__: creates ROS messages to be used for communication with a real robot.
- __iiwa_ros__: an interface to send and receive messages defined in iiwa_msgs to and from a real robot.
- __iiwa_ros_java__: the ROSJava interface to use on SunriseApplications - it allows to send and receive messages defined in iiwa_msgs.

### Contacts
Salvatore Virga : [email protected]
Expand Down
2 changes: 1 addition & 1 deletion iiwa_description/launch/iiwa14_upload.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,5 +5,5 @@
<arg name="hardware_interface" default="PositionJointInterface"/>
<arg name="robot_name" default="iiwa"/>

<param name="robot_description" command="$(find xacro)/xacro '$(find iiwa_description)/urdf/iiwa14.urdf.xacro' hardware_interface:=$(arg hardware_interface) robot_name:=$(arg robot_name)" />
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find iiwa_description)/urdf/iiwa14.urdf.xacro' hardware_interface:=$(arg hardware_interface) robot_name:=$(arg robot_name)" />
</launch>
2 changes: 1 addition & 1 deletion iiwa_description/launch/iiwa7_upload.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,5 +5,5 @@
<arg name="hardware_interface" default="PositionJointInterface"/>
<arg name="robot_name" default="iiwa"/>

<param name="robot_description" command="$(find xacro)/xacro '$(find iiwa_description)/urdf/iiwa7.urdf.xacro' hardware_interface:=$(arg hardware_interface) robot_name:=$(arg robot_name)" />
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find iiwa_description)/urdf/iiwa7.urdf.xacro' hardware_interface:=$(arg hardware_interface) robot_name:=$(arg robot_name)" />
</launch>
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
32 changes: 16 additions & 16 deletions iiwa_description/urdf/iiwa7.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -74,8 +74,8 @@
<link name="${robot_name}_link_1">
<inertial>
<origin xyz="0 -0.03 0.12" rpy="0 0 0"/>
<mass value="4"/>
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.09" iyz="0" izz="0.02" />
<mass value="3.4525"/>
<inertia ixx="0.02183" ixy="0" ixz="0" iyy="0.007703" iyz="-0.003887" izz="0.02083" />
</inertial>
<visual>
<origin xyz="0 0 0.0075" rpy="0 0 0"/>
Expand Down Expand Up @@ -110,8 +110,8 @@
<link name="${robot_name}_link_2">
<inertial>
<origin xyz="0.0003 0.059 0.042" rpy="0 0 0"/>
<mass value="4"/>
<inertia ixx="0.05" ixy="0" ixz="0" iyy="0.018" iyz="0" izz="0.044" />
<mass value="3.4821"/>
<inertia ixx="0.02076" ixy="0" ixz="-0.003626" iyy="0.02179" iyz="0" izz="0.00779" />
</inertial>
<visual>
<origin xyz="0 0 -0.0060" rpy="0 0 0"/>
Expand Down Expand Up @@ -147,8 +147,8 @@
<link name="${robot_name}_link_3">
<inertial>
<origin xyz="0 0.03 0.13" rpy="0 0 0"/>
<mass value="3"/>
<inertia ixx="0.08" ixy="0" ixz="0" iyy="0.075" iyz="0" izz="0.01" />
<mass value="4.05623"/>
<inertia ixx="0.03204" ixy="0" ixz="0" iyy="0.00972" iyz="0.006227" izz="0.03042" />
</inertial>

<visual>
Expand Down Expand Up @@ -186,8 +186,8 @@
<link name="${robot_name}_link_4">
<inertial>
<origin xyz="0 0.067 0.034" rpy="0 0 0"/>
<mass value="2.7"/>
<inertia ixx="0.03" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.029" />
<mass value="3.4822"/>
<inertia ixx="0.02178" ixy="0" ixz="0" iyy="0.02075" iyz="-0.003625" izz="0.007785" />
</inertial>

<visual>
Expand Down Expand Up @@ -224,8 +224,8 @@
<link name="${robot_name}_link_5">
<inertial>
<origin xyz="0.0001 0.021 0.076" rpy="0 0 0"/>
<mass value="1.7"/>
<inertia ixx="0.02" ixy="0" ixz="0" iyy="0.018" iyz="0" izz="0.005" />
<mass value="2.1633"/>
<inertia ixx="0.01287" ixy="0" ixz="0" iyy="0.005708" iyz="-0.003946" izz="0.01112" />
</inertial>

<visual>
Expand Down Expand Up @@ -262,8 +262,8 @@
<link name="${robot_name}_link_6">
<inertial>
<origin xyz="0 0.0006 0.0004" rpy="0 0 0"/>
<mass value="1.8"/>
<inertia ixx="0.005" ixy="0" ixz="0" iyy="0.0036" iyz="0" izz="0.0047" />
<mass value="2.3466"/>
<inertia ixx="0.006509" ixy="0" ixz="0" iyy="0.006259" iyz="0.00031891" izz="0.004527" />
</inertial>

<visual>
Expand Down Expand Up @@ -300,22 +300,22 @@
<link name="${robot_name}_link_7">
<inertial>
<origin xyz="0 0 0.02" rpy="0 0 0"/>
<mass value="0.3"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" />
<mass value="3.129"/>
<inertia ixx="0.01464" ixy="0.0005912" ixz="0" iyy="0.01465" iyz="0" izz="0.002872" />
</inertial>

<visual>
<origin xyz="0 0 -0.0005" rpy="0 0 0"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/iiwa7/visual/link_7_basic.stl"/>
<mesh filename="package://iiwa_description/meshes/iiwa7/visual/link_7.stl"/>
</geometry>
<material name="Grey"/>
</visual>

<collision>
<origin xyz="0 0 -0.0005" rpy="0 0 0"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/iiwa7/collision/link_7_basic.stl"/>
<mesh filename="package://iiwa_description/meshes/iiwa7/collision/link_7.stl"/>
</geometry>
<material name="Grey"/>
</collision>
Expand Down
30 changes: 11 additions & 19 deletions iiwa_hw/include/iiwa_hw.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,38 +10,32 @@
* Manuel Bonilla - [email protected]
*
* LICENSE :
*
* Copyright (C) 2016 Salvatore Virga - [email protected], Marco Esposito - [email protected]
* Copyright (C) 2016-2017 Salvatore Virga - [email protected], Marco Esposito - [email protected]
* Technische Universität München
* Chair for Computer Aided Medical Procedures and Augmented Reality
* Fakultät für Informatik / I16, Boltzmannstraße 3, 85748 Garching bei München, Germany
* http://campar.in.tum.de
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
*
* 2. 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.
*
* 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
* 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.
*
* \author Salvatore Virga
* \version 1.4.0
* \date 07/03/2016
*/

#ifndef IIWA_HW_H_
#define IIWA_HW_H_
#pragma once

// iiwa_msgs and ROS inteface includes
#include "iiwaRos.h"
#include "iiwa_ros.h"
#include <iiwa_msgs/JointPosition.h>
#include <iiwa_msgs/JointTorque.h>

Expand Down Expand Up @@ -205,7 +199,7 @@ class IIWA_HW : public hardware_interface::RobotHW {
ros::Rate* loop_rate_;
double control_frequency_;

iiwaRos iiwa_ros_conn_;
iiwa_ros::iiwaRos iiwa_ros_conn_;
iiwa_msgs::JointPosition joint_position_;
iiwa_msgs::JointTorque joint_torque_;

Expand Down Expand Up @@ -238,5 +232,3 @@ void vectorToIiwaMsgsJoint(const std::vector<T>& v, iiwa_msgs::JointQuantity& ax
ax.a6 = v[5];
ax.a7 = v[6];
}

#endif //IIWA_HW_H_
33 changes: 14 additions & 19 deletions iiwa_hw/src/iiwa_hw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,31 +10,27 @@
* Manuel Bonilla - [email protected]
*
* LICENSE :
*
* Copyright (C) 2016 Salvatore Virga - [email protected], Marco Esposito - [email protected]
*
* Copyright (C) 2016-2017 Salvatore Virga - [email protected], Marco Esposito - [email protected]
* Technische Universität München
* Chair for Computer Aided Medical Procedures and Augmented Reality
* Fakultät für Informatik / I16, Boltzmannstraße 3, 85748 Garching bei München, Germany
* http://campar.in.tum.de
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
*
* 2. 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.
*
* 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
* 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.
*
* \author Salvatore Virga
* \version 1.4.0
* \date 07/03/2016
*/

#include "iiwa_hw.h"
Expand Down Expand Up @@ -99,7 +95,7 @@ bool IIWA_HW::start() {
throw std::runtime_error("No URDF model available");
}

iiwa_ros_conn_.init(false);
iiwa_ros_conn_.init();

// initialize and set to zero the state and command values
device_->init();
Expand Down Expand Up @@ -215,8 +211,8 @@ bool IIWA_HW::read(ros::Duration period)

if (iiwa_ros_conn_.getRobotIsConnected()) {

iiwa_ros_conn_.getReceivedJointPosition(joint_position_);
iiwa_ros_conn_.getReceivedJointTorque(joint_torque_);
iiwa_ros_conn_.getJointPosition(joint_position_);
iiwa_ros_conn_.getJointTorque(joint_torque_);

device_->joint_position_prev = device_->joint_position;
iiwaMsgsJointToVector(joint_position_.position, device_->joint_position);
Expand Down Expand Up @@ -263,7 +259,7 @@ bool IIWA_HW::write(ros::Duration period) {
vectorToIiwaMsgsJoint(device_->joint_position_command, command_joint_position_.position);
command_joint_position_.header.stamp = ros::Time::now();

iiwa_ros_conn_.setCommandJointPosition(command_joint_position_);
iiwa_ros_conn_.setJointPosition(command_joint_position_);
}
// Joint Impedance Control
else if (interface_ == interface_type_.at(1)) {
Expand All @@ -274,9 +270,8 @@ bool IIWA_HW::write(ros::Duration period) {
// TODO
}

iiwa_ros_conn_.publish();
} else if (delta.toSec() >= 10) {
ROS_INFO("No LBR IIWA is connected. Waiting for the robot to connect before writing ...");
ROS_INFO_STREAM("No LBR IIWA is connected. Waiting for the robot to connect before writing ...");
timer_ = ros::Time::now();
}

Expand Down
Loading

0 comments on commit 943299a

Please sign in to comment.