Static Public Member Functions | Static Private Member Functions
laser_proc::LaserProc Class Reference

#include <LaserProc.h>

List of all members.

Static Public Member Functions

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 Private Member Functions

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.
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.
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)

Detailed Description

Definition at line 49 of file LaserProc.h.


Member Function Documentation

void LaserProc::fillLaserScan ( const sensor_msgs::MultiEchoLaserScan &  msg,
sensor_msgs::LaserScan &  out 
) [static, private]

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]

Definition at line 38 of file LaserProc.cpp.

size_t LaserProc::getFirstValue ( const sensor_msgs::LaserEcho &  ranges,
float &  range 
) [static, private]

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]

Definition at line 59 of file LaserProc.cpp.

size_t LaserProc::getLastValue ( const sensor_msgs::LaserEcho &  ranges,
float &  range 
) [static, private]

Definition at line 120 of file LaserProc.cpp.

sensor_msgs::LaserScanPtr LaserProc::getMostIntenseScan ( const sensor_msgs::MultiEchoLaserScan &  msg) [static]

Definition at line 79 of file LaserProc.cpp.

void LaserProc::getMostIntenseValue ( const sensor_msgs::LaserEcho &  ranges,
const sensor_msgs::LaserEcho &  intensities,
float &  range,
float &  intensity 
) [static, private]

Definition at line 131 of file LaserProc.cpp.


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


laser_proc
Author(s): Chad Rockey
autogenerated on Thu Aug 27 2015 13:47:25