mirror of
https://github.com/Livox-SDK/livox_ros_driver.git
synced 2023-04-06 15:49:55 +08:00
fix:add dependencies for gnenerate messages, fix compilation error on the first compilation
feature:add Livox-SDK binary lib only for ROS Distro jenkins build change:use ExternalProject_add to get thirdparty library
This commit is contained in:
@@ -37,27 +37,6 @@ find_package(Boost REQUIRED COMPONENTS thread)
|
|||||||
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
|
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
|
||||||
# catkin_python_setup()
|
# catkin_python_setup()
|
||||||
|
|
||||||
## make sure the livox_sdk_static library is installed
|
|
||||||
find_library(LIVOX_SDK_LIBRARY liblivox_sdk_static.a /usr/local/lib)
|
|
||||||
|
|
||||||
if((NOT LIVOX_SDK_LIBRARY) OR (NOT EXISTS ${LIVOX_SDK_LIBRARY}))
|
|
||||||
# couldn't find the livox sdk library
|
|
||||||
message("Coudn't find livox sdk library")
|
|
||||||
include(ExternalProject)
|
|
||||||
ExternalProject_Add(
|
|
||||||
Livox-SDK
|
|
||||||
GIT_REPOSITORY https://github.com/Livox-SDK/Livox-SDK.git
|
|
||||||
TIMEOUT 15
|
|
||||||
CONFIGURE_COMMAND ""
|
|
||||||
BUILD_COMMAND ""
|
|
||||||
INSTALL_COMMAND ""
|
|
||||||
UPDATE_COMMAND ""
|
|
||||||
PATCH_COMMAND ""
|
|
||||||
)
|
|
||||||
|
|
||||||
else()
|
|
||||||
message("find livox sdk library success")
|
|
||||||
endif()
|
|
||||||
|
|
||||||
|
|
||||||
################################################
|
################################################
|
||||||
@@ -155,9 +134,9 @@ catkin_package(
|
|||||||
## Specify additional locations of header files
|
## Specify additional locations of header files
|
||||||
## Your package locations should be listed before other locations
|
## Your package locations should be listed before other locations
|
||||||
include_directories(
|
include_directories(
|
||||||
# include
|
#include
|
||||||
${catkin_INCLUDE_DIRS}
|
${catkin_INCLUDE_DIRS}
|
||||||
# ${PCL_INCLUDE_DIRS}
|
#${PCL_INCLUDE_DIRS}
|
||||||
)
|
)
|
||||||
|
|
||||||
## Declare a C++ library
|
## Declare a C++ library
|
||||||
@@ -195,49 +174,95 @@ endif (APR_FOUND)
|
|||||||
include_directories(
|
include_directories(
|
||||||
./
|
./
|
||||||
${APR_INCLUDE_DIRS}
|
${APR_INCLUDE_DIRS}
|
||||||
)
|
)
|
||||||
|
|
||||||
|
|
||||||
## PCL library
|
## PCL library
|
||||||
#link_directories(${PCL_LIBRARY_DIRS})
|
#link_directories(${PCL_LIBRARY_DIRS})
|
||||||
#add_definitions(${PCL_DEFINITIONS})
|
#add_definitions(${PCL_DEFINITIONS})
|
||||||
|
|
||||||
add_executable(${PROJECT_LIDAR}_node
|
## make sure the livox_sdk_static library is installed
|
||||||
${PROJECT_LIDAR_SRC})
|
find_library(LIVOX_SDK_LIBRARY liblivox_sdk_static.a /usr/local/lib)
|
||||||
|
|
||||||
## Rename C++ executable without prefix
|
if((NOT LIVOX_SDK_LIBRARY) OR (NOT EXISTS ${LIVOX_SDK_LIBRARY}))
|
||||||
## The above recommended prefix causes long target names, the following renames the
|
# couldn't find the livox sdk library
|
||||||
## target back to the shorter version for ease of user use
|
message("Coudn't find livox sdk library!")
|
||||||
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
|
message("Download Livox-SDK from github and build&install it please!")
|
||||||
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
|
message("Download Livox-SDK from github and build&install it please!")
|
||||||
|
|
||||||
## Add cmake target dependencies of the executable
|
message("Use Livox-SDK binary lib in x86_64 platform, only for ROS distro jenkins build!")
|
||||||
## same as for the library above
|
include_directories(
|
||||||
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
|
./lib_backup
|
||||||
|
)
|
||||||
|
|
||||||
## Specify libraries to link a library or executable target against
|
link_directories(
|
||||||
target_link_libraries(${PROJECT_LIDAR}_node
|
./lib_backup
|
||||||
|
)
|
||||||
|
# link_directories(
|
||||||
|
#
|
||||||
|
# )
|
||||||
|
## add lidar project here
|
||||||
|
add_executable(${PROJECT_LIDAR}_node
|
||||||
|
${PROJECT_LIDAR_SRC}
|
||||||
|
)
|
||||||
|
|
||||||
|
#add_dependencies(${PROJECT_LIDAR}_node liblivox_sdk_static.a)
|
||||||
|
|
||||||
|
target_link_libraries(${PROJECT_LIDAR}_node
|
||||||
livox_sdk_static.a
|
livox_sdk_static.a
|
||||||
${APR_LIBRARIES}
|
${APR_LIBRARIES}
|
||||||
# ${PCL_LIBRARIES}
|
|
||||||
${catkin_LIBRARIES}
|
${catkin_LIBRARIES}
|
||||||
${Boost_LIBRARIES}
|
${Boost_LIBRARIES}
|
||||||
-lrt
|
-lrt
|
||||||
)
|
)
|
||||||
|
|
||||||
## add hub project here
|
## add hub project here
|
||||||
add_executable(${PROJECT_HUB}_node
|
add_executable(${PROJECT_HUB}_node
|
||||||
${PROJECT_HUB_SRC})
|
${PROJECT_HUB_SRC}
|
||||||
|
)
|
||||||
|
|
||||||
target_link_libraries(${PROJECT_HUB}_node
|
target_link_libraries(${PROJECT_HUB}_node
|
||||||
livox_sdk_static.a
|
livox_sdk_static.a
|
||||||
${APR_LIBRARIES}
|
${APR_LIBRARIES}
|
||||||
# ${PCL_LIBRARIES}
|
|
||||||
${catkin_LIBRARIES}
|
${catkin_LIBRARIES}
|
||||||
${Boost_LIBRARIES}
|
${Boost_LIBRARIES}
|
||||||
-lrt
|
-lrt
|
||||||
)
|
)
|
||||||
|
|
||||||
|
else()
|
||||||
|
message("find livox sdk library success")
|
||||||
|
|
||||||
|
## add lidar project here
|
||||||
|
add_executable(${PROJECT_LIDAR}_node
|
||||||
|
${PROJECT_LIDAR_SRC}
|
||||||
|
)
|
||||||
|
|
||||||
|
add_dependencies(${PROJECT_LIDAR}_node livox_ros_driver_generate_messages_cpp)
|
||||||
|
|
||||||
|
target_link_libraries(${PROJECT_LIDAR}_node
|
||||||
|
livox_sdk_static.a
|
||||||
|
${APR_LIBRARIES}
|
||||||
|
${catkin_LIBRARIES}
|
||||||
|
${Boost_LIBRARIES}
|
||||||
|
-lrt
|
||||||
|
)
|
||||||
|
|
||||||
|
## add hub project here
|
||||||
|
add_executable(${PROJECT_HUB}_node
|
||||||
|
${PROJECT_HUB_SRC}
|
||||||
|
)
|
||||||
|
|
||||||
|
add_dependencies(${PROJECT_HUB}_node livox_ros_driver_generate_messages_cpp)
|
||||||
|
|
||||||
|
target_link_libraries(${PROJECT_HUB}_node
|
||||||
|
livox_sdk_static.a
|
||||||
|
${APR_LIBRARIES}
|
||||||
|
${catkin_LIBRARIES}
|
||||||
|
${Boost_LIBRARIES}
|
||||||
|
-lrt
|
||||||
|
)
|
||||||
|
|
||||||
|
endif()
|
||||||
|
|
||||||
#############
|
#############
|
||||||
## Install ##
|
## Install ##
|
||||||
#############
|
#############
|
||||||
|
|||||||
BIN
livox_ros_driver/lib_backup/liblivox_sdk_static.a
Normal file
BIN
livox_ros_driver/lib_backup/liblivox_sdk_static.a
Normal file
Binary file not shown.
394
livox_ros_driver/lib_backup/livox_def.h
Normal file
394
livox_ros_driver/lib_backup/livox_def.h
Normal file
@@ -0,0 +1,394 @@
|
|||||||
|
//
|
||||||
|
// The MIT License (MIT)
|
||||||
|
//
|
||||||
|
// Copyright (c) 2019 Livox. All rights reserved.
|
||||||
|
//
|
||||||
|
// Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
// of this software and associated documentation files (the "Software"), to deal
|
||||||
|
// in the Software without restriction, including without limitation the rights
|
||||||
|
// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
// copies of the Software, and to permit persons to whom the Software is
|
||||||
|
// furnished to do so, subject to the following conditions:
|
||||||
|
//
|
||||||
|
// The above copyright notice and this permission notice shall be included in
|
||||||
|
// all copies or substantial portions of the Software.
|
||||||
|
//
|
||||||
|
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||||
|
// SOFTWARE.
|
||||||
|
//
|
||||||
|
|
||||||
|
#ifndef LIVOX_DEF_H_
|
||||||
|
#define LIVOX_DEF_H_
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#define kMaxLidarCount 32
|
||||||
|
|
||||||
|
/** Device type. */
|
||||||
|
typedef enum {
|
||||||
|
kDeviceTypeHub = 0, /**< Livox Hub. */
|
||||||
|
kDeviceTypeLidarMid40 = 1, /**< Mid-40. */
|
||||||
|
kDeviceTypeLidarTele = 2, /**< Tele. */
|
||||||
|
kDeviceTypeLidarHorizon = 3 /**< Horizon. */
|
||||||
|
} DeviceType;
|
||||||
|
|
||||||
|
/** Lidar state. */
|
||||||
|
typedef enum {
|
||||||
|
kLidarStateInit = 0, /**< Initialization state. */
|
||||||
|
kLidarStateNormal = 1, /**< Normal work state. */
|
||||||
|
kLidarStatePowerSaving = 2, /**< Power-saving state. */
|
||||||
|
kLidarStateStandBy = 3, /**< Standby state. */
|
||||||
|
kLidarStateError = 4, /**< Error state. */
|
||||||
|
kLidarStateUnknown = 5
|
||||||
|
} LidarState;
|
||||||
|
|
||||||
|
/** Lidar mode. */
|
||||||
|
typedef enum {
|
||||||
|
kLidarModeNormal = 1, /**< Normal mode. */
|
||||||
|
kLidarModePowerSaving = 2, /**< Power-saving mode. */
|
||||||
|
kLidarModeStandby = 3 /**< Standby mode. */
|
||||||
|
} LidarMode;
|
||||||
|
|
||||||
|
/** Lidar feature. */
|
||||||
|
typedef enum {
|
||||||
|
kLidarFeatureNone = 0, /**< No feature. */
|
||||||
|
kLidarFeatureRainFog = 1 /**< Rain and fog feature. */
|
||||||
|
} LidarFeature;
|
||||||
|
|
||||||
|
/** Function return value definition. */
|
||||||
|
typedef enum {
|
||||||
|
kStatusSuccess = 0, /**< Success. */
|
||||||
|
kStatusFailure = 1, /**< Failure. */
|
||||||
|
kStatusNotConnected = 2, /**< Requested device is not connected. */
|
||||||
|
kStatusNotSupported = 3, /**< Operation is not supported on this device. */
|
||||||
|
kStatusTimeout = 4, /**< Operation timeouts. */
|
||||||
|
kStatusNotEnoughMemory = 5 /**< No enough memory. */
|
||||||
|
} ResponseStatus;
|
||||||
|
|
||||||
|
/** Device update type, indicating the change of device connection or working state. */
|
||||||
|
typedef enum {
|
||||||
|
kEventConnect = 0, /**< Device is connected. */
|
||||||
|
kEventDisconnect = 1, /**< Device is removed. */
|
||||||
|
kEventStateChange = 2 /**< Device working state changes or an error occurs. */
|
||||||
|
} DeviceEvent;
|
||||||
|
|
||||||
|
/** Timestamp sync mode define. */
|
||||||
|
typedef enum {
|
||||||
|
kTimestampTypeNoSync = 0, /**< No sync signal mode. */
|
||||||
|
kTimestampTypePtp = 1, /**< 1588v2.0 PTP sync mode. */
|
||||||
|
kTimestampTypeRsvd = 2, /**< Reserved use. */
|
||||||
|
kTimestampTypePpsGps = 3, /**< pps+gps sync mode. */
|
||||||
|
kTimestampTypePps = 4, /**< pps only sync mode. */
|
||||||
|
kTimestampTypeUnknown = 5 /**< Unknown mode. */
|
||||||
|
} TimestampType;
|
||||||
|
|
||||||
|
#pragma pack(1)
|
||||||
|
|
||||||
|
#define LIVOX_SDK_MAJOR_VERSION 1
|
||||||
|
#define LIVOX_SDK_MINOR_VERSION 1
|
||||||
|
#define LIVOX_SDK_PATCH_VERSION 0
|
||||||
|
|
||||||
|
#define kBroadcastCodeSize 16
|
||||||
|
|
||||||
|
/** The numeric version information struct. */
|
||||||
|
typedef struct {
|
||||||
|
int major; /**< major number */
|
||||||
|
int minor; /**< minor number */
|
||||||
|
int patch; /**< patch number */
|
||||||
|
} LivoxSdkVersion;
|
||||||
|
|
||||||
|
/** Cartesian coordinate format. */
|
||||||
|
typedef struct {
|
||||||
|
int32_t x; /**< X axis, Unit:mm */
|
||||||
|
int32_t y; /**< Y axis, Unit:mm */
|
||||||
|
int32_t z; /**< Z axis, Unit:mm */
|
||||||
|
uint8_t reflectivity; /**< Reflectivity */
|
||||||
|
} LivoxRawPoint;
|
||||||
|
|
||||||
|
/** Standard point cloud format */
|
||||||
|
typedef struct {
|
||||||
|
float x; /**< X axis, Unit:m */
|
||||||
|
float y; /**< X axis, Unit:m */
|
||||||
|
float z; /**< X axis, Unit:m */
|
||||||
|
uint8_t reflectivity; /**< Reflectivity */
|
||||||
|
} LivoxPoint;
|
||||||
|
|
||||||
|
/** Point cloud packet. */
|
||||||
|
typedef struct {
|
||||||
|
uint8_t version; /**< Packet protocol version. */
|
||||||
|
uint8_t slot; /**< Slot number used for connecting LiDAR. */
|
||||||
|
uint8_t id; /**< LiDAR id. */
|
||||||
|
uint8_t rsvd; /**< Reserved. */
|
||||||
|
uint32_t err_code; /**< Device error status indicator information. */
|
||||||
|
uint8_t timestamp_type; /**< Timestamp type. */
|
||||||
|
/** Point cloud coordinate format, 1 for spherical coordinate data, 0 for cartesian coordinate data. */
|
||||||
|
uint8_t data_type;
|
||||||
|
uint8_t timestamp[8]; /**< Nanosecond or UTC format timestamp. */
|
||||||
|
uint8_t data[1]; /**< Point cloud data. */
|
||||||
|
} LivoxEthPacket;
|
||||||
|
|
||||||
|
/** Information of LiDAR work state. */
|
||||||
|
typedef union {
|
||||||
|
uint32_t status_code; /**< LiDAR work state status code. */
|
||||||
|
uint32_t progress; /**< LiDAR work state switching progress. */
|
||||||
|
} StatusUnion;
|
||||||
|
|
||||||
|
/** Information of the connected LiDAR or hub. */
|
||||||
|
typedef struct {
|
||||||
|
char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code, null-terminated string, 15 characters at most. */
|
||||||
|
uint8_t handle; /**< Device handle. */
|
||||||
|
uint8_t slot; /**< Slot number used for connecting LiDAR. */
|
||||||
|
uint8_t id; /**< LiDAR id. */
|
||||||
|
uint32_t type; /**< Device type, refer to \ref DeviceType. */
|
||||||
|
uint16_t data_port; /**< Point cloud data UDP port. */
|
||||||
|
uint16_t cmd_port; /**< Control command UDP port. */
|
||||||
|
char ip[16]; /**< IP address. */
|
||||||
|
LidarState state; /**< LiDAR state. */
|
||||||
|
LidarFeature feature; /**< LiDAR feature. */
|
||||||
|
StatusUnion status; /** LiDAR work state status. */
|
||||||
|
} DeviceInfo;
|
||||||
|
|
||||||
|
/** The information of broadcast device. */
|
||||||
|
typedef struct {
|
||||||
|
char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code, null-terminated string, 15 characters at most. */
|
||||||
|
uint8_t dev_type; /**< Device type, refer to \ref DeviceType. */
|
||||||
|
uint16_t reserved; /**< Reserved. */
|
||||||
|
} BroadcastDeviceInfo;
|
||||||
|
|
||||||
|
/** The information of LiDAR units that are connected to the Livox Hub. */
|
||||||
|
typedef struct {
|
||||||
|
char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code, null-terminated string, 15 characters at most. */
|
||||||
|
uint8_t dev_type; /**< Device type, refer to \ref DeviceType. */
|
||||||
|
uint8_t version[4]; /**< Firmware version. */
|
||||||
|
uint8_t slot; /**< Slot number used for connecting LiDAR units. */
|
||||||
|
uint8_t id; /**< Device id. */
|
||||||
|
} ConnectedLidarInfo;
|
||||||
|
|
||||||
|
/** LiDAR mode configuration information. */
|
||||||
|
typedef struct {
|
||||||
|
char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code, null-terminated string, 15 characters at most. */
|
||||||
|
uint8_t state; /**< LiDAR state. */
|
||||||
|
} LidarModeRequestItem;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
uint8_t ret_code; /**< Return code. */
|
||||||
|
char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code. */
|
||||||
|
} ReturnCode;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code. */
|
||||||
|
} DeviceBroadcastCode;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code. */
|
||||||
|
uint8_t feature; /**< Close or open the rain and fog feature. */
|
||||||
|
} RainFogSuppressRequestItem;
|
||||||
|
|
||||||
|
/** LiDAR configuration information. */
|
||||||
|
typedef struct {
|
||||||
|
char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code. */
|
||||||
|
float roll; /**< Roll angle, unit: degree. */
|
||||||
|
float pitch; /**< Pitch angle, unit: degree. */
|
||||||
|
float yaw; /**< Yaw angle, unit: degree. */
|
||||||
|
int32_t x; /**< X translation, unit: mm. */
|
||||||
|
int32_t y; /**< Y translation, unit: mm. */
|
||||||
|
int32_t z; /**< Z translation, unit: mm. */
|
||||||
|
} ExtrinsicParameterRequestItem;
|
||||||
|
|
||||||
|
/** LiDAR extrinsic parameters. */
|
||||||
|
typedef struct {
|
||||||
|
uint8_t ret_code; /**< Return code. */
|
||||||
|
char broadcast_code[kBroadcastCodeSize]; /**< Broadcast code. */
|
||||||
|
float roll; /**< Roll angle, unit: degree. */
|
||||||
|
float pitch; /**< Pitch angle, unit: degree. */
|
||||||
|
float yaw; /**< Yaw angle, unit: degree. */
|
||||||
|
int32_t x; /**< X translation, unit: mm. */
|
||||||
|
int32_t y; /**< Y translation, unit: mm. */
|
||||||
|
int32_t z; /**< Z translation, unit: mm. */
|
||||||
|
} ExtrinsicParameterResponseItem;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
char broadcast_code[kBroadcastCodeSize]; /**< Broadcast code. */
|
||||||
|
uint8_t state; /**< LiDAR state. */
|
||||||
|
uint8_t feature; /**< LiDAR feature. */
|
||||||
|
StatusUnion error_union; /** LiDAR work state. */
|
||||||
|
} LidarStateItem;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The request body for the command of handshake.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint32_t ip_addr; /**< IP address of the device. */
|
||||||
|
uint16_t data_port; /**< UDP port of the data connection. */
|
||||||
|
uint16_t cmd_port; /**< UDP port of the command connection. */
|
||||||
|
} HandshakeRequest;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The response body of querying device information.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t ret_code; /**< Return code. */
|
||||||
|
uint8_t firmware_version[4]; /**< Firmware version. */
|
||||||
|
} DeviceInformationResponse;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The response body of getting device error status.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint32_t error_code; /**< Error code. */
|
||||||
|
} ErrorMessage;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The request body of the command for setting device's IP mode.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t ip_mode; /**< IP address mode: 0 for dynamic IP address, 1 for static IP address. */
|
||||||
|
uint32_t ip_addr; /**< IP address. */
|
||||||
|
} SetDeviceIPModeRequest;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The response body of getting device's IP mode.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t ret_code; /**< Return code. */
|
||||||
|
uint8_t ip_mode; /**< IP address mode: 0 for dynamic IP address, 1 for static IP address. */
|
||||||
|
uint32_t ip_addr; /**< IP address. */
|
||||||
|
} GetDeviceIPModeResponse;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The body of heartbeat response.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t ret_code; /**< Return code. */
|
||||||
|
uint8_t state; /**< Working state. */
|
||||||
|
uint8_t feature; /**< LiDAR feature. */
|
||||||
|
StatusUnion error_union; /**< LiDAR work state. */
|
||||||
|
} HeartbeatResponse;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The request body for the command of setting LiDAR's parameters.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
float roll; /**< Roll angle, unit: degree. */
|
||||||
|
float pitch; /**< Pitch angle, unit: degree. */
|
||||||
|
float yaw; /**< Yaw angle, unit: degree. */
|
||||||
|
int32_t x; /**< X translation, unit: mm. */
|
||||||
|
int32_t y; /**< Y translation, unit: mm. */
|
||||||
|
int32_t z; /**< Z translation, unit: mm. */
|
||||||
|
} LidarSetExtrinsicParameterRequest;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The response body of getting LiDAR's parameters.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t ret_code;
|
||||||
|
float roll; /**< Roll angle, unit: degree. */
|
||||||
|
float pitch; /**< Pitch angle, unit: degree. */
|
||||||
|
float yaw; /**< Yaw angle, unit: degree. */
|
||||||
|
int32_t x; /**< X translation, unit: mm. */
|
||||||
|
int32_t y; /**< Y translation, unit: mm. */
|
||||||
|
int32_t z; /**< Z translation, unit: mm. */
|
||||||
|
} LidarGetExtrinsicParameterResponse;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The response body of querying the information of LiDAR units connected to the Livox Hub.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t ret_code; /**< Return code from device. */
|
||||||
|
uint8_t count; /**< Count of device_info_list. */
|
||||||
|
ConnectedLidarInfo device_info_list[1]; /**< Connected lidars information. */
|
||||||
|
} HubQueryLidarInformationResponse;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The request body of setting LiDAR units working mode.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t count; /**< Number of LiDAR units to set. */
|
||||||
|
LidarModeRequestItem config_list[1]; /**< LiDAR mode configuration list. */
|
||||||
|
} HubSetModeRequest;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The response of setting LiDAR units working mode.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t ret_code; /**< Return code from device. */
|
||||||
|
uint8_t count; /**< Count of ret_state_list. */
|
||||||
|
ReturnCode ret_state_list[1]; /**< Return status list. */
|
||||||
|
} HubSetModeResponse;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The request body of toggling the power supply of the slot.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t slot; /**< Slot of the hub. */
|
||||||
|
uint8_t state; /**< Status of toggling the power supply. */
|
||||||
|
} HubControlSlotPowerRequest;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The request body of setting the Livox Hub's parameters.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t count; /**< Count of cfg_param_list. */
|
||||||
|
ExtrinsicParameterRequestItem parameter_list[1]; /**< Configuration parameter list. */
|
||||||
|
} HubSetExtrinsicParameterRequest;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The response body of setting the Livox Hub's parameters.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t ret_code; /**< Return code. */
|
||||||
|
uint8_t count; /**< Count of ret_code_list. */
|
||||||
|
ReturnCode ret_code_list[1]; /**< Return code */
|
||||||
|
} HubSetExtrinsicParameterResponse;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The request body of getting the Livox Hub's parameters.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t count; /**< Count of code_list. */
|
||||||
|
DeviceBroadcastCode code_list[1]; /**< Broadcast code list. */
|
||||||
|
} HubGetExtrinsicParameterRequest;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The response body of getting the Livox Hub's parameters.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t ret_code; /**< Return code. */
|
||||||
|
uint8_t count; /**< Number of LiDAR units connected to the Livox Hub. */
|
||||||
|
ExtrinsicParameterResponseItem parameter_list[1]; /**< Postion parameters of connected LiDAR unit(s). */
|
||||||
|
} HubGetExtrinsicParameterResponse;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The response body of getting sub LiDAR's state.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t ret_code; /**< Return code. */
|
||||||
|
uint8_t count; /**< Number of LiDAR connected to the Livox Hub. */
|
||||||
|
LidarStateItem state_list[1]; /**< Device information of connected LiDAR units. */
|
||||||
|
} HubQueryLidarStatusResponse;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The request body of toggling the LiDAR units rain and fog mode.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t count; /**< Number of LiDAR units connected to the Livox Hub. */
|
||||||
|
RainFogSuppressRequestItem lidar_cfg_list[1]; /**< Command data of connected LiDAR units. */
|
||||||
|
} HubRainFogSuppressRequest;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The response body of toggling the LiDAR units rain and fog mode.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t ret_code; /**< Return code. */
|
||||||
|
uint8_t count; /**< Count of ret_state_list. */
|
||||||
|
ReturnCode ret_state_list[1]; /**< Return code */
|
||||||
|
} HubRainFogSuppressResponse;
|
||||||
|
|
||||||
|
#pragma pack()
|
||||||
|
|
||||||
|
#endif // LIVOX_DEF_H_
|
||||||
499
livox_ros_driver/lib_backup/livox_sdk.h
Normal file
499
livox_ros_driver/lib_backup/livox_sdk.h
Normal file
@@ -0,0 +1,499 @@
|
|||||||
|
//
|
||||||
|
// The MIT License (MIT)
|
||||||
|
//
|
||||||
|
// Copyright (c) 2019 Livox. All rights reserved.
|
||||||
|
//
|
||||||
|
// Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
// of this software and associated documentation files (the "Software"), to deal
|
||||||
|
// in the Software without restriction, including without limitation the rights
|
||||||
|
// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
// copies of the Software, and to permit persons to whom the Software is
|
||||||
|
// furnished to do so, subject to the following conditions:
|
||||||
|
//
|
||||||
|
// The above copyright notice and this permission notice shall be included in
|
||||||
|
// all copies or substantial portions of the Software.
|
||||||
|
//
|
||||||
|
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||||
|
// SOFTWARE.
|
||||||
|
//
|
||||||
|
|
||||||
|
#ifndef LIVOX_SDK_H_
|
||||||
|
#define LIVOX_SDK_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include "livox_def.h"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Return SDK's version information in a numeric form.
|
||||||
|
* @param version Pointer to a version structure for returning the version information.
|
||||||
|
*/
|
||||||
|
void GetLivoxSdkVersion(LivoxSdkVersion *version);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Initialize the SDK.
|
||||||
|
* @return true if successfully initialized, otherwise false.
|
||||||
|
*/
|
||||||
|
bool Init();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Start the device scanning routine which runs on a separate thread.
|
||||||
|
* @return true if successfully started, otherwise false.
|
||||||
|
*/
|
||||||
|
bool Start();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Uninitialize the SDK.
|
||||||
|
*/
|
||||||
|
void Uninit();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Save the log file.
|
||||||
|
*/
|
||||||
|
void SaveLoggerFile();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @c SetBroadcastCallback response callback function.
|
||||||
|
* @param info information of the broadcast device, becomes invalid after the function returns.
|
||||||
|
*/
|
||||||
|
typedef void (*DeviceBroadcastCallback)(const BroadcastDeviceInfo *info);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set the callback of listening device broadcast message. When broadcast message is received from Livox Hub/LiDAR, cb
|
||||||
|
* is called.
|
||||||
|
* @param cb callback for device broadcast.
|
||||||
|
*/
|
||||||
|
void SetBroadcastCallback(DeviceBroadcastCallback cb);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @c SetDeviceStateUpdateCallback response callback function.
|
||||||
|
* @param device information of the connected device.
|
||||||
|
* @param type the update type that indicates connection/disconnection of the device or change of working state.
|
||||||
|
*/
|
||||||
|
typedef void (*DeviceStateUpdateCallback)(const DeviceInfo *device, DeviceEvent type);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Add a callback for device connection or working state changing event.
|
||||||
|
* @note Livox SDK supports two hardware connection modes. 1: Directly connecting to the LiDAR device; 2. Connecting to
|
||||||
|
* the LiDAR device(s) via the Livox Hub. In the first mode, connection/disconnection of every LiDAR unit is reported by
|
||||||
|
* this callback. In the second mode, only connection/disconnection of the Livox Hub is reported by this callback. If
|
||||||
|
* you want to get information of the LiDAR unit(s) connected to hub, see \ref HubQueryLidarInformation.
|
||||||
|
* @note 3 conditions can trigger this callback:
|
||||||
|
* 1. Connection and disconnection of device.
|
||||||
|
* 2. A change of device working state.
|
||||||
|
* 3. An error occurs.
|
||||||
|
* @param cb callback for device connection/disconnection.
|
||||||
|
*/
|
||||||
|
void SetDeviceStateUpdateCallback(DeviceStateUpdateCallback cb);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add a broadcast code to the connecting list and only devices with broadcast code in this list will be connected. The
|
||||||
|
* broadcast code is unique for every device.
|
||||||
|
* @param broadcast_code device's broadcast code.
|
||||||
|
* @param handle device handle. For Livox Hub, the handle is always 31; for LiDAR units connected to the Livox Hub,
|
||||||
|
* the corresponding handle is (slot-1)*3+id-1.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t AddHubToConnect(const char *broadcast_code, uint8_t *handle);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add a broadcast code to the connecting list and only devices with broadcast code in this list will be connected. The
|
||||||
|
* broadcast code is unique for every device.
|
||||||
|
* @param broadcast_code device's broadcast code.
|
||||||
|
* @param handle device handle. The handle is the same as the order calling AddLidarToConnect starting from 0.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t AddLidarToConnect(const char *broadcast_code, uint8_t *handle);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Get all connected devices' information.
|
||||||
|
* @param devices list of connected devices' information.
|
||||||
|
* @param size number of devices connected.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t GetConnectedDevices(DeviceInfo *devices, uint8_t *size);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Function type of callback that queries device's information.
|
||||||
|
* @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref ResponseStatus for other
|
||||||
|
* error code.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param response response from the device.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
*/
|
||||||
|
typedef void (*DeviceInformationCallback)(uint8_t status,
|
||||||
|
uint8_t handle,
|
||||||
|
DeviceInformationResponse *response,
|
||||||
|
void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Command to query device's information.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t QueryDeviceInformation(uint8_t handle, DeviceInformationCallback cb, void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Callback function for receiving point cloud data.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param data device's data.
|
||||||
|
* @param data_num number of points in data.
|
||||||
|
*/
|
||||||
|
typedef void (*DataCallback)(uint8_t handle, LivoxEthPacket *data, uint32_t data_num);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set the callback to receive point cloud data. Only one callback is supported for a specific device. Set the point
|
||||||
|
* cloud data callback before beginning sampling.
|
||||||
|
* @param cb callback to receive point cloud data.
|
||||||
|
*/
|
||||||
|
void SetDataCallback(uint8_t handle, DataCallback cb);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Function type of callback with 1 byte of response.
|
||||||
|
* @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref ResponseStatus for other
|
||||||
|
* error code.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param response response from the device.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
*/
|
||||||
|
typedef void (*CommonCommandCallback)(uint8_t status, uint8_t handle, uint8_t response, void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Start hub sampling.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t HubStartSampling(CommonCommandCallback cb, void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Stop the Livox Hub's sampling.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t HubStopSampling(CommonCommandCallback cb, void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Get the LiDAR unit handle used in the Livox Hub data callback function from slot and id.
|
||||||
|
* @param slot Livox Hub's slot.
|
||||||
|
* @param id Livox Hub's id.
|
||||||
|
* @return LiDAR unit handle.
|
||||||
|
*/
|
||||||
|
uint8_t HubGetLidarHandle(uint8_t slot, uint8_t id);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Command to change point cloud coordinate system to cartesian coordinate.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t SetCartesianCoordinate(uint8_t handle, CommonCommandCallback cb, void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Change point cloud coordinate system to spherical coordinate.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t SetSphericalCoordinate(uint8_t handle, CommonCommandCallback cb, void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Callback of the error status message.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param response response from the device.
|
||||||
|
*/
|
||||||
|
typedef void (*ErrorMessageCallback)(uint8_t handle, ErrorMessage *message);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Add error status callback for the device.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t SetErrorMessageCallback(uint8_t handle, ErrorMessageCallback cb);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set device's IP mode.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param req request sent to device.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t SetStaticDynamicIP(uint8_t handle,
|
||||||
|
SetDeviceIPModeRequest *req,
|
||||||
|
CommonCommandCallback cb,
|
||||||
|
void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Callback function that gets device's IP information.
|
||||||
|
* @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref ResponseStatus for other
|
||||||
|
* error code.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param response response from the device.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
*/
|
||||||
|
typedef void (*GetDeviceIPInformationCallback)(uint8_t status,
|
||||||
|
uint8_t handle,
|
||||||
|
GetDeviceIPModeResponse *response,
|
||||||
|
void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Get device's IP mode.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t GetDeviceIPInformation(uint8_t handle, GetDeviceIPInformationCallback cb, void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @c HubQueryLidarInformation response callback function.
|
||||||
|
* @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref ResponseStatus for other
|
||||||
|
* error code.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param response response from the device.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
*/
|
||||||
|
typedef void (*HubQueryLidarInformationCallback)(uint8_t status,
|
||||||
|
uint8_t handle,
|
||||||
|
HubQueryLidarInformationResponse *response,
|
||||||
|
void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Query the information of LiDARs connected to the hub.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t HubQueryLidarInformation(HubQueryLidarInformationCallback cb, void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @c HubSetMode response callback function.
|
||||||
|
* @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref ResponseStatus for other
|
||||||
|
* error code.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param response response from the device.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
*/
|
||||||
|
typedef void (*HubSetModeCallback)(uint8_t status, uint8_t handle, HubSetModeResponse *response, void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set the mode of LiDAR unit connected to the Livox Hub.
|
||||||
|
* @param req mode configuration of LiDAR units.
|
||||||
|
* @param length length of req.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t HubSetMode(HubSetModeRequest *req, uint16_t length, HubSetModeCallback cb, void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @c HubQueryLidarStatus response callback function.
|
||||||
|
* @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref ResponseStatus for other
|
||||||
|
* error code.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param response response from the device.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
*/
|
||||||
|
typedef void (*HubQueryLidarStatusCallback)(uint8_t status, uint8_t handle, HubQueryLidarStatusResponse *response, void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Get the state of LiDAR units connected to the Livox Hub.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t HubQueryLidarStatus(HubQueryLidarStatusCallback cb, void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Toggle the power supply of designated slots.
|
||||||
|
* @param req request whether to enable or disable the power of designated slots.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
|
||||||
|
uint8_t HubControlSlotPower(HubControlSlotPowerRequest *req, CommonCommandCallback cb, void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @c HubSetExtrinsicParameter response callback function.
|
||||||
|
* @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref ResponseStatus for other
|
||||||
|
* error code.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param response response from the device.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
*/
|
||||||
|
typedef void (*HubSetExtrinsicParameterCallback)(uint8_t status,
|
||||||
|
uint8_t handle,
|
||||||
|
HubSetExtrinsicParameterResponse *response,
|
||||||
|
void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set extrinsic parameters of LiDAR units connected to the Livox Hub.
|
||||||
|
* @param req the parameters to write.
|
||||||
|
* @param length the request's length.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t HubSetExtrinsicParameter(HubSetExtrinsicParameterRequest *req,
|
||||||
|
uint16_t length,
|
||||||
|
HubSetExtrinsicParameterCallback cb,
|
||||||
|
void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @c HubGetExtrinsicParameter response callback function.
|
||||||
|
* @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref ResponseStatus for other
|
||||||
|
* error code.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param response response from the device.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
*/
|
||||||
|
typedef void (*HubGetExtrinsicParameterCallback)(uint8_t status,
|
||||||
|
uint8_t handle,
|
||||||
|
HubGetExtrinsicParameterResponse *response,
|
||||||
|
void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Get extrinsic parameters of LiDAR units connected to the Livox Hub.
|
||||||
|
* @param req the LiDAR units broadcast code list.
|
||||||
|
* @param length the request's length.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t HubGetExtrinsicParameter(HubGetExtrinsicParameterRequest *req,
|
||||||
|
uint16_t length,
|
||||||
|
HubGetExtrinsicParameterCallback cb,
|
||||||
|
void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Turn on or off the calculation of extrinsic parameters.
|
||||||
|
* @param enable the request whether enable or disable calculating the extrinsic parameters.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
|
||||||
|
uint8_t HubExtrinsicParameterCalculation(bool enable, CommonCommandCallback cb, void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @c HubRainFogSuppress response callback function.
|
||||||
|
* @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref ResponseStatus for other
|
||||||
|
* error code.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param response response from the device.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
*/
|
||||||
|
typedef void (*HubRainFogSuppressCallback)(uint8_t status,
|
||||||
|
uint8_t handle,
|
||||||
|
HubRainFogSuppressResponse *response,
|
||||||
|
void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Toggling the rain and fog mode for lidars connected to the hub.
|
||||||
|
* @param req the request whether open or close the rain and fog mode.
|
||||||
|
* @param length the request's length.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t HubRainFogSuppress(HubRainFogSuppressRequest *req,
|
||||||
|
uint16_t length,
|
||||||
|
HubRainFogSuppressCallback cb,
|
||||||
|
void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Start LiDAR sampling.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t LidarStartSampling(uint8_t handle, CommonCommandCallback cb, void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Stop LiDAR sampling.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t LidarStopSampling(uint8_t handle, CommonCommandCallback cb, void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set LiDAR mode.
|
||||||
|
* @note Successful callback function status only means LiDAR successfully starting the changing process of mode.
|
||||||
|
* You need to observe the actually change of mode in DeviceStateUpdateCallback function.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param mode the mode to change.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t LidarSetMode(uint8_t handle, LidarMode mode, CommonCommandCallback cb, void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set LiDAR extrinsic parameters.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param param the parameters to write.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t LidarSetExtrinsicParameter(uint8_t handle,
|
||||||
|
LidarSetExtrinsicParameterRequest *req,
|
||||||
|
CommonCommandCallback cb,
|
||||||
|
void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @c LidarGetExtrinsicParameter response callback function.
|
||||||
|
* @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref ResponseStatus for other
|
||||||
|
* error code.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param response response from the device.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
*/
|
||||||
|
typedef void (*LidarGetExtrinsicParameterCallback)(uint8_t status,
|
||||||
|
uint8_t handle,
|
||||||
|
LidarGetExtrinsicParameterResponse *response,
|
||||||
|
void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Get LiDAR extrinsic parameters.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t LidarGetExtrinsicParameter(uint8_t handle, LidarGetExtrinsicParameterCallback cb, void *client_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable and disable the rain/fog suppression.
|
||||||
|
* @param handle device handle.
|
||||||
|
* @param cb callback for the command.
|
||||||
|
* @param client_data user data associated with the command.
|
||||||
|
* @return kStatusSuccess on successful return, see \ref ResponseStatus for other error code.
|
||||||
|
*/
|
||||||
|
uint8_t LidarRainFogSuppress(uint8_t handle, bool enable, CommonCommandCallback cb, void *client_data);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // LIVOX_SDK_H_
|
||||||
Reference in New Issue
Block a user