|
ArmarX headers. More...
Namespaces | |
armem | |
armem_images | |
components | |
ConvexPolygonCalculations | |
depthfilter | |
depthfromstereo | |
exceptions | |
imrec | |
imrecman | |
opstress | |
playback | |
roboception | |
tools | |
utils | |
voxelgrid | |
yolo | |
Enumerations | |
enum | KinectProcessorType { CPU, OPENCL, OPENCLKDE, OPENGL, CUDA, CUDAKDE } |
enum | ViewMode { Full, StatusOnly } |
Functions | |
Eigen::Hyperplane3f | alignPlaneNormal (Eigen::Hyperplane3f plane, Eigen::Vector3f normal) |
Flip plane if its normal does not point towards normal . More... | |
bool | comparePointClustersDescending (const pcl::PointIndices &lhs, const pcl::PointIndices &rhs) |
void | convertDepthInMetersToWeirdArmarX (const cv::Mat &input, CByteImage *output) |
void | convertIvtRgbToCvGray (const CByteImage &ivt_rgb, cv::Mat &cv_gray) |
cv::Mat | convertWeirdArmarXToDepthInMeters (CByteImage const *input) |
Convert ArmarX encoding of depth information in an RGB image to depth in meters. More... | |
void | convertWeirdArmarXToDepthInMeters (const uint8_t *input, cv::Mat &output) |
Like convertWeirdArmarXToDepthInMeters(CByteImage const* input) , but writes into a pre-initialized cv::Mat with the correct size and type. More... | |
void | copyCvDepthToGrayscaleIVT (cv::Mat const &inputInMeters, CByteImage *output) |
Copies a floating point depth image (in meters) to an RGB depth representation. More... | |
void | copyCvMatToIVT (cv::Mat const &input, CByteImage *output) |
Copies the contents of an OpenCV matrix to an IVT CByteImage. More... | |
template<class PointT > | |
void | copyPointCloudWithoutIndices (const pcl::PointCloud< PointT > &input, const std::vector< int > &indices, pcl::PointCloud< PointT > &output) |
bool | eq (float lhs, float rhs, float tol=1e-6f) |
void | evaluateOLP (OLPEvaluation *p, bool testRecognition) |
void | ExtractAnglesFromRotationMatrix (const Mat3d &mat, Vec3d &angles) |
void | fillCameraMatrix (const CCalibration::CCameraParameters &ivtCameraParameters, cv::Mat &output) |
Fill a propertly initialized camera matrix with the given camera parameters. More... | |
void | fillCameraMatrix (const visionx::CameraParameters &cameraParams, cv::Mat &output) |
Fill a propertly initialized camera matrix with the given camera parameters. More... | |
template<class ColorT > | |
void | fillColorArray (float array[3], const ColorT &color) |
template<class PointT > | |
void | filterNaNs (pcl::PointCloud< PointT > &pc) |
Eigen::Hyperplane3f | fitPlaneSVD (const pcl::PointCloud< pcl::PointXYZRGBA > &cloud, const pcl::PointIndices &indices, Eigen::Vector3f center=Eigen::Vector3f::Zero()) |
Eigen::Hyperplane3f | fitPlaneSVD (const pcl::PointCloud< pcl::PointXYZRGBA > &cloud, Eigen::Vector3f center=Eigen::Vector3f::Zero()) |
template<class PointCloudPtrT > | |
FramedPointCloud (PointCloudPtrT pointCloudPtr) -> FramedPointCloud< typename PointCloudPtrT::element_type::PointType > | |
template<class PointCloudPtrT > | |
FramedPointCloud (PointCloudPtrT pointCloudPtr, const std::string &frameName) -> FramedPointCloud< typename PointCloudPtrT::element_type::PointType > | |
pcl::PointIndicesPtr | getPlaneInliers (const pcl::PointCloud< pcl::PointXYZRGBA > &cloud, Eigen::Hyperplane3f plane, float maxDistance) |
template<class PointT > | |
pcl::PointCloud< PointT >::Ptr | getPointCloudWithIndices (const pcl::PointCloud< PointT > &input, const pcl::PointIndices &indices) |
template<class PointT > | |
pcl::PointCloud< PointT >::Ptr | getPointCloudWithIndices (const pcl::PointCloud< PointT > &input, const std::vector< int > &indices) |
template<class PointT > | |
pcl::PointCloud< PointT >::Ptr | getPointCloudWithoutIndices (const pcl::PointCloud< PointT > &input, const std::vector< int > &indices) |
float | hsvDistance (const Eigen::Vector3f &lhs, const Eigen::Vector3f &rhs, const Eigen::Vector3f &hsvWeights=Eigen::Vector3f::Ones()) |
float | hsvDistance (const pcl::PointXYZHSV &lhs, const pcl::PointXYZHSV &rhs, const Eigen::Vector3f &hsvWeights=Eigen::Vector3f::Ones()) |
Eigen::Vector3f | hsvMean (const pcl::PointCloud< pcl::PointXYZHSV > &hsvCloud, const std::vector< int > &indices) |
template<class PointRGB > | |
Eigen::Vector3f | hsvMean (const pcl::PointCloud< PointRGB > &rgbCloud, const std::vector< int > &indices) |
template<class CameraParams > | |
cv::Mat | makeCameraMatrix (const CameraParams &cameraParams, int rows=3, int cols=3, int type=CV_64F) |
Builds a camera matrix. More... | |
cv::Mat | makeCameraMatrix (const visionx::CameraParameters &cameraParams) |
bool | operator!= (const ColoredPoint3D &lhs, const ColoredPoint3D &rhs) |
bool | operator!= (const LabeledPoint3D &lhs, const LabeledPoint3D &rhs) |
bool | operator!= (const Point3D &lhs, const Point3D &rhs) |
std::ostream & | operator<< (std::ostream &os, const ColoredPoint3D &rhs) |
std::ostream & | operator<< (std::ostream &os, const LabeledPoint3D &rhs) |
std::ostream & | operator<< (std::ostream &os, const Point3D &rhs) |
std::ostream & | operator<< (std::ostream &os, const RGBA &rhs) |
Eigen::Vector3f | pointCloudMedian (const pcl::PointCloud< pcl::PointXYZRGBA > &cloud, const pcl::PointIndices &indices={}) |
void | sortPointClustersDescending (std::vector< pcl::PointIndices > &clusterIndices) |
int | toByte (float f) |
template<class PointT > | |
void | transformPointCloudFromTo (const pcl::PointCloud< PointT > &sourceCloud, pcl::PointCloud< PointT > &targetCloud, const std::string &sourceFrame, const std::string &targetFrame, const VirtualRobot::RobotPtr &robot) |
Transform a point cloud from a robot frame to another. More... | |
Variables | |
const double | DSHT_default_allowed_deviation [12] |
const std::map< std::string, std::pair< unsigned int, std::string > > | MPII_TO_MPI |
ArmarX headers.
This package provides an API to read recordings frame-by-frame of any type and obtain their metadata.
Current available formats are:
.avi
, .mp4
; provided by OpenCV2) via VideoPlaybackStrategyRequired header:
Example (Play back an AVI recording):
::playback
using CByteImagePtr = std::shared_ptr<CByteImage> |
Definition at line 109 of file ImageMonitorWidgetController.h.
using CByteImageUPtr = std::unique_ptr<CByteImage> |
Definition at line 57 of file ImageProvider.h.
using CByteImageUPtrVec = std::vector<std::unique_ptr<CByteImage> > |
Definition at line 58 of file ImageProvider.h.
typedef std::shared_ptr< CColorParameterSet > CColorParameterSetPtr |
Definition at line 44 of file BlobRecognition.h.
using CObjectFinderStereoPtr = std::shared_ptr<CObjectFinderStereo> |
Definition at line 43 of file BlobRecognition.h.
typedef std::shared_ptr< CSegmentableRecognition > CSegmentableRecognitionPtr |
Definition at line 43 of file ColorMarkerObjectLocalizer.h.
using DebugDrawerPointCloudPtr = std::shared_ptr<armarx::DebugDrawer24BitColoredPointCloud> |
Definition at line 79 of file PointCloudVisualization.h.
Definition at line 113 of file Component.h.
using ImageContainer = std::vector<CByteImagePtr> |
Definition at line 110 of file ImageMonitorWidgetController.h.
Shared pointer for convenience.
Definition at line 428 of file ImageProcessor.h.
Definition at line 94 of file ImageRecordingManager.h.
Definition at line 11 of file LabelDensity.h.
Definition at line 9 of file LabelDensity.h.
Definition at line 10 of file LabelDensity.h.
Definition at line 11 of file LabelOccupancy.h.
Definition at line 9 of file LabelOccupancy.h.
Definition at line 10 of file LabelOccupancy.h.
Definition at line 82 of file OpenPoseStressTest.h.
typedef pcl::PointXYZRGBA Point |
Definition at line 69 of file ObjectShapeClassification.h.
using PointCloud = pcl::PointCloud<Point> |
Definition at line 54 of file RCPointCloudProvider.cpp.
Shared pointer for convenience.
Definition at line 630 of file PointCloudProcessor.h.
using PointCloudVisualizationCollection = std::map<visionx::PointContentType, DebugDrawerPointCloudPtr> |
Definition at line 80 of file PointCloudVisualization.h.
using PointCloudVisualizationHandlerPtr = std::shared_ptr<PointCloudVisualizationHandler> |
Definition at line 58 of file PointCloudVisualization.h.
typedef pcl::FPFHSignature33 PointD |
Definition at line 81 of file MaskRCNNPointCloudObjectLocalizer.h.
typedef pcl::PointXYZL PointL |
Definition at line 80 of file MaskRCNNPointCloudObjectLocalizer.h.
Definition at line 66 of file PointCloudSegmenter.h.
using PointO = pcl::PointXYZRGBA |
Definition at line 63 of file PointCloudSegmenter.h.
Definition at line 64 of file PointCloudSegmenter.h.
using PointRGBL = pcl::PointXYZRGBL |
Definition at line 67 of file PointCloudSegmenter.h.
using PointRGBLPtr = pcl::PointCloud<PointRGBL>::Ptr |
Definition at line 68 of file PointCloudSegmenter.h.
Definition at line 70 of file ObjectShapeClassification.h.
typedef pcl::PointXYZRGBA PointT |
Definition at line 79 of file MaskRCNNPointCloudObjectLocalizer.h.
using TaggedPoints = std::pair<std::string, Points> |
Definition at line 71 of file ObjectShapeClassification.h.
using VoxelGrid = voxelgrid::VoxelGrid<VoxelT> |
Definition at line 33 of file VoxelGridCore.h.
Definition at line 35 of file VoxelGridCore.h.
using Yolo = visionx::yolo::Component |
Definition at line 234 of file Component.h.
enum KinectProcessorType |
Enumerator | |
---|---|
CPU | |
OPENCL | |
OPENCLKDE | |
OPENGL | |
CUDA | |
CUDAKDE |
Definition at line 54 of file KinectV2PointCloudProvider.h.
|
strong |
Enumerator | |
---|---|
Full | |
StatusOnly |
Definition at line 52 of file ImageProviderConfigWidget.h.
Eigen::Hyperplane3f alignPlaneNormal | ( | Eigen::Hyperplane3f | plane, |
Eigen::Vector3f | normal | ||
) |
|
inline |
void convertDepthInMetersToWeirdArmarX | ( | const cv::Mat & | input, |
CByteImage * | output | ||
) |
void convertIvtRgbToCvGray | ( | const CByteImage & | ivt_rgb, |
cv::Mat & | cv_gray | ||
) |
Definition at line 14 of file opencv_conversions.cpp.
cv::Mat convertWeirdArmarXToDepthInMeters | ( | CByteImage const * | input | ) |
Convert ArmarX encoding of depth information in an RGB image to depth in meters.
ArmarX stores the depth in mm in the R and G channel of an RGB image. This is due to the fact that we cannot provide images of different types. So a RGB-D camera needs to use a single format for both color and depth.
input | Weird ArmarX encoding of depth image. |
Definition at line 61 of file OpenCVUtil.cpp.
void convertWeirdArmarXToDepthInMeters | ( | const uint8_t * | input, |
cv::Mat & | output | ||
) |
Like convertWeirdArmarXToDepthInMeters(CByteImage const* input)
, but writes into a pre-initialized cv::Mat with the correct size and type.
input | The raw pixel buffer with weird ArmarX depth encoding. |
output | A cv::Mat with the correct size and type. |
Definition at line 76 of file OpenCVUtil.cpp.
void copyCvDepthToGrayscaleIVT | ( | cv::Mat const & | inputInMeters, |
CByteImage * | output | ||
) |
Copies a floating point depth image (in meters) to an RGB depth representation.
Close to the camera: White Farther away: Black
inputInMeters | OpenCV floating point matrix (CV_32FC1) containting depth in meters. |
output | IVT CByteImage for visulaizing the depth info in an RGB image. |
Definition at line 26 of file OpenCVUtil.cpp.
void copyCvMatToIVT | ( | cv::Mat const & | input, |
CByteImage * | output | ||
) |
Copies the contents of an OpenCV matrix to an IVT CByteImage.
input | OpenCV matrix (RGB or grayscale) |
output | IVT CByteImage (RGB or grayscale) |
Definition at line 13 of file OpenCVUtil.cpp.
Definition at line 7 of file ice_point_operators.cpp.
void visionx::evaluateOLP | ( | OLPEvaluation * | p, |
bool | testRecognition | ||
) |
Definition at line 44 of file OLPEvaluation.cpp.
|
inline |
void fillCameraMatrix | ( | const CCalibration::CCameraParameters & | ivtCameraParameters, |
cv::Mat & | output | ||
) |
Fill a propertly initialized camera matrix with the given camera parameters.
cameraParams | The camera parameters. |
output | The cv matrix. Must be floating point, i.e. CV_32F or CV_64F. |
Definition at line 209 of file OpenCVUtil.cpp.
void fillCameraMatrix | ( | const visionx::CameraParameters & | cameraParams, |
cv::Mat & | output | ||
) |
Fill a propertly initialized camera matrix with the given camera parameters.
cameraParams | The camera parameters. |
output | The cv matrix. Must be floating point, i.e. CV_32F or CV_64F. |
Definition at line 195 of file OpenCVUtil.cpp.
void visionx::fillColorArray | ( | float | array[3], |
const ColorT & | color | ||
) |
|
inline |
Eigen::Hyperplane3f fitPlaneSVD | ( | const pcl::PointCloud< pcl::PointXYZRGBA > & | cloud, |
const pcl::PointIndices & | indices, | ||
Eigen::Vector3f | center = Eigen::Vector3f::Zero() |
||
) |
Eigen::Hyperplane3f fitPlaneSVD | ( | const pcl::PointCloud< pcl::PointXYZRGBA > & | cloud, |
Eigen::Vector3f | center = Eigen::Vector3f::Zero() |
||
) |
visionx::FramedPointCloud | ( | PointCloudPtrT | pointCloudPtr | ) | -> FramedPointCloud< typename PointCloudPtrT::element_type::PointType > |
visionx::FramedPointCloud | ( | PointCloudPtrT | pointCloudPtr, |
const std::string & | frameName | ||
) | -> FramedPointCloud< typename PointCloudPtrT::element_type::PointType > |
pcl::PointIndicesPtr getPlaneInliers | ( | const pcl::PointCloud< pcl::PointXYZRGBA > & | cloud, |
Eigen::Hyperplane3f | plane, | ||
float | maxDistance | ||
) |
float hsvDistance | ( | const Eigen::Vector3f & | lhs, |
const Eigen::Vector3f & | rhs, | ||
const Eigen::Vector3f & | hsvWeights = Eigen::Vector3f::Ones() |
||
) |
float hsvDistance | ( | const pcl::PointXYZHSV & | lhs, |
const pcl::PointXYZHSV & | rhs, | ||
const Eigen::Vector3f & | hsvWeights = Eigen::Vector3f::Ones() |
||
) |
Eigen::Vector3f hsvMean | ( | const pcl::PointCloud< pcl::PointXYZHSV > & | hsvCloud, |
const std::vector< int > & | indices | ||
) |
Eigen::Vector3f visionx::hsvMean | ( | const pcl::PointCloud< PointRGB > & | rgbCloud, |
const std::vector< int > & | indices | ||
) |
cv::Mat visionx::makeCameraMatrix | ( | const CameraParams & | cameraParams, |
int | rows = 3 , |
||
int | cols = 3 , |
||
int | type = CV_64F |
||
) |
Builds a camera matrix.
cameraParams | The camera matrix. |
Definition at line 77 of file OpenCVUtil.h.
cv::Mat makeCameraMatrix | ( | const visionx::CameraParameters & | cameraParams | ) |
bool operator!= | ( | const ColoredPoint3D & | lhs, |
const ColoredPoint3D & | rhs | ||
) |
Definition at line 29 of file ice_point_operators.cpp.
bool operator!= | ( | const LabeledPoint3D & | lhs, |
const LabeledPoint3D & | rhs | ||
) |
Definition at line 40 of file ice_point_operators.cpp.
bool operator!= | ( | const Point3D & | lhs, |
const Point3D & | rhs | ||
) |
std::ostream & operator<< | ( | std::ostream & | os, |
const ColoredPoint3D & | rhs | ||
) |
Definition at line 34 of file ice_point_operators.cpp.
std::ostream & operator<< | ( | std::ostream & | os, |
const LabeledPoint3D & | rhs | ||
) |
Definition at line 45 of file ice_point_operators.cpp.
std::ostream & operator<< | ( | std::ostream & | os, |
const Point3D & | rhs | ||
) |
Definition at line 17 of file ice_point_operators.cpp.
std::ostream & operator<< | ( | std::ostream & | os, |
const RGBA & | rhs | ||
) |
Definition at line 23 of file ice_point_operators.cpp.
Eigen::Vector3f pointCloudMedian | ( | const pcl::PointCloud< pcl::PointXYZRGBA > & | cloud, |
const pcl::PointIndices & | indices = {} |
||
) |
|
inline |
int visionx::toByte | ( | float | f | ) |
Definition at line 426 of file UserAssistedSegmenterGuiWidgetController.cpp.
void transformPointCloudFromTo | ( | const pcl::PointCloud< PointT > & | sourceCloud, |
pcl::PointCloud< PointT > & | targetCloud, | ||
const std::string & | sourceFrame, | ||
const std::string & | targetFrame, | ||
const VirtualRobot::RobotPtr & | robot | ||
) |
Transform a point cloud from a robot frame to another.
sourceCloud | The source point cloud. |
targetCloud | The target point cloud (may be same as sourceCloud ). |
sourceFrame | The current frame of sourceCloud . |
targetFrame | The current frame to transform to. |
robot | The reference robot to use for transformation. |
Definition at line 129 of file FramedPointCloud.h.
const double DSHT_default_allowed_deviation[12] |
const std::map<std::string, std::pair<unsigned int, std::string> > MPII_TO_MPI |
Definition at line 32 of file OpenPoseEstimationUtil.h.