Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpMegaPose.h
1/*
2 * ViSP, open source Visual Servoing Platform software.
3 * Copyright (C) 2005 - 2025 by Inria. All rights reserved.
4 *
5 * This software is free software; you can redistribute it and/or modify
6 * it under the terms of the GNU General Public License as published by
7 * the Free Software Foundation; either version 2 of the License, or
8 * (at your option) any later version.
9 * See the file LICENSE.txt at the root directory of this source
10 * distribution for additional information about the GNU GPL.
11 *
12 * For using ViSP with software that can not be combined with the GNU
13 * GPL, please contact Inria about acquiring a ViSP Professional
14 * Edition License.
15 *
16 * See https://visp.inria.fr for more information.
17 *
18 * This software was developed at:
19 * Inria Rennes - Bretagne Atlantique
20 * Campus Universitaire de Beaulieu
21 * 35042 Rennes Cedex
22 * France
23 *
24 * If you have questions regarding the use of this file, please contact
25 * Inria at visp@inria.fr
26 *
27 * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28 * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29 *
30 * Description:
31 * MegaPose wrapper.
32 */
33#ifndef VP_MEGAPOSE_H
34#define VP_MEGAPOSE_H
35
36#include <visp3/core/vpConfig.h>
37#if defined(VISP_HAVE_NLOHMANN_JSON) && defined(VISP_HAVE_THREADS)
38
39#include <vector>
40#include <string>
41#include <unordered_map>
42#include <mutex>
43
44#include <visp3/core/vpHomogeneousMatrix.h>
45#include <visp3/core/vpCameraParameters.h>
46#include <visp3/core/vpImage.h>
47#include <visp3/core/vpRGBa.h>
48#include <visp3/core/vpRect.h>
49
50#include VISP_NLOHMANN_JSON(json.hpp)
51
80
81// Don't use the default ViSP JSON conversion to avoid potential regressions (that wouldn't be detected)
82// and very specific parsing on the server side
83inline void from_megapose_json(const nlohmann::json &j, vpHomogeneousMatrix &T)
84{
85 std::vector<double> values = j;
86 assert(values.size() == 16);
87 std::copy(values.begin(), values.end(), T.data);
88}
89
90inline void to_megapose_json(nlohmann::json &j, const vpHomogeneousMatrix &T)
91{
92 std::vector<double> values;
93 values.reserve(16);
94 for (unsigned i = 0; i < 16; ++i) {
95 values.push_back(T.data[i]);
96 }
97 j = values;
98}
99
100inline void to_megapose_json(nlohmann::json &j, const vpRect &d)
101{
102 std::vector<double> values = {
103 d.getLeft(), d.getTop(), d.getRight(), d.getBottom()
104 };
105 j = values;
106}
107
108inline void from_megapose_json(const nlohmann::json &j, vpRect &d)
109{
110 std::vector<double> values = j.get<std::vector<double>>();
111 assert((values.size() == 4));
112 d.setLeft(values[0]);
113 d.setTop(values[1]);
114 d.setRight(values[2]);
115 d.setBottom(values[3]);
116}
117
118inline void from_json(const nlohmann::json &j, vpMegaPoseEstimate &m)
119{
120 m.score = j["score"];
121 from_megapose_json(j.at("cTo"), m.cTo);
122 from_megapose_json(j.at("boundingBox"), m.boundingBox);
123}
124
148class VISP_EXPORT vpMegaPose
149{
150public:
172
181 vpMegaPose(const std::string &host, int port, const vpCameraParameters &cam, unsigned height, unsigned width);
182
201 std::vector<vpMegaPoseEstimate> estimatePoses(const vpImage<vpRGBa> &image, const std::vector<std::string> &objectNames,
202 const vpImage<uint16_t> *const depth = nullptr, const double depthToM = 0.f,
203 const std::vector<vpRect> *const detections = nullptr,
204 const std::vector<vpHomogeneousMatrix> *const initial_cTos = nullptr,
205 int refinerIterations = -1);
216 std::vector<double> scorePoses(const vpImage<vpRGBa> &image, const std::vector<std::string> &objectNames,
217 const std::vector<vpHomogeneousMatrix> &cTos);
218
226 void setIntrinsics(const vpCameraParameters &cam, unsigned height, unsigned width);
227
228 vpImage<vpRGBa> viewObjects(const std::vector<std::string> &objectNames,
229 const std::vector<vpHomogeneousMatrix> &poses, const std::string &viewType);
230
235 void setCoarseNumSamples(const unsigned num);
236
241 std::vector<std::string> getObjectNames();
242
243 ~vpMegaPose();
244
245private:
246 // Server connection data
247 int m_serverSocket;
248 int m_fd;
249
250 std::mutex m_mutex; // Since client-server communications are synchronous, avoid multiple parallel communications
251
252 void makeMessage(const vpMegaPose::ServerMessage messageType, std::vector<uint8_t> &data) const;
253 std::pair<vpMegaPose::ServerMessage, std::vector<uint8_t>> readMessage() const;
254
255 const static std::unordered_map<vpMegaPose::ServerMessage, std::string> m_codeMap;
256 static std::string messageToString(const vpMegaPose::ServerMessage messageType);
257 static vpMegaPose::ServerMessage stringToMessage(const std::string &s);
258};
259
260END_VISP_NAMESPACE
261#endif // VISP_HAVE_NLOHMANN_JSON
262#endif
Type * data
Address of the first element of the data array.
Definition vpArray2D.h:149
Generic class defining intrinsic camera parameters.
Implementation of an homogeneous matrix and operations on such kind of matrices.
Definition of the vpImage class member functions.
Definition vpImage.h:131
vpHomogeneousMatrix cTo
Definition vpMegaPose.h:76
@ GET_LIST_OBJECTS
Ask the server to set the number of samples for coarse estimation.
Definition vpMegaPose.h:168
@ GET_VIZ
Code sent when server returns pose estimates.
Definition vpMegaPose.h:162
@ SET_SO3_GRID_SIZE
Code sent when server returns a pose score.
Definition vpMegaPose.h:167
@ RET_SCORE
Ask the server to score a pose estimate.
Definition vpMegaPose.h:166
@ GET_POSE
Server has successfully completed operation, no return value expected.
Definition vpMegaPose.h:160
@ RET_VIZ
Ask the server for a rendering of the object.
Definition vpMegaPose.h:163
@ OK
An error occurred server side.
Definition vpMegaPose.h:159
@ SET_INTR
Code sent when server returns the rendering of an object.
Definition vpMegaPose.h:164
@ GET_SCORE
Set the intrinsics for the MegaPose server.
Definition vpMegaPose.h:165
@ RET_POSE
Ask the server to estimate poses.
Definition vpMegaPose.h:161
vpMegaPose(const std::string &host, int port, const vpCameraParameters &cam, unsigned height, unsigned width)
Defines a rectangle in the plane.
Definition vpRect.h:79