Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes
naoqi::Driver Class Reference

Interface for naoqi driver which is registered as a naoqi2 Module, once the external roscore ip is set, this class will advertise and publish ros messages. More...

#include <naoqi_driver.hpp>

List of all members.

Classes

struct  ScheduledConverter

Public Member Functions

std::string _whoIsYourDaddy ()
void addMemoryConverters (std::string filepath)
 qicli call function to add on-the-fly some memory keys extractors
 Driver (qi::SessionPtr session, const std::string &prefix)
 Constructor for naoqi driver.
std::vector< std::string > getAvailableConverters ()
 get all available converters
float getBufferDuration ()
std::vector< std::string > getFilesList ()
std::string getMasterURI () const
 qicli call function to get current master uri
std::vector< std::string > getSubscribedPublishers () const
 get all subscribed publishers
void init ()
std::string minidump (const std::string &prefix)
 Write a ROSbag with the last bufferized data (10s by default)
std::string minidumpConverters (const std::string &prefix, const std::vector< std::string > &names)
void parseJsonFile (std::string filepath, boost::property_tree::ptree &pt)
void registerConverter (converter::Converter &conv)
 registers generall converter units they are connected via callbacks to various actions such as record, log, publish
void registerConverter (converter::Converter conv, publisher::Publisher pub, recorder::Recorder rec)
 register a converter with an associated publisher and recorder
bool registerEventConverter (const std::string &key, const dataType::DataType &type)
 qicli call function to register a converter for a given memory event
bool registerMemoryConverter (const std::string &key, float frequency, const dataType::DataType &type)
 qicli call function to register a converter for a given memory key
void registerPublisher (const std::string &conv_name, publisher::Publisher &pub)
 prepare and register a publisher
void registerPublisher (converter::Converter conv, publisher::Publisher pub)
 register a converter with an associated publisher instance
void registerRecorder (const std::string &conv_name, recorder::Recorder &rec, float frequency)
 prepare and register a recorder
void registerRecorder (converter::Converter conv, recorder::Recorder rec)
 register a converter with an associated recorder instance
void registerService (service::Service srv)
 registers a service
void registerSubscriber (subscriber::Subscriber sub)
 registers a subscriber
void removeAllFiles ()
void removeFiles (std::vector< std::string > files)
void setBufferDuration (float duration)
void setMasterURI (const std::string &uri)
 qicli call function to set current master uri
void setMasterURINet (const std::string &uri, const std::string &network_interface)
 qicli call function to set current master uri
void startLogging ()
void startPublishing ()
 qicli call function to start/enable publishing all registered publisher
void startRecording ()
 qicli call function to start recording all registered converter in a ROSbag
void startRecordingConverters (const std::vector< std::string > &names)
 qicli call function to start recording given topics in a ROSbag
void startRosLoop ()
void stopLogging ()
void stopPublishing ()
 qicli call function to stop/disable publishing all registered publisher
std::string stopRecording ()
 qicli call function to stop recording all registered publisher in a ROSbag
void stopRosLoop ()
void stopService ()
 ~Driver ()
 Destructor for naoqi driver, destroys all ros nodehandle and shutsdown all publisher.

Private Types

typedef std::map< std::string,
event::Event >::const_iterator 
EventConstIter
typedef std::map< std::string,
event::Event >::iterator 
EventIter
typedef std::map< std::string,
publisher::Publisher >
::const_iterator 
PubConstIter
typedef std::map< std::string,
publisher::Publisher >
::iterator 
PubIter
typedef std::map< std::string,
recorder::Recorder >
::const_iterator 
RecConstIter
typedef std::map< std::string,
recorder::Recorder >::iterator 
RecIter

Private Member Functions

template<typename T1 , typename T2 , typename T3 >
void _registerMemoryConverter (const std::string &key, float frequency)
void insertEventConverter (const std::string &key, event::Event event)
void loadBootConfig ()
void registerDefaultConverter ()
void registerDefaultServices ()
void registerDefaultSubscriber ()
void rosLoop ()

Private Attributes

boost::property_tree::ptree boot_config_
float buffer_duration_
std::priority_queue
< ScheduledConverter
conv_queue_
std::vector< converter::Converterconverters_
std::map< std::string,
event::Event
event_map_
const size_t freq_
bool keep_looping
bool log_enabled_
boost::mutex mutex_conv_queue_
boost::mutex mutex_record_
boost::mutex mutex_reinit_
boost::scoped_ptr
< ros::NodeHandle
nhPtr_
std::map< std::string,
publisher::Publisher
pub_map_
bool publish_enabled_
boost::thread publisherThread_
std::map< std::string,
recorder::Recorder
rec_map_
bool record_enabled_
boost::shared_ptr
< recorder::GlobalRecorder
recorder_
const robot::Robotrobot_
std::vector< service::Serviceservices_
qi::SessionPtr sessionPtr_
std::vector
< subscriber::Subscriber
subscribers_
boost::shared_ptr
< tf2_ros::Buffer
tf2_buffer_

Detailed Description

Interface for naoqi driver which is registered as a naoqi2 Module, once the external roscore ip is set, this class will advertise and publish ros messages.

Definition at line 65 of file naoqi_driver.hpp.


Member Typedef Documentation

typedef std::map< std::string, event::Event>::const_iterator naoqi::Driver::EventConstIter [private]

Definition at line 285 of file naoqi_driver.hpp.

typedef std::map< std::string, event::Event>::iterator naoqi::Driver::EventIter [private]

Definition at line 286 of file naoqi_driver.hpp.

typedef std::map< std::string, publisher::Publisher>::const_iterator naoqi::Driver::PubConstIter [private]

Definition at line 281 of file naoqi_driver.hpp.

typedef std::map< std::string, publisher::Publisher>::iterator naoqi::Driver::PubIter [private]

Definition at line 282 of file naoqi_driver.hpp.

typedef std::map< std::string, recorder::Recorder>::const_iterator naoqi::Driver::RecConstIter [private]

Definition at line 283 of file naoqi_driver.hpp.

typedef std::map< std::string, recorder::Recorder>::iterator naoqi::Driver::RecIter [private]

Definition at line 284 of file naoqi_driver.hpp.


Constructor & Destructor Documentation

naoqi::Driver::Driver ( qi::SessionPtr  session,
const std::string &  prefix 
)

Constructor for naoqi driver.

Parameters:
session[in]session pointer for naoqi2 service registration

Definition at line 116 of file naoqi_driver.cpp.

Destructor for naoqi driver, destroys all ros nodehandle and shutsdown all publisher.

Definition at line 137 of file naoqi_driver.cpp.


Member Function Documentation

template<typename T1 , typename T2 , typename T3 >
void naoqi::Driver::_registerMemoryConverter ( const std::string &  key,
float  frequency 
) [inline, private]

Definition at line 260 of file naoqi_driver.hpp.

std::string naoqi::Driver::_whoIsYourDaddy ( ) [inline]

Definition at line 149 of file naoqi_driver.hpp.

void naoqi::Driver::addMemoryConverters ( std::string  filepath)

qicli call function to add on-the-fly some memory keys extractors

Definition at line 1165 of file naoqi_driver.cpp.

std::vector< std::string > naoqi::Driver::getAvailableConverters ( )

get all available converters

Definition at line 894 of file naoqi_driver.cpp.

Definition at line 414 of file naoqi_driver.cpp.

std::vector< std::string > naoqi::Driver::getFilesList ( )

Definition at line 1320 of file naoqi_driver.cpp.

std::string naoqi::Driver::getMasterURI ( ) const

qicli call function to get current master uri

Returns:
string indicating http master uri

Definition at line 913 of file naoqi_driver.cpp.

std::vector< std::string > naoqi::Driver::getSubscribedPublishers ( ) const

get all subscribed publishers

Definition at line 1009 of file naoqi_driver.cpp.

Definition at line 148 of file naoqi_driver.cpp.

void naoqi::Driver::insertEventConverter ( const std::string &  key,
event::Event  event 
) [private]

Definition at line 446 of file naoqi_driver.cpp.

void naoqi::Driver::loadBootConfig ( ) [private]

Definition at line 158 of file naoqi_driver.cpp.

std::string naoqi::Driver::minidump ( const std::string &  prefix)

Write a ROSbag with the last bufferized data (10s by default)

Definition at line 257 of file naoqi_driver.cpp.

std::string naoqi::Driver::minidumpConverters ( const std::string &  prefix,
const std::vector< std::string > &  names 
)

Definition at line 316 of file naoqi_driver.cpp.

void naoqi::Driver::parseJsonFile ( std::string  filepath,
boost::property_tree::ptree &  pt 
)

Definition at line 1156 of file naoqi_driver.cpp.

registers generall converter units they are connected via callbacks to various actions such as record, log, publish

Definition at line 419 of file naoqi_driver.cpp.

register a converter with an associated publisher and recorder

Definition at line 453 of file naoqi_driver.cpp.

Info publisher

LOGS

DIAGNOSTICS

IMU TORSO

IMU BASE

Front Camera

Front Camera

Depth Camera

Infrared Camera

Joint States

Laser

Sonar

Audio

TOUCH

Odom

Definition at line 534 of file naoqi_driver.cpp.

Definition at line 889 of file naoqi_driver.cpp.

Definition at line 874 of file naoqi_driver.cpp.

bool naoqi::Driver::registerEventConverter ( const std::string &  key,
const dataType::DataType type 
)

qicli call function to register a converter for a given memory event

Definition at line 1234 of file naoqi_driver.cpp.

bool naoqi::Driver::registerMemoryConverter ( const std::string &  key,
float  frequency,
const dataType::DataType type 
)

qicli call function to register a converter for a given memory key

Definition at line 472 of file naoqi_driver.cpp.

void naoqi::Driver::registerPublisher ( const std::string &  conv_name,
publisher::Publisher pub 
)

prepare and register a publisher

Parameters:
conv_namethe name of the converter related to the publisher
pubthe publisher to add

Definition at line 428 of file naoqi_driver.cpp.

register a converter with an associated publisher instance

Definition at line 460 of file naoqi_driver.cpp.

void naoqi::Driver::registerRecorder ( const std::string &  conv_name,
recorder::Recorder rec,
float  frequency 
)

prepare and register a recorder

Parameters:
conv_namethe name of the converter related to the recorder
recthe recorder to add

Definition at line 438 of file naoqi_driver.cpp.

register a converter with an associated recorder instance

Definition at line 466 of file naoqi_driver.cpp.

registers a service

Parameters:
serviceto register
See also:
Service
Note:
it will be called by value to expose that internally there will be a copy, eventually this should be replaced by move semantics C++11

Definition at line 883 of file naoqi_driver.cpp.

registers a subscriber

Parameters:
subscriberto register
See also:
Subscriber
Note:
it will be called by value to expose that internally there will be a copy, eventually this should be replaced by move semantics C++11

Definition at line 853 of file naoqi_driver.cpp.

Definition at line 1335 of file naoqi_driver.cpp.

void naoqi::Driver::removeFiles ( std::vector< std::string >  files)

Definition at line 1348 of file naoqi_driver.cpp.

void naoqi::Driver::rosLoop ( ) [private]

Definition at line 176 of file naoqi_driver.cpp.

void naoqi::Driver::setBufferDuration ( float  duration)

Definition at line 401 of file naoqi_driver.cpp.

void naoqi::Driver::setMasterURI ( const std::string &  uri)

qicli call function to set current master uri

Parameters:
stringin form of http://<ip>:11311

Definition at line 918 of file naoqi_driver.cpp.

void naoqi::Driver::setMasterURINet ( const std::string &  uri,
const std::string &  network_interface 
)

qicli call function to set current master uri

Parameters:
stringin form of http://<ip>:11311
network_interfacethe network interface ("eth0", "tether" ...)

Definition at line 923 of file naoqi_driver.cpp.

Definition at line 1123 of file naoqi_driver.cpp.

qicli call function to start/enable publishing all registered publisher

Definition at line 991 of file naoqi_driver.cpp.

qicli call function to start recording all registered converter in a ROSbag

Definition at line 1025 of file naoqi_driver.cpp.

void naoqi::Driver::startRecordingConverters ( const std::vector< std::string > &  names)

qicli call function to start recording given topics in a ROSbag

Definition at line 1050 of file naoqi_driver.cpp.

Definition at line 1133 of file naoqi_driver.cpp.

Definition at line 1128 of file naoqi_driver.cpp.

qicli call function to stop/disable publishing all registered publisher

Definition at line 1000 of file naoqi_driver.cpp.

qicli call function to stop recording all registered publisher in a ROSbag

Definition at line 1104 of file naoqi_driver.cpp.

Definition at line 1145 of file naoqi_driver.cpp.

Definition at line 168 of file naoqi_driver.cpp.


Member Data Documentation

boost::property_tree::ptree naoqi::Driver::boot_config_ [private]

Definition at line 251 of file naoqi_driver.hpp.

Definition at line 291 of file naoqi_driver.hpp.

std::priority_queue<ScheduledConverter> naoqi::Driver::conv_queue_ [private]

Priority queue to process the publishers according to their frequency

Definition at line 310 of file naoqi_driver.hpp.

Definition at line 277 of file naoqi_driver.hpp.

std::map< std::string, event::Event > naoqi::Driver::event_map_ [private]

Definition at line 280 of file naoqi_driver.hpp.

const size_t naoqi::Driver::freq_ [private]

Definition at line 244 of file naoqi_driver.hpp.

Definition at line 242 of file naoqi_driver.hpp.

Definition at line 241 of file naoqi_driver.hpp.

boost::mutex naoqi::Driver::mutex_conv_queue_ [private]

Definition at line 274 of file naoqi_driver.hpp.

boost::mutex naoqi::Driver::mutex_record_ [private]

Definition at line 275 of file naoqi_driver.hpp.

boost::mutex naoqi::Driver::mutex_reinit_ [private]

Definition at line 273 of file naoqi_driver.hpp.

boost::scoped_ptr<ros::NodeHandle> naoqi::Driver::nhPtr_ [private]

Definition at line 272 of file naoqi_driver.hpp.

std::map< std::string, publisher::Publisher > naoqi::Driver::pub_map_ [private]

Definition at line 278 of file naoqi_driver.hpp.

Definition at line 239 of file naoqi_driver.hpp.

boost::thread naoqi::Driver::publisherThread_ [private]

Definition at line 245 of file naoqi_driver.hpp.

std::map< std::string, recorder::Recorder > naoqi::Driver::rec_map_ [private]

Definition at line 279 of file naoqi_driver.hpp.

Definition at line 240 of file naoqi_driver.hpp.

boost::shared_ptr<recorder::GlobalRecorder> naoqi::Driver::recorder_ [private]

Definition at line 248 of file naoqi_driver.hpp.

Definition at line 237 of file naoqi_driver.hpp.

std::vector< service::Service > naoqi::Driver::services_ [private]

Definition at line 289 of file naoqi_driver.hpp.

qi::SessionPtr naoqi::Driver::sessionPtr_ [private]

Definition at line 235 of file naoqi_driver.hpp.

Definition at line 288 of file naoqi_driver.hpp.

boost::shared_ptr<tf2_ros::Buffer> naoqi::Driver::tf2_buffer_ [private]

tf2 buffer that will be shared between different publishers/subscribers This is only for performance improvements

Definition at line 315 of file naoqi_driver.hpp.


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


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sun Sep 17 2017 02:57:14