Public Member Functions | Private Member Functions | Private Attributes | Friends
karto::Mapper Class Reference

#include <Mapper.h>

Inheritance diagram for karto::Mapper:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void AddListener (MapperListener *pListener)
void FireBeginLoopClosure (const std::string &rInfo) const
void FireDebug (const std::string &rInfo) const
void FireEndLoopClosure (const std::string &rInfo) const
void FireInfo (const std::string &rInfo) const
void FireLoopClosureCheck (const std::string &rInfo) const
virtual const
LocalizedRangeScanVector 
GetAllProcessedScans () const
virtual MapperGraphGetGraph () const
virtual ScanMatcherGetLoopScanMatcher () const
MapperSensorManagerGetMapperSensorManager () const
double getParamAngleVariancePenalty ()
double getParamCoarseAngleResolution ()
double getParamCoarseSearchAngleOffset ()
double getParamCorrelationSearchSpaceDimension ()
double getParamCorrelationSearchSpaceResolution ()
double getParamCorrelationSearchSpaceSmearDeviation ()
double getParamDistanceVariancePenalty ()
bool getParamDoLoopClosing ()
double getParamFineSearchAngleOffset ()
double getParamLinkMatchMinimumResponseFine ()
double getParamLinkScanMaximumDistance ()
double getParamLoopMatchMaximumVarianceCoarse ()
int getParamLoopMatchMinimumChainSize ()
double getParamLoopMatchMinimumResponseCoarse ()
double getParamLoopMatchMinimumResponseFine ()
double getParamLoopSearchMaximumDistance ()
double getParamLoopSearchSpaceDimension ()
double getParamLoopSearchSpaceResolution ()
double getParamLoopSearchSpaceSmearDeviation ()
double getParamMinimumAnglePenalty ()
double getParamMinimumDistancePenalty ()
double getParamMinimumTimeInterval ()
double getParamMinimumTravelDistance ()
double getParamMinimumTravelHeading ()
double getParamScanBufferMaximumScanDistance ()
int getParamScanBufferSize ()
bool getParamUseResponseExpansion ()
bool getParamUseScanBarycenter ()
bool getParamUseScanMatching ()
virtual ScanMatcherGetSequentialScanMatcher () const
void Initialize (kt_double rangeThreshold)
 Mapper ()
 Mapper (const std::string &rName)
virtual kt_bool Process (LocalizedRangeScan *pScan)
virtual kt_bool Process (Object *pObject)
void RemoveListener (MapperListener *pListener)
void Reset ()
void setParamAngleVariancePenalty (double d)
void setParamCoarseAngleResolution (double d)
void setParamCoarseSearchAngleOffset (double d)
void setParamCorrelationSearchSpaceDimension (double d)
void setParamCorrelationSearchSpaceResolution (double d)
void setParamCorrelationSearchSpaceSmearDeviation (double d)
void setParamDistanceVariancePenalty (double d)
void setParamDoLoopClosing (bool b)
void setParamFineSearchAngleOffset (double d)
void setParamLinkMatchMinimumResponseFine (double d)
void setParamLinkScanMaximumDistance (double d)
void setParamLoopMatchMaximumVarianceCoarse (double d)
void setParamLoopMatchMinimumChainSize (int i)
void setParamLoopMatchMinimumResponseCoarse (double d)
void setParamLoopMatchMinimumResponseFine (double d)
void setParamLoopSearchMaximumDistance (double d)
void setParamLoopSearchSpaceDimension (double d)
void setParamLoopSearchSpaceResolution (double d)
void setParamLoopSearchSpaceSmearDeviation (double d)
void setParamMinimumAnglePenalty (double d)
void setParamMinimumDistancePenalty (double d)
void setParamMinimumTimeInterval (double d)
void setParamMinimumTravelDistance (double d)
void setParamMinimumTravelHeading (double d)
void setParamScanBufferMaximumScanDistance (double d)
void setParamScanBufferSize (int i)
void setParamUseResponseExpansion (bool b)
void setParamUseScanBarycenter (bool b)
void setParamUseScanMatching (bool b)
void SetScanSolver (ScanSolver *pSolver)
void SetUseScanMatching (kt_bool val)
kt_bool TryCloseLoop (LocalizedRangeScan *pScan, const Name &rSensorName)
virtual ~Mapper ()

Private Member Functions

kt_bool HasMovedEnough (LocalizedRangeScan *pScan, LocalizedRangeScan *pLastScan) const
void InitializeParameters ()
 Mapper (const Mapper &)
const Mapperoperator= (const Mapper &)

Private Attributes

kt_bool m_Initialized
std::vector< MapperListener * > m_Listeners
Parameter< kt_double > * m_pAngleVariancePenalty
Parameter< kt_double > * m_pCoarseAngleResolution
Parameter< kt_double > * m_pCoarseSearchAngleOffset
Parameter< kt_double > * m_pCorrelationSearchSpaceDimension
Parameter< kt_double > * m_pCorrelationSearchSpaceResolution
Parameter< kt_double > * m_pCorrelationSearchSpaceSmearDeviation
Parameter< kt_double > * m_pDistanceVariancePenalty
Parameter< kt_bool > * m_pDoLoopClosing
Parameter< kt_double > * m_pFineSearchAngleOffset
MapperGraphm_pGraph
Parameter< kt_double > * m_pLinkMatchMinimumResponseFine
Parameter< kt_double > * m_pLinkScanMaximumDistance
Parameter< kt_double > * m_pLoopMatchMaximumVarianceCoarse
Parameter< kt_int32u > * m_pLoopMatchMinimumChainSize
Parameter< kt_double > * m_pLoopMatchMinimumResponseCoarse
Parameter< kt_double > * m_pLoopMatchMinimumResponseFine
Parameter< kt_double > * m_pLoopSearchMaximumDistance
Parameter< kt_double > * m_pLoopSearchSpaceDimension
Parameter< kt_double > * m_pLoopSearchSpaceResolution
Parameter< kt_double > * m_pLoopSearchSpaceSmearDeviation
MapperSensorManagerm_pMapperSensorManager
Parameter< kt_double > * m_pMinimumAnglePenalty
Parameter< kt_double > * m_pMinimumDistancePenalty
Parameter< kt_double > * m_pMinimumTimeInterval
Parameter< kt_double > * m_pMinimumTravelDistance
Parameter< kt_double > * m_pMinimumTravelHeading
Parameter< kt_double > * m_pScanBufferMaximumScanDistance
Parameter< kt_int32u > * m_pScanBufferSize
ScanSolverm_pScanOptimizer
ScanMatcherm_pSequentialScanMatcher
Parameter< kt_bool > * m_pUseResponseExpansion
Parameter< kt_bool > * m_pUseScanBarycenter
Parameter< kt_bool > * m_pUseScanMatching

Friends

class MapperGraph
class ScanMatcher

Detailed Description

Graph SLAM mapper. Creates a map given a set of LocalizedRangeScans The current Karto implementation is a proprietary, high-performance scan-matching algorithm that constructs a map from individual range scans and corrects for errors in the range and odometry data.

The following parameters can be set on the Mapper.

UseScanMatching (ParameterBool)
When set to true, the mapper will use a scan matching algorithm. In most real-world situations this should be set to true so that the mapper algorithm can correct for noise and errors in odometry and scan data. In some simulator environments where the simulated scan and odometry data are very accurate, the scan matching algorithm can produce worse results. In those cases set to false to improve results. Default value is true.

UseScanBarycenter (ParameterBool)

UseResponseExpansion (ParameterBool)

RangeThreshold (ParameterDouble - meters)
The range threshold is used to truncate range scan distance measurement readings. The threshold should be set such that adjacent range readings in a scan will generally give "solid" coverage of objects.

RangeThreshold.png

Having solid coverage depends on the map resolution and the angular resolution of the range scan device. The following are the recommended threshold values for the corresponding map resolution and range finder resolution values:

Map Resolution Laser Angular Resolution
1.0 degree 0.5 degree 0.25 degree
0.1 5.7m 11.4m 22.9m
0.05 2.8m 5.7m 11.4m
0.01 0.5m 1.1m 2.3m

Note that the value of RangeThreshold should be adjusted taking into account the values of MinimumTravelDistance and MinimumTravelHeading (see also below). By incorporating scans into the map more frequently, the RangeThreshold value can be increased as the additional scans will "fill in" the gaps of objects at greater distances where there is less solid coverage.

Default value is 12.0 (meters).

MinimumTravelDistance (ParameterDouble - meters)
Sets the minimum travel between scans. If a new scan's position is more than minimumDistance from the previous scan, the mapper will use the data from the new scan. Otherwise, it will discard the new scan if it also does not meet the minimum change in heading requirement. For performance reasons, generally it is a good idea to only process scans if the robot has moved a reasonable amount. Default value is 0.3 (meters).

MinimumTravelHeading (ParameterDouble - radians)
Sets the minimum heading change between scans. If a new scan's heading is more than minimumHeading from the previous scan, the mapper will use the data from the new scan. Otherwise, it will discard the new scan if it also does not meet the minimum travel distance requirement. For performance reasons, generally it is a good idea to only process scans if the robot has moved a reasonable amount. Default value is 0.08726646259971647 (radians) - 5 degrees.

ScanBufferSize (ParameterIn32u - size)
Scan buffer size is the length of the scan chain stored for scan matching. "ScanBufferSize" should be set to approximately "ScanBufferMaximumScanDistance" / "MinimumTravelDistance". The idea is to get an area approximately 20 meters long for scan matching. For example, if we add scans every MinimumTravelDistance = 0.3 meters, then "ScanBufferSize" should be 20 / 0.3 = 67.) Default value is 67.

ScanBufferMaximumScanDistance (ParameterDouble - meters)
Scan buffer maximum scan distance is the maximum distance between the first and last scans in the scan chain stored for matching. Default value is 20.0.

CorrelationSearchSpaceDimension (ParameterDouble - meters)
The size of the correlation grid used by the matcher. Default value is 0.3 meters which tells the matcher to use a 30cm x 30cm grid.

CorrelationSearchSpaceResolution (ParameterDouble - meters)
The resolution (size of a grid cell) of the correlation grid. Default value is 0.01 meters.

CorrelationSearchSpaceSmearDeviation (ParameterDouble - meters)
The robot position is smeared by this value in X and Y to create a smoother response. Default value is 0.03 meters.

LinkMatchMinimumResponseFine (ParameterDouble - probability (>= 0.0, <= 1.0))
Scans are linked only if the correlation response value is greater than this value. Default value is 0.4

LinkScanMaximumDistance (ParameterDouble - meters)
Maximum distance between linked scans. Scans that are farther apart will not be linked regardless of the correlation response value. Default value is 6.0 meters.

LoopSearchSpaceDimension (ParameterDouble - meters)
Dimension of the correlation grid used by the loop closure detection algorithm Default value is 4.0 meters.

LoopSearchSpaceResolution (ParameterDouble - meters)
Coarse resolution of the correlation grid used by the matcher to determine a possible loop closure. Default value is 0.05 meters.

LoopSearchSpaceSmearDeviation (ParameterDouble - meters)
Smearing distance in the correlation grid used by the matcher to determine a possible loop closure match. Default value is 0.03 meters.

LoopSearchMaximumDistance (ParameterDouble - meters)
Scans less than this distance from the current position will be considered for a match in loop closure. Default value is 4.0 meters.

LoopMatchMinimumChainSize (ParameterIn32s)
When the loop closure detection finds a candidate it must be part of a large set of linked scans. If the chain of scans is less than this value we do not attempt to close the loop. Default value is 10.

LoopMatchMaximumVarianceCoarse (ParameterDouble)
The co-variance values for a possible loop closure have to be less than this value to consider a viable solution. This applies to the coarse search. Default value is 0.16.

LoopMatchMinimumResponseCoarse (ParameterDouble - probability (>= 0.0, <= 1.0))
If response is larger then this then initiate loop closure search at the coarse resolution. Default value is 0.7.

LoopMatchMinimumResponseFine (ParameterDouble - probability (>= 0.0, <= 1.0))
If response is larger then this then initiate loop closure search at the fine resolution. Default value is 0.5.

Definition at line 1502 of file Mapper.h.


Constructor & Destructor Documentation

Default constructor

Definition at line 1624 of file Mapper.cpp.

karto::Mapper::Mapper ( const std::string &  rName)

Constructor a mapper with a name

Parameters:
rNamemapper name

Default constructor

Definition at line 1638 of file Mapper.cpp.

karto::Mapper::~Mapper ( ) [virtual]

Destructor

Definition at line 1652 of file Mapper.cpp.

karto::Mapper::Mapper ( const Mapper ) [private]

Restrict the copy constructor


Member Function Documentation

Add a listener to mapper

Parameters:
pListenerAdds a listener
pListener

Definition at line 2353 of file Mapper.cpp.

void karto::Mapper::FireBeginLoopClosure ( const std::string &  rInfo) const

Fire a message before loop closure to listeners

Parameters:
rInfo

Definition at line 2405 of file Mapper.cpp.

void karto::Mapper::FireDebug ( const std::string &  rInfo) const

Fire a debug message to listeners

Parameters:
rInfo

Definition at line 2379 of file Mapper.cpp.

void karto::Mapper::FireEndLoopClosure ( const std::string &  rInfo) const

Fire a message after loop closure to listeners

Parameters:
rInfo

Definition at line 2418 of file Mapper.cpp.

void karto::Mapper::FireInfo ( const std::string &  rInfo) const

Fire a general message to listeners

Parameters:
rInfo

Definition at line 2371 of file Mapper.cpp.

void karto::Mapper::FireLoopClosureCheck ( const std::string &  rInfo) const

Fire a message upon checking for loop closure to listeners

Parameters:
rInfo

Definition at line 2392 of file Mapper.cpp.

Returns all processed scans added to the mapper. NOTE: The returned scans have their corrected pose updated.

Returns:
list of scans received and processed by the mapper. If no scans have been processed, return an empty list.

Gets all the processed scans

Returns:
all scans

Definition at line 2337 of file Mapper.cpp.

MapperGraph * karto::Mapper::GetGraph ( ) const [virtual]

Get scan link graph

Returns:
graph

Definition at line 2436 of file Mapper.cpp.

Gets the loop scan matcher

Returns:
loop scan matcher

Definition at line 2446 of file Mapper.cpp.

Gets the device manager

Returns:
device manager

Definition at line 1603 of file Mapper.h.

Definition at line 1986 of file Mapper.cpp.

Definition at line 2001 of file Mapper.cpp.

Definition at line 1996 of file Mapper.cpp.

Definition at line 1947 of file Mapper.cpp.

Definition at line 1952 of file Mapper.cpp.

Definition at line 1957 of file Mapper.cpp.

Definition at line 1981 of file Mapper.cpp.

Definition at line 1920 of file Mapper.cpp.

Definition at line 1991 of file Mapper.cpp.

Definition at line 1905 of file Mapper.cpp.

Definition at line 1910 of file Mapper.cpp.

Definition at line 1930 of file Mapper.cpp.

Definition at line 1925 of file Mapper.cpp.

Definition at line 1935 of file Mapper.cpp.

Definition at line 1940 of file Mapper.cpp.

Definition at line 1915 of file Mapper.cpp.

Definition at line 1964 of file Mapper.cpp.

Definition at line 1969 of file Mapper.cpp.

Definition at line 1974 of file Mapper.cpp.

Definition at line 2006 of file Mapper.cpp.

Definition at line 2011 of file Mapper.cpp.

Definition at line 1880 of file Mapper.cpp.

Definition at line 1885 of file Mapper.cpp.

Definition at line 1890 of file Mapper.cpp.

Definition at line 1900 of file Mapper.cpp.

Definition at line 1895 of file Mapper.cpp.

Definition at line 2016 of file Mapper.cpp.

Definition at line 1875 of file Mapper.cpp.

Definition at line 1870 of file Mapper.cpp.

Gets the sequential scan matcher

Returns:
sequential scan matcher

Definition at line 2441 of file Mapper.cpp.

kt_bool karto::Mapper::HasMovedEnough ( LocalizedRangeScan pScan,
LocalizedRangeScan pLastScan 
) const [private]

Test if the scan is "sufficiently far" from the last scan added.

Parameters:
pScanscan to be checked
pLastScanlast scan added to mapper
Returns:
true if the scan is "sufficiently far" from the last scan added or the scan is the first scan to be added

Is the scan sufficiently far from the last scan?

Parameters:
pScan
pLastScan
Returns:
true if the scans are sufficiently far

Definition at line 2298 of file Mapper.cpp.

void karto::Mapper::Initialize ( kt_double  rangeThreshold)

Allocate memory needed for mapping

Parameters:
rangeThreshold

Definition at line 2175 of file Mapper.cpp.

Definition at line 1659 of file Mapper.cpp.

const Mapper& karto::Mapper::operator= ( const Mapper ) [private]

Restrict the assignment operator

Process a localized range scan for incorporation into the map. The scan must be identified with a range finder device. Once added to a map, the corrected pose information in the localized scan will be updated to the correct pose as determined by the mapper.

Parameters:
pScanA localized range scan that has pose information associated directly with the scan data. The pose is that of the range device originating the scan. Note that the mapper will set corrected pose information in the scan object.
Returns:
true if the scan was added successfully, false otherwise

Definition at line 2215 of file Mapper.cpp.

kt_bool karto::Mapper::Process ( Object pObject) [virtual]

Process an Object

Reimplemented from karto::Module.

Definition at line 2210 of file Mapper.cpp.

Remove a listener to mapper

Parameters:
pListenerRemoves a listener
pListener

Definition at line 2362 of file Mapper.cpp.

void karto::Mapper::Reset ( ) [virtual]

Resets the mapper. Deallocate memory allocated in Initialize()

Implements karto::Module.

Definition at line 2196 of file Mapper.cpp.

Definition at line 2138 of file Mapper.cpp.

Definition at line 2153 of file Mapper.cpp.

Definition at line 2148 of file Mapper.cpp.

Definition at line 2099 of file Mapper.cpp.

Definition at line 2104 of file Mapper.cpp.

Definition at line 2109 of file Mapper.cpp.

Definition at line 2133 of file Mapper.cpp.

Definition at line 2073 of file Mapper.cpp.

Definition at line 2143 of file Mapper.cpp.

Definition at line 2058 of file Mapper.cpp.

Definition at line 2063 of file Mapper.cpp.

Definition at line 2083 of file Mapper.cpp.

Definition at line 2078 of file Mapper.cpp.

Definition at line 2088 of file Mapper.cpp.

Definition at line 2093 of file Mapper.cpp.

Definition at line 2068 of file Mapper.cpp.

Definition at line 2116 of file Mapper.cpp.

Definition at line 2121 of file Mapper.cpp.

Definition at line 2126 of file Mapper.cpp.

Definition at line 2158 of file Mapper.cpp.

Definition at line 2163 of file Mapper.cpp.

Definition at line 2033 of file Mapper.cpp.

Definition at line 2038 of file Mapper.cpp.

Definition at line 2043 of file Mapper.cpp.

Definition at line 2053 of file Mapper.cpp.

Definition at line 2048 of file Mapper.cpp.

Definition at line 2168 of file Mapper.cpp.

Definition at line 2028 of file Mapper.cpp.

Definition at line 2023 of file Mapper.cpp.

Set scan optimizer used by mapper when closing the loop

Parameters:
pSolver

Definition at line 2431 of file Mapper.cpp.

Definition at line 1682 of file Mapper.h.

kt_bool karto::Mapper::TryCloseLoop ( LocalizedRangeScan pScan,
const Name rSensorName 
) [inline]

Tries to close a loop using the given scan with the scans from the given sensor

Parameters:
pScan
rSensorName

Definition at line 1613 of file Mapper.h.


Friends And Related Function Documentation

friend class MapperGraph [friend]

Definition at line 1504 of file Mapper.h.

friend class ScanMatcher [friend]

Definition at line 1505 of file Mapper.h.


Member Data Documentation

Definition at line 1685 of file Mapper.h.

std::vector<MapperListener*> karto::Mapper::m_Listeners [private]

Definition at line 1694 of file Mapper.h.

Definition at line 1865 of file Mapper.h.

Definition at line 1872 of file Mapper.h.

Definition at line 1869 of file Mapper.h.

The size of the search grid used by the matcher. Default value is 0.3 meters which tells the matcher to use a 30cm x 30cm grid.

Definition at line 1822 of file Mapper.h.

The resolution (size of a grid cell) of the correlation grid. Default value is 0.01 meters.

Definition at line 1828 of file Mapper.h.

The point readings are smeared by this value in X and Y to create a smoother response. Default value is 0.03 meters.

Definition at line 1834 of file Mapper.h.

Definition at line 1864 of file Mapper.h.

Enable/disable loop closure. Default is enabled.

Definition at line 1779 of file Mapper.h.

Definition at line 1868 of file Mapper.h.

Definition at line 1691 of file Mapper.h.

Scans are linked only if the correlation response value is greater than this value. Default value is 0.4

Definition at line 1766 of file Mapper.h.

Maximum distance between linked scans. Scans that are farther apart will not be linked regardless of the correlation response value. Default value is 6.0 meters.

Definition at line 1773 of file Mapper.h.

The co-variance values for a possible loop closure have to be less than this value to consider a viable solution. This applies to the coarse search. Default value is 0.16.

Definition at line 1801 of file Mapper.h.

When the loop closure detection finds a candidate it must be part of a large set of linked scans. If the chain of scans is less than this value we do not attempt to close the loop. Default value is 10.

Definition at line 1794 of file Mapper.h.

If response is larger then this, then initiate loop closure search at the coarse resolution. Default value is 0.7.

Definition at line 1807 of file Mapper.h.

If response is larger then this, then initiate loop closure search at the fine resolution. Default value is 0.7.

Definition at line 1813 of file Mapper.h.

Scans less than this distance from the current position will be considered for a match in loop closure. Default value is 4.0 meters.

Definition at line 1786 of file Mapper.h.

The size of the search grid used by the matcher. Default value is 0.3 meters which tells the matcher to use a 30cm x 30cm grid.

Definition at line 1844 of file Mapper.h.

The resolution (size of a grid cell) of the correlation grid. Default value is 0.01 meters.

Definition at line 1850 of file Mapper.h.

The point readings are smeared by this value in X and Y to create a smoother response. Default value is 0.03 meters.

Definition at line 1856 of file Mapper.h.

Definition at line 1689 of file Mapper.h.

Definition at line 1876 of file Mapper.h.

Definition at line 1877 of file Mapper.h.

Sets the minimum time between scans. If a new scan's time stamp is longer than MinimumTimeInterval from the previously processed scan, the mapper will use the data from the new scan. Otherwise, it will discard the new scan if it also does not meet the minimum travel distance and heading requirements. For performance reasons, it is generally it is a good idea to only process scans if a reasonable amount of time has passed. This parameter is particularly useful when there is a need to process scans while the robot is stationary. Default value is 3600 (seconds), effectively disabling this parameter.

Definition at line 1723 of file Mapper.h.

Sets the minimum travel between scans. If a new scan's position is more than minimumTravelDistance from the previous scan, the mapper will use the data from the new scan. Otherwise, it will discard the new scan if it also does not meet the minimum change in heading requirement. For performance reasons, generally it is a good idea to only process scans if the robot has moved a reasonable amount. Default value is 0.2 (meters).

Definition at line 1733 of file Mapper.h.

Sets the minimum heading change between scans. If a new scan's heading is more than minimumTravelHeading from the previous scan, the mapper will use the data from the new scan. Otherwise, it will discard the new scan if it also does not meet the minimum travel distance requirement. For performance reasons, generally it is a good idea to only process scans if the robot has moved a reasonable amount. Default value is 10 degrees.

Definition at line 1743 of file Mapper.h.

Scan buffer maximum scan distance is the maximum distance between the first and last scans in the scan chain stored for matching. Default value is 20.0.

Definition at line 1760 of file Mapper.h.

Scan buffer size is the length of the scan chain stored for scan matching. "scanBufferSize" should be set to approximately "scanBufferMaximumScanDistance" / "minimumTravelDistance". The idea is to get an area approximately 20 meters long for scan matching. For example, if we add scans every minimumTravelDistance == 0.3 meters, then "scanBufferSize" should be 20 / 0.3 = 67.) Default value is 67.

Definition at line 1753 of file Mapper.h.

Definition at line 1692 of file Mapper.h.

Definition at line 1687 of file Mapper.h.

Definition at line 1880 of file Mapper.h.

Default value is true.

Definition at line 1710 of file Mapper.h.

When set to true, the mapper will use a scan matching algorithm. In most real-world situations this should be set to true so that the mapper algorithm can correct for noise and errors in odometry and scan data. In some simulator environments where the simulated scan and odometry data are very accurate, the scan matching algorithm can produce worse results. In those cases set this to false to improve results. Default value is true.

Definition at line 1705 of file Mapper.h.


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


open_karto
Author(s):
autogenerated on Thu Jun 6 2019 21:02:57