Skip to content

Commit

Permalink
修改适配T-mini Pro
Browse files Browse the repository at this point in the history
  • Loading branch information
zhanyiaini committed Jul 6, 2022
1 parent 1dde80a commit 355ffa4
Show file tree
Hide file tree
Showing 8 changed files with 314 additions and 15 deletions.
1 change: 1 addition & 0 deletions core/common/DriverInterface.h
Original file line number Diff line number Diff line change
Expand Up @@ -474,6 +474,7 @@ class DriverInterface {

YDLIDAR_TSA = 130,/**< TSA LiDAR Model. */
YDLIDAR_Tmini = 140,/**< Tmini LiDAR Model. */
YDLIDAR_TminiPRO = 150,/**< Tmini PRO LiDAR Model. */

YDLIDAR_T15 = 200,/**< T15 LiDAR Model. */

Expand Down
2 changes: 1 addition & 1 deletion core/common/ydlidar_def.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ typedef enum {
TYPE_TOF = 0,/**< TG TX LiDAR.*/
TYPE_TRIANGLE = 1,/**< G4. G6. G2 LiDAR.*/
TYPE_TOF_NET = 2,/**< T15 LiDAR.*/
TYPE_GS = 3, //GS2
TYPE_GS = 3, //GS系列雷达(目前只有GS2)
TYPE_Tail,
} LidarTypeID;

Expand Down
7 changes: 5 additions & 2 deletions core/common/ydlidar_help.h
Original file line number Diff line number Diff line change
Expand Up @@ -188,7 +188,10 @@ inline std::string lidarModelToString(int model) {
name = "TSA";
break;
case DriverInterface::YDLIDAR_Tmini:
name = "Tmini";
name = "T-mini";
break;
case DriverInterface::YDLIDAR_TminiPRO:
name = "T-mini Pro";
break;

case DriverInterface::YDLIDAR_T15:
Expand Down Expand Up @@ -381,7 +384,7 @@ inline bool isSupportLidar(int model)
if (model < DriverInterface::YDLIDAR_F4 ||
(model > DriverInterface::YDLIDAR_G7 &&
model < DriverInterface::YDLIDAR_GS2) ||
(model > DriverInterface::YDLIDAR_Tmini &&
(model > DriverInterface::YDLIDAR_TminiPRO &&
model < DriverInterface::YDLIDAR_T15))
{
return false;
Expand Down
2 changes: 1 addition & 1 deletion core/common/ydlidar_protocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@

#define LIDAR_CMD_SET_HEART_BEAT 0xD9

//gs2
//GS2命令
#define GS_LIDAR_CMD_GET_ADDRESS 0x60
#define GS_LIDAR_CMD_GET_PARAMETER 0x61
#define GS_LIDAR_CMD_GET_VERSION 0x62
Expand Down
6 changes: 3 additions & 3 deletions doc/howto/how_to_build_and_install.md
Original file line number Diff line number Diff line change
Expand Up @@ -96,12 +96,12 @@ Three samples are provided in samples, which demonstrate how to configure YDLida
![](images/sequence.png)

### Ubuntu 18.04/16.04 /14.04 LTS
For Ubuntun 18.04/16.04/14.04 LTS, run the *ydlidar_test* if connect with the Triangle LiDAR unit(s) or TOF LiDAR unit(s):
For Ubuntun 18.04/16.04/14.04 LTS, run the *tri_test* if connect with the Triangle LiDAR unit(s) or TOF LiDAR unit(s):
```
./ydlidar_test
./tri_test
```
### Windows 7/10
After compiling the YDLidar SDK as shown in section 4.1.2, you can find `ydlidar_test.exe` in the {YDLidar-SDK}\build\Debug or {YDLidar-SDK}\build\Release folder, respectively, which can be run directly.
After compiling the YDLidar SDK as shown in section 4.1.2, you can find `tri_test.exe` in the {YDLidar-SDK}\build\Debug or {YDLidar-SDK}\build\Release folder, respectively, which can be run directly.

Then you can see SDK initializing the information as below:

Expand Down
291 changes: 291 additions & 0 deletions samples/tmini_test.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,291 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2018, EAIBOT, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
#include "CYdLidar.h"
#include <iostream>
#include <string>
#include <algorithm>
#include <cctype>
using namespace std;
using namespace ydlidar;

#if defined(_MSC_VER)
#pragma comment(lib, "ydlidar_sdk.lib")
#endif

/**
* @brief ydlidar test
* @param argc
* @param argv
* @return
* @par Flow chart
* Step1: instance CYdLidar.\n
* Step2: set paramters.\n
* Step3: initialize SDK and LiDAR.(::CYdLidar::initialize)\n
* Step4: Start the device scanning routine which runs on a separate thread and enable motor.(::CYdLidar::turnOn)\n
* Step5: Get the LiDAR Scan Data.(::CYdLidar::doProcessSimple)\n
* Step6: Stop the device scanning thread and disable motor.(::CYdLidar::turnOff)\n
* Step7: Uninitialize the SDK and Disconnect the LiDAR.(::CYdLidar::disconnecting)\n
*/

int main(int argc, char *argv[]) {
printf("__ ______ _ ___ ____ _ ____ \n");
printf("\\ \\ / / _ \\| | |_ _| _ \\ / \\ | _ \\ \n");
printf(" \\ V /| | | | | | || | | |/ _ \\ | |_) | \n");
printf(" | | | |_| | |___ | || |_| / ___ \\| _ < \n");
printf(" |_| |____/|_____|___|____/_/ \\_\\_| \\_\\ \n");
printf("\n");
fflush(stdout);
std::string port;
ydlidar::os_init();

std::map<std::string, std::string> ports =
ydlidar::lidarPortList();
std::map<std::string, std::string>::iterator it;

if (ports.size() == 1) {
port = ports.begin()->second;
} else {
int id = 0;

for (it = ports.begin(); it != ports.end(); it++) {
printf("%d. %s\n", id, it->first.c_str());
id++;
}

if (ports.empty()) {
printf("Not Lidar was detected. Please enter the lidar serial port:");
std::cin >> port;
} else {
while (ydlidar::os_isOk()) {
printf("Please select the lidar port:");
std::string number;
std::cin >> number;

if ((size_t)atoi(number.c_str()) >= ports.size()) {
continue;
}

it = ports.begin();
id = atoi(number.c_str());

while (id) {
id--;
it++;
}

port = it->second;
break;
}
}
}

int baudrate = 230400;
std::map<int, int> baudrateList;
baudrateList[0] = 115200;
baudrateList[1] = 128000;
baudrateList[2] = 153600;
baudrateList[3] = 230400;
baudrateList[4] = 460800;
baudrateList[5] = 512000;

printf("Baudrate:\n");

for (std::map<int, int>::iterator it = baudrateList.begin();
it != baudrateList.end(); it++) {
printf("%d. %d\n", it->first, it->second);
}

while (ydlidar::os_isOk()) {
printf("Please select the lidar baudrate:");
std::string number;
std::cin >> number;

if ((size_t)atoi(number.c_str()) > baudrateList.size()) {
continue;
}

baudrate = baudrateList[atoi(number.c_str())];
break;
}

if (!ydlidar::os_isOk()) {
return 0;
}

bool isSingleChannel = false;
std::string input_channel;
printf("Whether the Lidar is one-way communication[yes/no]:");
std::cin >> input_channel;
std::transform(input_channel.begin(), input_channel.end(),
input_channel.begin(),
[](unsigned char c) {
return std::tolower(c); // correct
});

if (input_channel.find("y") != std::string::npos) {
isSingleChannel = true;
}

if (!ydlidar::os_isOk()) {
return 0;
}

std::string input_frequency;

float frequency = 8.0;

while (ydlidar::os_isOk() && !isSingleChannel) {
printf("Please enter the lidar scan frequency[5-12]:");
std::cin >> input_frequency;
frequency = atof(input_frequency.c_str());

if (frequency <= 12 && frequency >= 5.0) {
break;
}

fprintf(stderr,
"Invalid scan frequency,The scanning frequency range is 5 to 12 HZ, Please re-enter.\n");
}

if (!ydlidar::os_isOk()) {
return 0;
}

CYdLidar laser;
//////////////////////string property/////////////////
/// lidar port
laser.setlidaropt(LidarPropSerialPort, port.c_str(), port.size());
/// ignore array
std::string ignore_array;
ignore_array.clear();
laser.setlidaropt(LidarPropIgnoreArray, ignore_array.c_str(),
ignore_array.size());

//////////////////////int property/////////////////
/// lidar baudrate
laser.setlidaropt(LidarPropSerialBaudrate, &baudrate, sizeof(int));
/// tof lidar
int optval = TYPE_TRIANGLE;
laser.setlidaropt(LidarPropLidarType, &optval, sizeof(int));
/// device type
optval = YDLIDAR_TYPE_SERIAL;
laser.setlidaropt(LidarPropDeviceType, &optval, sizeof(int));
/// sample rate
optval = isSingleChannel ? 3 : 4;
laser.setlidaropt(LidarPropSampleRate, &optval, sizeof(int));
/// abnormal count
optval = 4;
laser.setlidaropt(LidarPropAbnormalCheckCount, &optval, sizeof(int));
/// Intenstiy bit count
optval = 8;
laser.setlidaropt(LidarPropIntenstiyBit, &optval, sizeof(int));

//////////////////////bool property/////////////////
/// fixed angle resolution
bool b_optvalue = false;
laser.setlidaropt(LidarPropFixedResolution, &b_optvalue, sizeof(bool));
/// rotate 180
laser.setlidaropt(LidarPropReversion, &b_optvalue, sizeof(bool));
/// Counterclockwise
laser.setlidaropt(LidarPropInverted, &b_optvalue, sizeof(bool));
b_optvalue = true;
laser.setlidaropt(LidarPropAutoReconnect, &b_optvalue, sizeof(bool));
/// one-way communication
laser.setlidaropt(LidarPropSingleChannel, &isSingleChannel, sizeof(bool));
/// intensity
b_optvalue = true;
laser.setlidaropt(LidarPropIntenstiy, &b_optvalue, sizeof(bool));
/// Motor DTR
b_optvalue = true;
laser.setlidaropt(LidarPropSupportMotorDtrCtrl, &b_optvalue, sizeof(bool));
/// HeartBeat
b_optvalue = false;
laser.setlidaropt(LidarPropSupportHeartBeat, &b_optvalue, sizeof(bool));

//////////////////////float property/////////////////
/// unit: °
float f_optvalue = 180.0f;
laser.setlidaropt(LidarPropMaxAngle, &f_optvalue, sizeof(float));
f_optvalue = -180.0f;
laser.setlidaropt(LidarPropMinAngle, &f_optvalue, sizeof(float));
/// unit: m
f_optvalue = 64.f;
laser.setlidaropt(LidarPropMaxRange, &f_optvalue, sizeof(float));
f_optvalue = 0.05f;
laser.setlidaropt(LidarPropMinRange, &f_optvalue, sizeof(float));
/// unit: Hz
laser.setlidaropt(LidarPropScanFrequency, &frequency, sizeof(float));

bool ret = laser.initialize();
if (!ret) {
fprintf(stderr, "Fail to initialize %s\n", laser.DescribeError());
fflush(stderr);
return -1;
}

ret = laser.turnOn();
if (!ret) {
fprintf(stderr, "Fail to start %s\n", laser.DescribeError());
fflush(stderr);
return -1;
}

LaserScan scan;
while (ydlidar::os_isOk())
{
if (laser.doProcessSimple(scan))
{
printf("Scan received at [%lu] %u points is [%f]Hz\n",
scan.stamp / 1000000,
(unsigned int)scan.points.size(),
1.0 / scan.config.scan_time);
// for (size_t i=0; i<scan.points.size(); ++i)
// {
// const LaserPoint& p = scan.points.at(i);
// printf("%d d %f i %f\n", i, p.range, p.intensity);
// }
fflush(stdout);
}
else
{
fprintf(stderr, "Failed to get Lidar Data\n");
fflush(stderr);
}
}

laser.turnOff();
laser.disconnecting();

return 0;
}
18 changes: 11 additions & 7 deletions samples/tri_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -224,7 +224,7 @@ int main(int argc, char *argv[]) {
/// one-way communication
laser.setlidaropt(LidarPropSingleChannel, &isSingleChannel, sizeof(bool));
/// intensity
b_optvalue = true;
b_optvalue = false;
laser.setlidaropt(LidarPropIntenstiy, &b_optvalue, sizeof(bool));
/// Motor DTR
b_optvalue = true;
Expand All @@ -248,17 +248,21 @@ int main(int argc, char *argv[]) {
laser.setlidaropt(LidarPropScanFrequency, &frequency, sizeof(float));

bool ret = laser.initialize();
if (!ret) {
fprintf(stderr, "Fail to initialize %s\n", laser.DescribeError());
fflush(stderr);
return -1;
}

if (ret) {
ret = laser.turnOn();
} else {
fprintf(stderr, "%s\n", laser.DescribeError());
ret = laser.turnOn();
if (!ret) {
fprintf(stderr, "Fail to start %s\n", laser.DescribeError());
fflush(stderr);
return -1;
}

LaserScan scan;

while (ret && ydlidar::os_isOk())
while (ydlidar::os_isOk())
{
if (laser.doProcessSimple(scan))
{
Expand Down
Loading

0 comments on commit 355ffa4

Please sign in to comment.