Skip to content

Latest commit

 

History

History
130 lines (103 loc) · 5.93 KB

HowToUseYourInterfaceStruct.md

File metadata and controls

130 lines (103 loc) · 5.93 KB

How to Use Your Parameter Struct

Description: This tutorial will familiarize you with how you can use the autogenerated interface structs in your nodes.

Tutorial Level: INTERMEDIATE

Generated files

When creating interface files as described in How to write your first .rosif file, you will end up with the following two files:

  • 'include/rosinterface_tutorials/TutorialInterface.h'
  • 'include/rosinterface_tutorials/TutorialConfig.h'

The 'Interface.h' file will hold a struct called <name>Interface. The 'Config.h' file will hold the normal dynamic_reconfigure Config struct.

For your code it is enough to include the *Interface.h file, e.g.

#include "rosinterface_tutorials/TutorialInterface.h"

You can now add an instance of the interface struct to your class:

rosinterface_tutorials::TutorialInterface interface_;

Initializing the struct.

When initializing your node, the interface struct must be initialized with a private NodeHandle.

The call to fromParamServer() will take care of getting all parameter values from the parameter server, checking their type, and checking that a default value is set, if you haven't provided one on your own. If you have specified a default value, but the parameter is not yet present on the parameter server, it will be set. When min and max values are specified, these bounds will be checked as well.

MyNodeClass::MyNodeClass()
  : interface_{ros::NodeHandle("~")}
{
  interface_.fromParamServer();
}

If you do not use a class (which you should do though in my opinion), you can create it like so:

rosinterface_tutorials::TutorialInterface interface_{ros::NodeHandle("~")}
interface_.fromParamServer();

Note: If you have set the logger level for your node to debug, you will get information on which values have been retrieved.
Note: If you use nodelets, you have to use the getPrivateNodeHandle() function instead.

Using dynamic_reconfigure

Your dynamic_reconfigure callback can now look as simple as:

void reconfigureRequest(TutorialConfig& config, uint32_t level) {
    interface_.fromConfig(config);
}

This will update all values that were specified as configurable. At the same time, it assures that all dynamic_reconfigure parameters live in the same namespace as those on the parameter server to avoid problems with redundant parameters.

You can find a running version of this example code in the rosinterface_handler_tutorial-Repository

Setting parameters on the server

If you change your parameters at runtime from within the code, you can upload the current state of the parameters with

interface_.toParamServer();

This will set all non-const parameters with their current value on the ros parameter server.

Setting parameters at launch time

If you want to run your node with parameters other then the default parameters, then they have to be set on the parameter server before the node starts. To ease the burden of setting all parameters one after the other, roslaunch has the rosparam argument to load a YAML file containing a whole set of key value pairs. Rosinterface handler provides a script, to automatically generates a YAML file for you to use. Calling it will generate a file in your current directory.

rosrun rosinterface_handler generate_yaml <path/to/Tutorial.rosif>

Publisher and subscriber

Publishers and subscribers are already initialized and ready to use. If they are defined to be configruable, the fromParamServer() function takes care of updating the topic. In order to actually use the subscriber, you need to register your message callback(s) once on startup. Keep in mind that subscribers are actually shared pointers:

interface_.my_subscriber->registerCallback(&myCallback);

No work is required for publishers. Just use them:

std_msgs::Header my_msg;
interface_.my_publisher.publish(my_msg);

Synchronized subscribers

Because the subscribers are actually message_filters::Subscriber, you can directly use them to create a synchronized subscriber:

message_filters::TimeSynchronizer<sensor_msgs::Image, sensor_msgs::Image> sync(*interface_.my_subscriber1, *interface_.my_subscriber2, 10);
sync.registerCallback(boost::bind(&callback, _1, _2));

Diagnosed publishers/subscribers

Diagnosed publishers and subscribers work similar to the nomal publisher/subsribers and update their diagnostic status by themselves. No more action is required on them. However, the updater member inside your Interface object has an update() function that needs to be called regularly so that updates are published. Refer to the documentation of diagnostic_updater for more information.

Calling the update() function is not necessary if you are using diagnostics with simplified_status=True. In that case, the nodeStatus member of the Interface object will do the job for you.

You are suppoed to use this member in order to share the current state of the node. This could look like this:

interface_.nodeStatus.set(rosinterface_handler::NodeStatus::ERROR, "Something happened!");

Remember to also clear the error once your node has recovered by calling set with NodeStatus::OK.

Python

All your interface definitions are fully available in python nodes as well. Just import the interface file:

from rosinterface_tutorials.interface.TutorialInterface import TutorialInterface

Unlike in C++, the call to fromParamServer is not necessary:

self.interface = TutorialInterface()

And a dynamic_reconfigure callback might look like that:

def reconfigure_callback(self, config, level):
    self.interface.from_config(config)
    print("Parameter dummy changed to {}".format(self.interface.dummy))

And a call to set the parameters on the server will look like this:

self.interface.to_param_server()