Public Member Functions | Static Public Member Functions | Private Member Functions | Private Attributes | List of all members
ls::LS01B Class Reference

#include <ls01b.h>

Public Member Functions

int getRate ()
 
double getRPM ()
 
int getScan (std::vector< ScanPoint > &points, ros::Time &scan_time, float &scan_duration)
 
int getVersion (std::string &version)
 
bool isHealth ()
 
bool resetHealth ()
 
int setMotorSpeed (int rpm)
 
int setResolution (double resolution)
 
int setScanMode (bool is_continuous)
 
int startScan ()
 
int stopRecvData ()
 
int stopScan ()
 
int switchData (bool use_angle)
 
 ~LS01B ()
 

Static Public Member Functions

static LS01Binstance (std::string port, int baud_rate, double resolution)
 

Private Member Functions

uint16_t checkSum (const uint8_t *p_byte)
 
 LS01B (std::string port, int baud_rate, double resolution=0.25)
 
void recvThread ()
 

Private Attributes

int data_len_
 
bool is_shutdown_
 
bool is_start_
 
boost::mutex mutex_
 
int points_size_
 
ros::Time pre_time_
 
double real_rpm_
 
boost::thread * recv_thread_
 
double resolution_
 
int rpm_
 
int scan_health_
 
std::vector< ScanPointscan_points_
 
std::vector< ScanPointscan_points_bak_
 
LSIOSRserial_
 
ros::Time time_
 
bool use_angle_
 

Detailed Description

Definition at line 30 of file ls01b.h.

Constructor & Destructor Documentation

ls::LS01B::~LS01B ( )

Definition at line 36 of file ls01b.cpp.

ls::LS01B::LS01B ( std::string  port,
int  baud_rate,
double  resolution = 0.25 
)
private

Definition at line 19 of file ls01b.cpp.

Member Function Documentation

uint16_t ls::LS01B::checkSum ( const uint8_t *  p_byte)
private
int ls::LS01B::getRate ( )
double ls::LS01B::getRPM ( )

Definition at line 78 of file ls01b.cpp.

int ls::LS01B::getScan ( std::vector< ScanPoint > &  points,
ros::Time scan_time,
float &  scan_duration 
)

获取雷达数据 poins: 雷达点的数据。类型为ScanPoint数组

Definition at line 62 of file ls01b.cpp.

int ls::LS01B::getVersion ( std::string &  version)

获取软件版本号 version: 返回版本号

Definition at line 72 of file ls01b.cpp.

LS01B * ls::LS01B::instance ( std::string  port,
int  baud_rate,
double  resolution 
)
static

实例化雷达 port: 串口号, baud_rate: 波特率 460800 resolution: 雷达角度分辨率1.0度 0.5度 0.25度

Definition at line 13 of file ls01b.cpp.

bool ls::LS01B::isHealth ( )

判断雷达是否有效

Definition at line 52 of file ls01b.cpp.

void ls::LS01B::recvThread ( )
private

Definition at line 261 of file ls01b.cpp.

bool ls::LS01B::resetHealth ( )

恢复雷达状态

Definition at line 57 of file ls01b.cpp.

int ls::LS01B::setMotorSpeed ( int  rpm)

set the motor spped rpm: round per minute

Definition at line 194 of file ls01b.cpp.

int ls::LS01B::setResolution ( double  resolution)

设置雷达数据分辨率 resolution: 分辨率

Definition at line 216 of file ls01b.cpp.

int ls::LS01B::setScanMode ( bool  is_continuous)

set scan mode. continouse or once is_continuous:

Definition at line 120 of file ls01b.cpp.

int ls::LS01B::startScan ( )

start lidar, System work normally

Definition at line 83 of file ls01b.cpp.

int ls::LS01B::stopRecvData ( )

stop recv data from lidar

Definition at line 146 of file ls01b.cpp.

int ls::LS01B::stopScan ( )

stop lidar, System in sleep mode

Definition at line 102 of file ls01b.cpp.

int ls::LS01B::switchData ( bool  use_angle)

switch angle or intensity in recv data use_angle: true. the angle is chosed false. the intensity is chosed

Definition at line 165 of file ls01b.cpp.

Member Data Documentation

int ls::LS01B::data_len_
private

Definition at line 130 of file ls01b.h.

bool ls::LS01B::is_shutdown_
private

Definition at line 124 of file ls01b.h.

bool ls::LS01B::is_start_
private

Definition at line 125 of file ls01b.h.

boost::mutex ls::LS01B::mutex_
private

Definition at line 122 of file ls01b.h.

int ls::LS01B::points_size_
private

Definition at line 132 of file ls01b.h.

ros::Time ls::LS01B::pre_time_
private

Definition at line 136 of file ls01b.h.

double ls::LS01B::real_rpm_
private

Definition at line 134 of file ls01b.h.

boost::thread* ls::LS01B::recv_thread_
private

Definition at line 121 of file ls01b.h.

double ls::LS01B::resolution_
private

Definition at line 129 of file ls01b.h.

int ls::LS01B::rpm_
private

Definition at line 133 of file ls01b.h.

int ls::LS01B::scan_health_
private

Definition at line 128 of file ls01b.h.

std::vector<ScanPoint> ls::LS01B::scan_points_
private

Definition at line 116 of file ls01b.h.

std::vector<ScanPoint> ls::LS01B::scan_points_bak_
private

Definition at line 117 of file ls01b.h.

LSIOSR* ls::LS01B::serial_
private

Definition at line 120 of file ls01b.h.

ros::Time ls::LS01B::time_
private

Definition at line 137 of file ls01b.h.

bool ls::LS01B::use_angle_
private

Definition at line 126 of file ls01b.h.


The documentation for this class was generated from the following files:


ls01b_v2
Author(s): fu
autogenerated on Sat Sep 28 2019 03:51:19