OpenPose3DDepthImageConverter.cpp
Go to the documentation of this file.
1/*
2 * This file is part of ArmarX.
3 *
4 * ArmarX is free software; you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License version 2 as
6 * published by the Free Software Foundation.
7 *
8 * ArmarX is distributed in the hope that it will be useful, but
9 * WITHOUT ANY WARRANTY; without even the implied warranty of
10 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11 * GNU General Public License for more details.
12 *
13 * You should have received a copy of the GNU General Public License
14 * along with this program. If not, see <http://www.gnu.org/licenses/>.
15 *
16 * @package VisionX::ArmarXObjects::OpenPoseEstimation
17 * @author Stefan Reither ( stef dot reither at web dot de )
18 * @date 2018
19 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20 * GNU General Public License
21 */
22
24
25using namespace visionx;
26using namespace armarx;
27
28void
30{
31 OpenPoseEstimation::setupPropertyDefinitions(def);
32
33 def->optional(radius, "DepthMedianRadius", "Depth Median Radius");
34 def->optional(
36 "MaxDepth",
37 "Pixels with a distance higher than this value are masked out. Only for depth camera mode.",
39 def->optional(maxDepthDifference,
40 "MaxDepthDifference",
41 "Allowed difference of depth value for one keypoint to median of all keypoints.",
43 def->optional(cameraNodeName, "CameraNodeName");
44}
45
46void
48{
49 OpenPoseEstimation::setupLocalVariables();
50}
51
52void
54{
55 OpenPoseEstimation::destroyLocalVariables();
56}
57
58void
60{
61 if (!localRobot || !running3D_is_possible || !running3D)
62 {
63 return;
64 }
65
67 localRobot, robotStateInterface, timestamp_of_update);
68
69 const int depthThreshold = maxDepthDifference;
70 openposeResult3D.clear();
71
72 for (const auto& entities_iterator : openposeResult)
73 {
74 const std::string& name = entities_iterator->first;
75 const Entity2D& entity = entities_iterator->second;
76
77 if (entity.keypointMap.size() == 0)
78 {
79 continue;
80 }
81
82 std::map<std::string, int>
83 depthStorage; // we do not want to store perspective depth-values in a Keypoint, we transfer them into world-coordiantes (in cameraframe) anyways
84 std::vector<int> depthsCopy;
85
86 // Get camera depth information from image coordinates
87 for (const auto& entity_iterator : entity.keypointMap)
88 {
89 const std::string& kp_name = entities_iterator->first;
90 const Keypoint2D& point = entities_iterator->second;
91
92 int depth = getMedianDepthFromImage(
93 static_cast<int>(point.x), static_cast<int>(point.y), radius);
94 depthStorage[kp_name] = depth;
95 depthsCopy.push_back(depth);
96 }
97
98 // Find outlier in depth values and set them to median of depth values
99 std::sort(depthsCopy.begin(), depthsCopy.end());
100 const int medianDepth = depthsCopy.at(depthsCopy.size() / 2);
101 for (auto& depthStorage_iterator : depthStorage)
102 {
103 const std::string& storage_name = depthStorage_iterator->first;
104 int& depth = depthStorage_iterator->second;
105
106 if (depth > medianDepth + depthThreshold || depth < medianDepth - depthThreshold)
107 {
108 depth = medianDepth;
109 }
110 }
111
112 // Transform pixel + depth into world coordinates
113 // and update stored 3d entity
114 openposeResult3D[name] = Entity3D();
115 for (const auto& entity_iterator : entity.keypointMap)
116 {
117 const std::string& kp_name = entity_iterator->first;
118 const Keypoint3D& point = entity_iterator->second;
119
120 Vec2d imagePoint;
121 imagePoint.x = point.x;
122 imagePoint.y = point.y;
123
124 Vec3d result;
126 calibration->ImageToWorldCoordinates(imagePoint,
127 result,
128 static_cast<float>(depthStorage.at(i)),
129 useDistortionParameters);
130
131 //FramedPosition pos = FramedPosition(Eigen::Vector3f(result.x, result.y, result.z), cameraNodeName, localRobot->getName());
132 openposeResult3D[name].keypointMap[kp_name].x = result.x;
133 openposeResult3D[name].keypointMap[kp_name].y = result.y;
134 openposeResult3D[name].keypointMap[kp_name].z = result.z;
135 }
136
137 float average_x = 0;
138 float average_y = 0;
139 float average_z = 0;
140 }
141}
142
143int
144OpenPose3DDepthImageConverter::getMedianDepthFromImage(int x, int y, int radius) const
145{
146 std::vector<int> depths;
147 for (int xoffset = -radius; xoffset < radius; xoffset++)
148 {
149 int xo = x + xoffset;
150 if (xo < 0 || xo > depthImageBuffer->width)
151 {
152 continue;
153 }
154 for (int yoffset = -radius; yoffset < radius; yoffset++)
155 {
156 int yo = y + yoffset;
157 if (yo < 0 || yo > depthImageBuffer->height)
158 {
159 continue;
160 }
161
162 // Check whether (x,y) is in circle:
163 if (xoffset * xoffset + yoffset * yoffset <= radius * radius)
164 {
165 unsigned int pixelPos =
166 static_cast<unsigned int>(3 * (yo * depthImageBuffer->width + xo));
167 int z_value = depthImageBuffer->pixels[pixelPos + 0] +
168 (depthImageBuffer->pixels[pixelPos + 1] << 8) +
169 (depthImageBuffer->pixels[pixelPos + 2] << 16);
170 if (z_value > 0)
171 {
172 depths.push_back(z_value);
173 }
174 }
175 }
176 }
177 std::sort(depths.begin(), depths.end());
178
179 return depths.empty() ? 0 : depths[depths.size() / 2];
180}
181
182void
183OpenPose3DDepthImageConverter::maskOutBasedOnDepth(CByteImage& image, int maxDepth)
184{
185 std::unique_lock lock(depthImageBufferMutex);
186
187 if (maxDepth <= 0)
188 {
189 return;
190 }
191 int pixelCount = depthImageBuffer->width * depthImageBuffer->height;
192 int depthThresholdmm = maxDepth;
193 CByteImage maskImage(depthImageBuffer->width, depthImageBuffer->height, CByteImage::eGrayScale);
194 for (int i = 0; i < pixelCount; i += 1)
195 {
196 int z_value = depthImageBuffer->pixels[i * 3 + 0] +
197 (depthImageBuffer->pixels[i * 3 + 1] << 8) +
198 (depthImageBuffer->pixels[i * 3 + 2] << 16);
199 maskImage.pixels[i] = z_value > depthThresholdmm || z_value == 0 ? 0 : 255;
200 }
201 ::ImageProcessor::Erode(&maskImage, &maskImage, 5);
202 ::ImageProcessor::Dilate(&maskImage, &maskImage, 20);
203 for (int i = 0; i < pixelCount; i += 1)
204 {
205 if (maskImage.pixels[i] == 0)
206 {
207 image.pixels[i * 3] = 0;
208 image.pixels[i * 3 + 1] = 255;
209 image.pixels[i * 3 + 2] = 0;
210 }
211 }
212}
static bool synchronizeLocalCloneToTimestamp(VirtualRobot::RobotPtr robot, RobotStateComponentInterfacePrx robotStatePrx, Ice::Long timestamp)
Synchronizes a local robot to a robot state at timestamp.
virtual void setupPropertyDefinitions(armarx::PropertyDefinitionsPtr &def) override
#define ARMARX_CHECK_EXPRESSION(expression)
This macro evaluates the expression and if it turns out to be false it will throw an ExpressionExcept...
This file offers overloads of toIce() and fromIce() functions for STL container types.
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
ArmarX headers.