Public Member Functions | Protected Attributes | Static Protected Attributes | Private Member Functions | Static Private Member Functions
SickS3000 Class Reference

#include <sicks3000.h>

List of all members.

Public Member Functions

bool Close ()
 Close the port.
bool Open ()
 Open the port.
bool ReadLaser (sensor_msgs::LaserScan &scan)
 Read and process data.
 SickS3000 (std::string port, int baudrate, std::string parity, int datasize)
 Public constructor.
 ~SickS3000 ()

Protected Attributes

char read_buffer_ [READ_BUFFER_SIZE]
bool recognisedScanner
uint8_t * rx_buffer
unsigned int rx_buffer_size
unsigned int rx_count
SerialDevice serial_

Static Protected Attributes

static const size_t READ_BUFFER_SIZE = 2000

Private Member Functions

int ProcessLaserData (sensor_msgs::LaserScan &scan_msg, bool &bValidData)

Static Private Member Functions

static unsigned short CreateCRC (const uint8_t *data, ssize_t len)
static bool SetScannerParams (sensor_msgs::LaserScan &scan, int data_count)

Detailed Description

Definition at line 46 of file sicks3000.h.


Constructor & Destructor Documentation

SickS3000::SickS3000 ( std::string  port,
int  baudrate,
std::string  parity,
int  datasize 
)

Public constructor.

Definition at line 38 of file sicks3000.cc.

Definition at line 50 of file sicks3000.cc.


Member Function Documentation

bool SickS3000::Close ( )

Close the port.

Closes serial port.

Returns:
ERROR
OK

Definition at line 70 of file sicks3000.cc.

unsigned short SickS3000::CreateCRC ( const uint8_t *  data,
ssize_t  len 
) [static, private]

Definition at line 339 of file sicks3000.cc.

bool SickS3000::Open ( )

Open the port.

Open serial port.

Returns:
-1 Error
0 Ok

Definition at line 60 of file sicks3000.cc.

int SickS3000::ProcessLaserData ( sensor_msgs::LaserScan &  scan_msg,
bool &  bValidData 
) [private]

Definition at line 157 of file sicks3000.cc.

bool SickS3000::ReadLaser ( sensor_msgs::LaserScan &  scan)

Read and process data.

Definition at line 127 of file sicks3000.cc.

bool SickS3000::SetScannerParams ( sensor_msgs::LaserScan &  scan,
int  data_count 
) [static, private]

Definition at line 77 of file sicks3000.cc.


Member Data Documentation

Definition at line 89 of file sicks3000.h.

const size_t SickS3000::READ_BUFFER_SIZE = 2000 [static, protected]

Definition at line 88 of file sicks3000.h.

bool SickS3000::recognisedScanner [protected]

Definition at line 81 of file sicks3000.h.

uint8_t* SickS3000::rx_buffer [protected]

Definition at line 84 of file sicks3000.h.

unsigned int SickS3000::rx_buffer_size [protected]

Definition at line 85 of file sicks3000.h.

unsigned int SickS3000::rx_count [protected]

Definition at line 86 of file sicks3000.h.

Definition at line 79 of file sicks3000.h.


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


s3000_laser
Author(s): Roman Navarro Garcia
autogenerated on Sat Jun 8 2019 20:55:59