7 cameraInfo = ensenso::std::make_shared<sensor_msgs::msg::CameraInfo>();
47 NxLibItem imageNode =
cameraNode[itmImages][itmRaw];
48 if (imageNode.isArray())
50 imageNode = imageNode[0];
74 NxLibItem calibrationNode =
cameraNode[itmCalibration];
85 for (
int row = 0; row < 3; row++)
87 for (
int column = 0; column < 3; column++)
89 GET_K_MATRIX(info)[3 * row + column] = calibrationNode[itmCamera][column][row].asDouble();
103 ensenso::action::RequestDataMonoResult result;
104 ensenso::action::RequestDataMonoFeedback feedback;
106 bool publishResults = goal->publish_results;
107 if (!goal->publish_results && !goal->include_results_in_response)
109 publishResults =
true;
112 bool requestRectified = goal->request_rectified_images;
113 if (!goal->request_rectified_images && !goal->request_raw_images)
115 requestRectified =
true;
122 feedback.images_acquired =
true;
125 if (goal->request_raw_images)
128 cameraInfo->header.stamp = rawImages[0]->header.stamp;
130 if (goal->include_results_in_response)
132 for (
auto const& image : rawImages)
134 result.raw_images.push_back(*image);
146 if (requestRectified)
152 auto rectifiedImages =
156 if (goal->include_results_in_response)
158 for (
auto const& image : rectifiedImages)
160 result.rectified_images.push_back(*image);
179 ensenso::action::SetParameterResult result;
183 result.parameter_file_applied =
false;
184 if (!goal->parameter_file.empty())
186 result.parameter_file_applied =
loadSettings(goal->parameter_file);
187 if (!result.parameter_file_applied)
189 server->setAborted(std::move(result));
194 for (
auto const& parameter : goal->parameters)
200 NxLibCommand synchronize(cmdSynchronize,
params.
serial);
202 synchronize.execute();
210 for (
auto const& parameter : goal->parameters)
224 ensenso::action::LocatePatternMonoResult result;
225 ensenso::action::LocatePatternMonoFeedback feedback;
229 int numberOfShots = goal->number_of_shots;
230 if (numberOfShots < 1)
235 std::vector<MonoCalibrationPattern> patterns;
237 for (
int i = 0; i < numberOfShots; i++)
243 imageTimestamp = timestamp;
247 if (i == (numberOfShots - 1))
250 feedback.images_acquired =
true;
254 bool clearBuffer = (i == 0);
256 if (patterns.empty())
258 result.found_pattern =
false;
263 if (patterns.size() > 1)
271 result.found_pattern =
true;
272 result.mono_patterns.resize(patterns.size());
273 for (
size_t i = 0; i < patterns.size(); i++)
275 patterns[i].writeToMessage(result.mono_patterns[i]);
281 if (!goal->target_frame.empty())
283 patternFrame = goal->target_frame;
286 result.frame = patternFrame;
288 if (patterns.size() > 1)
293 result.mono_pattern_poses.resize(patternPoses.size());
294 for (
size_t i = 0; i < patternPoses.size(); i++)
296 result.mono_pattern_poses[i] = patternPoses[i];
304 result.mono_pattern_poses.resize(1);
305 result.mono_pattern_poses[0] = patternPose;
308 if (!goal->tf_frame.empty())
310 if (patterns.size() == 1)
312 geometry_msgs::msg::TransformStamped transform =
transformFromPose(result.mono_pattern_poses[0], goal->tf_frame);
317 ENSENSO_WARN(
nh,
"Cannot publish the pattern pose in tf, because there are multiple patterns!");
330 NxLibCommand(cmdDiscardPatterns,
params.
serial).execute();
340 catch (NxLibException& e)
342 if (e.getErrorCode() == NxLibExecutionFailed)
344 if (
collectPattern.result()[itmErrorSymbol] == errPatternNotFound ||
345 collectPattern.result()[itmErrorSymbol] == errPatternNotDecodable)
353 std::vector<MonoCalibrationPattern> result;
363 for (
size_t i = 0; i < result.size(); i++)
365 for (
int j = 0; j < pattern[i][itmPoints].count(); j++)
367 NxLibItem pointNode = pattern[i][itmPoints][j];
369 ensenso::msg::ImagePoint point;
370 point.x = pointNode[0].asDouble();
371 point.y = pointNode[1].asDouble();
372 result[i].points.push_back(point);
380 std::string
const& targetFrame,
381 bool latestPatternOnly)
const
387 if (latestPatternOnly)
391 int patternCount = NxLibItem()[itmParameters][itmPatternCount].asInt();
393 estimatePatternPose.parameters()[itmFilter][itmOr][0][itmAnd][0][itmValue] = patternCount - 1;
408 std::string
const& targetFrame)
const
421 std::vector<geometry_msgs::msg::PoseStamped> result;
422 result.reserve(patterns.count());
424 for (
int i = 0; i < patterns.count(); i++)
426 result.push_back(
stampedPoseFromNxLib(patterns[i][itmPatternPose], targetFrame, imageTimestamp));