#include <LaserProc.h>
|
static sensor_msgs::LaserScanPtr | getFirstScan (const sensor_msgs::MultiEchoLaserScan &msg) |
|
static sensor_msgs::LaserScanPtr | getLastScan (const sensor_msgs::MultiEchoLaserScan &msg) |
|
static sensor_msgs::LaserScanPtr | getMostIntenseScan (const sensor_msgs::MultiEchoLaserScan &msg) |
|
|
static void | fillLaserScan (const sensor_msgs::MultiEchoLaserScan &msg, sensor_msgs::LaserScan &out) |
| I'm assuming all laserscanners/drivers output the ranges in order received (shortest to longest). If this is not the case, please make an issue. More...
|
|
static size_t | getFirstValue (const sensor_msgs::LaserEcho &ranges, float &range) |
| I'm assuming all laserscanners/drivers output the ranges in order received (shortest to longest). If this is not the case, please make an issue. More...
|
|
static size_t | getLastValue (const sensor_msgs::LaserEcho &ranges, float &range) |
|
static void | getMostIntenseValue (const sensor_msgs::LaserEcho &ranges, const sensor_msgs::LaserEcho &intensities, float &range, float &intensity) |
|
Definition at line 49 of file LaserProc.h.
void LaserProc::fillLaserScan |
( |
const sensor_msgs::MultiEchoLaserScan & |
msg, |
|
|
sensor_msgs::LaserScan & |
out |
|
) |
| |
|
staticprivate |
I'm assuming all laserscanners/drivers output the ranges in order received (shortest to longest). If this is not the case, please make an issue.
Definition at line 96 of file LaserProc.cpp.
sensor_msgs::LaserScanPtr LaserProc::getFirstScan |
( |
const sensor_msgs::MultiEchoLaserScan & |
msg | ) |
|
|
static |
size_t LaserProc::getFirstValue |
( |
const sensor_msgs::LaserEcho & |
ranges, |
|
|
float & |
range |
|
) |
| |
|
staticprivate |
I'm assuming all laserscanners/drivers output the ranges in order received (shortest to longest). If this is not the case, please make an issue.
Definition at line 108 of file LaserProc.cpp.
sensor_msgs::LaserScanPtr LaserProc::getLastScan |
( |
const sensor_msgs::MultiEchoLaserScan & |
msg | ) |
|
|
static |
size_t LaserProc::getLastValue |
( |
const sensor_msgs::LaserEcho & |
ranges, |
|
|
float & |
range |
|
) |
| |
|
staticprivate |
sensor_msgs::LaserScanPtr LaserProc::getMostIntenseScan |
( |
const sensor_msgs::MultiEchoLaserScan & |
msg | ) |
|
|
static |
void LaserProc::getMostIntenseValue |
( |
const sensor_msgs::LaserEcho & |
ranges, |
|
|
const sensor_msgs::LaserEcho & |
intensities, |
|
|
float & |
range, |
|
|
float & |
intensity |
|
) |
| |
|
staticprivate |
The documentation for this class was generated from the following files: