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
{
namespace 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 StringCallback(const std::string & str);
std::string HttpGetRequest(const std::string & endpoint);
std::string HttpPostRequest(const std::string & endpoint, const std::string & body);
VelodyneStatus GetHttpClientDriverOnce(
std::shared_ptr<boost::asio::io_context> ctx,
std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> & hcd);
VelodyneStatus GetHttpClientDriverOnce(
std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> & hcd);
VelodyneStatus CheckAndSetConfig(
std::shared_ptr<const VelodyneSensorConfiguration> sensor_configuration,
boost::property_tree::ptree tree);
std::shared_ptr<rclcpp::Logger> parent_node_logger;
void PrintInfo(std::string info);
void PrintError(std::string error);
void PrintDebug(std::string debug);
public:
VelodyneHwInterface();
void ReceiveSensorPacketCallback(std::vector<uint8_t> & buffer);
Status SensorInterfaceStart();
Status SensorInterfaceStop();
Status GetSensorConfiguration(SensorConfigurationBase & sensor_configuration);
Status GetCalibrationConfiguration(CalibrationConfigurationBase & calibration_configuration);
Status InitializeSensorConfiguration(
std::shared_ptr<const VelodyneSensorConfiguration> sensor_configuration);
Status SetSensorConfiguration(
std::shared_ptr<const VelodyneSensorConfiguration> sensor_configuration);
Status RegisterScanCallback(std::function<void(std::vector<uint8_t> & packet)> scan_callback);
boost::property_tree::ptree ParseJson(const std::string & str);
VelodyneStatus InitHttpClient();
std::string GetStatus();
std::string GetDiag();
std::string GetSnapshot();
VelodyneStatus SetRpm(uint16_t rpm);
VelodyneStatus SetFovStart(uint16_t fov_start);
VelodyneStatus SetFovEnd(uint16_t fov_end);
VelodyneStatus SetReturnType(ReturnMode return_mode);
VelodyneStatus SaveConfig();
VelodyneStatus ResetSystem();
VelodyneStatus LaserOn();
VelodyneStatus LaserOff();
VelodyneStatus LaserOnOff(bool on);
VelodyneStatus SetHostAddr(std::string addr);
VelodyneStatus SetHostDport(uint16_t dport);
VelodyneStatus SetHostTport(uint16_t tport);
VelodyneStatus SetNetAddr(std::string addr);
VelodyneStatus SetNetMask(std::string mask);
VelodyneStatus SetNetGateway(std::string gateway);
VelodyneStatus SetNetDhcp(bool use_dhcp);
void SetLogger(std::shared_ptr<rclcpp::Logger> node);
};
} // namespace drivers
} // namespace nebula
#endif // NEBULA_VELODYNE_HW_INTERFACE_H