|

INTRODUCTION
Overview
Download and Install
Documentation
Publications
REPOSITORY
Libraries
DEVELOPER
Dev Guide
Dashboard
PEOPLE
Contributors
Users

Project
Download
Mailing lists
|
|
|
urg_nz::urg_laser Class ReferenceURG laser scanner class.
More...
#include <urg_nz.h>
List of all members.
|
Public Member Functions |
| urg_laser (void) |
| Constructor for URG laser scanner class.
|
| ~urg_laser (void) |
| Destructor for URG laser scanner class.
|
void | Open (const char *port_name, bool use_serial, int baud) |
| Open a laser scanner on the specified port.
|
void | Close (void) |
| Close the laser scanner connection.
|
bool | PortOpen (void) |
| Check if the port to the laser scanner is open.
|
int | ChangeBaud (int curr_baud, int new_baud) |
| Change the baud rate of the connection.
|
void | SetTimeOut (int timeout) |
| Set the time out for reads performed when talking to the laser.
|
unsigned int | GetReadings (urg_nz_laser_readings_t *readings, unsigned int min_i=0, unsigned int max_i=MAX_READINGS) |
| Retrieve a set of range readings from the scanner. Ranges are returned in millimetres.
|
int | GetIDInfo (void) |
| Get the laser scanner identification information.
|
void | GetSensorConfig (urg_nz_laser_config_t *cfg) |
| Get the laser scanner configuration (resolution, scan angles, etc.).
|
int | GetSCIPVersion (void) |
| Get the protocol version used by the connected laser scanner.
|
void | SetVerbose (bool verbose_mode) |
| Turns on and off printing of information to the console. Default is off.
|
Detailed Description
URG laser scanner class.
Provides an interface for interacting with a Hokuyo URG laser scanner.
To use a serial connection, ensure that you do not also have a USB cable connected, as this will force the scanner into USB mode, preventing the serial connection from functioning correctly.
All functions may throw instances of urg_nz_exception.
Member Function Documentation
int urg_laser::ChangeBaud |
( |
int |
curr_baud, |
|
|
int |
new_baud | |
|
) |
| | |
Change the baud rate of the connection.
Supported baud rates are 19200, 57600 and 115200. Not applicable to USB connections.
Note: Not tested with SCIP protocol version 2.
- Parameters:
-
| curr_baud | The current baud rate of the connection. |
| new_baud | The new baud rate to change the connection to. |
- Returns:
- 0 on success, non-zero for non-fatal failure. Fatal errors will throw an exception.
int urg_laser::GetIDInfo |
( |
void |
|
) |
|
Get the laser scanner identification information.
- Returns:
- The serial number of the laser scanner.
Retrieve a set of range readings from the scanner. Ranges are returned in millimetres.
The scan is a series of discrete values. They can be indexed, starting at 0 and going up to MAX_READINGS. A subset of these values only can be returned using min_i and max_i.
- Parameters:
-
| readings | Pointer to a urg_laser_readings_t structure to store the data in. |
| min_i | The minimum scan index to retrieve. Must be at least 0. Default is 0. |
| max_i | The maximum scan index to retrieve. Must be no greater than MAX_READINGS. Default is MAX_READINGS. |
- Returns:
- The number of range readings read.
int urg_laser::GetSCIPVersion |
( |
void |
|
) |
|
Get the protocol version used by the connected laser scanner.
Old firmware revisions support protocol SCIP1.0, and a max range of 4 meters. Since firmware revision 3.0.00, it's called SCIP2.0, and the max range is 5.6 meters.
- Returns:
- The protocol version in use.
Get the laser scanner configuration (resolution, scan angles, etc.).
- Parameters:
-
| cfg | Pointer to a urg_laser_config_t structure to store the configuration in. |
void urg_laser::Open |
( |
const char * |
port_name, |
|
|
bool |
use_serial, |
|
|
int |
baud | |
|
) |
| | |
Open a laser scanner on the specified port.
Supported baud rates for RS232 connections are 19200, 57600 and 115200. Baud rate is not applicable to USB connections.
- Parameters:
-
| PortName | Fully-qualified path to the port the scanner is connected to. |
| use_serial | Use a serial connection. The alternative is termios. |
| baud | Baud rate for serial connections. |
bool urg_laser::PortOpen |
( |
void |
|
) |
|
Check if the port to the laser scanner is open.
- Returns:
- true if the port is open, false otherwise.
void urg_nz::urg_laser::SetTimeOut |
( |
int |
timeout |
) |
[inline] |
Set the time out for reads performed when talking to the laser.
A large number of polls are performed while talking to the laser scanner to look for data, for example when getting scan data from it. This sets the timeout, in milliseconds, to use for these polls. Set it to a negative value for no timeout.
The default value is -1.
- Parameters:
-
| timeout | The time out for reads, in milliseconds. |
void urg_nz::urg_laser::SetVerbose |
( |
bool |
verbose_mode |
) |
[inline] |
Turns on and off printing of information to the console. Default is off.
- Parameters:
-
| verbose_mode | Set verbose mode on or off. |
The documentation for this class was generated from the following files:
|
|