Zivid C++ API 2.14.0+e4a0c4a9-1
HandEyeLowDOF.h
Go to the documentation of this file.
1/*******************************************************************************
2 * This file is part of the Zivid API
3 *
4 * Copyright 2015-2024 (C) Zivid AS
5 * All rights reserved.
6 *
7 * Zivid Software License, v1.0
8 *
9 * Redistribution and use in source and binary forms, with or without
10 * modification, are permitted provided that the following conditions are met:
11 *
12 * 1. Redistributions of source code must retain the above copyright notice,
13 * this list of conditions and the following disclaimer.
14 *
15 * 2. Redistributions in binary form must reproduce the above copyright notice,
16 * this list of conditions and the following disclaimer in the documentation
17 * and/or other materials provided with the distribution.
18 *
19 * 3. Neither the name of Zivid AS nor the names of its contributors may be used
20 * to endorse or promote products derived from this software without specific
21 * prior written permission.
22 *
23 * 4. This software, with or without modification, must not be used with any
24 * other 3D camera than from Zivid AS.
25 *
26 * 5. Any software provided in binary form under this license must not be
27 * reverse engineered, decompiled, modified and/or disassembled.
28 *
29 * THIS SOFTWARE IS PROVIDED BY ZIVID AS "AS IS" AND ANY EXPRESS OR IMPLIED
30 * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
31 * MERCHANTABILITY, NONINFRINGEMENT, AND FITNESS FOR A PARTICULAR PURPOSE ARE
32 * DISCLAIMED. IN NO EVENT SHALL ZIVID AS OR CONTRIBUTORS BE LIABLE FOR ANY
33 * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
34 * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
35 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
36 * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
37 * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
38 * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
39 *
40 * Contact: Zivid Customer Success Team <customersuccess@zivid.com>
41 * Info: http://www.zivid.com
42 ******************************************************************************/
43
44#pragma once
45
48
49#include <vector>
50
52{
57
58 namespace HandEyeLowDOF
59 {
64 {
66
67 public:
79
81 ZIVID_CORE_EXPORT int id() const;
82
85
87 ZIVID_CORE_EXPORT std::string toString() const;
88 };
89
90 ZIVID_CORE_EXPORT std::ostream &operator<<(std::ostream &stream, const FixedPlacementOfFiducialMarker &marker);
91
96 {
98
99 public:
108 const MarkerDictionary &dictionary,
109 const std::vector<FixedPlacementOfFiducialMarker> &markers);
110
112 ZIVID_CORE_EXPORT std::string toString() const;
113 };
114
116 std::ostream &stream,
117 const FixedPlacementOfFiducialMarkers &markers);
118
123 {
125
126 public:
139
151
153 ZIVID_CORE_EXPORT std::string toString() const;
154 };
155
157 std::ostream &stream,
158 const FixedPlacementOfCalibrationBoard &calibrationBoard);
159
164 {
166
167 public:
171
175 const FixedPlacementOfCalibrationBoard &calibrationBoard);
176
179 ZIVID_CORE_EXPORT std::string toString() const;
180 };
181
183 std::ostream &stream,
184 const FixedPlacementOfCalibrationObjects &fixedObjects);
185 } // namespace HandEyeLowDOF
186
206 const std::vector<HandEyeInput> &inputs,
208
228 const std::vector<HandEyeInput> &inputs,
230
231} // namespace Zivid::Experimental::Calibration
#define ZIVID_CORE_EXPORT
Definition CoreExport.h:56
#define ZIVID_PIMPL_VALUE_SEMANTICS(ClassName, Attributes)
Definition Pimpl.h:53
Binds together a robot pose and the detection result acquired from the pose.
Definition HandEye.h:63
The hand-eye calibration result containing the computed pose and reprojection errors for all the inpu...
Definition HandEye.h:151
Holds information about fiducial markers such as ArUco or AprilTag for detection.
Definition MarkerDictionary.h:65
Describes a robot pose.
Definition Pose.h:58
Specifies the fixed placement of a Zivid calibration board for low degrees-of-freedom hand-eye calibr...
Definition HandEyeLowDOF.h:123
ZIVID_CORE_EXPORT std::string toString() const
Get string representation.
ZIVID_CORE_EXPORT FixedPlacementOfCalibrationBoard(const Pose &pose)
Constructs a FixedPlacementOfCalibrationBoard instance using a pose.
ZIVID_CORE_EXPORT FixedPlacementOfCalibrationBoard(PointXYZ position)
Constructs a FixedPlacementOfCalibrationBoard instance using a position.
Specifies the fixed placement of calibration objects for low degrees-of-freedom hand-eye calibration.
Definition HandEyeLowDOF.h:164
ZIVID_CORE_EXPORT FixedPlacementOfCalibrationObjects(const FixedPlacementOfCalibrationBoard &calibrationBoard)
Constructs a FixedPlacementOfCalibrationObjects instance from a calibration board.
ZIVID_CORE_EXPORT std::string toString() const
Get string representation of the calibration features.
ZIVID_CORE_EXPORT FixedPlacementOfCalibrationObjects(const FixedPlacementOfFiducialMarkers &markers)
Constructs a FixedPlacementOfCalibrationObjects instance from fiducial markers.
Specifies the fixed placement of a fiducial marker for low degrees-of-freedom hand-eye calibration.
Definition HandEyeLowDOF.h:64
ZIVID_CORE_EXPORT PointXYZ position() const
Get position of fiducial marker.
ZIVID_CORE_EXPORT int id() const
Get ID of fiducial marker.
ZIVID_CORE_EXPORT std::string toString() const
Get string representation.
ZIVID_CORE_EXPORT FixedPlacementOfFiducialMarker(int markerId, PointXYZ position)
Constructs a FixedPlacementOfFiducialMarker instance.
Specifies the fixed placement of a list of fiducial markers for low degrees-of-freedom hand-eye calib...
Definition HandEyeLowDOF.h:96
ZIVID_CORE_EXPORT FixedPlacementOfFiducialMarkers(const MarkerDictionary &dictionary, const std::vector< FixedPlacementOfFiducialMarker > &markers)
Constructs a FixedPlacementOfFiducialMarkers instance.
ZIVID_CORE_EXPORT std::string toString() const
Get string representation.
ZIVID_CORE_EXPORT std::ostream & operator<<(std::ostream &stream, const FixedPlacementOfFiducialMarker &marker)
Definition Calibration.h:61
ZIVID_CORE_EXPORT HandEyeOutput calibrateEyeInHandLowDOF(const std::vector< HandEyeInput > &inputs, const HandEyeLowDOF::FixedPlacementOfCalibrationObjects &fixedObjects)
Performs eye-in-hand calibration for low degrees-of-freedom robots.
ZIVID_CORE_EXPORT HandEyeOutput calibrateEyeToHandLowDOF(const std::vector< HandEyeInput > &inputs, const HandEyeLowDOF::FixedPlacementOfCalibrationObjects &fixedObjects)
Performs eye-to-hand calibration for low degrees-of-freedom robots.
Point with three coordinates as float.
Definition Point.h:60