22 #include "pcl_db_merge_thread.h" 23 #include <interfaces/PclDatabaseMergeInterface.h> 25 #include <blackboard/utils/on_message_waker.h> 37 :
Thread(
"PointCloudDBMergeThread",
Thread::OPMODE_WAITFORWAKEUP)
61 foutput_->is_dense =
false;
63 output_ = pcl_utils::cloudptr_from_refptr(foutput_);
105 std::vector<long long> times;
106 std::string database;
107 std::string collection;
120 int64_t *timestamps = msg->timestamps();
121 for (
size_t i = 0; i < msg->maxlenof_timestamps(); ++i) {
122 if (timestamps[i] > 0) {
123 times.push_back(timestamps[i]);
127 (strcmp(msg->database(),
"") != 0) ? msg->database() : cfg_database_;
128 collection = msg->collection();
145 merge_if_->
set_error(
"Called for merge, but no non-zero times given");
152 for (
size_t i = 0; i < times.size(); ++i) {
156 ApplicabilityStatus st_xyz, st_xyzrgb;
158 pl_xyz_->
applicable(times, database, collection);
159 if ((st_xyz = pl_xyz_->
applicable(times, database, collection)) == APPLICABLE) {
160 pl_xyz_->
merge(times, database, collection);
162 pcl_utils::set_time(foutput_, now);
163 }
else if ((st_xyzrgb = pl_xyzrgb_->
applicable(times, database, collection)) == APPLICABLE) {
164 pl_xyzrgb_->
merge(times, database, collection);
166 pcl_utils::set_time(foutput_, now);
171 merge_if_->
set_error(
"Merge failed, see pcl-db-merge log");
PclDatabaseMergeInterface Fawkes BlackBoard Interface.
bool msgq_empty()
Check if queue is empty.
virtual void log_info(const char *component, const char *format,...)=0
Log informational message.
void remove_pointcloud(const char *id)
Remove the point cloud.
void set_final(const bool new_final)
Set final value.
void merge(std::vector< long long > ×, std::string &database, std::string &collection)
Merge point clouds.
virtual void loop()
Code to execute in the thread.
Fawkes library namespace.
mongo::DBClientBase * mongodb_client
MongoDB client to use to interact with the database.
Wake threads on receiving a blackboard message.
A class for handling time.
void add_pointcloud(const char *id, RefPtr< pcl::PointCloud< PointT > > cloud)
Add point cloud.
Thread class encapsulation of pthreads.
void write()
Write from local copy into BlackBoard memory.
Logger * logger
This is the Logger member used to access the logger.
MergeMessage Fawkes BlackBoard Interface Message.
virtual void finalize()
Finalize the thread.
PointCloudDBMergeThread()
Constructor.
Clock * clock
By means of this member access to the clock is given.
void reset()
Reset pointer.
void msgq_pop()
Erase first message from queue.
virtual ~PointCloudDBMergeThread()
Destructor.
PointCloudManager * pcl_manager
Manager to distribute and access point clouds.
Base class for exceptions in Fawkes.
void set_msgid(const uint32_t new_msgid)
Set msgid value.
void set_error(const char *new_error)
Set error value.
const char * name() const
Get name of thread.
virtual void log_warn(const char *component, const char *format,...)=0
Log warning message.
MessageType * msgq_first_safe(MessageType *&msg)
Get first message casted to the desired type without exceptions.
virtual void init()
Initialize the thread.
Configuration * config
This is the Configuration member used to access the configuration.
virtual Interface * open_for_writing(const char *interface_type, const char *identifier, const char *owner=NULL)=0
Open interface for writing.
virtual std::string get_string(const char *path)=0
Get value from configuration which is of type string.
ApplicabilityStatus applicable(std::vector< long long > ×, std::string &database, std::string &collection)
Check if this pipeline instance is suitable for the given times.
BlackBoard * blackboard
This is the BlackBoard instance you can use to interact with the BlackBoard.
virtual void close(Interface *interface)=0
Close interface.