Skip to content

Commit

Permalink
Another name change; using Handler instead of the more passive term, …
Browse files Browse the repository at this point in the history
…Monitor

Signed-off-by: Michael Jeronimo <michael.jeronimo@openrobotics.org>
  • Loading branch information
Michael Jeronimo committed Jan 8, 2021
1 parent 60533db commit 894da98
Show file tree
Hide file tree
Showing 6 changed files with 73 additions and 73 deletions.
2 changes: 1 addition & 1 deletion rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ 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_event_handler.cpp
src/rclcpp/parameter_events_filter.cpp
src/rclcpp/parameter_map.cpp
src/rclcpp/parameter_service.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef RCLCPP__PARAMETER_EVENT_MONITOR_HPP_
#define RCLCPP__PARAMETER_EVENT_MONITOR_HPP_
#ifndef RCLCPP__PARAMETER_EVENT_HANDLER_HPP_
#define RCLCPP__PARAMETER_EVENT_HANDLER_HPP_

#include <list>
#include <memory>
Expand Down Expand Up @@ -58,7 +58,7 @@ struct ParameterEventCallbackHandle
ParameterEventCallbackType callback;
};

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

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

using ParameterEventCallbackType =
Expand Down Expand Up @@ -238,4 +238,4 @@ class ParameterEventMonitor

} // namespace rclcpp

#endif // RCLCPP__PARAMETER_EVENT_MONITOR_HPP_
#endif // RCLCPP__PARAMETER_EVENT_HANDLER_HPP_
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/rclcpp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@
#include "rclcpp/logging.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp/parameter_client.hpp"
#include "rclcpp/parameter_event_monitor.hpp"
#include "rclcpp/parameter_event_handler.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/parameter_service.hpp"
#include "rclcpp/rate.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,14 +19,14 @@
#include <utility>
#include <vector>

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

namespace rclcpp
{

ParameterEventCallbackHandle::SharedPtr
ParameterEventMonitor::add_parameter_event_callback(
ParameterEventHandler::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
ParameterEventMonitor::remove_parameter_event_callback(
ParameterEventHandler::remove_parameter_event_callback(
const ParameterEventCallbackHandle * const handle)
{
std::lock_guard<std::recursive_mutex> lock(mutex_);
Expand All @@ -71,7 +71,7 @@ ParameterEventMonitor::remove_parameter_event_callback(
}

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

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

bool
ParameterEventMonitor::get_parameter_from_event(
ParameterEventHandler::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 @@ ParameterEventMonitor::get_parameter_from_event(
}

rclcpp::Parameter
ParameterEventMonitor::get_parameter_from_event(
ParameterEventHandler::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 @@ ParameterEventMonitor::get_parameter_from_event(
}

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

void
ParameterEventMonitor::event_callback(
ParameterEventHandler::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 @@ ParameterEventMonitor::event_callback(
}

std::string
ParameterEventMonitor::resolve_path(const std::string & path)
ParameterEventHandler::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_event_monitor test_parameter_event_monitor.cpp)
if(TARGET test_parameter_event_monitor)
ament_target_dependencies(test_parameter_event_monitor
ament_add_gtest(test_parameter_event_handler test_parameter_event_handler.cpp)
if(TARGET test_parameter_event_handler)
ament_target_dependencies(test_parameter_event_handler
"rcl_interfaces"
"rmw"
"rosidl_generator_cpp"
"rosidl_typesupport_cpp"
)
target_link_libraries(test_parameter_event_monitor ${PROJECT_NAME})
target_link_libraries(test_parameter_event_handler ${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 894da98

Please sign in to comment.