Class nebula::drivers::VelodyneHwInterface
ClassList > nebula > drivers > VelodyneHwInterface
Hardware interface of velodyne driver.
#include <velodyne_hw_interface.hpp>
Public Functions
Type | Name |
---|---|
Status | GetCalibrationConfiguration (CalibrationConfigurationBase & calibration_configuration) Printing calibration configuration. |
std::string | GetDiag () Getting diagnostic information from the sensor (sync) |
Status | GetSensorConfiguration (SensorConfigurationBase & sensor_configuration) Printing sensor configuration. |
std::string | GetSnapshot () Getting current sensor configuration and status data (sync) |
std::string | GetStatus () Getting the current operational state and parameters of the sensor (sync) |
VelodyneStatus | InitHttpClient () Initializing HTTP client (sync) |
Status | InitializeSensorConfiguration (std::shared_ptr< const VelodyneSensorConfiguration > sensor_configuration) Initializing sensor configuration. |
VelodyneStatus | LaserOff () Turn laser state off (sync) |
VelodyneStatus | LaserOn () Turn laser state on (sync) |
VelodyneStatus | LaserOnOff (bool on) Turn laser state on/off (sync) |
boost::property_tree::ptree | ParseJson (const std::string & str) Parsing JSON string to property_tree. |
void | ReceiveSensorPacketCallback (std::vector< uint8_t > & buffer) Callback function to receive the Cloud Packet data from the UDP Driver. |
Status | RegisterScanCallback (std::function< void(std::vector< uint8_t > &packet)> scan_callback) Registering callback for PandarScan. |
VelodyneStatus | ResetSystem () Resets the sensor (sync) |
VelodyneStatus | SaveConfig () Save Configuration to the LiDAR memory (sync) |
Status | SensorInterfaceStart () Starting the interface that handles UDP streams. |
Status | SensorInterfaceStop () Function for stopping the interface that handles UDP streams. |
VelodyneStatus | SetFovEnd (uint16_t fov_end) Setting Field of View End (sync) |
VelodyneStatus | SetFovStart (uint16_t fov_start) Setting Field of View Start (sync) |
VelodyneStatus | SetHostAddr (std::string addr) Setting host (destination) IP address (sync) |
VelodyneStatus | SetHostDport (uint16_t dport) Setting host (destination) data port (sync) |
VelodyneStatus | SetHostTport (uint16_t tport) Setting host (destination) telemetry port (sync) |
void | SetLogger (std::shared_ptr< rclcpp::Logger > node) Setting rclcpp::Logger. |
VelodyneStatus | SetNetAddr (std::string addr) Setting network (sensor) IP address (sync) |
VelodyneStatus | SetNetDhcp (bool use_dhcp) This determines if the sensor is to rely on a DHCP server for its IP address (sync) |
VelodyneStatus | SetNetGateway (std::string gateway) Setting the gateway address of the sensor (sync) |
VelodyneStatus | SetNetMask (std::string mask) Setting the network mask of the sensor (sync) |
VelodyneStatus | SetReturnType (ReturnMode return_mode) Setting Return Type (sync) |
VelodyneStatus | SetRpm (uint16_t rpm) Setting Motor RPM (sync) |
Status | SetSensorConfiguration (std::shared_ptr< const VelodyneSensorConfiguration > sensor_configuration) Setting sensor configuration with InitializeSensorConfiguration & CheckAndSetConfigBySnapshotAsync. |
VelodyneHwInterface () Constructor. |
Public Functions Documentation
function GetCalibrationConfiguration
Printing calibration configuration.
Status nebula::drivers::VelodyneHwInterface::GetCalibrationConfiguration (
CalibrationConfigurationBase & calibration_configuration
)
Parameters:
calibration_configuration
CalibrationConfiguration for the checking
Returns:
Resulting status
function GetDiag
Getting diagnostic information from the sensor (sync)
std::string nebula::drivers::VelodyneHwInterface::GetDiag ()
Returns:
Resulting JSON string
function GetSensorConfiguration
Printing sensor configuration.
Status nebula::drivers::VelodyneHwInterface::GetSensorConfiguration (
SensorConfigurationBase & sensor_configuration
)
Parameters:
sensor_configuration
SensorConfiguration for this interface
Returns:
Resulting status
function GetSnapshot
Getting current sensor configuration and status data (sync)
std::string nebula::drivers::VelodyneHwInterface::GetSnapshot ()
Returns:
Resulting JSON string
function GetStatus
Getting the current operational state and parameters of the sensor (sync)
std::string nebula::drivers::VelodyneHwInterface::GetStatus ()
Returns:
Resulting JSON string
function InitHttpClient
Initializing HTTP client (sync)
VelodyneStatus nebula::drivers::VelodyneHwInterface::InitHttpClient ()
Returns:
Resulting status
function InitializeSensorConfiguration
Initializing sensor configuration.
Status nebula::drivers::VelodyneHwInterface::InitializeSensorConfiguration (
std::shared_ptr< const VelodyneSensorConfiguration > sensor_configuration
)
Parameters:
sensor_configuration
SensorConfiguration for this interface
Returns:
Resulting status
function LaserOff
Turn laser state off (sync)
VelodyneStatus nebula::drivers::VelodyneHwInterface::LaserOff ()
Returns:
Resulting status
function LaserOn
Turn laser state on (sync)
VelodyneStatus nebula::drivers::VelodyneHwInterface::LaserOn ()
Returns:
Resulting status
function LaserOnOff
Turn laser state on/off (sync)
VelodyneStatus nebula::drivers::VelodyneHwInterface::LaserOnOff (
bool on
)
Parameters:
on
is ON
Returns:
Resulting status
function ParseJson
Parsing JSON string to property_tree.
boost::property_tree::ptree nebula::drivers::VelodyneHwInterface::ParseJson (
const std::string & str
)
Parameters:
str
JSON string
Returns:
property_tree
function ReceiveSensorPacketCallback
Callback function to receive the Cloud Packet data from the UDP Driver.
void nebula::drivers::VelodyneHwInterface::ReceiveSensorPacketCallback (
std::vector< uint8_t > & buffer
)
Parameters:
buffer
Buffer containing the data received from the UDP socket
function RegisterScanCallback
Registering callback for PandarScan.
Status nebula::drivers::VelodyneHwInterface::RegisterScanCallback (
std::function< void(std::vector< uint8_t > &packet)> scan_callback
)
Parameters:
scan_callback
Callback function
Returns:
Resulting status
function ResetSystem
Resets the sensor (sync)
VelodyneStatus nebula::drivers::VelodyneHwInterface::ResetSystem ()
Returns:
Resulting status
function SaveConfig
Save Configuration to the LiDAR memory (sync)
VelodyneStatus nebula::drivers::VelodyneHwInterface::SaveConfig ()
Returns:
Resulting status
function SensorInterfaceStart
Starting the interface that handles UDP streams.
Status nebula::drivers::VelodyneHwInterface::SensorInterfaceStart ()
Returns:
Resulting status
function SensorInterfaceStop
Function for stopping the interface that handles UDP streams.
Status nebula::drivers::VelodyneHwInterface::SensorInterfaceStop ()
Returns:
Resulting status
function SetFovEnd
Setting Field of View End (sync)
VelodyneStatus nebula::drivers::VelodyneHwInterface::SetFovEnd (
uint16_t fov_end
)
Parameters:
fov_end
FOV end
Returns:
Resulting status
function SetFovStart
Setting Field of View Start (sync)
VelodyneStatus nebula::drivers::VelodyneHwInterface::SetFovStart (
uint16_t fov_start
)
Parameters:
fov_start
FOV start
Returns:
Resulting status
function SetHostAddr
Setting host (destination) IP address (sync)
VelodyneStatus nebula::drivers::VelodyneHwInterface::SetHostAddr (
std::string addr
)
Parameters:
addr
destination IP address
Returns:
Resulting status
function SetHostDport
Setting host (destination) data port (sync)
VelodyneStatus nebula::drivers::VelodyneHwInterface::SetHostDport (
uint16_t dport
)
Parameters:
dport
destination data port
Returns:
Resulting status
function SetHostTport
Setting host (destination) telemetry port (sync)
VelodyneStatus nebula::drivers::VelodyneHwInterface::SetHostTport (
uint16_t tport
)
Parameters:
tport
destination telemetry port
Returns:
Resulting status
function SetLogger
Setting rclcpp::Logger.
void nebula::drivers::VelodyneHwInterface::SetLogger (
std::shared_ptr< rclcpp::Logger > node
)
Parameters:
node
Logger
function SetNetAddr
Setting network (sensor) IP address (sync)
VelodyneStatus nebula::drivers::VelodyneHwInterface::SetNetAddr (
std::string addr
)
Parameters:
addr
sensor IP address
Returns:
Resulting status
function SetNetDhcp
This determines if the sensor is to rely on a DHCP server for its IP address (sync)
VelodyneStatus nebula::drivers::VelodyneHwInterface::SetNetDhcp (
bool use_dhcp
)
Parameters:
use_dhcp
DHCP on
Returns:
Resulting status
function SetNetGateway
Setting the gateway address of the sensor (sync)
VelodyneStatus nebula::drivers::VelodyneHwInterface::SetNetGateway (
std::string gateway
)
Parameters:
gateway
Gateway address
Returns:
Resulting status
function SetNetMask
Setting the network mask of the sensor (sync)
VelodyneStatus nebula::drivers::VelodyneHwInterface::SetNetMask (
std::string mask
)
Parameters:
mask
Network mask
Returns:
Resulting status
function SetReturnType
Setting Return Type (sync)
VelodyneStatus nebula::drivers::VelodyneHwInterface::SetReturnType (
ReturnMode return_mode
)
Parameters:
return_mode
ReturnMode
Returns:
Resulting status
function SetRpm
Setting Motor RPM (sync)
VelodyneStatus nebula::drivers::VelodyneHwInterface::SetRpm (
uint16_t rpm
)
Parameters:
rpm
the RPM of the motor
Returns:
Resulting status
function SetSensorConfiguration
Setting sensor configuration with InitializeSensorConfiguration & CheckAndSetConfigBySnapshotAsync.
Status nebula::drivers::VelodyneHwInterface::SetSensorConfiguration (
std::shared_ptr< const VelodyneSensorConfiguration > sensor_configuration
)
Parameters:
sensor_configuration
SensorConfiguration for this interface
Returns:
Resulting status
function VelodyneHwInterface
nebula::drivers::VelodyneHwInterface::VelodyneHwInterface ()
The documentation for this class was generated from the following file nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp