Skip to content

Commit fae4ba2

Browse files
committed
Second sampling C3 example: push T (#384)
* Push t example; working in sim * Bazel build file fixes * Fix sample perimeter projection to proper clearance * Consolidate duplicated lines for building contact pairs * Minor tuning for push T
1 parent 62ea631 commit fae4ba2

25 files changed

+968
-52
lines changed

examples/sampling_c3/franka_sampling_c3_controller.cc

Lines changed: 46 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -104,6 +104,8 @@ int DoMain(int argc, char* argv[]) {
104104

105105
// Build the contact pairs based on the demo.
106106
std::vector<std::vector<SortedPair<GeometryId>>> contact_pairs;
107+
std::vector<SortedPair<GeometryId>> ee_contact_pairs;
108+
std::vector<SortedPair<GeometryId>> ground_object_contact_pairs;
107109
std::unordered_map<std::string, drake::geometry::GeometryId> contact_geoms;
108110

109111
// All demos include the end effector and ground.
@@ -117,7 +119,6 @@ int DoMain(int argc, char* argv[]) {
117119
contact_geoms["GROUND"] = ground_geoms;
118120
std::vector<SortedPair<GeometryId>> ee_ground_contact{
119121
SortedPair(contact_geoms["EE"], contact_geoms["GROUND"])};
120-
contact_pairs.push_back(ee_ground_contact);
121122

122123
if (FLAGS_demo_name == "jacktoy") {
123124
drake::geometry::GeometryId capsule1_geoms =
@@ -159,18 +160,13 @@ int DoMain(int argc, char* argv[]) {
159160
contact_geoms["CAPSULE_3_SPHERE_1"] = capsule3_sphere1_geoms;
160161
contact_geoms["CAPSULE_3_SPHERE_2"] = capsule3_sphere2_geoms;
161162

162-
// EE-object contact pairs second.
163-
std::vector<SortedPair<GeometryId>> ee_contact_pairs;
164163
ee_contact_pairs.push_back(
165164
SortedPair(contact_geoms["EE"], contact_geoms["CAPSULE_1"]));
166165
ee_contact_pairs.push_back(
167166
SortedPair(contact_geoms["EE"], contact_geoms["CAPSULE_2"]));
168167
ee_contact_pairs.push_back(
169168
SortedPair(contact_geoms["EE"], contact_geoms["CAPSULE_3"]));
170-
contact_pairs.push_back(ee_contact_pairs);
171169

172-
// Object-ground contact pairs third.
173-
std::vector<SortedPair<GeometryId>> ground_object_contact_pairs;
174170
ground_object_contact_pairs.push_back(SortedPair(
175171
contact_geoms["CAPSULE_1_SPHERE_1"], contact_geoms["GROUND"]));
176172
ground_object_contact_pairs.push_back(SortedPair(
@@ -183,11 +179,50 @@ int DoMain(int argc, char* argv[]) {
183179
contact_geoms["CAPSULE_3_SPHERE_1"], contact_geoms["GROUND"]));
184180
ground_object_contact_pairs.push_back(SortedPair(
185181
contact_geoms["CAPSULE_3_SPHERE_2"], contact_geoms["GROUND"]));
186-
contact_pairs.push_back(ground_object_contact_pairs);
182+
}
183+
else if (FLAGS_demo_name == "push_t") {
184+
drake::geometry::GeometryId vertical_geoms =
185+
plant_lcs.GetCollisionGeometriesForBody(
186+
plant_lcs.GetBodyByName("vertical_link"))[0];
187+
drake::geometry::GeometryId horizontal_geoms =
188+
plant_lcs.GetCollisionGeometriesForBody(
189+
plant_lcs.GetBodyByName("horizontal_link"))[0];
190+
191+
drake::geometry::GeometryId top_left_sphere_geoms =
192+
plant_lcs.GetCollisionGeometriesForBody(
193+
plant_lcs.GetBodyByName("vertical_link"))[1];
194+
drake::geometry::GeometryId top_right_sphere_geoms =
195+
plant_lcs.GetCollisionGeometriesForBody(
196+
plant_lcs.GetBodyByName("vertical_link"))[2];
197+
drake::geometry::GeometryId bottom_sphere_geoms =
198+
plant_lcs.GetCollisionGeometriesForBody(
199+
plant_lcs.GetBodyByName("vertical_link"))[3];
200+
201+
contact_geoms["VERTICAL_LINK"] = vertical_geoms;
202+
contact_geoms["HORIZONTAL_LINK"] = horizontal_geoms;
203+
contact_geoms["TOP_LEFT_SPHERE"] = top_left_sphere_geoms;
204+
contact_geoms["TOP_RIGHT_SPHERE"] = top_right_sphere_geoms;
205+
contact_geoms["BOTTOM_SPHERE"] = bottom_sphere_geoms;
206+
207+
ee_contact_pairs.push_back(
208+
SortedPair(contact_geoms["EE"], contact_geoms["HORIZONTAL_LINK"]));
209+
ee_contact_pairs.push_back(
210+
SortedPair(contact_geoms["EE"], contact_geoms["VERTICAL_LINK"]));
211+
212+
ground_object_contact_pairs.push_back(SortedPair(
213+
contact_geoms["TOP_LEFT_SPHERE"], contact_geoms["GROUND"]));
214+
ground_object_contact_pairs.push_back(SortedPair(
215+
contact_geoms["TOP_RIGHT_SPHERE"], contact_geoms["GROUND"]));
216+
ground_object_contact_pairs.push_back(SortedPair(
217+
contact_geoms["BOTTOM_SPHERE"], contact_geoms["GROUND"]));
187218
}
188219
else {
189220
throw std::runtime_error("Unknown --demo_name value: " + FLAGS_demo_name);
190221
}
222+
// Order: EE-ground, EE-object, object-ground.
223+
contact_pairs.push_back(ee_ground_contact);
224+
contact_pairs.push_back(ee_contact_pairs);
225+
contact_pairs.push_back(ground_object_contact_pairs);
191226

192227
// Piece together the diagram.
193228
DiagramBuilder<double> builder;
@@ -215,6 +250,10 @@ int DoMain(int argc, char* argv[]) {
215250
target_generator =
216251
std::make_unique<systems::SamplingC3GoalGeneratorJacktoy>(
217252
plant_object, controller_params.goal_params);
253+
} else if (FLAGS_demo_name == "push_t") {
254+
target_generator =
255+
std::make_unique<systems::SamplingC3GoalGeneratorPushT>(
256+
plant_object, controller_params.goal_params);
218257
} else {
219258
throw std::runtime_error("Unknown --demo_name value: " + FLAGS_demo_name);
220259
}

examples/sampling_c3/generate_samples.cc

Lines changed: 26 additions & 36 deletions
Original file line numberDiff line numberDiff line change
@@ -238,7 +238,6 @@ Eigen::Vector3d PerimeterSampling(
238238
double z_sample = 0;
239239

240240
// Convert to world frame using the current object state.
241-
Eigen::VectorXd x_lcs_world = x_lcs;
242241
Eigen::Quaterniond quat_object(x_lcs(3), x_lcs(4), x_lcs(5), x_lcs(6));
243242
Eigen::Vector3d object_position = x_lcs.segment(7, 3);
244243
candidate_state = x_lcs;
@@ -249,19 +248,19 @@ Eigen::Vector3d PerimeterSampling(
249248
// Project samples to specified sampling height in world frame.
250249
candidate_state[2] = sampling_params.sampling_height;
251250
} while (!IsSampleWithinDistanceOfSurface(
252-
n_q, n_v, n_u, 0.0, false, candidate_state, plant, context, plant_ad,
253-
context_ad, contact_geoms, sampling_c3_options, min_distance_index));
251+
n_q, n_v, n_u, 0.0, candidate_state, plant, context, plant_ad, context_ad,
252+
contact_geoms, sampling_c3_options, min_distance_index));
254253

255254
// Project the sample past the surface of the object with clearance.
256255
Eigen::VectorXd projected_state = ProjectSampleOutsideObject(
257-
candidate_state, min_distance_index, sampling_params, plant, *context,
258-
contact_geoms);
256+
candidate_state, min_distance_index, sampling_params, plant, *context,
257+
contact_geoms);
259258

260259
// Check the desired clearance is satisfied; otherwise try again.
261260
UpdateContext(n_q, n_v, n_u, plant, context, plant_ad, context_ad,
262261
projected_state);
263262
if (IsSampleWithinDistanceOfSurface(
264-
n_q, n_v, n_u, sampling_params.sample_projection_clearance, true,
263+
n_q, n_v, n_u, sampling_params.sample_projection_clearance,
265264
projected_state, plant, context, plant_ad, context_ad, contact_geoms,
266265
sampling_c3_options, min_distance_index)) {
267266
continue;
@@ -333,8 +332,8 @@ Eigen::Vector3d ShellSampling(
333332
y_samplec + sampling_radius * sin(theta) * sin(elevation_theta);
334333
candidate_state[2] = z_samplec + sampling_radius * cos(elevation_theta);
335334
} while (!IsSampleWithinDistanceOfSurface(
336-
n_q, n_v, n_u, 0.0, false, candidate_state, plant, context, plant_ad,
337-
context_ad, contact_geoms, sampling_c3_options, min_distance_index));
335+
n_q, n_v, n_u, 0.0, candidate_state, plant, context, plant_ad, context_ad,
336+
contact_geoms, sampling_c3_options, min_distance_index));
338337

339338
// Project the sample past the surface of the object with clearance.
340339
Eigen::VectorXd projected_state = ProjectSampleOutsideObject(
@@ -345,7 +344,7 @@ Eigen::Vector3d ShellSampling(
345344
UpdateContext(n_q, n_v, n_u, plant, context, plant_ad, context_ad,
346345
projected_state);
347346
if (IsSampleWithinDistanceOfSurface(
348-
n_q, n_v, n_u, sampling_params.sample_projection_clearance, true,
347+
n_q, n_v, n_u, sampling_params.sample_projection_clearance,
349348
projected_state, plant, context, plant_ad, context_ad, contact_geoms,
350349
sampling_c3_options, min_distance_index)) {
351350
continue;
@@ -390,7 +389,8 @@ double GetEERadiusFromPlant(
390389
query_port.template Eval<drake::geometry::QueryObject<double>>(context);
391390
const auto& inspector = query_object.inspector();
392391

393-
// Locate the EE and obtain its radius.
392+
// Locate the EE and obtain its radius. The first set of contact geoms has
393+
// the EE and ground.
394394
GeometryId ee_geom_id = contact_geoms.at(0).at(0).first();
395395
const drake::geometry::Shape& shape = inspector.GetShape(ee_geom_id);
396396
const auto* sphere = dynamic_cast<const drake::geometry::Sphere*>(&shape);
@@ -403,15 +403,14 @@ double GetEERadiusFromPlant(
403403
bool IsSampleWithinDistanceOfSurface(
404404
const int& n_q, const int& n_v, const int& n_u,
405405
const double& clearance_distance,
406-
const bool& factor_in_ee_radius,
407406
const Eigen::VectorXd& candidate_state,
408407
drake::multibody::MultibodyPlant<double>& plant,
409408
drake::systems::Context<double>* context,
410409
drake::multibody::MultibodyPlant<drake::AutoDiffXd>& plant_ad,
411410
drake::systems::Context<drake::AutoDiffXd>* context_ad,
412411
const std::vector<
413-
std::vector<drake::SortedPair<drake::geometry::GeometryId>>>&
414-
contact_geoms,
412+
std::vector<drake::SortedPair<drake::geometry::GeometryId>>>&
413+
contact_geoms,
415414
SamplingC3Options sampling_c3_options,
416415
int& min_distance_index)
417416
{
@@ -421,14 +420,12 @@ bool IsSampleWithinDistanceOfSurface(
421420

422421
// Find the closest pair if there are multiple pairs
423422
std::vector<double> distances;
424-
425-
for (int i = 0; i < contact_geoms.at(0).size(); i++) {
426-
// Evaluate the distance for each pair
427-
SortedPair<GeometryId> pair{(contact_geoms.at(0)).at(i)};
423+
for (int i = 0; i < contact_geoms.at(1).size(); i++) {
424+
SortedPair<GeometryId> pair{(contact_geoms.at(1)).at(i)};
428425
multibody::GeomGeomCollider collider(plant, pair);
429426

430427
auto [phi_i, J_i] = collider.EvalPolytope(
431-
*context, sampling_c3_options.num_friction_directions);
428+
*context, sampling_c3_options.num_friction_directions);
432429
distances.push_back(phi_i);
433430
}
434431

@@ -439,15 +436,8 @@ bool IsSampleWithinDistanceOfSurface(
439436
min_distance_index = std::distance(distances.begin(), min_distance_it);
440437
double min_distance = *min_distance_it;
441438

442-
// Factor the EE radius into the clearance distance if requested.
443-
double ee_radius_contribution = 0.0;
444-
if (factor_in_ee_radius) {
445-
ee_radius_contribution = GetEERadiusFromPlant(
446-
plant, *context, contact_geoms);
447-
}
448-
449439
// Require that min_distance be at least 1 mm within the clearance distance.
450-
return min_distance <= clearance_distance + ee_radius_contribution - 1e-3;
440+
return min_distance <= clearance_distance - 1e-3;
451441
}
452442

453443
Eigen::VectorXd ProjectSampleOutsideObject(
@@ -462,22 +452,22 @@ Eigen::VectorXd ProjectSampleOutsideObject(
462452
// Compute the witness points between the penetrating sample and the object
463453
// surface.
464454
multibody::GeomGeomCollider collider(
465-
plant, contact_geoms.at(0).at(min_distance_index));
466-
auto [p_world_contact_a, p_world_contact_b] = collider.CalcWitnessPoints(
455+
plant, contact_geoms.at(1).at(min_distance_index));
456+
auto [p_world_contact_ee, p_world_contact_obj] = collider.CalcWitnessPoints(
467457
context);
468458

469459
// Get the EE radius to factor into the projection.
470460
double ee_radius = GetEERadiusFromPlant(plant, context, contact_geoms);
471461

472-
// Find vector in direction from sample to contact point on object.
473-
Eigen::Vector3d a_to_b = p_world_contact_b - p_world_contact_a;
474-
Eigen::Vector3d a_to_b_normalized = a_to_b.normalized();
475-
// Add clearance to point b in the same direction.
476-
Eigen::Vector3d p_world_contact_b_clearance =
477-
p_world_contact_b +
462+
// Find vector in direction from EE to object witness points.
463+
Eigen::Vector3d ee_to_obj = p_world_contact_obj - p_world_contact_ee;
464+
Eigen::Vector3d ee_to_obj_normalized = ee_to_obj.normalized();
465+
// Add clearance to the object in the same direction.
466+
Eigen::Vector3d p_world_contact_obj_clearance =
467+
p_world_contact_obj +
478468
(ee_radius + sampling_params.sample_projection_clearance) *
479-
a_to_b_normalized;
480-
candidate_state.head(3) = p_world_contact_b_clearance;
469+
ee_to_obj_normalized;
470+
candidate_state.head(3) = p_world_contact_obj_clearance;
481471
return candidate_state;
482472
}
483473

examples/sampling_c3/generate_samples.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -129,7 +129,6 @@ bool IsSampleWithinDistanceOfSurface(
129129
const int& n_v,
130130
const int& n_u,
131131
const double& clearance_distance,
132-
const bool& factor_in_ee_radius,
133132
const Eigen::VectorXd& candidate_state,
134133
drake::multibody::MultibodyPlant<double>& plant,
135134
drake::systems::Context<double>* context,

examples/sampling_c3/goal_generator.cc

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -164,10 +164,10 @@ void SamplingC3GoalGenerator::SetRandomizedTargetFinalObjectPosition() const {
164164
double x, y = 0;
165165
while ((sqrt(x * x + y * y) > goal_params_.random_goal_radius_limits[1]) ||
166166
(sqrt(x * x + y * y) < goal_params_.random_goal_radius_limits[0])) {
167-
double x = RandomUniform(goal_params_.random_goal_x_limits[0],
168-
goal_params_.random_goal_x_limits[1]);
169-
double y = RandomUniform(goal_params_.random_goal_y_limits[0],
170-
goal_params_.random_goal_y_limits[1]);
167+
x = RandomUniform(goal_params_.random_goal_x_limits[0],
168+
goal_params_.random_goal_x_limits[1]);
169+
y = RandomUniform(goal_params_.random_goal_y_limits[0],
170+
goal_params_.random_goal_y_limits[1]);
171171
}
172172

173173
target_final_object_position_ << x, y, goal_params_.resting_object_height;

examples/sampling_c3/goal_generator.h

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,11 @@ inline const std::vector<Eigen::Quaterniond> kNominalOrientationsJack{
3838
kQuatAllUp, kQuatRedDown, kQuatBlueUp, kQuatAllDown,
3939
kQuatGreenUp, kQuatBlueDown, kQuatRedUp, kQuatGreenDown};
4040

41+
// Define the nominal orientations for any planar demo.
42+
inline const Eigen::Quaterniond kQUAT_FLAT{1.0, 0.0, 0.0, 0.0};
43+
inline const std::vector<Eigen::Quaterniond> kNominalOrientationsPlanar{
44+
kQUAT_FLAT};
45+
4146

4247
namespace dairlib {
4348
namespace systems {
@@ -137,5 +142,17 @@ class SamplingC3GoalGeneratorJacktoy : public SamplingC3GoalGenerator {
137142
object_plant, goal_params, kNominalOrientationsJack) {}
138143
};
139144

145+
146+
// class TargetGeneratorPushT : public TargetGenerator {
147+
class SamplingC3GoalGeneratorPushT : public SamplingC3GoalGenerator {
148+
public:
149+
SamplingC3GoalGeneratorPushT(
150+
const drake::multibody::MultibodyPlant<double>& object_plant,
151+
const SamplingC3GoalParams& goal_params) :
152+
SamplingC3GoalGenerator(
153+
object_plant, goal_params, kNominalOrientationsPlanar) {}
154+
};
155+
156+
140157
} // namespace systems
141158
} // namespace dairlib

examples/sampling_c3/jacktoy/BUILD.bazel

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,6 @@ cc_library(
1010
]),
1111
)
1212

13-
1413
cc_library(
1514
name = "lcm_channels_jacktoy",
1615
hdrs = [],
File renamed without changes.
File renamed without changes.

examples/sampling_c3/jacktoy/parameters/sampling_c3_controller_params.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@ lcm_channels_simulation_file: examples/sampling_c3/shared_parameters/lcm_channel
1515

1616
# Note: Use capsule_1 body name as representative of the pose of the entire
1717
# jack model. This works because capsule_1's origin is the same as the jack's.
18-
object_model: examples/sampling_c3/urdf/jack_ground.sdf
18+
object_model: examples/sampling_c3/urdf/jack_control.sdf
1919
object_body_name: capsule_1
2020

2121
include_end_effector_orientation: false

examples/sampling_c3/jacktoy/parameters/sampling_params.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ num_additional_samples_repos: 1
1919
num_additional_samples_c3: 2
2020

2121
# Sample buffer parameters.
22-
consider_best_buffer_sample_when_leaving_c3: false
22+
consider_best_buffer_sample_when_leaving_c3: true
2323
N_sample_buffer: 100
2424
pos_error_sample_retention: 0.005
2525
ang_error_sample_retention: 0.087 # 0.087 rad = 5 deg

0 commit comments

Comments
 (0)