Skip to content

Commit

Permalink
allow connection retries
Browse files Browse the repository at this point in the history
Signed-off-by: Kenji Brameld <kenjibrameld@gmail.com>
  • Loading branch information
ijnek committed Nov 30, 2023
1 parent 4339238 commit b40e986
Showing 1 changed file with 9 additions and 4 deletions.
13 changes: 9 additions & 4 deletions nao_lola_client/src/connection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,10 +21,15 @@ Connection::Connection()
: io_service(), socket(io_service), logger(rclcpp::get_logger("lola connection"))
{
boost::system::error_code ec;
socket.connect(ENDPOINT, ec);
if (ec) {
RCLCPP_ERROR(logger, (std::string{"Could not connect to LoLA: "} + ec.message()).c_str());
}
rclcpp::Clock clock;
do {
socket.connect(ENDPOINT, ec);
if (ec) {
RCLCPP_WARN_SKIPFIRST_THROTTLE(
logger, clock, 1000,
(std::string{"Could not connect to LoLA, retrying: "} + ec.message()).c_str());
}
} while (ec && rclcpp::ok());
}

std::array<char, MSGPACK_READ_LENGTH> Connection::receive()
Expand Down

0 comments on commit b40e986

Please sign in to comment.