Vizzy Cartesian Interface

From ISRWiki
Revision as of 17:01, 17 November 2011 by Daragao (talk | contribs)
Jump to navigation Jump to search

Introduction

The Cartesian Interface used with Vizzy to reach a XYZ point using its inverse kinematics is based in the tutorial "Customizing the Cartesian Interface for a Generic Robot"[1] by Ugo Pattacini. Reading Ugo's tutorial is strongly advised.

For the Cartesian Interface to work the iCubInterface (Vizzy adapted version) needs to be running, and the desired arm, shoulders and torso ports open.

The interface makes use of three distinct modules. A solver which solves the motors position for a desired XYZ position given a kinematic chain. A server which controls the motors directly while it tries to confer human like movements to the robot. Finally a client which calls the server and solver methods through a defined interface.

The modules used for the Vizzy robot are based and very similar to the ones available in the tutorial "Customizing the Cartesian Interface for a Generic Robot". The most important differences are in the ini files.

Solver

The solver ini file for the Vizzy robot has two extra parameters besides the ones presented in the original tutorial. The 'kinematics_file' and 'part' parameters.

  • kinematics_file: indicates the path and name of the file with the kinematic chain description.
  • part: indicates which part of the robot is going to be solved, the right_arm or left_arm part. The selected part does not only affect the part referred but also the respective shoulder and torso.

If there is an interest in blocking a motor the dof parameter can be used to do that, this can be set through the ini file or dynamically.

In the original tutorial the robot was constituted of only one part, in the Vizzy case each arm can be constituted of three parts: arm, shoulder, and torso. In the code a function was added just to simplify the part properties definition the "newPartProperties()", and the three part properties objects were added to the PartDescriptor:

PartDescriptor *p=new PartDescriptor;
p->lmb=limb;                // a pointer to the iKinLimb
p->chn=limb->asChain();     // the associated iKinChain object
p->cns=NULL;                // any further (linear) constraints on the joints other than the bounds? This requires some more effort
p->prp.push_back(optTorsoPart);
p->prp.push_back(optShoulderPart);
p->prp.push_back(optArmPart);
p->rvs.push_back(true);
p->rvs.push_back(true);
p->rvs.push_back(true);
p->num=3;

Server

The server ini file for the Vizzy robot has four extra parameters besides the ones presented in the original tutorial. The 'kinematics_file', 'robot', 'part', and 'local'.

  • kinematics_file: indicates the path and name of the file with the kinematic chain description.
  • part: indicates which part of the robot is going to be solved, the right_arm or left_arm part. The selected part does not only affect the part referred but also the respective shoulder and torso.
  • robot: indicates the name of the robot (in Vizzy's case 'vizzy').
  • local: indicates the prefix name for the server port.

The ini file also has three [DRIVER_X] groups one per each part of the robot that needs to be controlled. The 'JointsOrder' parameter depends on how the kinematic chain is described in it's ini file.

Just as the solver the server differentiates itself from the original because the Vizzy Cartesian Interface needs to control three distinct parts. This parts are added to a Polydriver list, which is attached to a wrapper.

PolyDriverList list;
list.push(&partDrvTorso,torsoPart.c_str());
list.push(&partDrvShoulder,shoulderPart.c_str());
list.push(&partDrvArm,armPart.c_str());

Client

The iCub Cartesian Interface client is also valid for the Vizzy robot[2].

Kinematic chain ini file

Tutorial files

An modified version of the "anyRobotCartesianInterface" tutorial files for the Vizzy robot can be found here.

This compressed file has four programs: a solver; a server; a client; and a testServer.

The server, solver and client are described in the "Customizing the Cartesian Interface for a Generic Robot" tutorial and also in the section above. The client also allows for keyboard input of positions (type help on the shell the client is running to get a full description of the commands), this client also has an ini where it is possible to define the trajectory time and a target tolerance value. Before using any of these programs make sure that the ini files in the "./app/conf" have the correct parameters.

The testServer is a simpler server, this server does not have try to make human like movement has the server does, instead it only sets the position of the motors to the one sent by the solver RPC port. This works by sending RPC commands for a new XYZ position to the solver input port.

<< Back to Vizzy wiki homepage