-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
query_object.cc
246 lines (202 loc) · 7.66 KB
/
query_object.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
#include "drake/geometry/query_object.h"
#include "drake/common/default_scalars.h"
#include "drake/common/drake_assert.h"
#include "drake/geometry/scene_graph.h"
namespace drake {
namespace geometry {
using math::RigidTransform;
using math::RigidTransformd;
using render::ColorRenderCamera;
using render::DepthRenderCamera;
using systems::sensors::ImageDepth32F;
using systems::sensors::ImageLabel16I;
using systems::sensors::ImageRgba8U;
template <typename T>
QueryObject<T>::QueryObject(const QueryObject& query_object) {
*this = query_object;
}
template <typename T>
QueryObject<T>& QueryObject<T>::operator=(const QueryObject<T>& query_object) {
if (this == &query_object) return *this;
DRAKE_DEMAND(query_object.is_copyable());
context_ = nullptr;
scene_graph_ = nullptr;
state_.reset();
if (query_object.state_) {
// Share the underlying baked state.
state_ = query_object.state_;
} else if (query_object.context_ && query_object.scene_graph_) {
// Create a new baked state; make sure the source is fully updated.
query_object.FullPoseUpdate();
state_ = std::make_shared<GeometryState<T>>(query_object.geometry_state());
}
inspector_.set(state_.get());
// If `query_object` is default, then this will likewise be default.
return *this;
}
template <typename T>
const RigidTransform<T>& QueryObject<T>::GetPoseInWorld(
FrameId frame_id) const {
ThrowIfNotCallable();
FullPoseUpdate();
const GeometryState<T>& state = geometry_state();
return state.get_pose_in_world(frame_id);
}
template <typename T>
const RigidTransform<T>& QueryObject<T>::GetPoseInParent(
FrameId frame_id) const {
ThrowIfNotCallable();
FullPoseUpdate();
const GeometryState<T>& state = geometry_state();
return state.get_pose_in_parent(frame_id);
}
template <typename T>
const RigidTransform<T>& QueryObject<T>::GetPoseInWorld(
GeometryId geometry_id) const {
ThrowIfNotCallable();
FullPoseUpdate();
const GeometryState<T>& state = geometry_state();
return state.get_pose_in_world(geometry_id);
}
template <typename T>
std::vector<PenetrationAsPointPair<T>>
QueryObject<T>::ComputePointPairPenetration() const {
ThrowIfNotCallable();
FullPoseUpdate();
const GeometryState<T>& state = geometry_state();
return state.ComputePointPairPenetration();
}
template <typename T>
std::vector<SortedPair<GeometryId>> QueryObject<T>::FindCollisionCandidates()
const {
ThrowIfNotCallable();
// TODO(amcastro-tri): Modify this when the cache system is in place.
FullPoseUpdate();
const GeometryState<T>& state = geometry_state();
return state.FindCollisionCandidates();
}
template <typename T>
bool QueryObject<T>::HasCollisions() const {
ThrowIfNotCallable();
FullPoseUpdate();
const GeometryState<T>& state = geometry_state();
return state.HasCollisions();
}
template <typename T>
template <typename T1>
typename std::enable_if_t<scalar_predicate<T1>::is_bool,
std::vector<ContactSurface<T>>>
QueryObject<T>::ComputeContactSurfaces(
HydroelasticContactRepresentation representation) const {
ThrowIfNotCallable();
FullPoseUpdate();
const GeometryState<T>& state = geometry_state();
return state.ComputeContactSurfaces(representation);
}
template <typename T>
template <typename T1>
typename std::enable_if_t<scalar_predicate<T1>::is_bool, void>
QueryObject<T>::ComputeContactSurfacesWithFallback(
HydroelasticContactRepresentation representation,
std::vector<ContactSurface<T>>* surfaces,
std::vector<PenetrationAsPointPair<T>>* point_pairs) const {
DRAKE_DEMAND(surfaces != nullptr);
DRAKE_DEMAND(point_pairs != nullptr);
ThrowIfNotCallable();
FullPoseUpdate();
const GeometryState<T>& state = geometry_state();
state.ComputeContactSurfacesWithFallback(representation, surfaces,
point_pairs);
}
template <typename T>
std::vector<SignedDistancePair<T>>
QueryObject<T>::ComputeSignedDistancePairwiseClosestPoints(
const double max_distance) const {
ThrowIfNotCallable();
FullPoseUpdate();
const GeometryState<T>& state = geometry_state();
return state.ComputeSignedDistancePairwiseClosestPoints(max_distance);
}
template <typename T>
SignedDistancePair<T> QueryObject<T>::ComputeSignedDistancePairClosestPoints(
GeometryId geometry_id_A, GeometryId geometry_id_B) const {
ThrowIfNotCallable();
FullPoseUpdate();
const GeometryState<T>& state = geometry_state();
return state.ComputeSignedDistancePairClosestPoints(geometry_id_A,
geometry_id_B);
}
template <typename T>
std::vector<SignedDistanceToPoint<T>>
QueryObject<T>::ComputeSignedDistanceToPoint(
const Vector3<T>& p_WQ,
const double threshold) const {
ThrowIfNotCallable();
FullPoseUpdate();
const GeometryState<T>& state = geometry_state();
return state.ComputeSignedDistanceToPoint(p_WQ, threshold);
}
template <typename T>
void QueryObject<T>::RenderColorImage(const ColorRenderCamera& camera,
FrameId parent_frame,
const RigidTransformd& X_PC,
ImageRgba8U* color_image_out) const {
ThrowIfNotCallable();
FullPoseUpdate();
const GeometryState<T>& state = geometry_state();
return state.RenderColorImage(camera, parent_frame, X_PC, color_image_out);
}
template <typename T>
void QueryObject<T>::RenderDepthImage(const DepthRenderCamera& camera,
FrameId parent_frame,
const RigidTransformd& X_PC,
ImageDepth32F* depth_image_out) const {
ThrowIfNotCallable();
FullPoseUpdate();
const GeometryState<T>& state = geometry_state();
return state.RenderDepthImage(camera, parent_frame, X_PC, depth_image_out);
}
template <typename T>
void QueryObject<T>::RenderLabelImage(const ColorRenderCamera& camera,
FrameId parent_frame,
const RigidTransformd& X_PC,
ImageLabel16I* label_image_out) const {
ThrowIfNotCallable();
FullPoseUpdate();
const GeometryState<T>& state = geometry_state();
return state.RenderLabelImage(camera, parent_frame, X_PC, label_image_out);
}
template <typename T>
const render::RenderEngine* QueryObject<T>::GetRenderEngineByName(
const std::string& name) const {
ThrowIfNotCallable();
FullPoseUpdate();
const GeometryState<T>& state = geometry_state();
return state.GetRenderEngineByName(name);
}
template <typename T>
const GeometryState<T>& QueryObject<T>::geometry_state() const {
// Some extra insurance in case some query *hadn't* called this.
DRAKE_ASSERT_VOID(ThrowIfNotCallable());
if (context_) {
return scene_graph_->geometry_state(*context_);
} else {
return *state_;
}
}
DRAKE_DEFINE_FUNCTION_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_NONSYMBOLIC_SCALARS(
(&QueryObject<T>::template ComputeContactSurfaces<T>))
// The DEFINE_FUNCTION_TEMPLATE macro doesn't handle 3 arguments yet.
template void QueryObject<double>::ComputeContactSurfacesWithFallback<double>(
HydroelasticContactRepresentation representation,
std::vector<ContactSurface<double>>* surfaces,
std::vector<PenetrationAsPointPair<double>>* point_pairs) const;
template void
QueryObject<AutoDiffXd>::ComputeContactSurfacesWithFallback<AutoDiffXd>(
HydroelasticContactRepresentation representation,
std::vector<ContactSurface<AutoDiffXd>>* surfaces,
std::vector<PenetrationAsPointPair<AutoDiffXd>>* point_pairs) const;
} // namespace geometry
} // namespace drake
DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS(
class ::drake::geometry::QueryObject)