json_conversions.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020 Roboception GmbH
3  *
4  * Author: Felix Ruess
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright notice,
10  * this list of conditions and the following disclaimer.
11  *
12  * 2. Redistributions in binary form must reproduce the above copyright notice,
13  * this list of conditions and the following disclaimer in the documentation
14  * and/or other materials provided with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its contributors
17  * may be used to endorse or promote products derived from this software without
18  * specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
23  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
24  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
25  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
26  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
27  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
28  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
29  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  */
32 
33 #ifndef RC_PICK_CLIENT_JSON_CONVERSIONS_H
34 #define RC_PICK_CLIENT_JSON_CONVERSIONS_H
35 
37 
38 #include <rc_common_msgs/ReturnCode.h>
39 
40 #include <rc_pick_client/Box.h>
41 #include <rc_pick_client/Item.h>
42 #include <rc_pick_client/ItemModel.h>
43 #include <rc_pick_client/LoadCarrier.h>
44 #include <rc_pick_client/SuctionGrasp.h>
45 #include <rc_pick_client/Compartment.h>
46 
47 #include <rc_pick_client/ComputeGrasps.h>
48 #include <rc_pick_client/ComputeBoxGrasps.h>
49 #include <rc_pick_client/DetectItems.h>
50 
51 namespace rc_common_msgs
52 {
53 inline void from_json(const nlohmann::json& j, ReturnCode& r)
54 {
55  j.at("value").get_to(r.value);
56  j.at("message").get_to(r.message);
57 }
58 
59 } // namespace rc_common_msgs
60 
61 namespace rc_pick_client
62 {
63 inline void to_json(nlohmann::json& j, const Box& r)
64 {
65  j["x"] = r.x;
66  j["y"] = r.y;
67  j["z"] = r.z;
68 }
69 
70 inline void from_json(const nlohmann::json& j, Box& r)
71 {
72  j.at("x").get_to(r.x);
73  j.at("y").get_to(r.y);
74  j.at("z").get_to(r.z);
75 }
76 
77 inline void to_json(nlohmann::json& j, const RangeBox& r)
78 {
79  j["min_dimensions"] = r.min_dimensions;
80  j["max_dimensions"] = r.max_dimensions;
81 }
82 
83 inline void from_json(const nlohmann::json& j, RangeBox& r)
84 {
85  j.at("min_dimensions").get_to(r.min_dimensions);
86  j.at("max_dimensions").get_to(r.max_dimensions);
87 }
88 
89 inline void to_json(nlohmann::json& j, const Rectangle& r)
90 {
91  j["x"] = r.x;
92  j["y"] = r.y;
93 }
94 
95 inline void from_json(const nlohmann::json& j, Rectangle& r)
96 {
97  j.at("x").get_to(r.x);
98  j.at("y").get_to(r.y);
99 }
100 
101 inline void to_json(nlohmann::json& j, const RangeRectangle& r)
102 {
103  j["min_dimensions"] = r.min_dimensions;
104  j["max_dimensions"] = r.max_dimensions;
105 }
106 
107 inline void from_json(const nlohmann::json& j, RangeRectangle& r)
108 {
109  j.at("min_dimensions").get_to(r.min_dimensions);
110  j.at("max_dimensions").get_to(r.max_dimensions);
111 }
112 
113 inline void from_json(const nlohmann::json& j, SuctionGrasp& r)
114 {
115  j.at("uuid").get_to(r.uuid);
116  j.at("item_uuid").get_to(r.item_uuid);
117  j.at("pose").get_to(r.pose.pose);
118  j.at("timestamp").get_to(r.pose.header.stamp);
119  j.at("pose_frame").get_to(r.pose.header.frame_id);
120  j.at("quality").get_to(r.quality);
121  j.at("max_suction_surface_length").get_to(r.max_suction_surface_length);
122  j.at("max_suction_surface_width").get_to(r.max_suction_surface_width);
123 }
124 
125 inline void to_json(nlohmann::json& j, const ItemModel& r)
126 {
127  j["type"] = r.type;
128  if (r.type == r.UNKNOWN)
129  {
130  j["unknown"] = r.unknown;
131  }
132  else if (r.type == r.RECTANGLE)
133  {
134  j["rectangle"] = r.rectangle;
135  }
136 }
137 
138 inline void from_json(const nlohmann::json& j, Item& r)
139 {
140  j.at("uuid").get_to(r.uuid);
141  j.at("grasp_uuids").get_to(r.grasp_uuids);
142  j.at("type").get_to(r.type);
143  j.at("rectangle").get_to(r.rectangle);
144  j.at("pose").get_to(r.pose.pose);
145  j.at("timestamp").get_to(r.pose.header.stamp);
146  j.at("pose_frame").get_to(r.pose.header.frame_id);;
147 }
148 
149 inline void to_json(nlohmann::json& j, const LoadCarrier& r)
150 {
151  j["id"] = r.id;
152  j["outer_dimensions"] = r.outer_dimensions;
153  j["inner_dimensions"] = r.inner_dimensions;
154  j["rim_thickness"] = r.rim_thickness;
155  j["pose"] = r.pose.pose;
156  j["pose_frame"] = r.pose.header.frame_id;
157  // timestamp and overfilled flag is not used when setting load carrier
158 }
159 
160 inline void from_json(const nlohmann::json& j, LoadCarrier& r)
161 {
162  j.at("id").get_to(r.id);
163  j.at("outer_dimensions").get_to(r.outer_dimensions);
164  j.at("inner_dimensions").get_to(r.inner_dimensions);
165  j.at("rim_thickness").get_to(r.rim_thickness);
166  j.at("pose").get_to(r.pose.pose);
167  j.at("pose_frame").get_to(r.pose.header.frame_id);
168  // timestamp is set from enclosing msg
169  if (j.count("overfilled"))
170  j.at("overfilled").get_to(r.overfilled);
171 }
172 
173 inline void to_json(nlohmann::json& j, const Compartment& r)
174 {
175  j["pose"] = r.pose;
176  j["box"] = r.box;
177 }
178 
179 inline void to_json(nlohmann::json& j, const CollisionDetection& r)
180 {
181  j["gripper_id"] = r.gripper_id;
182  if (r.pre_grasp_offset.x != 0 || r.pre_grasp_offset.y != 0 || r.pre_grasp_offset.z != 0)
183  {
184  j["pre_grasp_offset"] = r.pre_grasp_offset;
185  }
186 }
187 
188 // Services
189 inline void to_json(nlohmann::json& j, const ComputeGraspsRequest& r)
190 {
191  j["pose_frame"] = r.pose_frame;
192  if (r.pose_frame == "external")
193  {
194  j["robot_pose"] = r.robot_pose;
195  }
196  if (!r.region_of_interest_id.empty())
197  {
198  j["region_of_interest_id"] = r.region_of_interest_id;
199  }
200  if (!r.load_carrier_id.empty())
201  {
202  j["load_carrier_id"] = r.load_carrier_id;
203  j["load_carrier_compartment"] = r.load_carrier_compartment;
204  }
205  j["item_models"] = r.item_models;
206  j["suction_surface_length"] = r.suction_surface_length;
207  j["suction_surface_width"] = r.suction_surface_width;
208  if (!r.collision_detection.gripper_id.empty())
209  {
210  j["collision_detection"] = r.collision_detection;
211  }
212 }
213 
214 inline void from_json(const nlohmann::json& j, ComputeGraspsResponse& r)
215 {
216  j.at("timestamp").get_to(r.timestamp);
217  j.at("load_carriers").get_to(r.load_carriers);
218  j.at("grasps").get_to(r.grasps);
219  j.at("return_code").get_to(r.return_code);
220 }
221 
222 inline void to_json(nlohmann::json& j, const ComputeBoxGraspsRequest& r)
223 {
224  j["pose_frame"] = r.pose_frame;
225  if (r.pose_frame == "external")
226  {
227  j["robot_pose"] = r.robot_pose;
228  }
229  if (!r.region_of_interest_id.empty())
230  {
231  j["region_of_interest_id"] = r.region_of_interest_id;
232  }
233  if (!r.load_carrier_id.empty())
234  {
235  j["load_carrier_id"] = r.load_carrier_id;
236  j["load_carrier_compartment"] = r.load_carrier_compartment;
237  }
238  if (!r.item_models.empty())
239  {
240  j["item_models"] = r.item_models;
241  }
242  j["suction_surface_length"] = r.suction_surface_length;
243  j["suction_surface_width"] = r.suction_surface_width;
244  if (!r.collision_detection.gripper_id.empty())
245  {
246  j["collision_detection"] = r.collision_detection;
247  }
248 }
249 
250 inline void from_json(const nlohmann::json& j, ComputeBoxGraspsResponse& r)
251 {
252  j.at("timestamp").get_to(r.timestamp);
253  j.at("load_carriers").get_to(r.load_carriers);
254  j.at("items").get_to(r.items);
255  j.at("grasps").get_to(r.grasps);
256  j.at("return_code").get_to(r.return_code);
257 }
258 
259 inline void to_json(nlohmann::json& j, const DetectItemsRequest& r)
260 {
261  j["item_models"] = r.item_models;
262  j["pose_frame"] = r.pose_frame;
263  if (r.pose_frame == "external")
264  {
265  j["robot_pose"] = r.robot_pose;
266  }
267  if (!r.region_of_interest_id.empty())
268  {
269  j["region_of_interest_id"] = r.region_of_interest_id;
270  }
271  if (!r.load_carrier_id.empty())
272  {
273  j["load_carrier_id"] = r.load_carrier_id;
274  j["load_carrier_compartment"] = r.load_carrier_compartment;
275  }
276 }
277 
278 inline void from_json(const nlohmann::json& j, DetectItemsResponse& r)
279 {
280  j.at("timestamp").get_to(r.timestamp);
281  j.at("load_carriers").get_to(r.load_carriers);
282  j.at("items").get_to(r.items);
283  j.at("return_code").get_to(r.return_code);
284 }
285 
286 } // namespace rc_pick_client
287 
288 #endif // RC_PICK_CLIENT_JSON_CONVERSIONS_H
json
nlohmann::json json
Definition: pick_client.h:49
rc_common_msgs::from_json
void from_json(const nlohmann::json &j, ReturnCode &r)
Definition: json_conversions.h:53
rc_common_msgs
Definition: json_conversions.h:51
rc_pick_client::from_json
void from_json(const nlohmann::json &j, Box &r)
Definition: json_conversions.h:70
rc_pick_client
Definition: json_conversions.h:61
json_conversions_common.h
rc_pick_client::to_json
void to_json(nlohmann::json &j, const Box &r)
Definition: json_conversions.h:63


rc_pick_client
Author(s): Monika Florek-Jasinska
autogenerated on Sun May 15 2022 02:24:50