Skip to content

Commit

Permalink
Adding singleton pattern to notification manager (ROSI-AP/rosi-ap_com…
Browse files Browse the repository at this point in the history
…mercial/cag/rmf_scheduler!28)

* Fix inaccurate connection status

Signed-off-by: Chen Bainian <[email protected]>

* Add factory pattern to notification manager

Signed-off-by: Chen Bainian <[email protected]>
Co-authored-by: Chen Bainian <[email protected]>

* Adding singleton pattern to notification manager

Co-authored-by: Chen Bainian <[email protected]>
  • Loading branch information
Santosh Balaji and Briancbn committed Oct 19, 2023
1 parent e4563de commit 38d2fa2
Show file tree
Hide file tree
Showing 10 changed files with 667 additions and 346 deletions.
2 changes: 2 additions & 0 deletions rmf_notification/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,8 @@ include_directories(
add_library(${PROJECT_NAME}
SHARED
src/notification_manager.cpp
src/http_client.cpp
src/websocket_client.cpp
src/message.cpp
)

Expand Down
22 changes: 15 additions & 7 deletions rmf_notification/example/notification_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@

#include "rmf_notification/message.hpp"
#include "rmf_notification/notification_manager.hpp"
#include "rmf_notification/websocket_client.hpp"
#include "rmf_notification/http_client.hpp"

const rclcpp::Logger LOGGER = rclcpp::get_logger("test_notification");

Expand All @@ -32,29 +34,35 @@ class TestNotification : public rclcpp::Node
std::bind(&TestNotification::timer_callback, this));
std::string websocket_uri = "ws://localhost:8000/_internal";
std::string mobile_uri = "http://localhost:8000/notification/telegram";
notification_manager_ptr_ = new rmf_notification::NotificationManager(
websocket_uri,
mobile_uri
);
notify_ptr_ = rmf_notification::NotificationManager::get();
notify_ptr_->create_client<rmf_notification::WebsocketClient>(websocket_uri);
notify_ptr_->create_client<rmf_notification::HTTPClient>(mobile_uri);
RCLCPP_INFO(LOGGER, "Starting test notification node");
}

~TestNotification()
{
timer_->cancel();
delete notification_manager_ptr_;
}

private:
void timer_callback()
{
auto connections = notify_ptr_->get_connections();
RCLCPP_INFO(LOGGER, "Connections:");
for (auto & connection : connections) {
RCLCPP_INFO(
LOGGER, "- endpoint_uri: %s, connected: %s",
connection.first.c_str(),
(connection.second ? "true" : "false"));
}
counter_ = counter_ + 1;
std::string message = "test message: " + std::to_string(counter_);
notification_manager_ptr_->publish_state(message, "maintenance_log_update");
notify_ptr_->publish(message, "maintenance_log_update");
}

rclcpp::TimerBase::SharedPtr timer_;
rmf_notification::NotificationManager * notification_manager_ptr_;
std::shared_ptr<rmf_notification::NotificationManager> notify_ptr_;
int counter_;
};

Expand Down
48 changes: 48 additions & 0 deletions rmf_notification/include/rmf_notification/http_client.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
// Copyright 2023 ROS Industrial Consortium Asia Pacific
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef RMF_NOTIFICATION__HTTP_CLIENT_HPP_
#define RMF_NOTIFICATION__HTTP_CLIENT_HPP_

#include <memory>
#include <string>

#include "rmf_notification/notification_client_base.hpp"

namespace rmf_notification
{

class HTTPClient : public NotificationClientBase
{
public:
HTTPClient();
virtual ~HTTPClient();
void init(const std::string & endpoint_uri) override;

bool is_connected() const override;

void publish(
const Message & message) override;

void shutdown() override;

class Impl;

private:
std::unique_ptr<Impl> impl_ptr_;
};

} // namespace rmf_notification

#endif // RMF_NOTIFICATION__HTTP_CLIENT_HPP_
4 changes: 1 addition & 3 deletions rmf_notification/include/rmf_notification/message.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,7 @@
namespace rmf_notification
{

enum ConnectionState { CONNECTED, DISCONNECTED };
enum NotificationType { WEBSOCKET, REST };

/// Message wrapper for notifications
struct Message
{
explicit Message(
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
// Copyright 2023 ROS Industrial Consortium Asia Pacific
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef RMF_NOTIFICATION__NOTIFICATION_CLIENT_BASE_HPP_
#define RMF_NOTIFICATION__NOTIFICATION_CLIENT_BASE_HPP_

#include <string>
#include "rmf_notification/message.hpp"

namespace rmf_notification
{

class NotificationClientBase
{
public:
virtual ~NotificationClientBase() {}
virtual void init(
const std::string & endpoint_uri) = 0;

virtual bool is_connected() const = 0;

virtual void publish(
const Message & message) = 0;

virtual void shutdown() = 0;
};
} // namespace rmf_notification

#endif // RMF_NOTIFICATION__NOTIFICATION_CLIENT_BASE_HPP_
93 changes: 78 additions & 15 deletions rmf_notification/include/rmf_notification/notification_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,37 +19,100 @@
#include <utility>
#include <vector>
#include <memory>
#include <mutex>
#include <string>

#include "rmf_notification/message.hpp"
#include "rmf_notification/notification_client_base.hpp"

namespace rmf_notification
{

class NotificationManager
{
public:
NotificationManager(
std::string websocket_uri,
std::string mobile_uri);
std::string publish_state(
/// Method to get singleton instance of notification manager
/**
* This method is threadsafe. It has mutex lock which allows only one
* thread to access this method at the same time frame
*
* \return[out] Shared pointer instance of notification manager
*/
static std::shared_ptr<NotificationManager> get();

/// Method to publish notifications via both websocket and telegram
/**
* This method is asynchronous type as the message to be sent is stored in a
* local cache and sent over by separate threads
*
* \param[in] payload message to be sent via notification system
* \param[in] type categories for different notifications
* \return[out] Id assigned to the messages to be sent
*/
std::string publish(
const std::string payload,
const std::string type);
std::vector<std::pair<NotificationType, ConnectionState>> check_connection_state();
void clear_messages();
~NotificationManager();

/// Method to check connection status with both websocket and telegram modules
/**
* For websocket live connection tracking is performed which means the connection status
* changes to disconnected on immediate disconnection. For telegram connection status
* is updated only when a new request is triggered
*
* \return[out] Vector specifying the endpoint uri and it status
*/
std::unordered_map<std::string, bool> get_connections() const;

/// Method to create a client to a specified uri
/**
* This method is NOT thread safe
*/
template<typename ClientBaseT, typename ... ArgsT>
std::shared_ptr<ClientBaseT> create_client(
const std::string & uri,
ArgsT &&... args);

virtual ~NotificationManager();

private:
class WebsocketImplementation;
class MobileImplementation;

std::string websocket_uri_;
std::string mobile_uri_;
std::unique_ptr<WebsocketImplementation> websocket_pimpl_;
std::unique_ptr<MobileImplementation> mobile_pimpl_;
std::unordered_map<std::string, Message> message_map_;
// unique pointer to store instance for mobile notification manager
std::unordered_map<std::string, std::shared_ptr<NotificationClientBase>> clients_;

// shared pointer to store singleton instance for notification manager
static std::shared_ptr<NotificationManager> instance_;
// mutex lock which is used when acquiring instance of notification manager object
static std::mutex m_instance_;

/// Constructor
NotificationManager();
// Not copiable
NotificationManager(const NotificationManager &) = delete;
NotificationManager & operator=(const NotificationManager &) = delete;
};

template<typename ClientBaseT, typename ... ArgsT>
std::shared_ptr<ClientBaseT> NotificationManager::create_client(
const std::string & uri,
ArgsT &&... args)
{
static_assert(
std::is_base_of_v<NotificationClientBase, ClientBaseT>,
"Notification Client must be derived from NotificationClientBase"
);

// use a local variable to mimic the constructor
auto ptr = std::make_shared<ClientBaseT>(std::forward<ArgsT>(args)...);

// Initialize the client
ptr->init(uri);

clients_.emplace(
uri,
std::static_pointer_cast<ClientBaseT>(ptr));

return ptr;
}

} // namespace rmf_notification

#endif // RMF_NOTIFICATION__NOTIFICATION_MANAGER_HPP_
48 changes: 48 additions & 0 deletions rmf_notification/include/rmf_notification/websocket_client.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
// Copyright 2023 ROS Industrial Consortium Asia Pacific
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef RMF_NOTIFICATION__WEBSOCKET_CLIENT_HPP_
#define RMF_NOTIFICATION__WEBSOCKET_CLIENT_HPP_

#include <memory>
#include <string>

#include "rmf_notification/notification_client_base.hpp"

namespace rmf_notification
{

class WebsocketClient : public NotificationClientBase
{
public:
WebsocketClient();
virtual ~WebsocketClient();
void init(const std::string & endpoint_uri) override;

bool is_connected() const override;

void publish(
const Message & message) override;

void shutdown() override;

class Impl;

private:
std::unique_ptr<Impl> impl_ptr_;
};

} // namespace rmf_notification

#endif // RMF_NOTIFICATION__WEBSOCKET_CLIENT_HPP_
Loading

0 comments on commit 38d2fa2

Please sign in to comment.