|
naoqidriver
|
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::Robot & | robot_ |
| bool | publish_enabled_ |
| bool | record_enabled_ |
| bool | log_enabled_ |
| bool | keep_looping |
| const size_t | freq_ |
| boost::thread | publisherThread_ |
| boost::shared_ptr< recorder::GlobalRecorder > | recorder_ |
| 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::Converter > | converters_ |
| std::map< std::string, publisher::Publisher > | pub_map_ |
| std::map< std::string, recorder::Recorder > | rec_map_ |
| std::map< std::string, event::Event > | event_map_ |
| std::vector< subscriber::Subscriber > | subscribers_ |
| std::vector< service::Service > | services_ |
| float | buffer_duration_ |
| std::priority_queue< ScheduledConverter > | conv_queue_ |
| boost::shared_ptr< tf2_ros::Buffer > | tf2_buffer_ |
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.
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
| naoqi::Driver::Driver | ( | qi::SessionPtr & | session, |
| const std::string & | prefix | ||
| ) |
Constructor for naoqi driver.
| session[in] | session pointer for naoqi2 service registration |
| naoqi::Driver::~Driver | ( | ) |
Destructor for naoqi driver, destroys all ros nodehandle and shutsdown all publisher.
|
inlineprivate |
|
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
| std::vector< std::string > naoqi::Driver::getSubscribedPublishers | ( | ) | const |
get all subscribed publishers
| void naoqi::Driver::init | ( | ) |
|
private |
|
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
|
private |
Info publisher
LOGS
DIAGNOSTICS
IMU TORSO
IMU BASE
Front Camera
Front Camera
Depth Camera
Infrared Camera
Joint States
Laser
Sonar
Audio
|
private |
|
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
| conv_name | the name of the converter related to the publisher |
| pub | the 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
| conv_name | the name of the converter related to the recorder |
| rec | the 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
| service | to register |
| void naoqi::Driver::registerSubscriber | ( | subscriber::Subscriber | sub | ) |
registers a subscriber
| subscriber | to register |
| void naoqi::Driver::removeAllFiles | ( | ) |
| void naoqi::Driver::removeFiles | ( | std::vector< std::string > | files | ) |
|
private |
| void naoqi::Driver::setBufferDuration | ( | float | duration | ) |
| void naoqi::Driver::setMasterURI | ( | const std::string & | uri | ) |
qicli call function to set current master uri
| string | in 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
| string | in form of http://<ip>:11311 |
| network_interface | the 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 | ( | ) |
|
private |
|
private |
|
private |
Priority queue to process the publishers according to their frequency
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
tf2 buffer that will be shared between different publishers/subscribers This is only for performance improvements
1.8.9.1