Skip to content

Commit

Permalink
Support saving debug point cloud of Hap.
Browse files Browse the repository at this point in the history
Support setting the default work mode after boot of Hap.
  • Loading branch information
louie.xu committed Feb 18, 2024
1 parent dc361aa commit 6a94015
Show file tree
Hide file tree
Showing 9 changed files with 58 additions and 8 deletions.
5 changes: 5 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,11 @@
# Changelog

All notable changes to Livox-SDK2 will be documentd in this file.
## [1.2.5]
### Added

- Support saving debug point cloud of Hap.
- Support setting the default work mode after boot of Hap.

## [1.2.4]
### Added
Expand Down
9 changes: 9 additions & 0 deletions include/livox_lidar_api.h
Original file line number Diff line number Diff line change
Expand Up @@ -446,6 +446,15 @@ livox_status SetLivoxLidarDebugPointCloud(uint32_t handle, bool enable, LivoxLid
*/
livox_status SetLivoxLidarRmcSyncTime(uint32_t handle, const char* rmc, uint16_t rmc_length, LivoxLidarRmcSyncTimeCallBack cb, void* client_data);

/**
* Set LiDAR work mode after boot.
* @param handle device handle.
* @param work_mode lidar work mode after boot.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status SetLivoxLidarWorkModeAfterBoot(const uint32_t handle,const LivoxLidarWorkModeAfterBoot work_mode, LivoxLidarAsyncControlCallback cb, void* client_data);
/*******Upgrade Module***********/

/**
Expand Down
13 changes: 10 additions & 3 deletions include/livox_lidar_def.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,9 +31,9 @@

#pragma pack(1)

#define LIVOX_LIDAR_SDK_MAJOR_VERSION 3
#define LIVOX_LIDAR_SDK_MINOR_VERSION 1
#define LIVOX_LIDAR_SDK_PATCH_VERSION 1
#define LIVOX_LIDAR_SDK_MAJOR_VERSION 1
#define LIVOX_LIDAR_SDK_MINOR_VERSION 2
#define LIVOX_LIDAR_SDK_PATCH_VERSION 5

#define kBroadcastCodeSize 16

Expand Down Expand Up @@ -90,6 +90,7 @@ typedef enum {
kKeyFovCfgEn = 0x0017,
kKeyDetectMode = 0x0018,
kKeyFuncIoCfg = 0x0019,
kKeyWorkModeAfterBoot = 0x0020,
kKeyWorkMode = 0x001A,
kKeyGlassHeat = 0x001B,
kKeyImuDataEn = 0x001C,
Expand Down Expand Up @@ -255,6 +256,12 @@ typedef enum {
kLivoxLidarUpgrade = 0x08
} LivoxLidarWorkMode;

typedef enum {
kLivoxLidarWorkModeAfterBootDefault = 0x00,
kLivoxLidarWorkModeAfterBootNormal = 0x01,
kLivoxLidarWorkModeAfterBootWakeUp = 0x02
} LivoxLidarWorkModeAfterBoot;

typedef struct {
float roll_deg;
float pitch_deg;
Expand Down
8 changes: 4 additions & 4 deletions samples/livox_lidar_rmc_time_sync/win/synchro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@

Synchro::Synchro() {
hfile_ = INVALID_HANDLE_VALUE;
is_quite_ = false;
is_quit_ = false;
rmc_buff_.resize(128,0);
}

Expand All @@ -53,13 +53,13 @@ bool Synchro::Start() {
if (!Open()) {
return false;
}
is_quite_ = false;
is_quit_ = false;
listener_ = std::make_shared<std::thread>(&Synchro::IOLoop, this);
return true;
}

void Synchro::Stop() {
is_quite_ = true;
is_quit_ = true;
if (listener_) {
listener_->join();
listener_ = nullptr;
Expand All @@ -70,7 +70,7 @@ void Synchro::Stop() {
void Synchro::IOLoop() {
uint8_t buff[READ_BUF];
size_t size = 0;
while (!is_quite_) {
while (!is_quit_) {
if (0 < (size = Read(buff, READ_BUF))) {
Decode(buff, size);
}
Expand Down
1 change: 1 addition & 0 deletions sdk_core/comm/define.h
Original file line number Diff line number Diff line change
Expand Up @@ -181,6 +181,7 @@ static const uint16_t kHAPPushMsgPort = 56000;
static const uint16_t kHAPPointDataPort = 57000;
static const uint16_t kHAPIMUPort = 58000;
static const uint16_t kHAPLogPort = 59000;
static const uint16_t kHAPDebugPointCloudPort = 60000;

/** kLogPort, which is the log port to be banned. */
static const uint16_t kLogPort = 0;
Expand Down
22 changes: 22 additions & 0 deletions sdk_core/command_handler/command_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -759,6 +759,28 @@ livox_status CommandImpl::SetLivoxLidarRmcSyncTime(uint32_t handle, const char*
MakeCommandCallback<LivoxLidarRmcSyncTimeResponse>(cb, client_data));
}

livox_status CommandImpl::SetLivoxLidarWorkModeAfterBoot(uint32_t handle, LivoxLidarWorkModeAfterBoot work_mode, LivoxLidarAsyncControlCallback cb, void* client_data) {
uint8_t req_buff[kMaxCommandBufferSize] = {0};
uint16_t req_len = 0;

uint16_t key_num = 1;
memcpy(&req_buff[req_len], &key_num, sizeof(key_num));
req_len = sizeof(key_num) + sizeof(uint16_t);

LivoxLidarKeyValueParam * kv = (LivoxLidarKeyValueParam *)&req_buff[req_len];
kv->key = static_cast<uint16_t>(kKeyWorkModeAfterBoot);
kv->length = sizeof(uint8_t);
uint8_t* val_work_mode = reinterpret_cast<uint8_t*>(&kv->value[0]);
*val_work_mode = work_mode;
req_len += sizeof(LivoxLidarKeyValueParam) - 1 + sizeof(uint8_t);

return GeneralCommandHandler::GetInstance().SendCommand(handle,
kCommandIDLidarWorkModeControl,
req_buff,
req_len,
MakeCommandCallback<LivoxLidarAsyncControlResponse>(cb, client_data));
}

// Upgrade
livox_status CommandImpl::LivoxLidarStartUpgrade(uint32_t handle, uint8_t *data, uint16_t length,
LivoxLidarStartUpgradeCallback cb, void* client_data) {
Expand Down
2 changes: 2 additions & 0 deletions sdk_core/command_handler/command_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,8 @@ class CommandImpl {

static livox_status SetLivoxLidarRmcSyncTime(uint32_t handle, const char* rmc, uint16_t rmc_length, LivoxLidarRmcSyncTimeCallBack cb, void* client_data);

static livox_status SetLivoxLidarWorkModeAfterBoot(uint32_t handle, LivoxLidarWorkModeAfterBoot work_mode, LivoxLidarAsyncControlCallback cb, void* client_data);

/*******Upgrade Module***********/
static livox_status LivoxLidarRequestReboot(uint32_t handle, LivoxLidarRebootCallback cb, void* client_data);

Expand Down
2 changes: 1 addition & 1 deletion sdk_core/device_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -473,7 +473,7 @@ void DeviceManager::OnData(socket_t sock, void *client_data) {
return;
}

if (port == kMid360LidarDebugPointCloudPort) {
if (port == kMid360LidarDebugPointCloudPort || port == kHAPDebugPointCloudPort) {
DebugPointCloudManager::GetInstance().Handler(handle, port, (uint8_t*)(buf.get()), size);
}

Expand Down
4 changes: 4 additions & 0 deletions sdk_core/livox_lidar_sdk.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -298,6 +298,10 @@ livox_status SetLivoxLidarRmcSyncTime(uint32_t handle, const char* rmc, uint16_t
return CommandImpl::SetLivoxLidarRmcSyncTime(handle, rmc, rmc_length, cb, client_data);
}

livox_status SetLivoxLidarWorkModeAfterBoot(const uint32_t handle,const LivoxLidarWorkModeAfterBoot work_mode, LivoxLidarAsyncControlCallback cb, void* client_data){
return CommandImpl::SetLivoxLidarWorkModeAfterBoot(handle, work_mode, cb, client_data);
}

// reset lidar
livox_status LivoxLidarRequestReset(uint32_t handle, LivoxLidarResetCallback cb, void* client_data) {
return CommandImpl::LivoxLidarRequestReset(handle, cb, client_data);
Expand Down

0 comments on commit 6a94015

Please sign in to comment.