35 #ifndef _vpMegaPose_h_
36 #define _vpMegaPose_h_
38 #include <visp3/core/vpConfig.h>
39 #if defined(VISP_HAVE_NLOHMANN_JSON) && defined(VISP_HAVE_THREADS)
43 #include <unordered_map>
46 #include <visp3/core/vpHomogeneousMatrix.h>
47 #include <visp3/core/vpCameraParameters.h>
48 #include <visp3/core/vpImage.h>
49 #include <visp3/core/vpRGBa.h>
50 #include <visp3/core/vpRect.h>
52 #include VISP_NLOHMANN_JSON(json.hpp)
79 std::vector<double> values = j;
80 assert(values.size() == 16);
81 std::copy(values.begin(), values.end(), T.
data);
86 std::vector<double> values;
88 for (
unsigned i = 0; i < 16; ++i) {
89 values.push_back(T.
data[i]);
94 inline void to_megapose_json(nlohmann::json &j,
const vpRect &d)
96 std::vector<double> values = {
97 d.getLeft(), d.getTop(), d.getRight(), d.getBottom()
102 inline void from_megapose_json(
const nlohmann::json &j,
vpRect &d)
104 std::vector<double> values = j.get<std::vector<double>>();
105 assert((values.size() == 4));
106 d.setLeft(values[0]);
108 d.setRight(values[2]);
109 d.setBottom(values[3]);
114 m.
score = j[
"score"];
115 from_megapose_json(j.at(
"cTo"), m.
cTo);
116 from_megapose_json(j.at(
"boundingBox"), m.
boundingBox);
156 SET_SO3_GRID_SIZE = 10,
157 GET_LIST_OBJECTS = 11,
158 RET_LIST_OBJECTS = 12,
190 std::vector<vpMegaPoseEstimate> estimatePoses(
const vpImage<vpRGBa> &image,
const std::vector<std::string> &objectNames,
192 const std::vector<vpRect> *
const detections =
nullptr,
193 const std::vector<vpHomogeneousMatrix> *
const initial_cTos =
nullptr,
194 int refinerIterations = -1);
205 std::vector<double> scorePoses(
const vpImage<vpRGBa> &image,
const std::vector<std::string> &objectNames,
206 const std::vector<vpHomogeneousMatrix> &cTos);
217 vpImage<vpRGBa> viewObjects(
const std::vector<std::string> &objectNames,
218 const std::vector<vpHomogeneousMatrix> &poses,
const std::string &viewType);
224 void setCoarseNumSamples(
const unsigned num);
230 std::vector<std::string> getObjectNames();
242 std::pair<vpMegaPose::ServerMessage, std::vector<uint8_t>> readMessage()
const;
244 const static std::unordered_map<vpMegaPose::ServerMessage, std::string> m_codeMap;
Type * data
Address of the first element of the data array.
Generic class defining intrinsic camera parameters.
Implementation of an homogeneous matrix and operations on such kind of matrices.
Defines a rectangle in the plane.