Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
117 changes: 117 additions & 0 deletions doc/HowToUseYourParameterPtr.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,117 @@
# How to Use Your `rosparam_handler::ParameterPtr`
**Description**: This tutorial will familiarize you with how you can use the autogenerated parameter structs in your nodes from a base class smart-pointer. It is thus recommended to read the tutorial [How to use your parameters struct file](HowToUseYourParametersStruct.md) if you haven't yet.
**Tutorial Level**: INTERMEDIATE

## Generated files
When creating params files as described in [How to write your first .params file](HowToWriteYourFirstParamsFile.md), you will end up with the following two files:
- *'include/rosparam_tutorials/TutorialParameters.h'*
- *'include/rosparam_tutorials/TutorialConfig.h'*

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

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

```cpp
#include "rosparam_tutorials/TutorialParameters.h"
```

You can now add an instance of the base parameter pointer to your class:

```cpp
rosparam_tutorials::ParametersPtr params_ptr_;
```

## Initializing the pointer
When initializing your node, the params pointer `params_ptr_` must be instantiated to the appropriate parameter type with a private `NodeHandle`.

```cpp
MyNodeClass::MyNodeClass()
: params_ptr_{boost::make_shared<TutorialParameters>(ros::NodeHandle("~"))}
{
...
}
```

In case your node has several classes, each using a different `ParameterPtr` object, the private `NodeHandle` must have a sub-namespace that is unique to your object in order to avoid parameters name collision.

```cpp
MyNodeClass::MyClass()
: params_ptr_{boost::make_shared<TutorialParameters>(ros::NodeHandle("~/my_class"))}
{
...
}

MyNodeClass::MyOtherClass()
: params_ptr_{boost::make_shared<TutorialParameters>(ros::NodeHandle("~/my_other_class"))}
{
...
}
```

## Initializing the struct

The call to `fromParamServer()` is done the very same manner as for a normal parameter object.
It 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.

```cpp
MyNodeClass::MyNodeClass()
: params_ptr_{boost::make_shared<TutorialParameters>(ros::NodeHandle("~"))}
{
params_ptr_->fromParamServer();
}
```

If you do not use a class (which you should do though in my opinion), you can create it like so:
```cpp
rosparam_tutorials::ParametersPtr params_ptr{boost::make_shared<TutorialParameters>(ros::NodeHandle("~"))}
params_ptr->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.

## Retrieving the actual parameter

Since you are using here a `ParametersPtr`, you cannot access directly the parameters held by the structure:
```cpp
params_ptr_->my_int = 42; // Will NOT compile
```

To do so, you have to cast the base pointer to its appropriate derived type:
```cpp
boost::shared_ptr<TutorialParameters> params_ptr_cast = rosparam_handler::dynamic_parameters_cast<TutorialParameters>(params_ptr_);
assert(params_ptr_cast != nullptr);

if (params_ptr_cast != nullptr)
{
params_ptr_cast->my_int = 42;
}
```
Both dynamic and static cast helper function are provided:
```cpp
auto my_cast = rosparam_handler::dynamic_parameters_cast<DerivedType>(ptr);
auto my_cast = rosparam_handler::static_parameters_cast<DerivedType>(ptr);
```
which simply are aliases to:
```cpp
auto my_cast = boost::dynamic_pointer_cast<DerivedType>(ptr);
auto my_cast = boost::static_pointer_cast_cast<DerivedType>(ptr);
```

## Using dynamic_reconfigure
Your dynamic_reconfigure callback can now look as simple as:
```cpp
void reconfigureRequest(TutorialConfig& config, uint32_t level) {
params_ptr_->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 [rosparam_handler_tutorial](https://github.com/cbandera/rosparam_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
```cpp
params_ptr_->toParamServer();
```
This will set all non-const parameters with their current value on the ros parameter server.
11 changes: 11 additions & 0 deletions doc/HowToUseYourParameterStruct.md
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,17 @@ This will update all values that were specified as configurable. At the same tim

You can find a running version of this example code in the [rosparam_handler_tutorial](https://github.com/cbandera/rosparam_handler_tutorial)-Repository

## From another parameters structure
You can also simply copy your current parameters:
```cpp
rosparam_tutorials::TutorialParameters params_{ros::NodeHandle("~")}
params_.fromParamServer();

rosparam_tutorials::TutorialParameters params_copy_(params_);
// equivalently
params_copy_ = params_;
```

## 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
```cpp
Expand Down
103 changes: 103 additions & 0 deletions include/rosparam_handler/ParametersBase.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,103 @@
/**
* \file ParametersBase.h
*
* Created on: Oct 28, 2017
*
* \authors: Claudio Bandera
* Sascha Wirges
* Niels Ole Salscheider
* Jeremie Deray
*/

#ifndef _ROSPARAM_HANDLER_PARAMETERS_BASE_H_
#define _ROSPARAM_HANDLER_PARAMETERS_BASE_H_

#include <ros/param.h>
#include <ros/node_handle.h>
#include <rosparam_handler/utilities.hpp>
#include <rosparam_handler/pointer.hpp>

namespace rosparam_handler {

/// \brief ParametersBase An abstract base struct for struct generated by rosparam_handler.
struct ParametersBase {

ParametersBase(const ros::NodeHandle& private_node_handle)
: globalNamespace{"/"},
privateNamespace{private_node_handle.getNamespace() + "/"},
nodeName{rosparam_handler::getNodeName(private_node_handle)} {}

ParametersBase(const ParametersBase& o)
: globalNamespace(o.globalNamespace)
, privateNamespace(o.privateNamespace)
, nodeName(o.nodeName) {}

virtual ~ParametersBase() = default;

ParametersBase& operator=(const ParametersBase& o)
{
globalNamespace = o.globalNamespace;
privateNamespace = o.privateNamespace;
nodeName = o.nodeName;
return *this;
}

/// \brief Get values from parameter server
///
/// Will fail if a value can not be found and no default value is given.
inline void fromParamServer(){
if(!fromParamServerImpl()){
missingParamsWarning();
rosparam_handler::exit("RosparamHandler: GetParam could net retrieve parameter.");
}
ROS_DEBUG_STREAM(*this);
}

/// \brief Set parameters on ROS parameter server.
virtual void toParamServer() = 0;

/// \brief Update configurable parameters.
///
/// \param config dynamic reconfigure struct
/// \level ?
template <typename T>
inline void fromConfig(const T& config, const uint32_t level = 0){
#ifdef DYNAMIC_RECONFIGURE_FOUND
fromConfigImpl<T>(config, level);
#else
ROS_FATAL_STREAM("dynamic_reconfigure was not found during compilation. So fromConfig() is not available. Please recompile with dynamic_reconfigure.");
rosparam_handler::exit("dynamic_reconfigure was not found during compilation. So fromConfig() is not available. Please recompile with dynamic_reconfigure.");
#endif
}

/// \brief Stream operator for printing parameter struct
inline friend std::ostream& operator<<(std::ostream& os, const ParametersBase& p)
{
return p.print(os);
}

protected:

/// \brief The actual implementation of 'fromParamServer'
/// overriden by the derived class
virtual bool fromParamServerImpl() = 0;

/// \brief The actual implementation os 'fromConfig' specialized
/// for the 'DerivedConfig' type.
template <typename T>
void fromConfigImpl(const T& config, const uint32_t level);

/// \brief A helper function for ostram operator <<
virtual std::ostream& print(std::ostream& os) const = 0;

/// \brief Issue a warning about missing default parameters.
virtual void missingParamsWarning() = 0;

std::string globalNamespace = {"/"};
std::string privateNamespace;
std::string nodeName;
};

} // namespace rosparam_handler

#endif /* _ROSPARAM_HANDLER_PARAMETERS_BASE_H_ */
37 changes: 37 additions & 0 deletions include/rosparam_handler/pointer.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
/**
* \file pointer.h
*
* Created on: Oct 28, 2017
*
* \authors: Jeremie Deray
*/

#ifndef _ROSPARAM_HANDLER_POINTER_H_
#define _ROSPARAM_HANDLER_POINTER_H_

#include <boost/shared_ptr.hpp>

namespace rosparam_handler {

/// \brief forward declaration
struct ParametersBase;

/// \brief base pointer declaration
using ParametersPtr = boost::shared_ptr<ParametersBase>;
using ParametersConstPtr = boost::shared_ptr<const ParametersBase>;

template <typename T>
boost::shared_ptr<T> static_parameters_cast(const rosparam_handler::ParametersPtr& ptr)
{
return boost::static_pointer_cast<T>(ptr);
}

template <typename T>
boost::shared_ptr<T> dynamic_parameters_cast(const rosparam_handler::ParametersPtr& ptr)
{
return boost::dynamic_pointer_cast<T>(ptr);
}

} /* namespace rosparam_handler */

#endif /* _ROSPARAM_HANDLER_POINTER_H_ */
29 changes: 21 additions & 8 deletions src/rosparam_handler/parameter_generator_catkin.py
Original file line number Diff line number Diff line change
Expand Up @@ -383,6 +383,8 @@ def _generatehpp(self):
template = f.read()

param_entries = []
copy_constructor_entries = []
assignment_operator_entries = []
string_representation = []
from_server = []
to_server = []
Expand All @@ -405,17 +407,21 @@ def _generatehpp(self):

# Test for default value
if param["default"] is None:
value = ""
default = ""
non_default_params.append(Template(' << "\t" << $namespace << "$name" << " ($type) '
'\\n"\n').substitute(
namespace=namespace, name=name, type=param["type"]))
else:
if param['is_vector']:
default = ', {}'.format(str(param['type']) + "{" + self._get_cvaluelist(param, "default") + "}")
value = ' = {}'.format("{" + self._get_cvaluelist(param, "default") + "}")
default = ', ' + name
elif param['is_map']:
default = ', {}'.format(str(param['type']) + "{" + self._get_cvaluedict(param, "default") + "}")
value = ' = {}'.format("{" + self._get_cvaluedict(param, "default") + "}")
default = ', ' + name
else:
default = ', {}'.format(str(param['type']) + "{" + self._get_cvalue(param, "default") + "}")
value = ' = {}'.format(self._get_cvalue(param, "default"))
default = ', ' + name

# Test for constant value
if param['constant']:
Expand All @@ -425,16 +431,18 @@ def _generatehpp(self):
default=self._get_cvalue(param, "default")))
from_server.append(Template(' rosparam_handler::testConstParam($paramname);').substitute(paramname=full_name))
else:
param_entries.append(Template(' ${type} ${name}; /*!< ${description} */').substitute(
type=param['type'], name=name, description=param['description']))
param_entries.append(Template(' ${type} ${name}${value}; /*!< ${description} */').substitute(
type=param['type'], name=name, value=value, description=param['description']))
copy_constructor_entries.append(Template(' , ${name}(o.${name})').substitute(name=name))
assignment_operator_entries.append(Template(' ${name} = o.${name};').substitute(name=name))
from_server.append(Template(' success &= rosparam_handler::getParam($paramname, $name$default);').substitute(
paramname=full_name, name=name, default=default, description=param['description']))
to_server.append(
Template(' rosparam_handler::setParam(${paramname},${name});').substitute(paramname=full_name, name=name))

# Test for configurable params
if param['configurable']:
from_config.append(Template(' $name = config.$name;').substitute(name=name))
from_config.append(Template(' casted_ref.$name = config.$name;').substitute(name=name))

# Test limits
if param['is_vector']:
Expand All @@ -451,10 +459,12 @@ def _generatehpp(self):
paramname=full_name, name=name, max=param['max'], type=ttype))

# Add debug output
string_representation.append(Template(' << "\t" << p.$namespace << "$name:" << p.$name << '
string_representation.append(Template(' << "\t" << $namespace << "$name:" << $name << '
'"\\n"\n').substitute(namespace=namespace, name=name))

param_entries = "\n".join(param_entries)
copy_constructor_entries = "\n".join(copy_constructor_entries)
assignment_operator_entries = "\n".join(assignment_operator_entries)
string_representation = "".join(string_representation)
non_default_params = "".join(non_default_params)
from_server = "\n".join(from_server)
Expand All @@ -463,7 +473,10 @@ def _generatehpp(self):
test_limits = "\n".join(test_limits)

content = Template(template).substitute(pkgname=self.pkgname, ClassName=self.classname,
parameters=param_entries, fromConfig=from_config,
parameters=param_entries,
copyConstructor=copy_constructor_entries,
assignOperator=assignment_operator_entries,
fromConfig=from_config,
fromParamServer=from_server,
string_representation=string_representation,
non_default_params=non_default_params, nodename=self.nodename,
Expand Down
Loading