Class Driver
Defined in File naoqi_driver.hpp
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public rclcpp::Node
Class Documentation
-
class Driver : public rclcpp::Node
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.
Public Functions
-
Driver()
Constructor for the naoqi driver.
-
~Driver()
Destructor for naoqi driver, destroys all ros nodehandle and shutsdown all publisher.
-
void run()
Register the ROS components and start the ROS loop.
-
void setQiSession(const qi::SessionPtr &session_ptr)
Set the Session object.
-
void stop()
-
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 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
-
void registerPublisher(const std::string &conv_name, publisher::Publisher &pub)
prepare and register a publisher
- Parameters:
conv_name – the name of the converter related to the publisher
pub – the publisher to add
-
void registerRecorder(const std::string &conv_name, recorder::Recorder &rec, float frequency)
prepare and register a recorder
- Parameters:
conv_name – the name of the converter related to the recorder
rec – the recorder to add
-
void registerConverter(converter::Converter conv, publisher::Publisher pub, recorder::Recorder rec)
register a converter with an associated publisher and recorder
-
void registerPublisher(converter::Converter conv, publisher::Publisher pub)
register a converter with an associated publisher instance
-
void registerRecorder(converter::Converter conv, recorder::Recorder rec)
register a converter with an associated recorder instance
-
bool registerMemoryConverter(const std::string &key, float frequency, const dataType::DataType &type)
qicli call function to register a converter for a given memory key
-
bool registerEventConverter(const std::string &key, const dataType::DataType &type)
qicli call function to register a converter for a given memory event
-
std::vector<std::string> getAvailableConverters()
get all available converters
-
std::vector<std::string> getSubscribedPublishers() const
get all subscribed publishers
-
inline std::string _whoIsYourDaddy()
-
void registerSubscriber(subscriber::Subscriber sub)
registers a subscriber
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
- Parameters:
subscriber – to register
-
void registerService(service::Service srv)
registers a service
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
- Parameters:
service – to register
-
void startPublishing()
qicli call function to start/enable publishing all registered publisher
-
void stopPublishing()
qicli call function to stop/disable 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
-
std::string stopRecording()
qicli call function to stop recording all registered publisher in a ROSbag
-
void startLogging()
-
void stopLogging()
-
void addMemoryConverters(std::string filepath)
qicli call function to add on-the-fly some memory keys extractors
-
void parseJsonFile(std::string filepath, boost::property_tree::ptree &pt)
-
std::vector<std::string> getFilesList()
-
void removeAllFiles()
-
void removeFiles(std::vector<std::string> files)
-
Driver()