[Documentation] [TitleIndex] [WordIndex

Parameters

Run time configuration of your node is one of the most valuable features of ROS. ROSserial exposes this by extending the parameter server to your hardware. This way you can load settings for your hardware into the parameter server and the hardware can retrieve the parameters when it starts up.

Since ROSSerial is meant for memory & cpu limited hardware, dictionary and multi-type lists of parameters are not supported. All lists and single values of integers, floats, and strings are supported.

Below, is an example code for query the parameter server over rosserial.

   1 #include "ros.h"
   2 
   3 //create your handle
   4 ros::NodeHandle nh;
   5 
   6 char buffer[250];
   7 float pid_constants[3];
   8 
   9 void setup(){
  10     while (!nh.connected()) {
  11         nh.spinOnce();
  12     }
  13 }
  14 
  15 void loop(){
  16     if (! nh.getParam("~pid", pid_constants,3)) { 
  17         //default values
  18         pid_constants[0]= 1;
  19         pid_constants[1]=0.24;
  20         pid_constants[2]=0.01; 
  21     }
  22     nh.spinOnce();
  23 }

   5 ros::NodeHandle nh;

As always, statically allocate your node handle.

   7 char buffer[250];
   8 float pid_constants[3];

Setup buffer and assign variables.

  11     while (!nh.connected()) {
  12         nh.spinOnce();

Wait until the node handle has connected to ROS. If you request parameters before the node handle has connected, the request will fail.

  17     if (! nh.getParam("~pid", pid_constants,3)) { 
  18         //default values
  19         pid_constants[0]= 1;
  20         pid_constants[1]=0.24;
  21         pid_constants[2]=0.01; 

Finally, allocate memory for your parameters and request them from the Parameter server. You must give nh.getParam the name of the parameter, a point to the memory location of the result, and the expected length of the parameter list. For a single parameter , leave out the length or put 1.

Your request can fail. It can fail because the node handle isnt connected, the parameter does not exist, the parameter is of the wrong type, the parameter is a dictionary, or the parameter has a list of items of a different length than you specified. It can even fail because something corrupted communication between the hardware and the device.

YOU MUST PROVIDE DEFAULT VALUES FOR YOUR PROGRAM TO WORK CORRECTLY.

   1   ros::NodeHandle::getParam(const char* param_name, int*   val,int length=1);
   2   ros::NodeHandle::getParam(const char* param_name, float* val,int length=1);
   3   ros::NodeHandle::getParam(const char* param_name, char** val,int length=1);

Above are the functions for retrieving parameters from the Parameter Server.


2023-10-28 13:00