@@ -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(
403403bool 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
453443Eigen::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
0 commit comments