#include <sicks3000.h>
Public Member Functions | |
int | Close () |
Close the port. | |
int | Open () |
Open the port. | |
void | ReadLaser (sensor_msgs::LaserScan &scan_msg, bool &bValidData) |
Read and process data. | |
SickS3000 (std::string port) | |
Public constructor. | |
~SickS3000 () | |
Protected Attributes | |
int | max_angle |
int | min_angle |
int | mirror |
bool | recognisedScanner |
uint8_t * | rx_buffer |
unsigned int | rx_buffer_size |
unsigned int | rx_count |
int | scan_max_segment |
int | scan_min_segment |
int | scan_res |
int | scan_width |
SerialDevice * | serial |
Private Member Functions | |
unsigned short | CreateCRC (uint8_t *data, ssize_t len) |
int64_t | GetTime () |
int | ProcessLaserData (sensor_msgs::LaserScan &scan_msg, bool &bValidData) |
void | SetScannerParams (sensor_msgs::LaserScan &scan, int data_count) |
Definition at line 47 of file sicks3000.h.
SickS3000::SickS3000 | ( | std::string | port | ) |
Public constructor.
Definition at line 51 of file sicks3000.cc.
Definition at line 68 of file sicks3000.cc.
int SickS3000::Close | ( | ) |
unsigned short SickS3000::CreateCRC | ( | uint8_t * | data, |
ssize_t | len | ||
) | [private] |
Definition at line 317 of file sicks3000.cc.
int64_t SickS3000::GetTime | ( | ) | [private] |
int SickS3000::Open | ( | ) |
int SickS3000::ProcessLaserData | ( | sensor_msgs::LaserScan & | scan_msg, |
bool & | bValidData | ||
) | [private] |
Definition at line 164 of file sicks3000.cc.
void SickS3000::ReadLaser | ( | sensor_msgs::LaserScan & | scan_msg, |
bool & | bValidData | ||
) |
Read and process data.
Definition at line 140 of file sicks3000.cc.
void SickS3000::SetScannerParams | ( | sensor_msgs::LaserScan & | scan, |
int | data_count | ||
) | [private] |
Definition at line 109 of file sicks3000.cc.
int SickS3000::max_angle [protected] |
Definition at line 93 of file sicks3000.h.
int SickS3000::min_angle [protected] |
Definition at line 93 of file sicks3000.h.
int SickS3000::mirror [protected] |
Definition at line 86 of file sicks3000.h.
bool SickS3000::recognisedScanner [protected] |
Definition at line 99 of file sicks3000.h.
uint8_t* SickS3000::rx_buffer [protected] |
Definition at line 102 of file sicks3000.h.
unsigned int SickS3000::rx_buffer_size [protected] |
Definition at line 103 of file sicks3000.h.
unsigned int SickS3000::rx_count [protected] |
Definition at line 104 of file sicks3000.h.
int SickS3000::scan_max_segment [protected] |
Definition at line 97 of file sicks3000.h.
int SickS3000::scan_min_segment [protected] |
Definition at line 97 of file sicks3000.h.
int SickS3000::scan_res [protected] |
Definition at line 89 of file sicks3000.h.
int SickS3000::scan_width [protected] |
Definition at line 89 of file sicks3000.h.
SerialDevice* SickS3000::serial [protected] |
Definition at line 83 of file sicks3000.h.