Skip to content

Commit

Permalink
Merge pull request #1 from mjeronimo/mjeronimo/address-review-feedback
Browse files Browse the repository at this point in the history
Address code review feedback
  • Loading branch information
bpwilcox authored Jan 8, 2021
2 parents 8fb32de + 60533db commit ab4ff32
Show file tree
Hide file tree
Showing 6 changed files with 101 additions and 96 deletions.
2 changes: 1 addition & 1 deletion rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -79,8 +79,8 @@ set(${PROJECT_NAME}_SRCS
src/rclcpp/parameter.cpp
src/rclcpp/parameter_value.cpp
src/rclcpp/parameter_client.cpp
src/rclcpp/parameter_event_monitor.cpp
src/rclcpp/parameter_events_filter.cpp
src/rclcpp/parameter_events_subscriber.cpp
src/rclcpp/parameter_map.cpp
src/rclcpp/parameter_service.cpp
src/rclcpp/publisher_base.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,17 +12,16 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef RCLCPP__PARAMETER_EVENTS_SUBSCRIBER_HPP_
#define RCLCPP__PARAMETER_EVENTS_SUBSCRIBER_HPP_
#ifndef RCLCPP__PARAMETER_EVENT_MONITOR_HPP_
#define RCLCPP__PARAMETER_EVENT_MONITOR_HPP_

#include <list>
#include <memory>
#include <string>
#include <utility>
#include <unordered_map>
#include <utility>
#include <vector>

#include "rcl_interfaces/msg/parameter_event.hpp"
#include "rclcpp/create_subscription.hpp"
#include "rclcpp/node_interfaces/get_node_base_interface.hpp"
#include "rclcpp/node_interfaces/get_node_logging_interface.hpp"
Expand All @@ -33,6 +32,7 @@
#include "rclcpp/parameter.hpp"
#include "rclcpp/qos.hpp"
#include "rclcpp/subscription.hpp"
#include "rcl_interfaces/msg/parameter_event.hpp"

namespace rclcpp
{
Expand All @@ -58,12 +58,16 @@ struct ParameterEventCallbackHandle
ParameterEventCallbackType callback;
};

class ParameterEventsSubscriber
class ParameterEventMonitor
{
public:
/// Construct a subscriber to parameter events
/// Construct a parameter events monitor.
/**
* \param[in] node The node to use to create any required subscribers.
* \param[in] qos The QoS settings to use for any subscriptions.
*/
template<typename NodeT>
ParameterEventsSubscriber(
ParameterEventMonitor(
NodeT node,
const rclcpp::QoS & qos =
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)))
Expand All @@ -74,26 +78,27 @@ class ParameterEventsSubscriber

event_subscription_ = rclcpp::create_subscription<rcl_interfaces::msg::ParameterEvent>(
node_topics, "/parameter_events", qos,
std::bind(&ParameterEventsSubscriber::event_callback, this, std::placeholders::_1));
std::bind(&ParameterEventMonitor::event_callback, this, std::placeholders::_1));
}

using ParameterEventCallbackType =
ParameterEventCallbackHandle::ParameterEventCallbackType;

/// Set a custom callback for parameter events.
/// Set a callback for all parameter events.
/**
* Multiple callbacks are allowed.
* This function may be called multiple times to set multiple parameter event callbacks.
*
* \param[in] callback Function callback to be evaluated on event.
* \param[in] callback Function callback to be invoked on parameter updates.
* \returns A handle used to refer to the callback.
*/
RCLCPP_PUBLIC
ParameterEventCallbackHandle::SharedPtr
add_parameter_event_callback(
ParameterEventCallbackType callback);

/// Remove parameter event callback.
/// Remove parameter event callback registered with add_parameter_event_callback.
/**
* Calling this function will set the event callback to nullptr.
* \param[in] handle Pointer to the handle for the callback to remove.
*/
RCLCPP_PUBLIC
void
Expand All @@ -102,13 +107,14 @@ class ParameterEventsSubscriber

using ParameterCallbackType = ParameterCallbackHandle::ParameterCallbackType;

/// Add a custom callback for a specified parameter.
/// Add a callback for a specified parameter.
/**
* If a node_name is not provided, defaults to the current node.
*
* \param[in] parameter_name Name of parameter.
* \param[in] callback Function callback to be evaluated upon parameter event.
* \param[in] parameter_name Name of parameter to monitor.
* \param[in] callback Function callback to be invoked upon parameter update.
* \param[in] node_name Name of node which hosts the parameter.
* \returns A handle used to refer to the callback.
*/
RCLCPP_PUBLIC
ParameterCallbackHandle::SharedPtr
Expand All @@ -117,7 +123,7 @@ class ParameterEventsSubscriber
ParameterCallbackType callback,
const std::string & node_name = "");

/// Remove a custom callback for a specified parameter given its callback handle.
/// Remove a parameter callback registered with add_parameter_callback.
/**
* The parameter name and node name are inspected from the callback handle. The callback handle
* is erased from the list of callback handles on the {parameter_name, node_name} in the map.
Expand All @@ -130,15 +136,16 @@ class ParameterEventsSubscriber
remove_parameter_callback(
const ParameterCallbackHandle * const handle);

/// Get a rclcpp::Parameter from parameter event, return true if parameter name & node in event.
/// Get an rclcpp::Parameter from a parameter event.
/**
* If a node_name is not provided, defaults to the current node.
*
* \param[in] event Event msg to be inspected.
* \param[out] parameter Reference to rclcpp::Parameter to be assigned.
* \param[in] parameter_name Name of parameter.
* \param[in] node_name Name of node which hosts the parameter.
* \returns true if requested parameter name & node is in event, false otherwise
* \returns Output parameter is set with requested parameter info and returns true if
* requested parameter name and node is in event. Otherwise, returns false.
*/
RCLCPP_PUBLIC
static bool
Expand All @@ -148,7 +155,7 @@ class ParameterEventsSubscriber
const std::string parameter_name,
const std::string node_name = "");

/// Get a rclcpp::Parameter from parameter event
/// Get an rclcpp::Parameter from parameter event
/**
* If a node_name is not provided, defaults to the current node.
*
Expand All @@ -159,7 +166,7 @@ class ParameterEventsSubscriber
* \param[in] event Event msg to be inspected.
* \param[in] parameter_name Name of parameter.
* \param[in] node_name Name of node which hosts the parameter.
* \returns The resultant rclcpp::Parameter from the event
* \returns The resultant rclcpp::Parameter from the event.
*/
RCLCPP_PUBLIC
static rclcpp::Parameter
Expand All @@ -171,7 +178,7 @@ class ParameterEventsSubscriber
/// Get all rclcpp::Parameter values from a parameter event
/**
* \param[in] event Event msg to be inspected.
* \returns A vector rclcpp::Parameter values from the event
* \returns A vector rclcpp::Parameter values from the event.
*/
RCLCPP_PUBLIC
static std::vector<rclcpp::Parameter>
Expand Down Expand Up @@ -215,7 +222,7 @@ class ParameterEventsSubscriber
};
// *INDENT-ON*

// Map container for registered parameters.
// Map container for registered parameters
std::unordered_map<
std::pair<std::string, std::string>,
CallbacksContainerType,
Expand All @@ -231,4 +238,4 @@ class ParameterEventsSubscriber

} // namespace rclcpp

#endif // RCLCPP__PARAMETER_EVENTS_SUBSCRIBER_HPP_
#endif // RCLCPP__PARAMETER_EVENT_MONITOR_HPP_
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/rclcpp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,15 +147,15 @@
#include "rclcpp/guard_condition.hpp"
#include "rclcpp/logging.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/parameter_client.hpp"
#include "rclcpp/parameter_event_monitor.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/parameter_service.hpp"
#include "rclcpp/parameter_events_subscriber.hpp"
#include "rclcpp/rate.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp/utilities.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rclcpp/wait_set.hpp"
#include "rclcpp/waitable.hpp"
#include "rclcpp/wait_set.hpp"

#endif // RCLCPP__RCLCPP_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -19,14 +19,14 @@
#include <utility>
#include <vector>

#include "rclcpp/parameter_events_subscriber.hpp"
#include "rclcpp/parameter_event_monitor.hpp"
#include "rcpputils/join.hpp"

namespace rclcpp
{

ParameterEventCallbackHandle::SharedPtr
ParameterEventsSubscriber::add_parameter_event_callback(
ParameterEventMonitor::add_parameter_event_callback(
ParameterEventCallbackType callback)
{
std::lock_guard<std::recursive_mutex> lock(mutex_);
Expand Down Expand Up @@ -55,7 +55,7 @@ struct HandleCompare
};

void
ParameterEventsSubscriber::remove_parameter_event_callback(
ParameterEventMonitor::remove_parameter_event_callback(
const ParameterEventCallbackHandle * const handle)
{
std::lock_guard<std::recursive_mutex> lock(mutex_);
Expand All @@ -71,7 +71,7 @@ ParameterEventsSubscriber::remove_parameter_event_callback(
}

ParameterCallbackHandle::SharedPtr
ParameterEventsSubscriber::add_parameter_callback(
ParameterEventMonitor::add_parameter_callback(
const std::string & parameter_name,
ParameterCallbackType callback,
const std::string & node_name)
Expand All @@ -90,7 +90,7 @@ ParameterEventsSubscriber::add_parameter_callback(
}

void
ParameterEventsSubscriber::remove_parameter_callback(
ParameterEventMonitor::remove_parameter_callback(
const ParameterCallbackHandle * const handle)
{
std::lock_guard<std::recursive_mutex> lock(mutex_);
Expand All @@ -110,7 +110,7 @@ ParameterEventsSubscriber::remove_parameter_callback(
}

bool
ParameterEventsSubscriber::get_parameter_from_event(
ParameterEventMonitor::get_parameter_from_event(
const rcl_interfaces::msg::ParameterEvent & event,
rclcpp::Parameter & parameter,
const std::string parameter_name,
Expand Down Expand Up @@ -138,7 +138,7 @@ ParameterEventsSubscriber::get_parameter_from_event(
}

rclcpp::Parameter
ParameterEventsSubscriber::get_parameter_from_event(
ParameterEventMonitor::get_parameter_from_event(
const rcl_interfaces::msg::ParameterEvent & event,
const std::string parameter_name,
const std::string node_name)
Expand All @@ -153,7 +153,7 @@ ParameterEventsSubscriber::get_parameter_from_event(
}

std::vector<rclcpp::Parameter>
ParameterEventsSubscriber::get_parameters_from_event(
ParameterEventMonitor::get_parameters_from_event(
const rcl_interfaces::msg::ParameterEvent & event)
{
std::vector<rclcpp::Parameter> params;
Expand All @@ -170,7 +170,7 @@ ParameterEventsSubscriber::get_parameters_from_event(
}

void
ParameterEventsSubscriber::event_callback(
ParameterEventMonitor::event_callback(
const rcl_interfaces::msg::ParameterEvent::SharedPtr event)
{
std::lock_guard<std::recursive_mutex> lock(mutex_);
Expand Down Expand Up @@ -200,7 +200,7 @@ ParameterEventsSubscriber::event_callback(
}

std::string
ParameterEventsSubscriber::resolve_path(const std::string & path)
ParameterEventMonitor::resolve_path(const std::string & path)
{
std::string full_path;

Expand Down
8 changes: 4 additions & 4 deletions rclcpp/test/rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -323,15 +323,15 @@ if(TARGET test_parameter)
)
target_link_libraries(test_parameter ${PROJECT_NAME})
endif()
ament_add_gtest(test_parameter_events_subscriber test_parameter_events_subscriber.cpp)
if(TARGET test_parameter_events_subscriber)
ament_target_dependencies(test_parameter_events_subscriber
ament_add_gtest(test_parameter_event_monitor test_parameter_event_monitor.cpp)
if(TARGET test_parameter_event_monitor)
ament_target_dependencies(test_parameter_event_monitor
"rcl_interfaces"
"rmw"
"rosidl_generator_cpp"
"rosidl_typesupport_cpp"
)
target_link_libraries(test_parameter_events_subscriber ${PROJECT_NAME})
target_link_libraries(test_parameter_event_monitor ${PROJECT_NAME})
endif()
ament_add_gtest(test_parameter_map test_parameter_map.cpp)
if(TARGET test_parameter_map)
Expand Down
Loading

0 comments on commit ab4ff32

Please sign in to comment.