kinematics-dynamics
Classes

Contains roboticslab::BasicCartesianControl. More...

Classes

class  roboticslab::BasicCartesianControl
 The BasicCartesianControl class implements ICartesianControl. More...
 

Detailed Description

Example with a Fake robot

First we must run a YARP name server if it is not running in our current namespace:

[on terminal 1] yarp server

And then launch the actual library:

[on terminal 2] yarpdev --device BasicCartesianControl --robot EmulatedControlBoard --angleRepr axisAngle --link_0 "(A 1)"

Along the output, observe a line like the following.

[info] DeviceDriverImpl.cpp:26 open(): Using angleRepr: axisAngle.

This would mean we are using an axis/angle notation (par de rotaciĆ³n). Note that it is a variable parameter; in fact, we have forced it above.

We connect, can ask for help, etc. Here's an example interaction:

[on terminal 3] yarp rpc /CartesianControl/rpc_transform:s
[>>] help
Response: [stat] [inv] [movj] [movl] [movv] [gcmp] [forc] [stop]
[>>] stat
Response: [ccnc] 1.0 0.0 0.0 0.0 0.0 1.0 0.0

Stat returns the controller status, and forward kinematics. [ccnc] means Cartesian Control Not Controlling (also note that notation is in constant evolution, so put an issue if it's not updated!). The first 3 parameters of the forward kinnematics are X,Y,Z of the end-effector. The other parameters correspond to orientation in the previously set notation, which in this example is axis/angle, so this would read: on Z, 0 degrees.

Let's now move to a reachable position/orientation.

[>>] movj 1.0 0.0 0.0 0.0 0.0 1.0 0.0
Response: [ok]

Example with teoSim

What moslty changes is the library command line invocation. We also change the server port name. The following is an example for the simulated robot's right arm.

[on terminal 2] yarpdev --device BasicCartesianControl --name /teoSim/rightArm/CartesianControl --from /usr/local/share/teo-configuration-files/contexts/kinematics/rightArmKinematics.ini --angleRepr axisAngle --robot remote_controlboard --local /BasicCartesianControl/teoSim/rightArm --remote /teoSim/rightArm
[on terminal 3] yarp rpc /teoSim/rightArm/CartesianControl/rpc_transform:s

Example with real TEO

What moslty changes is the library command line invocation. We also change the server port name. The following is an example for the robot's right arm.

[on terminal 2] yarpdev --device BasicCartesianControl --name /teo/rightArm/CartesianControl  --from /usr/local/share/teo-configuration-files/contexts/kinematics/rightArmKinematics.ini --angleRepr axisAngle --robot remote_controlboard --local /BasicCartesianControl/teo/rightArm --remote /teo/rightArm
[on terminal 3] yarp rpc /teo/rightArm/CartesianControl/rpc:s

On the real robot, you can even activate Gravity Compensation (warning: dangerous if kinematic/dynamic model has not been reviewed!).

[>>] gcmp

Very Important

When you launch the BasicCartesianControl device as in [terminal 2], it's actually wrapped: CartesianControlServer is the device that is actually loaded, and BasicCartesianControl becomes its subdevice. The server is what allows us to interact via the YARP RPC port mechanism. If you are creating a C++ program, you do not have to sned these raw port commands. Use CartesianControlClient instead, because the server and client are YARP devices (further reading on why this is good: here (spanish)).