Skip to content

Commit

Permalink
iiqka instructions
Browse files Browse the repository at this point in the history
  • Loading branch information
Svastits committed Jan 3, 2024
1 parent 4770fa6 commit 99d1702
Show file tree
Hide file tree
Showing 4 changed files with 63 additions and 17 deletions.
5 changes: 5 additions & 0 deletions doc/wiki/Realtime.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
## Setting up the real-time patch

## Configuration

Besides, the setting of scheduling priorities must be allowed for your user (extend /etc/security/limits.conf with "username - rtprio 98" and restart) to enable real-time performance.
71 changes: 58 additions & 13 deletions doc/wiki/iiQKA_EAC.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,31 +2,76 @@

### Setup

The driver depends on some KUKA-specific packages, which are only available with the real robot, but setting the MOCK_HW_ONLY flag in the hardware_interface enables the usage of the driver in a simulated way, so that motion planning problems can be tried out with the same components running. By default, the mock libraries are used, this can be changed in the cmake file by setting MOCK_KUKA_LIBS to FALSE before building.
#### Client side
It is recommended to use the driver in a real-time capable client machine (further information about setting up the PREEMPT_RT patch can be found [here](Realtime.md)).

The IP addresses of the client machine and controller must be given in the *config/driver_config.yaml* configuration file. A rebuild is not needed after the changes, but the file has to be modified before starting the nodes. The control mode of the robot can also be modified in the same configuration file: you can choose either 1 (POSITION_CONTROL), 2 (JOINT_IMPEDANCE_CONTROL) or 4 (JOINT_TORQUE_CONTROL). This also sets the control_mode parameter of the `robot_manager` node.
The driver depends on some KUKA-specific packages, which are only available with the real robot, therefore a mock mode is provided to enable trying out solutions with the same components running. By default, the mock libraries are used, this can be changed in the `CmakeLists.txt` file by setting `MOCK_KUKA_LIBS` to `FALSE` before building.

Besides, the setting of scheduling priorities must be allowed for your user (extend /etc/security/limits.conf with "username - rtprio 98" and restart) to enable real-time performance.
#### Controller side

If the ExternalAPI.Control toolbox is installed on the robot, it is ready for external control. You only have to release SPOC on the Teach Pendant, no other setup is needed on the controller.
- Install ExternalAPI.Control toolbox (requires iiQKA 1.2)
- Set KONI IP (System Settings -> Network -> KONI) + restart
- Connect external client to KONI port (XF7)
- Release SPOC on the Teach Pendant

### Configuration

#### Startup configuration

The following configuration files are available in the `config` directory of the package:
- `driver_config.yaml`: contains IP addresses and runtime parameters
- `qos_profiles.yaml`: contains the configuration options for the QoS profile defining the connection quality (description later)
- `ros2_controller_config.yaml`: contains the controller types for every controller name. Should be only modified if a different controller is to be used. The `configure_components_on_start` parameter should never be modified, which ensures that the hardware interface is not activated at startup.
- configuration files for specific controllers, for further information, see the documentation of the given controller

##### QoS profile configuration
It is possible to configure the required connection quality of external control using a QoS profile, which defines under which conditions should external control be terminated in case of packet losses. A packet is considered lost if the controller does not receive a command in 2.5 milliseconds after publishing the state. In case of a packet loss, extrapolation is used to optimize the robot behaviour, unless the limits defined in the profile are violated. Two limits can be defined:
- Consequent packet losses allowed, defined by `consequent_lost_packets` parameter, maximum value is 5
- Allowed packet losses in given timeframe: defined by `lost_packets_in_timeframe` (maximum value is 25) and `timeframe_ms` parameters, maximum ratio is 25/sec

##### IP configuration
The following parameters must be set in the driver configuration file:
- `client_ip`: IP address of the client machine
- `controller_ip`: KONI IP of the controller

#### Runtime parameters
The not IP-related parameters in the driver configuration file can be also changed during runtime using the parameter interface of the `robot_manager` node:
- `control_mode`: The enum value of the control mode should be given. It can be changed in all primary states, but in active state the brakes are always closed before control is started in a new mode.
- `position_controller_name`: The name of the controller (string) that controls the `position` interface of the robot. It can't be changed in active state.
- `impedance_controller_name`: The name of the controller (string) that controls the `stiffness` and `damping` interfaces of the robot. It can't be changed in active state.
- `torque_controller_name`: The name of the controller (string) that controls the `effort` interface of the robot. It can't be changed in active state.

### Usage

The usage of the driver is quite simple, one has to start the launch file in the package to start all required nodes:
#### Starting the driver

To start the driver, two launch file are available, with and without `rviz`. To launch (without `rviz`), run:

`ros2 launch kuka_iiqka_eac_driver startup.launch.py`

This starts the 3 core components of every driver (described in the *Non-real-time interface* section of the [project overview](Project%20overview.md)) and the following controllers:
- `joint_state_broadcaster` (no configuration file, all state interfaces are published)
- `joint_trajectory_controller` ([configuration file](../../kuka_iiqka_eac_driver/config/joint_trajectory_controller_config.yaml))
- `joint_group_impedance_controller` ([configuration file](../../kuka_iiqka_eac_driver/config/joint_impedance_controller_config.yaml))
- `effort_controller` (of type `JointGroupPositionController`, [configuration file](../../kuka_iiqka_eac_driver/config/effort_controller_config.yaml))
- [`control_mode_handler`](https://github.com/kroshu/kuka_controllers?tab=readme-ov-file#control_mode_handler) (no configuration file)

After succesful startup, the `robot_manager` node has to be activated to start the cyclic communication with the robot controller:

**`ros2 launch kuka_iiqka_eac_driver startup.launch.py`**
`ros2 lifecycle set robot_manager configure`

After all components have started successfully, the system needs to be configured and activated to start external control:
`ros2 lifecycle set robot_manager activate`

**`ros2 lifecycle set robot_manager configure`**
On successful activation the brakes of the robot will be released and external control is started using the requested control mode. To test moving the robot, the `rqt_joint_trajectory_controller` is not recommended, use the launch file in the `iiqka_moveit_example` package instead (usage is described in the *Additional packages* section of the [project overview](Project%20overview.md)).


**`ros2 lifecycle set robot_manager activate`**
##### Launch arguments

On successful activation the robot controller and the driver start communication with a 4 ms cycle time, and it is possible to move the robot through the joint trajectory controller.
Both launch files support the following argument:
- `robot_model`: defines which LBR iisy robot to use. Available options: `lbr_iisy3_r760` (default), `lbr_iisy11_r1300`, `lbr_iisy15_r930`

To stop external control, the components have to be deactivated with **`ros2 lifecycle set robot_manager deactivate`**
#### Stopping external control

BEWARE, that this is a non-realtime process including lifecycle management, so the connection is not terminated immediately, in cases where an abrupt stop is needed, the safety stop of the Teach Pendant should be used!
To stop external control, all components have to be deactivated with `ros2 lifecycle set robot_manager deactivate`

It is also possible to use different controllers with some modifications in the launch and yaml files (for example ForwardCommandController, which forwards the commands send to a ROS2 topic towards the robot). In these cases, one has to make sure, that the commands sent to the robot are close to the current position, otherwise the machine protection will stop the robot movement.
BEWARE, that this is a non-realtime process including lifecycle management, so the connection is not terminated immediately, in cases where an abrupt stop is needed, the safety stop of the Teach Pendant should be used! (This will also deactivate all components to allow reactivation without a restart.)
1 change: 0 additions & 1 deletion kuka_iiqka_eac_driver/config/ros2_controller_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -13,5 +13,4 @@
control_mode_handler:
type: kuka_controllers/ControlModeHandler


configure_components_on_start: [""]
3 changes: 0 additions & 3 deletions kuka_sunrise_fri_driver/config/ros2_controller_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,6 @@ controller_manager:

joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController

effort_controller:
type: effort_controllers/JointEffortController

joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
Expand Down

0 comments on commit 99d1702

Please sign in to comment.