File velodyne_hw_interface.hpp
File List > include > nebula_hw_interfaces > nebula_hw_interfaces_velodyne > velodyne_hw_interface.hpp
Go to the documentation of this file
// Copyright 2024 TIER IV, Inc.
//
// 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 NEBULA_VELODYNE_HW_INTERFACE_H
#define NEBULA_VELODYNE_HW_INTERFACE_H
// Have to define macros to silence warnings about deprecated headers being used by
// boost/property_tree/ in some versions of boost.
// See: https://github.com/boostorg/property_tree/issues/51
#include <boost/version.hpp>
#if (BOOST_VERSION / 100 >= 1073 && BOOST_VERSION / 100 <= 1076) // Boost 1.73 - 1.76
#define BOOST_BIND_GLOBAL_PLACEHOLDERS
#endif
#if (BOOST_VERSION / 100 == 1074) // Boost 1.74
#define BOOST_ALLOW_DEPRECATED_HEADERS
#endif
#include "nebula_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp"
#include <boost_tcp_driver/http_client_driver.hpp>
#include <boost_udp_driver/udp_driver.hpp>
#include <nebula_common/velodyne/velodyne_common.hpp>
#include <nebula_common/velodyne/velodyne_status.hpp>
#include <rclcpp/rclcpp.hpp>
#include <boost/property_tree/json_parser.hpp>
#include <boost/property_tree/ptree.hpp>
#include <memory>
#include <string>
#include <vector>
namespace nebula::drivers
{
class VelodyneHwInterface
{
private:
std::unique_ptr<::drivers::common::IoContext> cloud_io_context_;
std::unique_ptr<::drivers::udp_driver::UdpDriver> cloud_udp_driver_;
std::shared_ptr<const VelodyneSensorConfiguration> sensor_configuration_;
std::function<void(std::vector<uint8_t> &)>
cloud_packet_callback_;
std::shared_ptr<boost::asio::io_context> boost_ctx_;
std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> http_client_driver_;
std::mutex mtx_inflight_request_;
std::string target_status_{"/cgi/status.json"};
std::string target_diag_{"/cgi/diag.json"};
std::string target_snapshot_{"/cgi/snapshot.hdl"};
std::string target_setting_{"/cgi/setting"};
std::string target_fov_{"/cgi/setting/fov"};
std::string target_host_{"/cgi/setting/host"};
std::string target_net_{"/cgi/setting/net"};
std::string target_save_{"/cgi/save"};
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);
VelodyneStatus get_http_client_driver_once(
std::shared_ptr<boost::asio::io_context> ctx,
std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> & hcd);
VelodyneStatus get_http_client_driver_once(
std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> & hcd);
VelodyneStatus check_and_set_config(
std::shared_ptr<const VelodyneSensorConfiguration> sensor_configuration,
boost::property_tree::ptree tree);
std::shared_ptr<rclcpp::Logger> parent_node_logger_;
void print_info(std::string info);
void print_error(std::string error);
void print_debug(std::string debug);
public:
VelodyneHwInterface();
void receive_sensor_packet_callback(std::vector<uint8_t> & buffer);
Status sensor_interface_start();
Status sensor_interface_stop();
Status get_sensor_configuration(SensorConfigurationBase & sensor_configuration);
Status get_calibration_configuration(CalibrationConfigurationBase & calibration_configuration);
Status initialize_sensor_configuration(
std::shared_ptr<const VelodyneSensorConfiguration> sensor_configuration);
Status set_sensor_configuration(
std::shared_ptr<const VelodyneSensorConfiguration> sensor_configuration);
Status register_scan_callback(std::function<void(std::vector<uint8_t> & packet)> scan_callback);
boost::property_tree::ptree parse_json(const std::string & str);
VelodyneStatus init_http_client();
std::string get_status();
std::string get_diag();
std::string get_snapshot();
VelodyneStatus set_rpm(uint16_t rpm);
VelodyneStatus set_fov_start(uint16_t fov_start);
VelodyneStatus set_fov_end(uint16_t fov_end);
VelodyneStatus set_return_type(ReturnMode return_mode);
VelodyneStatus save_config();
VelodyneStatus reset_system();
VelodyneStatus laser_on();
VelodyneStatus laser_off();
VelodyneStatus laser_on_off(bool on);
VelodyneStatus set_host_addr(std::string addr);
VelodyneStatus set_host_dport(uint16_t dport);
VelodyneStatus set_host_tport(uint16_t tport);
VelodyneStatus set_net_addr(std::string addr);
VelodyneStatus set_net_mask(std::string mask);
VelodyneStatus set_net_gateway(std::string gateway);
VelodyneStatus set_net_dhcp(bool use_dhcp);
void set_logger(std::shared_ptr<rclcpp::Logger> node);
};
} // namespace nebula::drivers
#endif // NEBULA_VELODYNE_HW_INTERFACE_H