Public Slots | Signals | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Static Protected Attributes
LaserScanThread Class Reference

#include <laserscanthread.h>

List of all members.

Public Slots

void laserScanCallback (const sensor_msgs::LaserScan::ConstPtr &msg)

Signals

void trianglesFound (std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > *triangles)
void valueChanged ()

Public Member Functions

 LaserScanThread (Abstract_LaserScanner *scanner, double segmentation_lambda, double maxVarianceFilter, double maxAngleDeviation, double variationStep, int variationStepCount)
void stop ()
 ~LaserScanThread ()

Public Attributes

float angle_spread
double * data_avg
double * data_edges
unsigned int data_field_size
double * data_filtered
double * data_raw
double * data_segments
double * dx
float starting_angle

Protected Member Functions

void calculateGaussianMatrix ()
void launchSICK ()
void run ()

Protected Attributes

double * averagedRanges
Eigen::Vector2d * coordinates
std::vector< Eigen::Vector2d,
Eigen::aligned_allocator
< Eigen::Vector2d > > 
edgesfound
double feld [2 *GAUSSIANFIELDSIZE+1]
double * filteredRanges
double gaussFactor
LinearApproximatorlinearApproximator
double markersize = 0.02
double maxAngleDeviation
double maxVarianceFilter = 0.15
ros::NodeHandle nh
double * rotatingAccumulationWindow [AVERAGINGWINDOW]
ros::Publisher scanDataPublisher
Abstract_LaserScannerscanner
double segmentation_lambda = 1.5
ros::Publisher segmentBorderPublisher
ros::Publisher segmentDataPublisher
std::vector< int > segmentdistance
std::vector< float > segments
std::vector< int > segmentsizes
unsigned int stepNumber
double variationStep = 0.006
int variationStepCount = 2

Static Protected Attributes

static constexpr unsigned int AVERAGINGWINDOW = 450
static constexpr unsigned int DETECTIONWINDOW = 10
static constexpr unsigned int GAUSSIANFIELDSIZE = 20
static constexpr double sigma = 1.5

Detailed Description

Definition at line 34 of file laserscanthread.h.


Constructor & Destructor Documentation

LaserScanThread::LaserScanThread ( Abstract_LaserScanner scanner,
double  segmentation_lambda,
double  maxVarianceFilter,
double  maxAngleDeviation,
double  variationStep,
int  variationStepCount 
) [explicit]

Copyright (c) 2016, Aumann Florian, Heller Florian, Meißner Pascal All rights reserved.

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:

1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.

2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.

3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

Definition at line 28 of file laserscanthread.cpp.

Definition at line 79 of file laserscanthread.cpp.


Member Function Documentation

Definition at line 113 of file laserscanthread.cpp.

void LaserScanThread::laserScanCallback ( const sensor_msgs::LaserScan::ConstPtr &  msg) [slot]

Definition at line 142 of file laserscanthread.cpp.

void LaserScanThread::launchSICK ( ) [protected]

Definition at line 133 of file laserscanthread.cpp.

void LaserScanThread::run ( ) [protected]

Definition at line 128 of file laserscanthread.cpp.

Definition at line 106 of file laserscanthread.cpp.

void LaserScanThread::trianglesFound ( std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > *  triangles) [signal]
void LaserScanThread::valueChanged ( ) [signal]

Member Data Documentation

Definition at line 41 of file laserscanthread.h.

double* LaserScanThread::averagedRanges [protected]

Definition at line 63 of file laserscanthread.h.

constexpr unsigned int LaserScanThread::AVERAGINGWINDOW = 450 [static, protected]

Definition at line 54 of file laserscanthread.h.

Eigen::Vector2d* LaserScanThread::coordinates [protected]

Definition at line 66 of file laserscanthread.h.

Definition at line 45 of file laserscanthread.h.

Definition at line 48 of file laserscanthread.h.

Definition at line 40 of file laserscanthread.h.

Definition at line 46 of file laserscanthread.h.

Definition at line 44 of file laserscanthread.h.

Definition at line 47 of file laserscanthread.h.

constexpr unsigned int LaserScanThread::DETECTIONWINDOW = 10 [static, protected]

Definition at line 55 of file laserscanthread.h.

Definition at line 43 of file laserscanthread.h.

std::vector<Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> > LaserScanThread::edgesfound [protected]

Definition at line 67 of file laserscanthread.h.

double LaserScanThread::feld[2 *GAUSSIANFIELDSIZE+1] [protected]

Definition at line 68 of file laserscanthread.h.

double* LaserScanThread::filteredRanges [protected]

Definition at line 65 of file laserscanthread.h.

double LaserScanThread::gaussFactor [protected]

Definition at line 69 of file laserscanthread.h.

constexpr unsigned int LaserScanThread::GAUSSIANFIELDSIZE = 20 [static, protected]

Definition at line 53 of file laserscanthread.h.

Definition at line 80 of file laserscanthread.h.

double LaserScanThread::markersize = 0.02 [protected]

Definition at line 76 of file laserscanthread.h.

Definition at line 71 of file laserscanthread.h.

double LaserScanThread::maxVarianceFilter = 0.15 [protected]

Definition at line 70 of file laserscanthread.h.

Definition at line 82 of file laserscanthread.h.

Definition at line 64 of file laserscanthread.h.

Definition at line 83 of file laserscanthread.h.

Definition at line 78 of file laserscanthread.h.

double LaserScanThread::segmentation_lambda = 1.5 [protected]

Definition at line 74 of file laserscanthread.h.

Definition at line 85 of file laserscanthread.h.

Definition at line 84 of file laserscanthread.h.

std::vector<int> LaserScanThread::segmentdistance [protected]

Definition at line 62 of file laserscanthread.h.

std::vector<float> LaserScanThread::segments [protected]

Definition at line 60 of file laserscanthread.h.

std::vector<int> LaserScanThread::segmentsizes [protected]

Definition at line 61 of file laserscanthread.h.

constexpr double LaserScanThread::sigma = 1.5 [static, protected]

Definition at line 56 of file laserscanthread.h.

Definition at line 42 of file laserscanthread.h.

unsigned int LaserScanThread::stepNumber [protected]

Definition at line 59 of file laserscanthread.h.

double LaserScanThread::variationStep = 0.006 [protected]

Definition at line 72 of file laserscanthread.h.

Definition at line 73 of file laserscanthread.h.


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


asr_mild_calibration_tool
Author(s): Aumann Florian, Heller Florian, Meißner Pascal
autogenerated on Thu Jun 6 2019 21:22:45