22 #include "pcl_db_retrieve_thread.h"
24 #include <blackboard/utils/on_message_waker.h>
25 #include <interfaces/PclDatabaseRetrieveInterface.h>
58 foutput_->is_dense =
false;
60 output_ = pcl_utils::cloudptr_from_refptr(foutput_);
63 foriginal_->is_dense =
false;
65 original_ = pcl_utils::cloudptr_from_refptr(foriginal_);
106 std::vector<long long> times(1);
107 std::string database;
108 std::string collection;
109 std::string target_frame;
110 bool original_timestamp;
112 if (retrieve_if_->msgq_empty())
115 if (PclDatabaseRetrieveInterface::RetrieveMessage *msg = retrieve_if_->msgq_first_safe(msg)) {
116 retrieve_if_->set_final(
false);
117 retrieve_if_->set_msgid(msg->id());
118 retrieve_if_->set_error(
"");
119 retrieve_if_->write();
121 timestamp = msg->timestamp();
122 times[0] = timestamp;
123 database = (strcmp(msg->database(),
"") != 0) ? msg->database() : cfg_database_;
124 collection = msg->collection();
125 target_frame = msg->target_frame();
126 original_timestamp = msg->is_original_timestamp();
129 retrieve_if_->msgq_pop();
132 retrieve_if_->msgq_pop();
134 logger->
log_info(
name(),
"Restoring from '%s' for the time %li", collection.c_str(), timestamp);
136 ApplicabilityStatus st_xyz, st_xyzrgb;
137 long actual_time = 0;
139 pl_xyz_->
applicable(times, database, collection);
140 if ((st_xyz = pl_xyz_->
applicable(times, database, collection)) == APPLICABLE) {
142 pl_xyz_->
retrieve(timestamp, database, collection, target_frame, actual_time);
143 }
else if ((st_xyzrgb = pl_xyzrgb_->
applicable(times, database, collection)) == APPLICABLE) {
145 pl_xyzrgb_->
retrieve(timestamp, database, collection, target_frame, actual_time);
146 if (!original_timestamp) {
148 pcl_utils::set_time(foutput_, now);
154 retrieve_if_->set_error(
"No applicable merging pipeline known (for details see log)");
157 if (actual_time != 0) {
158 if (original_timestamp) {
159 Time now((
long)actual_time);
161 pcl_utils::get_time(foutput_, last);
165 pcl_utils::set_time(foutput_, now);
168 pcl_utils::set_time(foutput_, now);
172 retrieve_if_->set_final(
true);
173 retrieve_if_->write();
ApplicabilityStatus applicable(std::vector< long long > ×, std::string &database, std::string &collection)
Check if this pipeline instance is suitable for the given times.
void retrieve(long timestamp, std::string &database, std::string &collection, std::string &target_frame, long &actual_time)
Retrieve point clouds.
PointCloudDBRetrieveThread()
Constructor.
virtual ~PointCloudDBRetrieveThread()
Destructor.
virtual void loop()
Code to execute in the thread.
virtual void finalize()
Finalize the thread.
virtual void init()
Initialize the thread.
BlackBoard * blackboard
This is the BlackBoard instance you can use to interact with the BlackBoard.
Wake threads on receiving a blackboard message.
virtual Interface * open_for_writing(const char *interface_type, const char *identifier, const char *owner=NULL)=0
Open interface for writing.
virtual void close(Interface *interface)=0
Close interface.
Clock * clock
By means of this member access to the clock is given.
Configuration * config
This is the Configuration member used to access the configuration.
virtual std::string get_string(const char *path)=0
Get value from configuration which is of type string.
Base class for exceptions in Fawkes.
virtual void log_warn(const char *component, const char *format,...)=0
Log warning message.
virtual void log_info(const char *component, const char *format,...)=0
Log informational message.
Logger * logger
This is the Logger member used to access the logger.
Thread aspect to access MongoDB.
mongocxx::client * mongodb_client
MongoDB client to use to interact with the database.
PointCloudManager * pcl_manager
Manager to distribute and access point clouds.
void remove_pointcloud(const char *id)
Remove the point cloud.
void add_pointcloud(const char *id, RefPtr< pcl::PointCloud< PointT >> cloud)
Add point cloud.
void reset()
Reset pointer.
Thread class encapsulation of pthreads.
const char * name() const
Get name of thread.
A class for handling time.
Fawkes library namespace.