28#include <Eigen/Geometry>
30#include <opencv2/opencv.hpp>
35#include <RobotAPI/interface/core/RobotState.h>
41#include <VisionX/interface/components/RTABMapInterface.h>
45#include <Image/IplImageAdaptor.h>
47#include <MemoryX/interface/components/WorkingMemoryInterface.h>
50#pragma GCC diagnostic push
51#pragma GCC diagnostic ignored "-Wpedantic"
52#include <pcl/common/transforms.h>
53#include <pcl/filters/filter.h>
54#include <pcl/filters/passthrough.h>
55#include <pcl/io/pcd_io.h>
57#include <rtabmap/core/CameraEvent.h>
58#include <rtabmap/core/Odometry.h>
59#include <rtabmap/core/OdometryEvent.h>
60#include <rtabmap/core/OdometryThread.h>
61#include <rtabmap/core/Rtabmap.h>
62#include <rtabmap/core/RtabmapThread.h>
63#include <rtabmap/utilite/UEventsHandler.h>
64#include <rtabmap/utilite/UEventsManager.h>
65#include <rtabmap/utilite/ULogger.h>
67#pragma GCC diagnostic pop
88 "RobotStateComponentName",
89 "RobotStateComponent",
90 "Name of the robot state component that should be used");
92 "WorkingMemoryName",
"WorkingMemory",
"Name of the working memory");
94 "provideGlobalPointCloud",
96 "provide global point cloud if set. otherwise only the current view");
112 virtual public visionx::RTABMapInterface,
115 virtual public UEventsHandler
124 return "RTABMapRegistration";
147 CapturingPointCloudProvider::onInitComponent();
148 ImageProcessor::onInitComponent();
154 ImageProcessor::onConnectComponent();
155 CapturingPointCloudProvider::onConnectComponent();
161 CapturingPointCloudProvider::onDisconnectComponent();
162 ImageProcessor::onDisconnectComponent();
168 CapturingPointCloudProvider::onExitComponent();
169 ImageProcessor::onExitComponent();
178 bool extractPointCloud(rtabmap::SensorData sensorData,
180 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr& tempCloudPtr);
181 void updatePosition(Eigen::Matrix4f pose);
184 std::string agentName;
185 std::string providerName;
186 std::string sourceFrameName;
187 bool provideGlobalPointCloud;
189 rtabmap::Rtabmap* rtabmap;
190 rtabmap::RtabmapThread* rtabmapThread;
191 rtabmap::OdometryThread* odomThread;
192 rtabmap::CameraModel cameraModel;
196 armarx::MetaInfoSizeBasePtr imageMetaInfo;
199 Eigen::Matrix4f initialCameraPose;
201 boost::mutex RTABDataMutex;
203 boost::condition dataCondition;
205 void requestGlobalPointCloud();
206 std::map<int, rtabmap::Signature> signatures;
207 std::map<int, rtabmap::Transform> poses;
209 boost::mutex resultPointCloudMutex;
210 boost::condition resultCondition;
211 bool hasNewResultPointCloud;
212 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr resultPointCloudPtr;
214 pcl::PassThrough<pcl::PointXYZRGBA> passThroughFilter;
217 memoryx::WorkingMemoryInterfacePrx workingMemory;
218 memoryx::AgentInstancesSegmentBasePrx agentInstancesSegment;
221 std::string agentInstanceId;
IceUtil::Handle< PeriodicTask< T > > pointer_type
Shared pointer type for convenience.
std::string prefix
Prefix of the properties such as namespace, domain, component name, etc.
PropertyDefinition< PropertyType > & defineOptionalProperty(const std::string &name, PropertyType defaultValue, const std::string &description="", PropertyDefinitionBase::PropertyConstness constness=PropertyDefinitionBase::eConstant)
RTABMapRegistrationPropertyDefinitions(std::string prefix)
void onInitComponent() override
Pure virtual hook for the subclass.
void onConnectImageProcessor() override
Implement this method in the ImageProcessor in order execute parts when the component is fully initia...
bool doCapture() override
Main capturing function.
void onExitCapturingPointCloudProvider() override
This is called when the Component::onExitComponent() setup is called.
void onDisconnectComponent() override
Hook for subclass.
void onExitImageProcessor() override
Exit the ImapeProcessor component.
void onStartCapture(float framesPerSecond) override
This is called when the point cloud provider capturing has been started.
visionx::MetaPointCloudFormatPtr getDefaultPointCloudFormat() override
default point cloud format used to initialize shared memory
bool handleEvent(UEvent *event) override
void process() override
Process the vision component.
void onInitCapturingPointCloudProvider() override
This is called when the Component::onInitComponent() is called.
void onInitImageProcessor() override
Setup the vision component.
void onConnectComponent() override
Pure virtual hook for the subclass.
void onStopCapture() override
This is called when the point cloud provider capturing has been stopped.
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
void onExitComponent() override
Hook for subclass.
std::string getDefaultName() const override
CapturingPointCloudProviderPropertyDefinitions(std::string prefix)
The CapturingPointCloudProvider provides a callback function to trigger the capturing of point clouds...
The ImageProcessor class provides an interface for access to ImageProviders via Ice and shared memory...
This file offers overloads of toIce() and fromIce() functions for STL container types.
auto transform(const Container< InputT, Alloc > &in, OutputT(*func)(InputT const &)) -> Container< OutputT, typename std::allocator_traits< Alloc >::template rebind_alloc< OutputT > >
Convenience function (with less typing) to transform a container of type InputT into the same contain...
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
::IceInternal::ProxyHandle<::IceProxy::armarx::RobotStateComponentInterface > RobotStateComponentInterfacePrx
IceInternal::Handle< AgentInstance > AgentInstancePtr
Typedef of AgentEntityPtr as IceInternal::Handle<AgentEntity> for convenience.