naoqidriver
Data Structures | 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>

Data Structures

struct  ScheduledConverter
 

Public Member Functions

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

Private Types

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
 
typedef std::map< std::string, event::Event >::const_iterator EventConstIter
 
typedef std::map< std::string, event::Event >::iterator EventIter
 

Private Member Functions

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

Private Attributes

qi::SessionPtr sessionPtr_
 
const robot::Robotrobot_
 
bool publish_enabled_
 
bool record_enabled_
 
bool log_enabled_
 
bool keep_looping
 
const size_t freq_
 
boost::thread publisherThread_
 
boost::shared_ptr< recorder::GlobalRecorderrecorder_
 
boost::property_tree::ptree boot_config_
 
boost::scoped_ptr< ros::NodeHandle > nhPtr_
 
boost::mutex mutex_reinit_
 
boost::mutex mutex_conv_queue_
 
boost::mutex mutex_record_
 
std::vector< converter::Converterconverters_
 
std::map< std::string, publisher::Publisherpub_map_
 
std::map< std::string, recorder::Recorderrec_map_
 
std::map< std::string, event::Eventevent_map_
 
std::vector< subscriber::Subscribersubscribers_
 
std::vector< service::Serviceservices_
 
float buffer_duration_
 
std::priority_queue< ScheduledConverterconv_queue_
 
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.

Member Typedef Documentation

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

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
naoqi::Driver::~Driver ( )

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

Member Function Documentation

template<typename T1 , typename T2 , typename T3 >
void naoqi::Driver::_registerMemoryConverter ( const std::string &  key,
float  frequency 
)
inlineprivate
std::string naoqi::Driver::_whoIsYourDaddy ( )
inline
void naoqi::Driver::addMemoryConverters ( std::string  filepath)

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

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

get all available converters

float naoqi::Driver::getBufferDuration ( )
std::vector< std::string > naoqi::Driver::getFilesList ( )
std::string naoqi::Driver::getMasterURI ( ) const

qicli call function to get current master uri

Returns
string indicating http master uri
std::vector< std::string > naoqi::Driver::getSubscribedPublishers ( ) const

get all subscribed publishers

void naoqi::Driver::init ( )
void naoqi::Driver::insertEventConverter ( const std::string &  key,
event::Event  event 
)
private
void naoqi::Driver::loadBootConfig ( )
private
std::string naoqi::Driver::minidump ( const std::string &  prefix)

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

std::string naoqi::Driver::minidumpConverters ( const std::string &  prefix,
const std::vector< std::string > &  names 
)
void naoqi::Driver::parseJsonFile ( std::string  filepath,
boost::property_tree::ptree &  pt 
)
void naoqi::Driver::registerConverter ( converter::Converter conv)

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

void naoqi::Driver::registerConverter ( converter::Converter  conv,
publisher::Publisher  pub,
recorder::Recorder  rec 
)

register a converter with an associated publisher and recorder

void naoqi::Driver::registerDefaultConverter ( )
private

Info publisher

LOGS

DIAGNOSTICS

IMU TORSO

IMU BASE

Front Camera

Front Camera

Depth Camera

Infrared Camera

Joint States

Laser

Sonar

Audio

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

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

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

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
void naoqi::Driver::registerPublisher ( converter::Converter  conv,
publisher::Publisher  pub 
)

register a converter with an associated publisher instance

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
void naoqi::Driver::registerRecorder ( converter::Converter  conv,
recorder::Recorder  rec 
)

register a converter with an associated recorder instance

void naoqi::Driver::registerService ( service::Service  srv)

registers a service

Parameters
serviceto register
See also
Service
Note
it iwll be called by value to expose that internally there will be a copy, eventually this should be replaced by move semantics C++11
void naoqi::Driver::registerSubscriber ( subscriber::Subscriber  sub)

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
void naoqi::Driver::removeAllFiles ( )
void naoqi::Driver::removeFiles ( std::vector< std::string >  files)
void naoqi::Driver::rosLoop ( )
private
void naoqi::Driver::setBufferDuration ( float  duration)
void naoqi::Driver::setMasterURI ( const std::string &  uri)

qicli call function to set current master uri

Parameters
stringin form of http://<ip>:11311
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" ...)
void naoqi::Driver::startLogging ( )
void naoqi::Driver::startPublishing ( )

qicli call function to start/enable publishing all registered publisher

void naoqi::Driver::startRecording ( )

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

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

qicli call function to start recording given topics in a ROSbag

void naoqi::Driver::startRosLoop ( )
void naoqi::Driver::stopLogging ( )
void naoqi::Driver::stopPublishing ( )

qicli call function to stop/disable publishing all registered publisher

std::string naoqi::Driver::stopRecording ( )

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

void naoqi::Driver::stopRosLoop ( )
void naoqi::Driver::stopService ( )

Field Documentation

boost::property_tree::ptree naoqi::Driver::boot_config_
private
float naoqi::Driver::buffer_duration_
private
std::priority_queue<ScheduledConverter> naoqi::Driver::conv_queue_
private

Priority queue to process the publishers according to their frequency

std::vector< converter::Converter > naoqi::Driver::converters_
private
std::map< std::string, event::Event > naoqi::Driver::event_map_
private
const size_t naoqi::Driver::freq_
private
bool naoqi::Driver::keep_looping
private
bool naoqi::Driver::log_enabled_
private
boost::mutex naoqi::Driver::mutex_conv_queue_
private
boost::mutex naoqi::Driver::mutex_record_
private
boost::mutex naoqi::Driver::mutex_reinit_
private
boost::scoped_ptr<ros::NodeHandle> naoqi::Driver::nhPtr_
private
std::map< std::string, publisher::Publisher > naoqi::Driver::pub_map_
private
bool naoqi::Driver::publish_enabled_
private
boost::thread naoqi::Driver::publisherThread_
private
std::map< std::string, recorder::Recorder > naoqi::Driver::rec_map_
private
bool naoqi::Driver::record_enabled_
private
boost::shared_ptr<recorder::GlobalRecorder> naoqi::Driver::recorder_
private
const robot::Robot& naoqi::Driver::robot_
private
std::vector< service::Service > naoqi::Driver::services_
private
qi::SessionPtr naoqi::Driver::sessionPtr_
private
std::vector< subscriber::Subscriber > naoqi::Driver::subscribers_
private
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


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