26#include <pcl/common/transforms.h>
27#include <pcl/point_types.h>
34#include <VisionX/interface/components/Calibration.h>
37static constexpr auto InMaskSuff =
"_in_mask";
38static constexpr auto OutOfMaskSuff =
"_out_of_mask";
39static constexpr auto OutOfMaskImgSuff =
"_out_of_image";
40static constexpr auto MaskVisuSuff =
"_mask_visu";
41static constexpr auto MaskAsCloudSuff =
"_mask_as_cloud";
43#define call_template_function(F) \
44 switch (_pointCloudProviderInfo.pointCloudFormat->type) \
47 case visionx::PointContentType::eColoredPoints: \
48 F<pcl::PointXYZRGBA>(); \
50 case visionx::PointContentType::eColoredOrientedPoints: \
51 F<pcl::PointXYZRGBNormal>(); \
54 case visionx::PointContentType::eColoredLabeledPoints: \
55 F<pcl::PointXYZRGBL>(); \
58 case visionx::PointContentType::eOrientedPoints: \
59 ARMARX_ERROR << "eOrientedPoints NOT HANDLED IN VISIONX"; \
62 ARMARX_ERROR << "Could not process point cloud, because format '" \
63 << _pointCloudProviderInfo.pointCloudFormat->type << "' is unknown"; \
110 VirtualRobot::RobotIO::eStructure);
185 if (calibProviderName.empty())
188 visionx::MonocularCalibrationCapturingProviderInterfacePrx::checkedCast(
196 scalibprov->getStereoCalibration().calibrationLeft.cameraParam.focalLength.at(
199 scalibprov->getStereoCalibration().calibrationLeft.cameraParam.focalLength.at(
205 mcalibprov->getCalibration().cameraParam.focalLength.at(0);
207 mcalibprov->getCalibration().cameraParam.focalLength.at(1);
214 visionx::MonocularCalibrationCapturingProviderInterfacePrx::checkedCast(
216 auto scalibprov = visionx::StereoCalibrationInterfacePrx::checkedCast(calibProvider);
221 scalibprov->getStereoCalibration().calibrationLeft.cameraParam.focalLength.at(
224 scalibprov->getStereoCalibration().calibrationLeft.cameraParam.focalLength.at(
230 mcalibprov->getCalibration().cameraParam.focalLength.at(0);
232 mcalibprov->getCalibration().cameraParam.focalLength.at(1);
241 auto makeSlider = [&](std::string name,
int val,
int min = 0,
int max = 255)
250 auto makeFSlider = [&](std::string name,
int min,
int max,
float val)
256 static_cast<int>(
max -
min)))
262 makeSlider(
"red lo",
_redLo);
263 makeSlider(
"red hi",
_redHi);
266 makeSlider(
"blue lo",
_blueLo);
267 makeSlider(
"blue hi",
_blueHi);
289 const int focaladjrange = 10000;
298 .addOptions({
"Global",
"root"})
304 checkboxBuilder.widget().label =
"Sync using timestamp";
305 rootLayoutBuilder.
addChild(checkboxBuilder);
306 rootLayoutBuilder.
addChild(
new RemoteGui::VSpacer());
313 _redLo =
static_cast<std::uint8_t
>(
_guiTab.getValue<
int>(
"red lo").get());
316 _redHi =
static_cast<std::uint8_t
>(
_guiTab.getValue<
int>(
"red hi").get());
319 _greenLo =
static_cast<std::uint8_t
>(
_guiTab.getValue<
int>(
"green lo").get());
322 _greenHi =
static_cast<std::uint8_t
>(
_guiTab.getValue<
int>(
"green hi").get());
325 _blueLo =
static_cast<std::uint8_t
>(
_guiTab.getValue<
int>(
"blue lo").get());
328 _blueHi =
static_cast<std::uint8_t
>(
_guiTab.getValue<
int>(
"blue hi").get());
353 RemoteGui::WidgetPtr rootLayout = rootLayoutBuilder;
370std::pair<float, float>
381 const float s = std::sin(alpha);
382 const float c = std::cos(alpha);
388 const float ushifted = u - +width / 2.f +
_offsetX;
389 const float vshifted = v - +height / 2.f +
_offsetY;
391 const float rotatedU =
c * ushifted + s * vshifted;
392 const float rotatedV = -s * ushifted +
c * vshifted;
394 const float x = (
_flipX ? 1 : -1) * rotatedU;
395 const float y = (
_flipY ? 1 : -1) * rotatedV;
400std::array<std::int64_t, 2>
404 const float s = std::sin(alpha);
405 const float c = std::cos(alpha);
408 const float u = (
_flipX ? 1 : -1) * (
x / z) * fx;
409 const float v = (
_flipY ? 1 : -1) * (y / z) * fy;
411 const float rotatedU =
c * u + -s * v;
412 const float rotatedV = s * u +
c * v;
418 const std::int64_t imgx =
static_cast<std::int64_t
>(rotatedU + width / 2.f) -
_offsetX;
419 const std::int64_t imgy =
static_cast<std::int64_t
>(rotatedV + height / 2.f) -
_offsetY;
431template <
typename Po
intType>
457 typename pcl::PointCloud<PointType>::Ptr inputCloud(
new pcl::PointCloud<PointType>());
476 Eigen::Matrix4f pclInCamFrame = Eigen::Matrix4f::Identity();
477 Eigen::Matrix4f camInReportFrame = Eigen::Matrix4f::Identity();
488 camInReportFrame = fp.toEigen();
494 pclInCamFrame = fp.toEigen();
499 typename pcl::PointCloud<PointType>::Ptr tmpCloud(
new pcl::PointCloud<PointType>());
500 pcl::transformPointCloud(*inputCloud, *tmpCloud, pclInCamFrame);
501 tmpCloud.swap(inputCloud);
508 std::uint64_t pointsInImage = 0;
509 std::uint64_t pointsOutOfImage = 0;
510 _maskedCloud.reset(
new pcl::PointCloud<pcl::PointXYZRGBA>());
511 _inputCloud.reset(
new pcl::PointCloud<pcl::PointXYZRGBA>());
512 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr unmaskedCloud(
new pcl::PointCloud<pcl::PointXYZRGBA>());
513 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr outOfImageCloud(
514 new pcl::PointCloud<pcl::PointXYZRGBA>());
515 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr visuCloud(
new pcl::PointCloud<pcl::PointXYZRGBA>());
519 for (
const auto& point : inputCloud->points)
527 static_assert(std::is_same<PointType, pcl::PointXYZRGBA>::value ||
528 std::is_same<PointType, pcl::PointXYZRGB>::value ||
529 std::is_same<PointType, pcl::PointXYZRGBL>::value ||
530 std::is_same<PointType, pcl::PointXYZRGBNormal>::value,
547 const auto uv =
xyz2uv(p.x, p.y, p.z, fx, fy);
548 const std::int64_t u = uv.at(0);
549 const std::int64_t v = uv.at(1);
550 if (u < 0 || u >= img.width || v < 0 || v >= img.height)
554 p.r = p.b = p.a = 255;
556 outOfImageCloud->push_back(p);
561 p.r = img.pixels[(u + v * img.width) * 3 + 0];
562 p.g = img.pixels[(u + v * img.width) * 3 + 1];
563 p.b = img.pixels[(u + v * img.width) * 3 + 2];
567 const bool okR = r.first <= p.r && r.second >= p.r;
568 const bool okG = g.first <= p.g && g.second >= p.g;
569 const bool okB = b.first <= p.b && b.second >= p.b;
577 unmaskedCloud->push_back(p);
579 visuCloud->push_back(p);
583 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr tmpCloud(
new pcl::PointCloud<pcl::PointXYZRGBA>());
585 pcl::transformPointCloud(*
_maskedCloud, *tmpCloud, camInReportFrame);
588 pcl::transformPointCloud(*unmaskedCloud, *tmpCloud, camInReportFrame);
591 pcl::transformPointCloud(*outOfImageCloud, *tmpCloud, camInReportFrame);
594 pcl::transformPointCloud(*visuCloud, *tmpCloud, camInReportFrame);
599 for (
int u = 0; u < img.width; ++u)
601 for (
int v = 0; v < img.height; ++v)
604 auto xyz =
uvz2xyz(u, v, (fx + fy) / 2, fx, fy);
610 p.r = img.pixels[(u + v * img.width) * 3 + 0];
611 p.g = img.pixels[(u + v * img.width) * 3 + 1];
612 p.b = img.pixels[(u + v * img.width) * 3 + 2];
613 visuCloud->push_back(p);
616 pcl::transformPointCloud(*visuCloud, *tmpCloud, camInReportFrame);
std::string getConfigIdentifier()
Retrieve config identifier for this component as set in constructor.
Property< PropertyType > getProperty(const std::string &name)
void changeFrame(const SharedRobotInterfacePrx &referenceRobot, const std::string &newFrame)
void offeringTopic(const std::string &name)
Registers a topic for retrival after initialization.
TopicProxyType getTopic(const std::string &name)
Returns a proxy of the specified topic.
bool usingProxy(const std::string &name, const std::string &endpoints="")
Registers a proxy for retrieval after initialization and adds it to the dependency list.
std::string getName() const
Retrieve name of object.
Ice::ObjectPrx getProxy(long timeoutMs=0, bool waitForScheduler=true) const
Returns the proxy of this object (optionally it waits for the proxy)
visionx::PointCloudProviderInterfacePrx _pointCloudProvider
VirtualRobot::RobotPtr _localRobot
visionx::ImageProviderInterfacePrx _maskImageProvider
visionx::ImageProviderInfo _maskImageProviderInfo
void onDisconnectPointCloudAndImageProcessor() override
Implement this method in the PointCloudAndImageProcessor in order to execute parts when the component...
std::string _remoteGuiName
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr _maskedCloud
void onConnectPointCloudAndImageProcessor() override
Implement this method in your PointCloudAndImageProcessor in order execute parts when the component i...
std::atomic< std::uint8_t > _greenLo
std::atomic< std::int64_t > _offsetY
std::string _pointCloudReportFrame
armarx::PropertyDefinitionsPtr createPropertyDefinitions() override
std::mutex _pointCloudReportFrameMutex
void process() override
Process the vision component.
RemoteGui::TabProxy _guiTab
std::array< float, 3 > uvz2xyz(int u, int v, float z, float fx, float fy) const
std::string _pointCloudProviderRefFrame
std::atomic< std::uint8_t > _blueHi
float _maskImageProviderFocalLengthY
std::string _pointCloudProviderName
std::atomic_bool _syncRobotWithTimestamp
std::atomic< std::uint8_t > _blueLo
std::atomic< std::uint8_t > _redLo
std::vector< visionx::CByteImageUPtr > _maskImageProviderImageOwner
std::string _maskImageProviderName
float _maskImageProviderFocalLengthX
RobotStateComponentInterfacePrx _robotStateComponent
void onInitPointCloudAndImageProcessor() override
Setup the vision component.
std::atomic< std::uint8_t > _greenHi
visionx::PointCloudProviderInfo _pointCloudProviderInfo
std::string _maskImageProviderRefFrame
DebugDrawerInterfacePrx _debugDrawerTopic
RemoteGuiInterfacePrx _remoteGui
std::string _robotStateComponentName
std::pair< float, float > maskImageProviderFocalLength() const
std::atomic< std::int64_t > _guiParamUpdated
SimplePeriodicTask ::pointer_type _guiTask
std::vector< void * > _maskImageProviderImages
std::atomic< float > _focalLengthAdjustment
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr _inputCloud
std::atomic_bool _maskMatchOneRangeInsteadOfAll
std::string _debugDrawerTopicName
std::atomic< std::uint8_t > _redHi
std::atomic< float > _maskZRotation
std::atomic< std::int64_t > _offsetX
std::array< std::int64_t, 2 > xyz2uv(float x, float y, float z, float fx, float fy) const
static VirtualRobot::RobotPtr createLocalCloneFromFile(RobotStateComponentInterfacePrx robotStatePrx, VirtualRobot::RobotIO::RobotDescription loadMode=VirtualRobot::RobotIO::eFull)
This is a convenience function for createLocalClone, which automatically gets the filename from the R...
static bool synchronizeLocalClone(VirtualRobot::RobotPtr robot, RobotStateComponentInterfacePrx robotStatePrx)
static bool synchronizeLocalCloneToTimestamp(VirtualRobot::RobotPtr robot, RobotStateComponentInterfacePrx robotStatePrx, Ice::Long timestamp)
Synchronizes a local robot to a robot state at timestamp.
void usingImageProvider(std::string name)
Registers a delayed topic subscription and a delayed provider proxy retrieval which all will be avail...
bool waitForImages(int milliseconds=1000)
Wait for new images.
ImageProviderInfo getImageProvider(std::string name, ImageType destinationImageType=eRgb, bool waitForProxy=false)
Select an ImageProvider.
int getImages(CByteImage **ppImages)
Poll images from provider.
void enableResultPointClouds(std::string resultProviderName="")
Enables visualization.
int getPointClouds(const PointCloudPtrT &pointCloudPtr)
Poll PointClouds from provider.
MetaPointCloudFormatPtr getPointCloudFormat(std::string providerName)
void usingPointCloudProvider(std::string providerName)
Registers a delayed topic subscription and a delayed provider proxy retrieval which will be available...
PointCloudProviderInfo getPointCloudProvider(std::string name, bool waitForProxy=false)
Select an PointCloudProvider.
bool waitForPointClouds(int milliseconds=1000)
Wait for new PointClouds.
void provideResultPointClouds(const PointCloudPtrT &pointClouds, std::string providerName="")
sends result PointClouds for visualization
#define ARMARX_CHECK_EXPRESSION(expression)
This macro evaluates the expression and if it turns out to be false it will throw an ExpressionExcept...
#define ARMARX_CHECK_GREATER_EQUAL(lhs, rhs)
This macro evaluates whether lhs is greater or equal (>=) rhs and if it turns out to be false it will...
#define ARMARX_CHECK_EQUAL(lhs, rhs)
This macro evaluates whether lhs is equal (==) rhs and if it turns out to be false it will throw an E...
#define ARMARX_INFO
The normal logging level.
detail::IntSpinBoxBuilder makeIntSpinBox(std::string const &name)
detail::CheckBoxBuilder makeCheckBox(std::string const &name)
detail::ComboBoxBuilder makeComboBox(std::string const &name)
detail::FloatSliderBuilder makeFloatSlider(std::string const &name)
detail::VBoxLayoutBuilder makeVBoxLayout(std::string const &name="")
detail::FloatSpinBoxBuilder makeFloatSpinBox(std::string const &name)
detail::LabelBuilder makeTextLabel(std::string const &text)
detail::HBoxLayoutBuilder makeHBoxLayout(std::string const &name="")
detail::IntSliderBuilder makeIntSlider(std::string const &name)
This file offers overloads of toIce() and fromIce() functions for STL container types.
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
std::vector< T > max(const std::vector< T > &v1, const std::vector< T > &v2)
SimplePeriodicTask(Ts...) -> SimplePeriodicTask< std::function< void(void)> >
std::vector< T > min(const std::vector< T > &v1, const std::vector< T > &v2)
Derived & addChild(WidgetPtr const &child)