Skip to content

Commit

Permalink
updated demostration with new values to improve reachability
Browse files Browse the repository at this point in the history
  • Loading branch information
rsantos88 committed Feb 14, 2018
1 parent 624f6c9 commit c124ccb
Showing 1 changed file with 40 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,9 @@ make -j$(nproc)
* What mostly 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.
\verbatim
[on terminal 2] teoSim
[on terminal 3] 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] 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/righ --angleRepr axisAngletArm

This comment has been minimized.

Copy link
@PeterBowman

PeterBowman Feb 14, 2018

Member

Duplicate (and broken) angleRepr option.

This comment has been minimized.

Copy link
@rsantos88

rsantos88 Feb 14, 2018

Author Contributor

Fixed the broken parameter. Duplicated because in this issue: #113 you put an example that it allow to launch the cartesian controller plugin with an angle representation:

Follow-up announcement: @roboticslab-uc3m/teo developers should note that the /rpc:s port is no longer handling vectors in the representation given by --angleRepr; besides, this option is not recognized anymore by cartesian solvers (e.g. KdlSolver) and can be safely deleted from .ini files (teo-configuration-files/share/kinematics/). Now, users should explicitly launch the cartesian controller plugin with an angle representation of their choice, for example:

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 --angleRepr axisAngle

...and connect via RPC to the new /rpc_transform:s port:

yarp rpc /teoSim/rightArm/CartesianControl/rpc_transform:s

In case angleRepr is missing or not recognized, no /rpc_transform:s port will be opened. C++ applications may talk through this new port instead of the standard /rpc:s if --transform is provided (see example app in /example/cpp/cartesianControlExample/).

Is that correct?

This comment has been minimized.

Copy link
@jgvictores

jgvictores Feb 14, 2018

Member

I think @PeterBowman refers to two facts that are present in the same commit:

  1. The actual angleRepr is present twice in the same command (line 29).
  2. The second invocation is malformed, --angleRepr axisAngletArm does not look like a good --angleRepr.

Additionally, newly truncated --remote /teoSim/righ does not look like a good --remote.

This comment has been minimized.

Copy link
@jgvictores

jgvictores Feb 14, 2018

Member

Okay, spoken with @rsantos88 the attempt to duplicate was that the --angleRepr as actually duplicate at #113 (comment) (edited out as commented at #113 (comment) )

[on terminal 4] ./cartesianControlExample
[on possible terminal 5] yarp rpc /teoSim/rightArm/CartesianControl/rpc_transform:s (for manual operation)
\endverbatim
*/

Expand Down Expand Up @@ -98,28 +99,59 @@ int main(int argc, char *argv[])
// movl -> go to end position in task space
printf("Position 1: poss (0 0 0 90 0 0 0)\n");
iCartesianControl->movj(position);
yarp::os::Time::delay(8);

// -- Position 2: move forward along axis X
printf("Position 2: move forward along axis X\n");
position[0] = 0.5;
iCartesianControl->movj(position);
yarp::os::Time::delay(4);

// -- Position 3: move right along axis Y
printf("Position 3: move right along axis Y\n");
position[1] = -0.5;
position[1] = -0.4;
iCartesianControl->movj(position);
yarp::os::Time::delay(4);

// -- Position 4: rotate 10 degrees about axis Y
printf("Position 4: rotate 10 degrees about axis Y\n");
// -- Position 4: rotate -12 degrees about axis Y
printf("Position 4: rotate -12 degrees about axis Y\n");
position[3] = 0.0;
position[4] = 1.0;
position[5] = 0.0;
position[6] = 10.0;
position[6] = -12.0;
iCartesianControl->movj(position);
yarp::os::Time::delay(4);

// -- Position 5: rotate 30 degrees about axis Y
printf("Position 5: rotate 30 degrees about axis Y\n");
position[6] = 30.0;
// -- Position 5: rotate 50 degrees about axis X
printf("Position 5: rotate 50 degrees about axis X\n");
position[3] = 1.0;
position[4] = 0.0;
position[5] = 0.0;
position[6] = -50.0;
iCartesianControl->movj(position);
yarp::os::Time::delay(4);

// -- Position 6:
printf("Position 6: poss (0 0 0 90 0 0 0)\n");
position[0] = 0.390926; // 0.390926 -0.346663 0.166873 -0.004334 0.70944 0.704752 0.353119
position[1] = -0.346663;
position[2] = 0.166873;
position[3] = -0.004334;
position[4] = 0.70944;
position[5] = 0.704752;
position[6] = 0.353119;
iCartesianControl->movj(position);
yarp::os::Time::delay(4);

// 3.25149848407618e-17 -0.34692 -0.221806 1.53080849893419e-16 1.0 -3.06161699786838e-17 90.0
printf("Position 7: Homing\n");
position[0] = 3.25149848407618e-17;
position[1] = -0.34692;
position[2] = -0.221806;
position[3] = 1.53080849893419e-16;
position[4] = 1.0;
position[5] = -3.06161699786838e-17;
position[6] = 90.0;
iCartesianControl->movj(position);

dd.close();
Expand Down

0 comments on commit c124ccb

Please sign in to comment.