Your first application

A quick tutorial to get you started with OpenPHRI

Unless you want to add new things to OpenPHRI, there's no reason for you to write code directly inside the open-phri package. So let's create a new one! For that, we have to use PID workspace commands:

cd pid-workspace/pid
make create package=my-package # you can replace 'my-package' whith whatever you want

Now you have your new package created in the workspace. The first thing to do is to declare the open-phri package as a dependency of this one. To do so, we need to edit the CMakeLists.txt file located at the root of your package (pid-workspace/packages/my-package/CMakeLists.txt) and add the following line before the build_PID_Package() command:

Then, to create an application, we first have to create a new folder under apps to put our source code:

apps/
├── CMakeLists.txt
├── my-app/
│   ├── main.cpp

and a resource folder for the application's configuration file:

share/
├── resources/
│   ├── my-app/
│      ├── configuration.yaml

and to declare it within the CMakeLists.txt file of the apps folder.

PID_Component(
    APPLICATION
    NAME my-app
    DIRECTORY my-app
    RUNTIME_RESOURCES my-app
    DEPEND open-phri open-phri-vrep-driver
)

What we do here is declare a new PID component which type is APPLICATION, we give it a NAME, specify its containing DIRECTORY and tell what RUNTIME_RESOURCES do we need (more on that later). Then we declare two dependencies for this application, the OpenPHRI library itself and its V-REP driver so that we can run our example with the simulator.

Now that our application is configured, let's write some code! Fire up your favorite code editor and open apps/my-app/main.cpp. We will start with some header inclusions:

main.cpp

#include <OpenPHRI/OpenPHRI.h>
#include <OpenPHRI/drivers/vrep_driver.h>
#include <pid/rpath.h>

#include <iostream>
#include <signal.h>

The first two lines include the OpenPHRI library and its V-REP driver, the next one includes pid-rpath, allowing the resolution of paths to runtime resources, and the last two are required to print some messages to the console and to be able to catch the interrupt signal (ctrl+c) to properly stop the application.

Now, we can declare the function that will catch the interrupt signal and its associated global variable:

main.cpp
bool _stop = false;


void sigint_handler(int sig) {
	_stop = true;
}

Nothing fancy here, just some C code. Time to write our main function:

main.cpp
int main(int argc, char const *argv[]) {
	phri::AppMaker app("my-app/configuration.yaml");

	auto robot = app.getRobot();
	*robot->controlPointDampingMatrix() *= 100.;

	auto safety_controller = app.getController();
	safety_controller->add(
		"ext force",
		phri::ExternalForce(robot));

	auto maximum_velocity = std::make_shared<double>(0.1);
	safety_controller->add(
		"velocity constraint",
		phri::VelocityConstraint(maximum_velocity));

	bool init_ok = app.init();

	if(init_ok) {
		std::cout << "Starting the main loop\n";
		signal(SIGINT, sigint_handler);
	}
	else {
		std::cout << "Initialization failed\n";
	}

	while(init_ok and not _stop) {
		_stop |= not app.run();
	}

	app.stop();

	return 0;
}

Ok, let's break it down a bit.

phri::AppMaker app("my-app/configuration.yaml");

In order to simplify the writing of this application, we use the phri::AppMaker class that creates everything needed to run our application (a robot, a controller, the robot's model, its driver and a data logger). When we instanciate this class, we pass it a configuration file, my-app/configuration.yaml here. This file will be resolved by pid-rpath, a library to help manage runtime resources in PID, so that you don't have to give an full absolute path (but you can if you want to). Various things can be set from this configuration file such as the robot's joint count, which driver to use, what data to log, etc.

The goal we set for this application is to be able to manually guide the robot by its end-effector and to apply a velocity limit for it. This is a very simple collaborative application but that's good enough for the example.

	auto robot = app.getRobot();
	*robot->controlPointDampingMatrix() *= 100.;

With these two lines, we first retrieve the robot from the app and set the control-point damping matrix (initialized as an identity matrix) to be a diagonal matrix of 100. This damping matrix will translate the forces applied to the end-effector into velocities.

	auto safety_controller = app.getController();
	safety_controller->add(
		"ext force",
		phri::ExternalForce(robot));

Here we get the controller from the app and add a new input to it, the external force applied to the robot's end-effector. The add method on the controller can be used to add new inputs, as we just did, or new constraints, as we can see with the next lines:

	auto maximum_velocity = std::make_shared<double>(0.1);
	safety_controller->add(
		"velocity constraint",
		phri::VelocityConstraint(maximum_velocity));

The first line creates a shared pointer to a double value, initialized to 0.1 m/s. This will be used as our velocity limit. The advantage of using a shared pointer instead of a simple value is that we can update the velocity limit later without having to reconfigure the controller. The next ones create a new velocity constraint and add it to the controller.

Now that we have configured our controller as we wanted (manual guidance + velocity limit), we have to perform some initialization. For that, we just have to call init on the app and check that everything went fine.

	bool init_ok = app.init();

	if(init_ok) {
		std::cout << "Starting main loop\n";
		signal(SIGINT, sigint_handler);
	}
	else {
		std::cout << "Initialization failed\n";
	}

If the initialization was successful, we register the sigint_handler function with the interrupt signal SIGINT. One the initialization is performed, we can run our main loop and start playing with the robot:

	while(init_ok and not _stop) {
		_stop |= not app.run();
	}

Pretty simple right? We enter the loop if the previous initialization went fine and exit it if the user asks for it (using the interrupt signal) or if the app.run() function returns false, meaning that something went wrong (e.g. driver communication error).

Once the loop has exited, we call app.app() to properly stop the application and then we can return from the main function.

	app.stop();

	return 0;

Now that the code is written, we have to write the configuration file for the application:

configuration.yaml

robot:
  name: LBR4p
  joint_count: 7

model:
  path: robot_models/kuka_lwr4.yaml
  control_point: end-effector

driver:
  type: vrep
  sample_time: 0.01
  synchronous: true

controller:
  use_dynamic_dls: true
  lambda_max: 0.1
  sigma_min_threshold: 0.1

data_logger:
  log_control_data: true
  log_robot_data: true
  folder: /tmp

In this file, the robot field describes the robot we control, the model field indicates the path to the robot's kinematic model and which body we use as a control point, the driver field gives information about which driver to use and its specific parameters, the controller filed defines parameters for the SafetyController and lastly, the data_logger field tells what type of data do we want to log and where.

Now that everything is ready, I suppose that you want to run this application to check that everything works as expected. Do do so, we first have to configure and build the package:

cd pid-workspace/packages/my-package/build
cmake ..
make build

Then, launch the V-REP simulator (you can get it for free form here if you don't already have it) and open the scene located at pid-workspace/packages/open-phri/share/scenes/KukaLWR4.ttt.

Finally, go to your package installation directory and start the application:

cd pid-workspace/install/<your-architecture>/my-package/<current-version>/bin
./my-app

And voilà! The application should start and connect to V-REP. A GUI with some sliders will appear, allowing you to create some forces on the end-effector to mimic manual guidance.

I hope this short tutorial was enough to get you started with OpenPHRI. You can now start to tinker around this application or to continue reading the docs to learn more about what you can do with OpenPHRI and how it works internally (don't worry, the mathematics behind it are pretty simple).

Last updated