Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add example using ParameterPtr #3

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
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
15 changes: 14 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,10 @@ endif()
catkin_python_setup()

# Generate parameter files
generate_ros_parameter_files(cfg/Demo.params)
generate_ros_parameter_files(cfg/Demo.params
cfg/Foo.params
cfg/Bar.params
)

# Create package
catkin_package()
Expand All @@ -33,6 +36,16 @@ install(TARGETS demo
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

# Demo Ptr Node
add_executable(demo_ptr src/demo/demo_ptr.cpp src/demo/demo_ptr_node.cpp)
add_dependencies(demo_ptr ${catkin_EXPORTED_TARGETS} rosparam_handler_tutorial_gencfg)
target_link_libraries(demo_ptr ${catkin_LIBRARIES})
install(TARGETS demo_ptr
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

# Nodelet
add_library(demo_nodelet src/demo/demo.cpp src/demo/demo_nodelet.cpp)
target_link_libraries(demo_nodelet ${catkin_LIBRARIES})
Expand Down
6 changes: 6 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,12 @@ or run it as a nodelet
roslaunch rosparam_handler_tutorial demo_nodelet.launch
```

or run an example using `rosparam_handler::ParametersPtr`

```shell
roslaunch rosparam_handler_tutorial demo_ptr_node.launch
```

or as python module
```shell
roslaunch rosparam_handler_tutorial demo_node_python.launch
Expand Down
18 changes: 18 additions & 0 deletions cfg/Bar.params
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
#!/usr/bin/env python
####### workaround so that the module is found #######
import sys
import os
sys.path.append(os.path.join(os.path.dirname(__file__),"../../src"))
######################################################

from rosparam_handler.parameter_generator_catkin import *
gen = ParameterGenerator()

gen.add("rate", paramtype="int",description="Rate for timer", default=2, min=1, max=10, configurable=True)

# Parameters with different types
gen.add("str_param", paramtype="std::string", description="A string parameter", default="param b", configurable=True)
gen.add("vector_int_param", paramtype="std::vector<int>", description="A vector of int parameter", default=[1,2,3])

#Syntax : Package, Node, Config Name(The final name will be MyDummyConfig)
exit(gen.generate("rosparam_handler_tutorial", "demo_ptr_node", "Bar"))
18 changes: 18 additions & 0 deletions cfg/Foo.params
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
#!/usr/bin/env python
####### workaround so that the module is found #######
import sys
import os
sys.path.append(os.path.join(os.path.dirname(__file__),"../../src"))
######################################################

from rosparam_handler.parameter_generator_catkin import *
gen = ParameterGenerator()

gen.add("rate", paramtype="int", description="Rate for timer", default=2, min=1, max=10, configurable=True)

# Parameters with different types
gen.add("int_param", paramtype="int", description="An Integer parameter", default=1, configurable=True)
gen.add("str_param", paramtype="std::string", description="A string parameter", default="param a", configurable=True)

#Syntax : Package, Node, Config Name(The final name will be MyDummyConfig)
exit(gen.generate("rosparam_handler_tutorial", "demo_ptr_node", "Foo"))
13 changes: 13 additions & 0 deletions launch/demo_ptr_node.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
<launch>

<arg name="foo_config" default="$(find rosparam_handler_tutorial)/launch/params/foo_parameters.yaml" />
<arg name="bar_config" default="$(find rosparam_handler_tutorial)/launch/params/bar_parameters.yaml" />

<node pkg="rosparam_handler_tutorial" type="demo_ptr" name="demo_ptr" output="screen">
<rosparam command="load" file="$(arg foo_config)" ns="foo"/>
<rosparam command="load" file="$(arg bar_config)" ns="bar"/>
</node>

<node name="reconfigure_gui" pkg="rqt_reconfigure" type="rqt_reconfigure" />

</launch>
17 changes: 17 additions & 0 deletions launch/params/bar_parameters.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
### This file was generated using the rosparam_handler generate_yaml script.

# Name: rate
# Desc: Rate for timer
# Type: int
# [min,max]: [1/10]
rate: 2

# Name: str_param
# Desc: A string parameter
# Type: std::string
str_param: test another string

# Name: vector_int_param
# Desc: A vector of int parameter
# Type: std::vector<int>
vector_int_param: [1, 2, 3]
17 changes: 17 additions & 0 deletions launch/params/foo_parameters.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
### This file was generated using the rosparam_handler generate_yaml script.

# Name: rate
# Desc: Rate for timer
# Type: int
# [min,max]: [1/10]
rate: 2

# Name: int_param
# Desc: An Integer parameter
# Type: int
int_param: 42

# Name: str_param
# Desc: A string parameter
# Type: std::string
str_param: param a
165 changes: 165 additions & 0 deletions src/demo/demo_ptr.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,165 @@
#include "demo_ptr.hpp"

namespace rosparam_handler_tutorial {

void DemoBase::timerCallback(const ros::TimerEvent&) const {
if (params_ptr_ != nullptr)
ROS_INFO_STREAM("Parameter :\n" << *params_ptr_);
else
ROS_WARN("Timer callback executed before object params_ptr_ is instantiated !");
}

void DemoBase::fromParamServer()
{
params_ptr_->fromParamServer();
}

void DemoBase::toParamServer()
{
params_ptr_->toParamServer();
}

Foo::Foo(ros::NodeHandle private_node_handle) :
DemoBase(), dr_srv_(private_node_handle)
{
/**
* Instantiation
*/
init<FooParameters>(private_node_handle);

/**
* Initialization
*/
fromParamServer();

/**
* Set up timer
*/

/// @note We are certain that the object hold in params_ptr_
/// is of type FooParameters and we don't want to pay for
/// a dynamic_cast.
FooParameters& param = *boost::static_pointer_cast<FooParameters>(params_ptr_);

ros::TimerOptions timer_opt;
timer_opt.oneshot = false;
timer_opt.autostart = true;

timer_opt.callback = boost::bind(&Foo::timerCallback, this, _1);
timer_opt.period = ros::Rate(param.rate).expectedCycleTime();

timer_ = private_node_handle.createTimer(timer_opt);

/**
* Set up dynamic reconfigure server
*/
dynamic_reconfigure::Server<FooConfig>::CallbackType cb;
cb = boost::bind(&Foo::configCallback, this, _1, _2);
//dr_srv_.setCallback(cb);
}

void Foo::configCallback(FooConfig &config, uint32_t /*level*/)
{
if (params_ptr_ != nullptr)
{
params_ptr_->fromConfig(config);

int rate = boost::static_pointer_cast<FooParameters>(params_ptr_)->rate;

timer_.setPeriod(ros::Rate(rate).expectedCycleTime());

ROS_WARN_STREAM("Parameter update:\n" << *params_ptr_);
}
else
{
ROS_WARN("Dynamic reconfigure callback executed "
"before parameters initialization !");
}
}


Bar::Bar(ros::NodeHandle private_node_handle) :
DemoBase(), dr_srv_(private_node_handle)
{
/**
* Instantiation
*/
init<BarParameters>(private_node_handle);

/**
* Initialization
*/
fromParamServer();

/**
* Set up timer
*/

/// @note We are quite sure that the object hold in params_ptr_
/// is of type BarParameters but we want to play it safe.

boost::shared_ptr<BarParameters> bar_param_ptr =
boost::dynamic_pointer_cast<BarParameters>(params_ptr_);

int rate = 2;

if (bar_param_ptr != nullptr)
{
rate = bar_param_ptr->rate;
}
else
{
ROS_WARN("Could not cast param_ptr_ to type BarParameters !"
"\nUsing default rate (%i Hz)", rate);
}

ros::TimerOptions timer_opt;
timer_opt.oneshot = false;
timer_opt.autostart = true;

timer_opt.callback = boost::bind(&Bar::timerCallback, this, _1);
timer_opt.period = ros::Rate(rate).expectedCycleTime();

timer_ = private_node_handle.createTimer(timer_opt);

/**
* Set up dynamic reconfigure server
*/
dynamic_reconfigure::Server<BarConfig>::CallbackType cb;
cb = boost::bind(&Bar::configCallback, this, _1, _2);
//dr_srv_.setCallback(cb);
}

void Bar::configCallback(BarConfig &config, uint32_t /*level*/)
{
if (params_ptr_ != nullptr)
{
params_ptr_->fromConfig(config);

int rate = 2;

boost::shared_ptr<BarParameters> bar_param_ptr =
boost::dynamic_pointer_cast<BarParameters>(params_ptr_);

if (bar_param_ptr != nullptr)
{
rate = bar_param_ptr->rate;
}
else
{
ROS_WARN("Could not cast param_ptr_ to type BarParameters !"
"\nUsing default rate (%i Hz)", rate);
}

timer_.setPeriod(ros::Rate(rate).expectedCycleTime());

ROS_WARN_STREAM("Parameter update:\n" << *params_ptr_);
}
else
{
ROS_WARN("Dynamic reconfigure callback executed "
"before parameters initialization !");
}
}

} // namespace rosparam_handler_tutorial
73 changes: 73 additions & 0 deletions src/demo/demo_ptr.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
#ifndef _ROSPARAM_HANDLER_TUTORIAL_DEMO_BASE_H_
#define _ROSPARAM_HANDLER_TUTORIAL_DEMO_BASE_H_

#include <dynamic_reconfigure/server.h>
#include <ros/ros.h>

#include "rosparam_handler_tutorial/FooParameters.h"
#include "rosparam_handler_tutorial/BarParameters.h"

namespace rosparam_handler_tutorial {

struct DemoBase
{
DemoBase() = default;
virtual ~DemoBase() = default;

/// \brief A helper function to instantiate the
/// params_ptr_ properly
template <typename T>
void init(ros::NodeHandle& private_node_handle);

/// \brief A herlper function to call
/// params_ptr_->fromParamServer
void fromParamServer();

/// \brief A herlper function to call
/// params_ptr_->toParamServer
void toParamServer();

/// \brief A function to periodically print the params_ptr_
void timerCallback(const ros::TimerEvent&) const;

/// \brief A base pointer to the xParameters object
rosparam_handler::ParametersPtr params_ptr_;

ros::NodeHandle private_node_handle_;

ros::Timer timer_;
};

template <typename T>
inline void DemoBase::init(ros::NodeHandle& private_node_handle)
{
params_ptr_ = boost::make_shared<T>(private_node_handle);
}

struct Foo : public DemoBase
{
using DemoBase::timerCallback;

Foo(ros::NodeHandle private_node_handle);

/// \brief The dynamic reconfigure callback
void configCallback(FooConfig &config, uint32_t /*level*/);

/// \brief The dynamic reconfigure server
dynamic_reconfigure::Server<FooConfig> dr_srv_;
};

struct Bar : public DemoBase
{
Bar(ros::NodeHandle private_node_handle);

/// \brief The dynamic reconfigure callback
void configCallback(BarConfig &config, uint32_t /*level*/);

/// \brief The dynamic reconfigure server
dynamic_reconfigure::Server<BarConfig> dr_srv_;
};

} // namespace rosparam_handler_tutorial

#endif /* _ROSPARAM_HANDLER_TUTORIAL_DEMO_BASE_H_ */
20 changes: 20 additions & 0 deletions src/demo/demo_ptr_node.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
#include "demo_ptr.hpp"

int main(int argc, char* argv[]) {

ros::init(argc, argv, "demo_ptr_node");

// We give custom private sub-namespaces so
// that rosparam_handler objects
// do not collide.
// More specifically the dynamic
// reconfigure configCallback
ros::NodeHandle foo_nh("~/foo");
ros::NodeHandle bar_nh("~/bar");

rosparam_handler_tutorial::Foo demo_foo(foo_nh);
rosparam_handler_tutorial::Bar demo_bar(bar_nh);

ros::spin();
return 0;
}