Skip to content

Commit

Permalink
fix(nebula_hw_interfaces): handling http get post request exception (#…
Browse files Browse the repository at this point in the history
…264)

* fix(nebula_velodyne_hx_interface): handling http get post request exception

* feat: expected handling

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* ci(pre-commit): autofix

* fix

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* ci(pre-commit): autofix

* fix

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* feat add template

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* ci(pre-commit): autofix

* fix

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* fix snapshot error

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* ci(pre-commit): autofix

* move template

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* ci(pre-commit): autofix

* chore: return error status from util::expected instead of hard-coded one

* chore: change Status to VelodyneStatus in all HTTP code

* ci(pre-commit): autofix

---------

Signed-off-by: Shumpei Wakabayashi <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: Max Schmeller <[email protected]>
  • Loading branch information
3 people authored Feb 17, 2025
1 parent 9e40e2e commit 1953495
Show file tree
Hide file tree
Showing 3 changed files with 143 additions and 50 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#define BOOST_ALLOW_DEPRECATED_HEADERS
#endif

#include "nebula_common/util/expected.hpp"
#include "nebula_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp"

#include <boost_tcp_driver/http_client_driver.hpp>
Expand Down Expand Up @@ -69,8 +70,49 @@ class VelodyneHwInterface
std::string target_reset_{"/cgi/reset"};
void string_callback(const std::string & str);

std::string http_get_request(const std::string & endpoint);
std::string http_post_request(const std::string & endpoint, const std::string & body);
template <typename CallbackType>
nebula::util::expected<std::string, VelodyneStatus> do_http_request_with_retries(
CallbackType do_request, std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> & client)
{
constexpr int max_retries = 3;
constexpr int retry_delay_ms = 100;

for (int retry = 0; retry < max_retries; ++retry) {
try {
if (!client->client()->isOpen()) {
client->client()->open();
}

std::string response = do_request();
client->client()->close();
return nebula::util::expected<std::string, VelodyneStatus>(response);
} catch (const std::exception & ex) {
if (retry == max_retries - 1) {
return nebula::util::expected<std::string, VelodyneStatus>(
VelodyneStatus::HTTP_CONNECTION_ERROR);
}

if (client->client()->isOpen()) {
try {
client->client()->close();
} catch (const std::exception & ex) {
return nebula::util::expected<std::string, VelodyneStatus>(
VelodyneStatus::HTTP_CONNECTION_ERROR);
}
}

std::this_thread::sleep_for(std::chrono::milliseconds(retry_delay_ms));
}
}

return nebula::util::expected<std::string, VelodyneStatus>(
VelodyneStatus::HTTP_CONNECTION_ERROR);
}

nebula::util::expected<std::string, VelodyneStatus> http_get_request(
const std::string & endpoint);
nebula::util::expected<std::string, VelodyneStatus> http_post_request(
const std::string & endpoint, const std::string & body);

/// @brief Get a one-off HTTP client to communicate with the hardware
/// @param ctx IO Context
Expand Down Expand Up @@ -152,13 +194,13 @@ class VelodyneHwInterface
VelodyneStatus init_http_client();
/// @brief Getting the current operational state and parameters of the sensor (sync)
/// @return Resulting JSON string
std::string get_status();
nebula::util::expected<std::string, VelodyneStatus> get_status();
/// @brief Getting diagnostic information from the sensor (sync)
/// @return Resulting JSON string
std::string get_diag();
nebula::util::expected<std::string, VelodyneStatus> get_diag();
/// @brief Getting current sensor configuration and status data (sync)
/// @return Resulting JSON string
std::string get_snapshot();
nebula::util::expected<std::string, VelodyneStatus> get_snapshot();
/// @brief Setting Motor RPM (sync)
/// @param rpm the RPM of the motor
/// @return Resulting status
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,29 +17,22 @@ VelodyneHwInterface::VelodyneHwInterface()
{
}

std::string VelodyneHwInterface::http_get_request(const std::string & endpoint)
nebula::util::expected<std::string, VelodyneStatus> VelodyneHwInterface::http_get_request(
const std::string & endpoint)
{
std::lock_guard lock(mtx_inflight_request_);
if (!http_client_driver_->client()->isOpen()) {
http_client_driver_->client()->open();
}

std::string response = http_client_driver_->get(endpoint);
http_client_driver_->client()->close();
return response;
auto do_request = [this, &endpoint]() { return http_client_driver_->get(endpoint); };
return do_http_request_with_retries(do_request, http_client_driver_);
}

std::string VelodyneHwInterface::http_post_request(
nebula::util::expected<std::string, VelodyneStatus> VelodyneHwInterface::http_post_request(
const std::string & endpoint, const std::string & body)
{
std::lock_guard lock(mtx_inflight_request_);
if (!http_client_driver_->client()->isOpen()) {
http_client_driver_->client()->open();
}

std::string response = http_client_driver_->post(endpoint, body);
http_client_driver_->client()->close();
return response;
auto do_request = [this, &endpoint, &body]() {
return http_client_driver_->post(endpoint, body);
};
return do_http_request_with_retries(do_request, http_client_driver_);
}

Status VelodyneHwInterface::initialize_sensor_configuration(
Expand All @@ -53,7 +46,10 @@ Status VelodyneHwInterface::set_sensor_configuration(
std::shared_ptr<const VelodyneSensorConfiguration> sensor_configuration)
{
auto snapshot = get_snapshot();
auto tree = parse_json(snapshot);
if (!snapshot.has_value()) {
return snapshot.error();
}
auto tree = parse_json(snapshot.value());
VelodyneStatus status = check_and_set_config(sensor_configuration, tree);

return status;
Expand Down Expand Up @@ -243,19 +239,21 @@ VelodyneStatus VelodyneHwInterface::check_and_set_config(

// sync

std::string VelodyneHwInterface::get_status()
nebula::util::expected<std::string, VelodyneStatus> VelodyneHwInterface::get_status()
{
return http_get_request(target_status_);
}

std::string VelodyneHwInterface::get_diag()
nebula::util::expected<std::string, VelodyneStatus> VelodyneHwInterface::get_diag()
{
auto rt = http_get_request(target_diag_);
std::cout << "read_response: " << rt << std::endl;
return rt;
auto response = http_get_request(target_diag_);
if (response.has_value()) {
std::cout << "read_response: " << response.value() << std::endl;
}
return response;
}

std::string VelodyneHwInterface::get_snapshot()
nebula::util::expected<std::string, VelodyneStatus> VelodyneHwInterface::get_snapshot()
{
return http_get_request(target_snapshot_);
}
Expand All @@ -266,7 +264,10 @@ VelodyneStatus VelodyneHwInterface::set_rpm(uint16_t rpm)
return VelodyneStatus::INVALID_RPM_ERROR;
}
auto rt = http_post_request(target_setting_, (boost::format("rpm=%d") % rpm).str());
string_callback(rt);
if (!rt.has_value()) {
return rt.error();
}
string_callback(rt.value());
return Status::OK;
}

Expand All @@ -276,7 +277,10 @@ VelodyneStatus VelodyneHwInterface::set_fov_start(uint16_t fov_start)
return VelodyneStatus::INVALID_FOV_ERROR;
}
auto rt = http_post_request(target_fov_, (boost::format("start=%d") % fov_start).str());
string_callback(rt);
if (!rt.has_value()) {
return rt.error();
}
string_callback(rt.value());
return Status::OK;
}

Expand All @@ -286,7 +290,10 @@ VelodyneStatus VelodyneHwInterface::set_fov_end(uint16_t fov_end)
return VelodyneStatus::INVALID_FOV_ERROR;
}
auto rt = http_post_request(target_fov_, (boost::format("end=%d") % fov_end).str());
string_callback(rt);
if (!rt.has_value()) {
return rt.error();
}
string_callback(rt.value());
return Status::OK;
}

Expand All @@ -307,97 +314,136 @@ VelodyneStatus VelodyneHwInterface::set_return_type(nebula::drivers::ReturnMode
return VelodyneStatus::INVALID_RETURN_MODE_ERROR;
}
auto rt = http_post_request(target_setting_, body_str);
string_callback(rt);
if (!rt.has_value()) {
return rt.error();
}
string_callback(rt.value());
return Status::OK;
}

VelodyneStatus VelodyneHwInterface::save_config()
{
std::string body_str = "submit";
auto rt = http_post_request(target_save_, body_str);
string_callback(rt);
if (!rt.has_value()) {
return rt.error();
}
string_callback(rt.value());
return Status::OK;
}

VelodyneStatus VelodyneHwInterface::reset_system()
{
std::string body_str = "reset_system";
auto rt = http_post_request(target_reset_, body_str);
string_callback(rt);
if (!rt.has_value()) {
return rt.error();
}
string_callback(rt.value());
return Status::OK;
}

VelodyneStatus VelodyneHwInterface::laser_on()
{
std::string body_str = "laser=on";
auto rt = http_post_request(target_setting_, body_str);
string_callback(rt);
if (!rt.has_value()) {
return rt.error();
}
string_callback(rt.value());
return Status::OK;
}

VelodyneStatus VelodyneHwInterface::laser_off()
{
std::string body_str = "laser=off";
auto rt = http_post_request(target_setting_, body_str);
string_callback(rt);
if (!rt.has_value()) {
return rt.error();
}
string_callback(rt.value());
return Status::OK;
}

VelodyneStatus VelodyneHwInterface::laser_on_off(bool on)
{
std::string body_str = (boost::format("laser=%s") % (on ? "on" : "off")).str();
auto rt = http_post_request(target_setting_, body_str);
string_callback(rt);
if (!rt.has_value()) {
return rt.error();
}
string_callback(rt.value());
return Status::OK;
}

VelodyneStatus VelodyneHwInterface::set_host_addr(std::string addr)
{
auto rt = http_post_request(target_host_, (boost::format("addr=%s") % addr).str());
string_callback(rt);
if (!rt.has_value()) {
return rt.error();
}
string_callback(rt.value());
return Status::OK;
}

VelodyneStatus VelodyneHwInterface::set_host_dport(uint16_t dport)
{
auto rt = http_post_request(target_host_, (boost::format("dport=%d") % dport).str());
string_callback(rt);
if (!rt.has_value()) {
return rt.error();
}
string_callback(rt.value());
return Status::OK;
}

VelodyneStatus VelodyneHwInterface::set_host_tport(uint16_t tport)
{
auto rt = http_post_request(target_host_, (boost::format("tport=%d") % tport).str());
string_callback(rt);
if (!rt.has_value()) {
return rt.error();
}
string_callback(rt.value());
return Status::OK;
}

VelodyneStatus VelodyneHwInterface::set_net_addr(std::string addr)
{
auto rt = http_post_request(target_net_, (boost::format("addr=%s") % addr).str());
string_callback(rt);
if (!rt.has_value()) {
return rt.error();
}
string_callback(rt.value());
return Status::OK;
}

VelodyneStatus VelodyneHwInterface::set_net_mask(std::string mask)
{
auto rt = http_post_request(target_net_, (boost::format("mask=%s") % mask).str());
string_callback(rt);
if (!rt.has_value()) {
return rt.error();
}
string_callback(rt.value());
return Status::OK;
}

VelodyneStatus VelodyneHwInterface::set_net_gateway(std::string gateway)
{
auto rt = http_post_request(target_net_, (boost::format("gateway=%s") % gateway).str());
string_callback(rt);
if (!rt.has_value()) {
return rt.error();
}
string_callback(rt.value());
return Status::OK;
}

VelodyneStatus VelodyneHwInterface::set_net_dhcp(bool use_dhcp)
{
auto rt =
http_post_request(target_net_, (boost::format("dhcp=%s") % (use_dhcp ? "on" : "off")).str());
string_callback(rt);
if (!rt.has_value()) {
return rt.error();
}
string_callback(rt.value());
return Status::OK;
}

Expand Down
Loading

0 comments on commit 1953495

Please sign in to comment.