19 #ifndef NAOQI_DRIVER_HPP
20 #define NAOQI_DRIVER_HPP
28 #include <boost/property_tree/ptree.hpp>
29 #include <boost/thread/thread.hpp>
30 #include <boost/thread/mutex.hpp>
31 #include <boost/scoped_ptr.hpp>
36 #include <qi/session.hpp>
72 Driver( qi::SessionPtr& session,
const std::string&
prefix );
87 std::string
minidump(
const std::string& prefix);
88 std::string
minidumpConverters(
const std::string& prefix,
const std::vector<std::string>& names);
151 return "the coolest German in Paris";
182 void setMasterURINet(
const std::string& uri,
const std::string& network_interface );
224 void parseJsonFile(std::string filepath, boost::property_tree::ptree& pt);
259 template <
typename T1,
typename T2,
typename T3>
261 boost::shared_ptr<T1> mfp = boost::make_shared<T1>( key );
262 boost::shared_ptr<T2> mfr = boost::make_shared<T2>( key );
263 boost::shared_ptr<T3> mfc = boost::make_shared<T3>( key , frequency,
sessionPtr_, key );
272 boost::scoped_ptr<ros::NodeHandle>
nhPtr_;
278 std::map< std::string, publisher::Publisher >
pub_map_;
279 std::map< std::string, recorder::Recorder >
rec_map_;
281 typedef std::map< std::string, publisher::Publisher>::const_iterator
PubConstIter;
282 typedef std::map< std::string, publisher::Publisher>::iterator
PubIter;
283 typedef std::map< std::string, recorder::Recorder>::const_iterator
RecConstIter;
284 typedef std::map< std::string, recorder::Recorder>::iterator
RecIter;
286 typedef std::map< std::string, event::Event>::iterator
EventIter;
Converter concept interface.
Definition: converter.hpp:42
void rosLoop()
Definition: naoqi_driver.cpp:165
std::map< std::string, recorder::Recorder >::iterator RecIter
Definition: naoqi_driver.hpp:284
void startPublishing()
qicli call function to start/enable publishing all registered publisher
Definition: naoqi_driver.cpp:900
void removeFiles(std::vector< std::string > files)
Definition: naoqi_driver.cpp:1257
bool registerEventConverter(const std::string &key, const dataType::DataType &type)
qicli call function to register a converter for a given memory event
Definition: naoqi_driver.cpp:1143
void stopRosLoop()
Definition: naoqi_driver.cpp:1054
void stopLogging()
Definition: naoqi_driver.cpp:1037
Driver(qi::SessionPtr &session, const std::string &prefix)
Constructor for naoqi driver.
Definition: naoqi_driver.cpp:112
qi::SessionPtr sessionPtr_
Definition: naoqi_driver.hpp:235
std::vector< converter::Converter > converters_
Definition: naoqi_driver.hpp:277
void registerPublisher(const std::string &conv_name, publisher::Publisher &pub)
prepare and register a publisher
Definition: naoqi_driver.cpp:417
Definition: message_actions.h:13
void stopService()
Definition: naoqi_driver.cpp:157
void startLogging()
Definition: naoqi_driver.cpp:1032
Recorder concept interface.
Definition: recorder.hpp:46
static std::string prefix
Definition: ros_env.hpp:64
Definition: naoqi_driver.hpp:294
void registerSubscriber(subscriber::Subscriber sub)
registers a subscriber
Definition: naoqi_driver.cpp:763
std::string getMasterURI() const
qicli call function to get current master uri
Definition: naoqi_driver.cpp:822
std::vector< std::string > getSubscribedPublishers() const
get all subscribed publishers
Definition: naoqi_driver.cpp:918
void startRosLoop()
Definition: naoqi_driver.cpp:1042
Subscriber concept interface.
Definition: subscriber.hpp:41
Definition: message_actions.h:12
bool log_enabled_
Definition: naoqi_driver.hpp:241
void parseJsonFile(std::string filepath, boost::property_tree::ptree &pt)
Definition: naoqi_driver.cpp:1065
boost::mutex mutex_conv_queue_
Definition: naoqi_driver.hpp:274
ros::Time schedule_
Definition: naoqi_driver.hpp:304
bool registerMemoryConverter(const std::string &key, float frequency, const dataType::DataType &type)
qicli call function to register a converter for a given memory key
Definition: naoqi_driver.cpp:461
std::map< std::string, publisher::Publisher >::iterator PubIter
Definition: naoqi_driver.hpp:282
Robot
Definition: tools.hpp:37
void loadBootConfig()
Definition: naoqi_driver.cpp:147
DataType
Definition: tools.hpp:52
void registerDefaultConverter()
Definition: naoqi_driver.cpp:523
boost::property_tree::ptree boot_config_
Definition: naoqi_driver.hpp:251
const size_t freq_
Definition: naoqi_driver.hpp:244
Definition: message_actions.h:11
std::vector< subscriber::Subscriber > subscribers_
Definition: naoqi_driver.hpp:288
boost::scoped_ptr< ros::NodeHandle > nhPtr_
Definition: naoqi_driver.hpp:272
boost::thread publisherThread_
Definition: naoqi_driver.hpp:245
Converter concept interface.
Definition: event.hpp:44
bool operator<(const ScheduledConverter &sp_in) const
Definition: naoqi_driver.hpp:300
std::string stopRecording()
qicli call function to stop recording all registered publisher in a ROSbag
Definition: naoqi_driver.cpp:1013
bool keep_looping
Definition: naoqi_driver.hpp:242
void stopPublishing()
qicli call function to stop/disable publishing all registered publisher
Definition: naoqi_driver.cpp:909
Interface for naoqi driver which is registered as a naoqi2 Module, once the external roscore ip is se...
Definition: naoqi_driver.hpp:65
Publisher concept interface.
Definition: publisher.hpp:41
std::map< std::string, event::Event > event_map_
Definition: naoqi_driver.hpp:280
void registerDefaultServices()
Definition: naoqi_driver.cpp:798
std::map< std::string, publisher::Publisher >::const_iterator PubConstIter
Definition: naoqi_driver.hpp:281
size_t conv_index_
Definition: naoqi_driver.hpp:306
void startRecording()
qicli call function to start recording all registered converter in a ROSbag
Definition: naoqi_driver.cpp:934
boost::shared_ptr< tf2_ros::Buffer > tf2_buffer_
Definition: naoqi_driver.hpp:315
boost::shared_ptr< recorder::GlobalRecorder > recorder_
Definition: naoqi_driver.hpp:248
void removeAllFiles()
Definition: naoqi_driver.cpp:1244
bool publish_enabled_
Definition: naoqi_driver.hpp:239
boost::mutex mutex_record_
Definition: naoqi_driver.hpp:275
std::string minidump(const std::string &prefix)
Write a ROSbag with the last bufferized data (10s by default)
Definition: naoqi_driver.cpp:246
std::vector< std::string > getFilesList()
Definition: naoqi_driver.cpp:1229
void setMasterURI(const std::string &uri)
qicli call function to set current master uri
Definition: naoqi_driver.cpp:827
const robot::Robot & robot_
Definition: naoqi_driver.hpp:237
std::priority_queue< ScheduledConverter > conv_queue_
Definition: naoqi_driver.hpp:310
std::string minidumpConverters(const std::string &prefix, const std::vector< std::string > &names)
Definition: naoqi_driver.cpp:305
void _registerMemoryConverter(const std::string &key, float frequency)
Definition: naoqi_driver.hpp:260
Definition: naoqi_driver.hpp:49
~Driver()
Destructor for naoqi driver, destroys all ros nodehandle and shutsdown all publisher.
Definition: naoqi_driver.cpp:126
void addMemoryConverters(std::string filepath)
qicli call function to add on-the-fly some memory keys extractors
Definition: naoqi_driver.cpp:1074
void setMasterURINet(const std::string &uri, const std::string &network_interface)
qicli call function to set current master uri
Definition: naoqi_driver.cpp:832
void init()
Definition: naoqi_driver.cpp:137
std::vector< service::Service > services_
Definition: naoqi_driver.hpp:289
void registerDefaultSubscriber()
Definition: naoqi_driver.cpp:784
std::vector< std::string > getAvailableConverters()
get all available converters
Definition: naoqi_driver.cpp:803
bool record_enabled_
Definition: naoqi_driver.hpp:240
ScheduledConverter(const ros::Time &schedule, size_t conv_index)
Definition: naoqi_driver.hpp:295
std::string _whoIsYourDaddy()
Definition: naoqi_driver.hpp:149
void insertEventConverter(const std::string &key, event::Event event)
Definition: naoqi_driver.cpp:435
void registerRecorder(const std::string &conv_name, recorder::Recorder &rec, float frequency)
prepare and register a recorder
Definition: naoqi_driver.cpp:427
std::map< std::string, event::Event >::const_iterator EventConstIter
Definition: naoqi_driver.hpp:285
std::map< std::string, recorder::Recorder >::const_iterator RecConstIter
Definition: naoqi_driver.hpp:283
void setBufferDuration(float duration)
Definition: naoqi_driver.cpp:390
boost::mutex mutex_reinit_
Definition: naoqi_driver.hpp:273
void registerService(service::Service srv)
registers a service
Definition: naoqi_driver.cpp:792
std::map< std::string, recorder::Recorder > rec_map_
Definition: naoqi_driver.hpp:279
void startRecordingConverters(const std::vector< std::string > &names)
qicli call function to start recording given topics in a ROSbag
Definition: naoqi_driver.cpp:959
std::map< std::string, event::Event >::iterator EventIter
Definition: naoqi_driver.hpp:286
float getBufferDuration()
Definition: naoqi_driver.cpp:403
float buffer_duration_
Definition: naoqi_driver.hpp:291
Service concept interface.
Definition: service.hpp:41
std::map< std::string, publisher::Publisher > pub_map_
Definition: naoqi_driver.hpp:278
void registerConverter(converter::Converter &conv)
registers generall converter units they are connected via callbacks to various actions such as record...
Definition: naoqi_driver.cpp:408