-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
gripper_brick.cc
225 lines (202 loc) · 7.54 KB
/
gripper_brick.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
#include "drake/examples/planar_gripper/gripper_brick.h"
#include "drake/examples/planar_gripper/planar_gripper_common.h"
#include "drake/geometry/drake_visualizer.h"
#include "drake/multibody/parsing/parser.h"
#include "drake/systems/analysis/simulator.h"
#include "drake/systems/framework/diagram_builder.h"
namespace drake {
namespace examples {
namespace planar_gripper {
std::string to_string(Finger finger) {
switch (finger) {
case Finger::kFinger1: {
return "finger 1";
}
case Finger::kFinger2: {
return "finger 2";
}
case Finger::kFinger3: {
return "finger 3";
}
default:
throw std::runtime_error("Finger not valid.");
}
}
template <typename T>
void AddDrakeVisualizer(systems::DiagramBuilder<T>*,
const geometry::SceneGraph<T>&) {
// Disabling visualization for non-double scalar type T.
}
template <>
void AddDrakeVisualizer<double>(
systems::DiagramBuilder<double>* builder,
const geometry::SceneGraph<double>& scene_graph) {
geometry::DrakeVisualizerd::AddToBuilder(builder, scene_graph);
}
template <typename T>
void InitializeDiagramSimulator(const systems::Diagram<T>&) {}
template <>
void InitializeDiagramSimulator<double>(
const systems::Diagram<double>& diagram) {
systems::Simulator<double>(diagram).Initialize();
}
template <typename T>
std::unique_ptr<systems::Diagram<T>> ConstructDiagram(
multibody::MultibodyPlant<T>** plant,
geometry::SceneGraph<T>** scene_graph) {
systems::DiagramBuilder<T> builder;
std::tie(*plant, *scene_graph) =
multibody::AddMultibodyPlantSceneGraph(&builder, 0.0);
const std::string gripper_url =
"package://drake/examples/planar_gripper/planar_gripper.sdf";
multibody::Parser parser(*plant, *scene_graph);
parser.AddModelsFromUrl(gripper_url);
examples::planar_gripper::WeldGripperFrames(*plant);
const std::string brick_url =
"package://drake/examples/planar_gripper/planar_brick.sdf";
parser.AddModelsFromUrl(brick_url);
(*plant)->WeldFrames((*plant)->world_frame(),
(*plant)->GetFrameByName("brick_base"),
math::RigidTransformd());
(*plant)->Finalize();
AddDrakeVisualizer<T>(&builder, **scene_graph);
return builder.Build();
}
template <typename T>
GripperBrickHelper<T>::GripperBrickHelper() {
diagram_ = ConstructDiagram<T>(&plant_, &scene_graph_);
InitializeDiagramSimulator(*diagram_);
const geometry::SceneGraphInspector<T>& inspector =
scene_graph_->model_inspector();
for (int i = 0; i < 3; ++i) {
finger_tip_sphere_geometry_ids_[i] = inspector.GetGeometryIdByName(
plant_->GetBodyFrameIdOrThrow(
plant_
->GetBodyByName("finger" + std::to_string(i + 1) + "_tip_link")
.index()),
geometry::Role::kProximity, "planar_gripper::tip_sphere_collision");
}
const geometry::Shape& fingertip_shape =
inspector.GetShape(finger_tip_sphere_geometry_ids_[0]);
finger_tip_radius_ =
dynamic_cast<const geometry::Sphere&>(fingertip_shape).radius();
const multibody::Frame<double>& l2_frame =
plant_->GetBodyByName("finger1_link2").body_frame();
const multibody::Frame<double>& tip_frame =
plant_->GetBodyByName("finger1_tip_link").body_frame();
math::RigidTransform<double> X_L2LTip = plant_->CalcRelativeTransform(
*(plant_->CreateDefaultContext()), l2_frame, tip_frame);
p_L2Fingertip_ =
X_L2LTip * inspector.GetPoseInFrame(finger_tip_sphere_geometry_ids_[0])
.translation();
const geometry::Shape& brick_shape =
inspector.GetShape(inspector.GetGeometryIdByName(
plant_->GetBodyFrameIdOrThrow(
plant_->GetBodyByName("brick_link").index()),
geometry::Role::kProximity, "brick::box_collision"));
brick_size_ = dynamic_cast<const geometry::Box&>(brick_shape).size();
for (int i = 0; i < 3; ++i) {
finger_base_position_indices_[i] =
plant_->GetJointByName("finger" + std::to_string(i + 1) + "_BaseJoint")
.position_start();
finger_mid_position_indices_[i] =
plant_->GetJointByName("finger" + std::to_string(i + 1) + "_MidJoint")
.position_start();
finger_link2_frames_[i] =
&(plant_->GetFrameByName("finger" + std::to_string(i + 1) + "_link2"));
}
brick_translate_y_position_index_ =
plant_->GetJointByName("brick_translate_y_joint").position_start();
brick_translate_z_position_index_ =
plant_->GetJointByName("brick_translate_z_joint").position_start();
brick_revolute_x_position_index_ =
plant_->GetJointByName("brick_revolute_x_joint").position_start();
brick_frame_ = &(plant_->GetFrameByName("brick_link"));
}
template <typename T>
const multibody::Frame<double>& GripperBrickHelper<T>::finger_link2_frame(
Finger finger) const {
switch (finger) {
case Finger::kFinger1: {
return *(finger_link2_frames_[0]);
}
case Finger::kFinger2: {
return *(finger_link2_frames_[1]);
}
case Finger::kFinger3: {
return *(finger_link2_frames_[2]);
}
default:
throw std::invalid_argument("finger_link2_frame(), unknown finger.");
}
}
template <typename T>
int GripperBrickHelper<T>::finger_base_position_index(Finger finger) const {
switch (finger) {
case Finger::kFinger1:
return finger_base_position_indices_[0];
case Finger::kFinger2:
return finger_base_position_indices_[1];
case Finger::kFinger3:
return finger_base_position_indices_[2];
default:
throw std::invalid_argument(
"finger_base_position_index(): unknown finger");
}
}
template <typename T>
int GripperBrickHelper<T>::finger_mid_position_index(Finger finger) const {
switch (finger) {
case Finger::kFinger1:
return finger_mid_position_indices_[0];
case Finger::kFinger2:
return finger_mid_position_indices_[1];
case Finger::kFinger3:
return finger_mid_position_indices_[2];
default:
throw std::invalid_argument(
"finger_mid_position_index(): unknown finger");
}
}
template <typename T>
geometry::GeometryId GripperBrickHelper<T>::finger_tip_sphere_geometry_id(
Finger finger) const {
switch (finger) {
case Finger::kFinger1: {
return finger_tip_sphere_geometry_ids_[0];
}
case Finger::kFinger2: {
return finger_tip_sphere_geometry_ids_[1];
}
case Finger::kFinger3: {
return finger_tip_sphere_geometry_ids_[2];
}
default: {
throw std::invalid_argument(
"finger_tip_sphere_geometry_id(): unknown finger.");
}
}
}
template <typename T>
multibody::CoulombFriction<T>
GripperBrickHelper<T>::GetFingerTipBrickCoulombFriction(Finger finger) const {
const geometry::ProximityProperties& brick_props =
*scene_graph_->model_inspector().GetProximityProperties(
plant_->GetCollisionGeometriesForBody(brick_frame().body())[0]);
const geometry::ProximityProperties& finger_props =
*scene_graph_->model_inspector().GetProximityProperties(
finger_tip_sphere_geometry_id(finger));
const multibody::CoulombFriction<T>& brick_friction =
brick_props.GetProperty<multibody::CoulombFriction<T>>(
"material", "coulomb_friction");
const multibody::CoulombFriction<T>& finger_tip_friction =
finger_props.GetProperty<multibody::CoulombFriction<T>>(
"material", "coulomb_friction");
return multibody::CalcContactFrictionFromSurfaceProperties(
brick_friction, finger_tip_friction);
}
// Explicit instantiation
template class GripperBrickHelper<double>;
} // namespace planar_gripper
} // namespace examples
} // namespace drake