Skip to content

Input Devices

Adnan Munawar edited this page Jan 25, 2021 · 1 revision

1. Understanding the input_devices.yaml file:

An Input Device Configuration file is set in the launch.yaml file. This file contains information about the device specifications as well as how to pair simulated rigid-bodies to the device. In the rest of this document, we shall refer to the input device as IID (Input Interface Device). We can inspect an example IID configuration in the input_devices.yaml file below.

Geomagic Touch:
    hardware name: PHANTOM Omni #(REQUIRED)
    haptic gain: {linear: 0.01, angular: 0.0} #(REQUIRED)
    deadband: 0.01 #(OPTIONAL)
    max force: 2 #(OPTIONAL)
    max jerk: 0.2 #(OPTIONAL)
    workspace scaling: 2 #(REQUIRED)
    simulated multibody: "../multi-bodies/grippers/pr2 gripper.yaml" #(REQUIRED IF NO ROOT LINK SPECIFIED)
    root link: "kuka_tip" #(REQUIRED IF NO SIMULATED MULTI-BODY SPECIFIED)
    location: {
      position: {x: 0.2839, y: 0.3299, z: 1.4126},
      orientation: {r: 0, p: 0, y: 0}} #(OPTIONAL)
    orientation offset: {r: 0.0, p: -1.57079, y: 1.57079} #(OPTIONAL)
    controller gain: {
      linear: {
        P: 20,
        I: 0.0,
        D: 0.0
        }, #(OPTIONAL)
      angular: {
        P: 10,
        I: 0.0,
        D: 0.0
        }
      }
    button mapping: {
      a1: 0,
      a2: -1,
      g1: 1,
      next mode: 2,
      prev mode: 3} #(REQUIRED)
    # visible: True
    # visible size: 0.005

1.1 workspace scaling:

Important for scaling the motion of the IID in simulation. A lower number scales the motion down and a higher one scales it up.

1.2 simulated multibody:

Specifies an ADF description file to be loaded alongside the IID.

1.3 root link:

A rigid body within the simulated multibody (if specified above), or a rigid body launched separately in the simulation. If no root link is specified and a simulated multibody is defined, a root link is computed automatically. This would be the rigid body in the mechanism with the least number of parents. As an example, if the simulated multi-body is a free-floating gripper (with a palm and attached fingers), then commenting out the root link will result in the palm being assigned as the root link. On the other hand, if the simulated multi-body is an articulated robot (such as the Kuka), one should specify the root link to be the distal end-effector, or else, the base will be assigned as the root link.

1.4 location:

This the location of the SDE in the world where the position and orientation are initialized to and overrides the set pose of the root link. If this field is commented out, the pose specified in the ADF file of the root link is used.

1.5 orientation offset:

The goal of the orientation offset is to change the angular mapping between IID and the root link and is an optional field.

1.6 haptic gains:

The gains scale the magnitude of the force feedback to the IID.

1.7 controller gain:

The controller gains help to impose the motions of the IID on the root link. This is an optional field. If not specified, the controller gains of the root link that are specified in its ADF file are used.

2. Notes on Mapping a Simulated Rigid Body:

The pairing between an IID and a root link do not take into account the kinematics of the mechanism to which the root link belongs. For example, if the simulated multibody is a KUKA robot, and the root link is the distal end-effector, the movements of the IID will directly influence the motions of this end-effector in the cartesian space rather than commanding the joints of the robot to move the end-effector. For some cases, this may not be what is desired. To control the joints of a mechanism to move the end-effector using an Input Device, one may use the Python client, and handle the teleoperation in their code and finally command the joints of the robot using the provided joint control APIs.

Clone this wiki locally