Skip to content

Commit

Permalink
Reconfigure client cpp (#78)
Browse files Browse the repository at this point in the history
* Added C++ Client class

* typo

* use configuration server rather than ActionServer

* clearer Debug message

* add check for values in getConfigs

* trying longer timeouts, it may help getting correct configs

* trailing whitespace
  • Loading branch information
mikaelarguedas committed Mar 14, 2017
1 parent 492f94a commit 37b8777
Show file tree
Hide file tree
Showing 5 changed files with 478 additions and 3 deletions.
6 changes: 3 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,15 @@ cmake_minimum_required(VERSION 2.8)
project(dynamic_reconfigure)

find_package(catkin REQUIRED COMPONENTS message_generation roscpp std_msgs)
find_package(Boost REQUIRED COMPONENTS system thread)
find_package(Boost REQUIRED COMPONENTS system thread chrono)

include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})

catkin_python_setup()

add_message_files(
DIRECTORY msg
FILES
FILES
BoolParameter.msg Config.msg Group.msg IntParameter.msg SensorLevels.msg
ConfigDescription.msg DoubleParameter.msg GroupState.msg ParamDescription.msg StrParameter.msg)

Expand Down Expand Up @@ -41,7 +41,7 @@ target_link_libraries(dynamic_reconfigure_config_init_mutex ${Boost_LIBRARIES})
install(DIRECTORY include/dynamic_reconfigure/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
FILES_MATCHING PATTERN "*.h")

install(TARGETS dynamic_reconfigure_config_init_mutex
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
Expand Down
342 changes: 342 additions & 0 deletions include/dynamic_reconfigure/client.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,342 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2015-2016, Myrmex, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Myrmex, Inc nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

/**
Author: Aris Synodinos
Handles sychronizing node state with the configuration server and setting/getting
configuration.
*/

#ifndef __CLIENT_H__
#define __CLIENT_H__

#include <boost/chrono.hpp>
#include <boost/function.hpp>
#include <boost/thread.hpp>
#include <ros/node_handle.h>
#include <dynamic_reconfigure/ConfigDescription.h>
#include <dynamic_reconfigure/Reconfigure.h>

namespace dynamic_reconfigure {

template <class ConfigType>
class Client {
public:
/**
* @brief Client Constructs a statefull dynamic_reconfigure client
* @param name The full path of the dynamic_reconfigure::Server
* @param config_callback A callback that should be called when the server
* informs the clients of a successful reconfiguration
* @param description_callback A callback that should be called when the
* server infrorms the clients of the description of the reconfiguration
* parameters and groups
*/
Client(
const std::string& name,
const boost::function<void(const ConfigType&)> config_callback = 0,
const boost::function<void(const dynamic_reconfigure::ConfigDescription&)>
description_callback = 0)
: name_(name),
nh_(name),
received_configuration_(false),
received_description_(false),
config_callback_(config_callback),
description_callback_(description_callback) {
set_service_ =
nh_.serviceClient<dynamic_reconfigure::Reconfigure>("set_parameters");

config_sub_ =
nh_.subscribe("parameter_updates", 1,
&Client<ConfigType>::configurationCallback, this);

descr_sub_ = nh_.subscribe("parameter_descriptions", 1,
&Client<ConfigType>::descriptionCallback, this);
}
/**
* @brief Client Constructs a statefull dynamic_reconfigure client
* @param name The full path of the dynamic_reconfigure::Server
* @param nh The nodehandle to the full path of the Server (for nodelets)
* @param config_callback A callback that should be called when the server
* informs the clients of a successful reconfiguration
* @param description_callback A callback that should be called when the
* server infrorms the clients of the description of the reconfiguration
* parameters and groups
*/
Client(
const std::string& name, const ros::NodeHandle& nh,
const boost::function<void(const ConfigType&)> config_callback = 0,
const boost::function<void(const dynamic_reconfigure::ConfigDescription&)>
description_callback = 0)
: name_(name),
nh_(nh),
received_configuration_(false),
received_description_(false),
config_callback_(config_callback),
description_callback_(description_callback) {
set_service_ =
nh_.serviceClient<dynamic_reconfigure::Reconfigure>("set_parameters");

config_sub_ =
nh_.subscribe("parameter_updates", 1,
&Client<ConfigType>::configurationCallback, this);

descr_sub_ = nh_.subscribe("parameter_descriptions", 1,
&Client<ConfigType>::descriptionCallback, this);
}
/**
* @brief setConfigurationCallback Sets the user defined configuration
* callback function
* @param config_callback A function pointer
*/
void setConfigurationCallback(
const boost::function<void(const ConfigType&)>& config_callback) {
config_callback_ = config_callback;
}
/**
* @brief setDescriptionCallback Sets the user defined description callback
* function
* @param description_callback A function pointer
*/
void setDescriptionCallback(const boost::function<void(
const dynamic_reconfigure::ConfigDescription&)>& description_callback) {
description_callback_ = description_callback;
}
/**
* @brief setConfiguration Attempts to set the configuration to the server
* @param configuration The requested configuration
* @return True if the server accepted the request (not the reconfiguration)
*/
bool setConfiguration(const ConfigType& configuration) {
ConfigType temp = configuration;
return setConfiguration(temp);
}
/**
* @brief setConfiguration Attempts to set the configuration to the server
* @param configuration The requested configuration, gets overwritten with the
* reply from the reconfigure server
* @return True if the server accepted the request (not the reconfiguration)
*/
bool setConfiguration(ConfigType& configuration) {
dynamic_reconfigure::Reconfigure srv;
configuration.__toMessage__(srv.request.config);
if (set_service_.call(srv)) {
configuration.__fromMessage__(srv.response.config);
return true;
} else {
ROS_WARN("Could not set configuration");
return false;
}
}
/**
* @brief getCurrentConfiguration Gets the latest configuration from the
* dynamic_reconfigure::Server
* @param configuration The object where the configuration will be stored
* @param timeout The duration that the client should wait for the
* configuration, if set to ros::Duration(0) will wait indefinetely
* @return False if the timeout has happened
*/
bool getCurrentConfiguration(
ConfigType& configuration,
const ros::Duration& timeout = ros::Duration(0)) {
if (timeout == ros::Duration(0)) {
ROS_INFO_ONCE("Waiting for configuration...");
boost::mutex::scoped_lock lock(mutex_);
while (!received_configuration_) {
if (!ros::ok()) return false;
cv_.wait(lock);
}
} else {
ros::Time start_time = ros::Time::now();
boost::mutex::scoped_lock lock(mutex_);
while (!received_configuration_) {
if (!ros::ok()) return false;
ros::Duration time_left = timeout - (ros::Time::now() - start_time);
if (time_left.toSec() <= 0.0) return false;
cv_.wait_for(lock, boost::chrono::nanoseconds(time_left.toNSec()));
}
}
configuration = latest_configuration_;
return true;
}
/**
* @brief getDefaultConfiguration Gets the latest default configuration from
* the dynamic_reconfigure::Server
* @param configuration The object where the configuration will be stored
* @param timeout The duration that the client should wait for the
* configuration, if set to ros::Duration(0) will wait indefinetely
* @return False if the timeout has happened
*/
bool getDefaultConfiguration(
ConfigType& configuration,
const ros::Duration& timeout = ros::Duration(0)) {
ConfigDescription answer;
if (getDescription(answer, timeout)) {
configuration.__fromMessage__(answer.dflt);
return true;
} else {
return false;
}
}
/**
* @brief getMinConfiguration Gets the latest minimum configuration from
* the dynamic_reconfigure::Server
* @param configuration The object where the configuration will be stored
* @param timeout The duration that the client should wait for the
* configuration, if set to ros::Duration(0) will wait indefinetely
* @return False if the timeout has happened
*/
bool getMinConfiguration(ConfigType& configuration,
const ros::Duration& timeout = ros::Duration(0)) {
ConfigDescription answer;
if (getDescription(answer, timeout)) {
configuration.__fromMessage__(answer.min);
return true;
} else {
return false;
}
}
/**
* @brief getMaxConfiguration Gets the latest maximum configuration from
* the dynamic_reconfigure::Server
* @param configuration The object where the configuration will be stored
* @param timeout The duration that the client should wait for the
* configuration, if set to ros::Duration(0) will wait indefinetely
* @return False if the timeout has happened
*/
bool getMaxConfiguration(ConfigType& configuration,
const ros::Duration& timeout = ros::Duration(0)) {
ConfigDescription answer;
if (getDescription(answer, timeout)) {
configuration.__fromMessage__(answer.max);
return true;
} else {
return false;
}
}
/**
* @brief getName Gets the name of the Dynamic Reconfigure Client
* @return Copy of the member variable
*/
std::string getName() const { return name_; }

private:
void configurationCallback(const dynamic_reconfigure::Config& configuration) {
boost::mutex::scoped_lock lock(mutex_);
dynamic_reconfigure::Config temp_config = configuration;
received_configuration_ = true;
latest_configuration_.__fromMessage__(temp_config);
cv_.notify_all();

if (config_callback_) {
try {
config_callback_(latest_configuration_);
} catch (std::exception& e) {
ROS_WARN("Configuration callback failed with exception %s", e.what());
} catch (...) {
ROS_WARN("Configuration callback failed with unprintable exception");
}
} else {
ROS_DEBUG(
"Unable to call Configuration callback because none was set.\n" \
"See setConfigurationCallback");
}
}

void descriptionCallback(
const dynamic_reconfigure::ConfigDescription& description) {
boost::mutex::scoped_lock lock(mutex_);
received_description_ = true;
latest_description_ = description;
cv_.notify_all();

if (description_callback_) {
try {
description_callback_(description);
} catch (std::exception& e) {
ROS_WARN("Description callback failed with exception %s", e.what());
} catch (...) {
ROS_WARN("Description callback failed with unprintable exception");
}
} else {
ROS_DEBUG(
"Unable to call Description callback because none was set.\n" \
"See setDescriptionCallback");
}
}

bool getDescription(ConfigDescription& configuration,
const ros::Duration& timeout) {
if (timeout == ros::Duration(0)) {
ROS_INFO_ONCE("Waiting for configuration...");
boost::mutex::scoped_lock lock(mutex_);
while (!received_description_) {
if (!ros::ok()) return false;
cv_.wait(lock);
}
} else {
ros::Time start_time = ros::Time::now();
boost::mutex::scoped_lock lock(mutex_);
while (!received_description_) {
if (!ros::ok()) return false;
ros::Duration time_left = timeout - (ros::Time::now() - start_time);
if (time_left.toSec() <= 0.0) return false;
cv_.wait_for(lock, boost::chrono::nanoseconds(time_left.toNSec()));
}
}
configuration = latest_description_;
return true;
}

std::string name_;
bool received_configuration_;
ConfigType latest_configuration_;
bool received_description_;
dynamic_reconfigure::ConfigDescription latest_description_;
boost::condition_variable cv_;
boost::mutex mutex_;
ros::NodeHandle nh_;
ros::ServiceClient set_service_;
ros::Subscriber descr_sub_;
ros::Subscriber config_sub_;

boost::function<void(const ConfigType&)> config_callback_;
boost::function<void(const dynamic_reconfigure::ConfigDescription&)>
description_callback_;
};
}

#endif // __CLIENT_H__
6 changes: 6 additions & 0 deletions test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,4 +4,10 @@ target_link_libraries(dynamic_reconfigure-ref_server pthread dynamic_reconfigure

add_dependencies(tests dynamic_reconfigure-ref_server)

add_rostest_gtest(dynamic_reconfigure-test_client test_cpp_simple_client.launch test_client.cpp)
add_dependencies(dynamic_reconfigure-test_client ${PROJECT_NAME}_gencfg ${PROJECT_NAME}_generate_messages_py)
target_link_libraries(dynamic_reconfigure-test_client pthread dynamic_reconfigure_config_init_mutex ${catkin_LIBRARIES})

add_dependencies(tests dynamic_reconfigure-test_client)

add_rostest(test_python_simple_client.launch)
Loading

0 comments on commit 37b8777

Please sign in to comment.