Your first application using semantic checking on geometric relations (without coordinate checking)

This tutorial assumes you have prepared a ROS package with name myApplication and that you have set your ROS_PACKAGE_PATH environment variable accordingly, as explained in this tutorial.

In this tutorial we first explain how you can create basic semantic objects (without coordinates and coordinate checking) and perform semantic operations on them. We will show how you can create any of the supported geometric relations: position, orientation, pose, transational velocity, rotational velocity, twist, force, torque, and wrench.

Remark that the file resulting from following this tutorial is attached to this wiki page for completeness.

Prepare the main file

  • Go to the directory of our first application using:

roscd myApplication
  • Create a main file (in this tutorial called myFirstApplication.cpp) in which we will put the code of our first application.

touch myFirstApplication.cpp
  • Edit the C++ file with your favorite editor. For instance:

vim myFirstApplication.cpp
  • Include the necessary headers.

#include <Position/PositionSemantics.h>
#include <Orientation/OrientationSemantics.h>
#include <Pose/PoseSemantics.h>
#include <LinearVelocity/LinearVelocitySemantics.h>
#include <AngularVelocity/AngularVelocitySemantics.h>
#include <Twist/TwistSemantics.h>
#include <Force/ForceSemantics.h>
#include <Torque/TorqueSemantics.h>
#include <Wrench/WrenchSemantics.h>

  • Next we use the geometric_semantics namespace for convenience:

using namespace geometric_semantics;

  • Create a main program:

int main (int argc, const char* argv[])
{
// Here comes the code of our first application
}

Building your first application

  • To build you application you should edit the CMakeLists.txt file created in your application directory.

vim CMakeLists.txt

  • Add the C++ main file to be build as an executable by adding the following line:

rosbuild_add_executable(myFirstApplication myFirstApplication.cpp)

  • Now you are ready to build, so type

rosmake myApplication

and the executable will be created in the bin directory.

  • To run the executable do:

bin/myFirstApplication

You will get the semantic output on your screen.

Creating the geometric relations semantics

  • We will start with creating the geometric relation semantics objects for the relation between body C with point a and orientation frame [e], and body D with point b and orientation frame [f]:

    // Creating the geometric relations semantics
    PositionSemantics position("a","C","b","D");
    OrientationSemantics orientation("e","C","f","D");
    PoseSemantics pose("a","e","C","b","f","D");
 
    LinearVelocitySemantics linearVelocity("a","C","D");
    AngularVelocitySemantics angularVelocity("C","D");
    TwistSemantics twist("a","C","D");
 
    TorqueSemantics torque("a","C","D");
    ForceSemantics force("C","D");
    WrenchSemantics wrench("a","C","D");

Doing semantic operations

  • We can for instance take the inverses of the created semantic geometric relations by:

    //Doing semantic operations with the geometric relations
    // inverting
    PositionSemantics positionInv = position.inverse();
    OrientationSemantics orientationInv = orientation.inverse();
    PoseSemantics poseInv = pose.inverse();
    LinearVelocitySemantics linearVelocityInv = linearVelocity.inverse();
    AngularVelocitySemantics angularVelocityInv = angularVelocity.inverse();
    TwistSemantics twistInv = twist.inverse();
    TorqueSemantics torqueInv = torque.inverse();
    ForceSemantics forceInv = force.inverse();
    WrenchSemantics wrenchInv = wrench.inverse();
And if we print the inverses, we will see they are semantically correct:
    std::cout << "-----------------------------------------" << std::endl;
    std::cout << "Inverses: " << std::endl;
    std::cout << "     " << positionInv << " is the inverse of " << position << std::endl;
    std::cout << "     " << orientationInv << " is the inverse of " << orientation << std::endl;
    std::cout << "     " << poseInv << " is the inverse of " << pose << std::endl;
    std::cout << "     " << linearVelocityInv << " is the inverse of " << linearVelocity << std::endl;
    std::cout << "     " << angularVelocityInv << " is the inverse of " << angularVelocity << std::endl;
    std::cout << "     " << twistInv << " is the inverse of " << twist << std::endl;
    std::cout << "     " << torqueInv << " is the inverse of " << torque << std::endl;
    std::cout << "     " << forceInv << " is the inverse of " << force << std::endl;
    std::cout << "     " << wrenchInv << " is the inverse of " << wrench << std::endl;

  • Now we can for instance compose the result with their inverses. Mind that the order of composition does not matter, since this is automatically derived from the semantic information in the objects.

    //Composing
    PositionSemantics positionComp = compose(position,positionInv);
    OrientationSemantics orientationComp = compose(orientation,orientationInv);
    PoseSemantics poseComp = compose(pose,poseInv);
    LinearVelocitySemantics linearVelocityComp = compose(linearVelocity,linearVelocityInv);
    AngularVelocitySemantics angularVelocityComp = compose(angularVelocity,angularVelocityInv);
    TwistSemantics twistComp = compose(twist,twistInv);
    TorqueSemantics torqueComp = compose(torque,torqueInv);
    ForceSemantics forceComp = compose(force,forceInv);
    WrenchSemantics wrenchComp = compose(wrench,wrenchInv);
If you execute the program you will get screen output on the semantic correctness of the compositions (if not check the build flags of your geometric_semantics library as explained in the user guide. You can print and check the result of the composition using:
    std::cout << "-----------------------------------------" << std::endl;
    std::cout << "Composed objects: " << std::endl;
    std::cout << "     " << positionComp << " is the composition of " << position << " and " << positionInv << std::endl;
    std::cout << "     " << orientationComp << " is the composition of " << orientation << " and " << orientationInv <<  std::endl;
    std::cout << "     " << poseComp << " is the composition of " << pose <<  " and " << poseInv << std::endl;
    std::cout << "     " << linearVelocityComp << " is the composition of " << linearVelocity  << " and " << linearVelocityInv << std::endl;
    std::cout << "     " << angularVelocityComp << " is the composition of " << angularVelocity  << " and " << angularVelocityInv << std::endl;
    std::cout << "     " << twistComp << " is the composition of " << twist <<  " and " << twistInv << std::endl;
    std::cout << "     " << torqueComp << " is the composition of " << torque <<  " and " << torqueInv << std::endl;
    std::cout << "     " << forceComp << " is the composition of " << force <<  " and " << forceInv << std::endl;
    std::cout << "     " << wrenchComp << " is the composition of " << wrench <<  " and " << wrenchInv << std::endl;

AttachmentSize
myFirstApplication.cpp4.28 KB