Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
Fake_data_publisher Class Reference

Public Member Functions

 Fake_data_publisher ()
 
void getNodeParameters (std::string &pObjectTopic, std::string &pDbfilename, std::string &pVisualizationTopic)
 
virtual ~Fake_data_publisher ()
 

Private Types

typedef std::pair< std::string, std::string > RecordKey
 
typedef std::map< RecordKey, const asr_msgs::AsrObject > RecordMapType
 

Private Member Functions

std::vector< std::vector< ISM::ObjectSetPtr > > getDbEntries ()
 
asr_msgs::AsrObjectPtr objectToMessage (ISM::ObjectPtr object)
 
void timerCallback (const ros::TimerEvent &timerEvent)
 

Private Attributes

int firstUsedSet
 
int lastUsedSet
 
std::string mBaseFrame
 
IH::ObjectConvertermConverter
 
ros::Publisher mDataPub
 
ros::NodeHandle mNh
 
VIZ::ObjectModelVisualizerRVIZ * mObjectModelVisualizer
 
RecordMapType mObjectRecord
 
std::vector< std::vector< ISM::ObjectSetPtr > > mObjectSets
 
double mPublishInterval
 
ISM::Recognizer * mRecognizer
 
double mStep
 
ros::Subscriber mSub
 
ISM::TableHelperPtr mTableHelper
 
ros::Timer mTimer
 
ros::Publisher mVisualizationPub
 
unsigned int patternIter
 
unsigned int setIter
 
int usedPattern
 

Detailed Description

Copyright (c) 2016, Borella Jocelyn, Hanselmann Fabian, Heller Florian, Heizmann Heinrich, Kübler Marcel, Mehlhaus Jonas, Meißner Pascal, Qattan Mohamad, Reckling Reno, Stroh Daniel 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. Fake_data_publisher. Publishs data from dbfile so Recognizer has some data even when no cameras are available. Wip.

Author
Fabian Hanselmann
Version
See SVN

Definition at line 52 of file fake_data_publisher.cpp.

Member Typedef Documentation

typedef std::pair<std::string, std::string> Fake_data_publisher::RecordKey
private

Definition at line 193 of file fake_data_publisher.cpp.

typedef std::map<RecordKey, const asr_msgs::AsrObject> Fake_data_publisher::RecordMapType
private

Definition at line 194 of file fake_data_publisher.cpp.

Constructor & Destructor Documentation

Fake_data_publisher::Fake_data_publisher ( )
inline

Constructor processing parameters of scene recognition and setting up ros node.

Definition at line 58 of file fake_data_publisher.cpp.

virtual Fake_data_publisher::~Fake_data_publisher ( )
inlinevirtual

Definition at line 148 of file fake_data_publisher.cpp.

Member Function Documentation

std::vector<std::vector<ISM::ObjectSetPtr> > Fake_data_publisher::getDbEntries ( )
inlineprivate

Definition at line 232 of file fake_data_publisher.cpp.

void Fake_data_publisher::getNodeParameters ( std::string &  pObjectTopic,
std::string &  pDbfilename,
std::string &  pVisualizationTopic 
)
inline

Definition at line 150 of file fake_data_publisher.cpp.

asr_msgs::AsrObjectPtr Fake_data_publisher::objectToMessage ( ISM::ObjectPtr  object)
inlineprivate

Definition at line 259 of file fake_data_publisher.cpp.

void Fake_data_publisher::timerCallback ( const ros::TimerEvent timerEvent)
inlineprivate

Definition at line 311 of file fake_data_publisher.cpp.

Member Data Documentation

int Fake_data_publisher::firstUsedSet
private

Definition at line 212 of file fake_data_publisher.cpp.

int Fake_data_publisher::lastUsedSet
private

Definition at line 213 of file fake_data_publisher.cpp.

std::string Fake_data_publisher::mBaseFrame
private

Definition at line 203 of file fake_data_publisher.cpp.

IH::ObjectConverter* Fake_data_publisher::mConverter
private

Definition at line 198 of file fake_data_publisher.cpp.

ros::Publisher Fake_data_publisher::mDataPub
private

Definition at line 219 of file fake_data_publisher.cpp.

ros::NodeHandle Fake_data_publisher::mNh
private

Definition at line 220 of file fake_data_publisher.cpp.

VIZ::ObjectModelVisualizerRVIZ* Fake_data_publisher::mObjectModelVisualizer
private

Definition at line 224 of file fake_data_publisher.cpp.

RecordMapType Fake_data_publisher::mObjectRecord
private

Definition at line 196 of file fake_data_publisher.cpp.

std::vector<std::vector<ISM::ObjectSetPtr> > Fake_data_publisher::mObjectSets
private

Definition at line 206 of file fake_data_publisher.cpp.

double Fake_data_publisher::mPublishInterval
private

Definition at line 201 of file fake_data_publisher.cpp.

ISM::Recognizer* Fake_data_publisher::mRecognizer
private

Definition at line 208 of file fake_data_publisher.cpp.

double Fake_data_publisher::mStep
private

Definition at line 202 of file fake_data_publisher.cpp.

ros::Subscriber Fake_data_publisher::mSub
private

Definition at line 221 of file fake_data_publisher.cpp.

ISM::TableHelperPtr Fake_data_publisher::mTableHelper
private

Definition at line 207 of file fake_data_publisher.cpp.

ros::Timer Fake_data_publisher::mTimer
private

Definition at line 218 of file fake_data_publisher.cpp.

ros::Publisher Fake_data_publisher::mVisualizationPub
private

Definition at line 217 of file fake_data_publisher.cpp.

unsigned int Fake_data_publisher::patternIter
private

Definition at line 209 of file fake_data_publisher.cpp.

unsigned int Fake_data_publisher::setIter
private

Definition at line 210 of file fake_data_publisher.cpp.

int Fake_data_publisher::usedPattern
private

Definition at line 214 of file fake_data_publisher.cpp.


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


asr_ism
Author(s): Borella Jocelyn, Hanselmann Fabian, Heller Florian, Heizmann Heinrich, Kübler Marcel, Mehlhaus Jonas, Meißner Pascal, Qattan Mohamad, Reckling Reno, Stroh Daniel
autogenerated on Thu Jan 9 2020 07:20:58