Skip to content

Commit

Permalink
- Fixed errors with HTTP requests not triggering,
Browse files Browse the repository at this point in the history
- Fixed response callback not triggering correctly and causing a crash
- Fixed example not transitioning back to state 1 after a response has been received
  • Loading branch information
yassiezar committed Sep 4, 2023
1 parent d49f71a commit fec79eb
Show file tree
Hide file tree
Showing 4 changed files with 35 additions and 28 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -25,13 +25,11 @@
#include <boost/beast/core.hpp>
#include <boost/beast/http.hpp>
#include <boost/beast/version.hpp>

#include <smacc2/smacc_client.hpp>
#include <smacc2/smacc.hpp>

#include <iostream>
#include <memory>
#include <optional>
#include <smacc2/smacc.hpp>
#include <smacc2/smacc_client.hpp>
#include <string>
#include <thread>
#include <unordered_map>
Expand All @@ -41,12 +39,12 @@ class ClHttp : public smacc2::ISmaccClient {
class http_session : public std::enable_shared_from_this<http_session> {
public:
using TResponse =
const boost::beast::http::response<boost::beast::http::string_body> &;
boost::beast::http::response<boost::beast::http::string_body>;

// Objects are constructed with a strand to
// ensure that handlers do not execute concurrently.
http_session(boost::asio::io_context &ioc,
const std::function<void(TResponse)> response);
const std::function<void(const TResponse &)> response);

// Start the asynchronous operation
void run(const std::string &host, const std::string &target,
Expand All @@ -64,9 +62,7 @@ class ClHttp : public smacc2::ISmaccClient {
void on_write(boost::beast::error_code ec, std::size_t bytes_transferred);
void on_read(boost::beast::error_code ec, std::size_t bytes_transferred);

std::function<void(const boost::beast::http::response<
boost::beast::http::string_body> &response)>
onResponse;
std::function<void(const TResponse &)> onResponse;

boost::asio::ip::tcp::resolver resolver_;
boost::beast::tcp_stream stream_;
Expand All @@ -79,11 +75,14 @@ class ClHttp : public smacc2::ISmaccClient {
enum class kHttpRequestMethod {
GET = static_cast<int>(boost::beast::http::verb::get),
POST = static_cast<int>(boost::beast::http::verb::post),
PUT = static_cast<int>(boost::beast::http::verb::put),
};

using TResponse = http_session::TResponse;

template <typename T>
boost::signals2::connection onResponseReceived(
void (T::*callback)(const std::string &), T *object) {
void (T::*callback)(const TResponse&), T *object) {
return this->getStateMachine()->createSignalConnection(onResponseReceived_,
callback, object);
}
Expand All @@ -92,7 +91,8 @@ class ClHttp : public smacc2::ISmaccClient {

virtual ~ClHttp();

void configure();
void onInitialize() override;

void makeRequest(const kHttpRequestMethod http_method,
const std::string &path = "/");

Expand All @@ -109,8 +109,10 @@ class ClHttp : public smacc2::ISmaccClient {
worker_guard_;
std::thread tcp_connection_runner_;

std::function<void(http_session::TResponse)> callbackHandler;
smacc2::SmaccSignal<void(const TResponse &)> onResponseReceived_;

smacc2::SmaccSignal<void(const std::string &)> onResponseReceived_;
std::function<void(TResponse)> callbackHandler = [&](const TResponse& res) {
onResponseReceived_(res);
};
};
} // namespace cl_http
22 changes: 12 additions & 10 deletions smacc2_client_library/http_client/src/http_client/http_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,30 +18,29 @@
*
******************************************************************************************************************/


#include <http_client/http_client.hpp>

namespace cl_http {

///////////////////////////
// ClHttp implementation //
// ////////////////////////
///////////////////////////

ClHttp::ClHttp(const std::string &server, const int &timeout)
: initialized_{false},
timeout_{timeout},
server_name_{server},
worker_guard_{boost::asio::make_work_guard(io_context_)} {
worker_guard_{boost::asio::make_work_guard(io_context_.get_executor())} {
// User explicitly using http
is_ssl_ = server.substr(0, 5).compare("https") ? true : false;
is_ssl_ = server.substr(0, 8).compare("https://") ? false : true;
}

ClHttp::~ClHttp() {
worker_guard_.reset();
tcp_connection_runner_.join();
}

void ClHttp::configure() {
void ClHttp::onInitialize() {
if (!initialized_) {
tcp_connection_runner_ = std::thread{[&]() { io_context_.run(); }};
this->initialized_ = true;
Expand All @@ -50,6 +49,7 @@ void ClHttp::configure() {

void ClHttp::makeRequest(const kHttpRequestMethod http_method,
const std::string &path) {
RCLCPP_INFO(this->getLogger(), "SSL? %d", is_ssl_);
std::make_shared<http_session>(io_context_, callbackHandler)
->run(server_name_, path, is_ssl_ ? "443" : "80",
static_cast<boost::beast::http::verb>(http_method), HTTP_VERSION);
Expand All @@ -60,10 +60,11 @@ void ClHttp::makeRequest(const kHttpRequestMethod http_method,
/////////////////////////////////

ClHttp::http_session::http_session(
boost::asio::io_context &ioc, const std::function<void(TResponse)> response)
boost::asio::io_context &ioc,
const std::function<void(const TResponse &)> response)
: onResponse{response},
resolver_(boost::asio::make_strand(ioc)),
stream_(boost::asio::make_strand(ioc)) {}
resolver_{boost::asio::make_strand(ioc)},
stream_{boost::asio::make_strand(ioc)} {}

void ClHttp::http_session::run(const std::string &host,
const std::string &target,
Expand All @@ -89,14 +90,15 @@ void ClHttp::http_session::on_resolve(
if (ec) return fail(ec, "resolve");

// Set a timeout on the operation
stream_.expires_after(std::chrono::seconds(30));
stream_.expires_after(std::chrono::seconds(1));

// Make the connection on the IP address we get from a lookup
stream_.async_connect(
results, boost::beast::bind_front_handler(&http_session::on_connect,
shared_from_this()));
}
void ClHttp::http_session::fail(boost::beast::error_code ec, char const *what) {
std::cout << "Failure!..." << std::endl;
std::cerr << what << ": " << ec.message() << "\n";
res_.result(boost::beast::http::status::bad_request);
res_.reason() = ec.message();
Expand All @@ -109,7 +111,7 @@ void ClHttp::http_session::on_connect(
if (ec) return fail(ec, "connect");

// Set a timeout on the operation
stream_.expires_after(std::chrono::seconds(30));
stream_.expires_after(std::chrono::seconds(1));

// Send the HTTP request to the remote host
boost::beast::http::async_write(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,16 +45,20 @@ class CbHttpRequest : public smacc2::SmaccClientBehavior {
cl_http_->onResponseReceived(&CbHttpRequest::onResponseReceived, this);
}

void onResponseReceived(const std::string& response) { triggerTranstition(); }
void onResponseReceived(const cl_http::ClHttp::TResponse& response) {
RCLCPP_INFO_STREAM(this->getLogger(), "ON RESPONSE");
// RCLCPP_INFO_STREAM(this->getLogger(), response);
triggerTranstition();
}

void onEntry() override {
RCLCPP_INFO(getLogger(), "On Entry!");
RCLCPP_INFO(this->getLogger(), "On Entry!");

cl_http_->makeRequest(
cl_http::ClHttp::kHttpRequestMethod::GET);
}

void onExit() override { RCLCPP_INFO(getLogger(), "Cb on exit!"); }
void onExit() override { RCLCPP_INFO(this->getLogger(), "Cb on exit!"); }

private:
cl_http::ClHttp* cl_http_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,12 +21,11 @@ struct State2 : smacc2::SmaccState<State2, SmAtomicHttp> {

// TRANSITION TABLE
typedef mpl::list<
Transition<EvTimer<CbHttpRequest, OrHttp>, State1, SUCCESS> >
Transition<EvHttp<CbHttpRequest, OrHttp>, State1, SUCCESS> >
reactions;

// STATE FUNCTIONS
static void staticConfigure() {
// EvTimer triggers once at 10 client ticks
configure_orthogonal<OrHttp, CbHttpRequest>();
}

Expand Down

0 comments on commit fec79eb

Please sign in to comment.