RobotLocomotion / drake

Model-based design and verification for robotics.
https://drake.mit.edu
Other
3.24k stars 1.25k forks source link

Build errors upon trying to import `multibody_plant.h` #21195

Closed alberthli closed 5 months ago

alberthli commented 5 months ago

What happened?

I'm currently using drake in a docker container running ubuntu 22.04 installed by following these instructions. In a test c++ project that depends on drake, upon trying to import multibody_plant.h, I see the below error. This error only occurred today when I rebuilt my container without the Docker cache without any modification to the lines regarding drake, so it seems to be related to one of the newer releases, though I can't say which one with certainty. I do think the last time I built from scratch, the most recent drake release was 1.26.0.

1.867 In file included from /opt/drake/include/drake/geometry/collision_filter_declaration.h:7,
1.867                  from /opt/drake/include/drake/geometry/collision_filter_manager.h:4,
1.867                  from /opt/drake/include/drake/geometry/scene_graph.h:9,
1.867                  from /opt/drake/include/drake/multibody/plant/multibody_plant.h:21,
1.867                  from /home/test/test.cpp:1:
1.867 /opt/drake/include/drake/geometry/geometry_set.h: In member function 'bool drake::geometry::GeometrySet::contains(drake::geometry::FrameId) const':
1.867 /opt/drake/include/drake/geometry/geometry_set.h:285:23: error: 'const class std::unordered_set<drake::Identifier<drake::geometry::FrameTag> >' has no member named 'contains'
1.867   285 |     return frame_ids_.contains(frame_id);
1.867       |                       ^~~~~~~~
1.867 /opt/drake/include/drake/geometry/geometry_set.h: In member function 'bool drake::geometry::GeometrySet::contains(drake::geometry::GeometryId) const':
1.867 /opt/drake/include/drake/geometry/geometry_set.h:291:26: error: 'const class std::unordered_set<drake::geometry::GeometryId>' has no member named 'contains'
1.867   291 |     return geometry_ids_.contains(geometry_id);
1.867       |                          ^~~~~~~~
1.883 In file included from /opt/drake/include/drake/geometry/collision_filter_manager.h:6,
1.883                  from /opt/drake/include/drake/geometry/scene_graph.h:9,
1.883                  from /opt/drake/include/drake/multibody/plant/multibody_plant.h:21,
1.883                  from /home/test/test.cpp:1:
1.883 /opt/drake/include/drake/geometry/proximity/collision_filter.h: In member function 'bool drake::geometry::internal::CollisionFilter::HasGeometry(drake::geometry::GeometryId) const':
1.883 /opt/drake/include/drake/geometry/proximity/collision_filter.h:129:64: error: 'const FilterState' {aka 'const class std::unordered_map<drake::geometry::GeometryId, std::unordered_map<drake::geometry::GeometryId, drake::geometry::internal::CollisionFilter::PairRelationship> >'} has no member named 'contains'
1.883   129 |   bool HasGeometry(GeometryId id) const { return filter_state_.contains(id); }
1.883       |                                                                ^~~~~~~~
2.111 In file included from /opt/drake/include/drake/geometry/query_object.h:9,
2.111                  from /opt/drake/include/drake/geometry/scene_graph.h:13,
2.111                  from /opt/drake/include/drake/multibody/plant/multibody_plant.h:21,
2.111                  from /home/test/test.cpp:1:
2.111 /opt/drake/include/drake/geometry/query_results/deformable_contact.h: In member function 'bool drake::geometry::internal::DeformableContact<T>::IsRegistered(drake::geometry::GeometryId) const':
2.111 /opt/drake/include/drake/geometry/query_results/deformable_contact.h:383:36: error: 'const class std::unordered_map<drake::geometry::GeometryId, drake::geometry::internal::ContactParticipation>' has no member named 'contains'
2.111   383 |     return contact_participations_.contains(id);
2.111       |                                    ^~~~~~~~
2.177 In file included from /opt/drake/include/drake/geometry/geometry_roles.h:9,
2.177                  from /opt/drake/include/drake/geometry/render/render_engine.h:14,
2.177                  from /opt/drake/include/drake/geometry/query_object.h:14,
2.177                  from /opt/drake/include/drake/geometry/scene_graph.h:13,
2.177                  from /opt/drake/include/drake/multibody/plant/multibody_plant.h:21,
2.177                  from /home/test/test.cpp:1:
2.177 /opt/drake/include/drake/geometry/geometry_properties.h: In member function 'bool drake::geometry::GeometryProperties::HasGroup(const string&) const':
2.177 /opt/drake/include/drake/geometry/geometry_properties.h:236:20: error: 'const class std::unordered_map<std::__cxx11::basic_string<char>, std::unordered_map<std::__cxx11::basic_string<char>, drake::copyable_unique_ptr<drake::AbstractValue> > >' has no member named 'contains'
2.177   236 |     return values_.contains(group_name);
2.177       |                    ^~~~~~~~
2.301 In file included from /opt/drake/include/drake/geometry/scene_graph_inspector.h:17,
2.301                  from /opt/drake/include/drake/geometry/query_object.h:15,
2.301                  from /opt/drake/include/drake/geometry/scene_graph.h:13,
2.301                  from /opt/drake/include/drake/multibody/plant/multibody_plant.h:21,
2.301                  from /home/test/test.cpp:1:
2.301 /opt/drake/include/drake/geometry/internal_frame.h: In member function 'bool drake::geometry::internal::InternalFrame::has_child(drake::geometry::FrameId) const':
2.301 /opt/drake/include/drake/geometry/internal_frame.h:115:26: error: 'const class std::unordered_set<drake::Identifier<drake::geometry::FrameTag> >' has no member named 'contains'
2.301   115 |     return child_frames_.contains(frame_id);
2.301       |                          ^~~~~~~~
2.301 /opt/drake/include/drake/geometry/internal_frame.h: In member function 'bool drake::geometry::internal::InternalFrame::has_child(drake::geometry::GeometryId) const':
2.301 /opt/drake/include/drake/geometry/internal_frame.h:125:30: error: 'const class std::unordered_set<drake::geometry::GeometryId>' has no member named 'contains'
2.301   125 |     return child_geometries_.contains(geometry_id);
2.301       |                              ^~~~~~~~
2.302 In file included from /opt/drake/include/drake/common/eigen_types.h:20,
2.302                  from /opt/drake/include/drake/common/eigen_autodiff_types.h:17,
2.302                  from /opt/drake/include/drake/common/autodiff.h:27,
2.302                  from /opt/drake/include/drake/common/default_scalars.h:3,
2.302                  from /opt/drake/include/drake/multibody/plant/multibody_plant.h:17,
2.302                  from /home/test/test.cpp:1:
2.302 /opt/drake/include/drake/geometry/internal_frame.h: In member function 'void drake::geometry::internal::InternalFrame::remove_child(drake::geometry::GeometryId)':
2.302 /opt/drake/include/drake/geometry/internal_frame.h:138:5: error: 'class std::unordered_set<drake::geometry::GeometryId>' has no member named 'contains'
2.302   138 |     DRAKE_ASSERT(child_geometries_.contains(geometry_id));
2.302       |     ^~~~~~~~~~~~
2.302 /opt/drake/include/drake/geometry/internal_frame.h:138:5: error: 'class std::unordered_set<drake::geometry::GeometryId>' has no member named 'contains'
2.302 /opt/drake/include/drake/geometry/internal_frame.h:138:5: error: template argument 1 is invalid
2.302   138 |     DRAKE_ASSERT(child_geometries_.contains(geometry_id));
2.302       |     ^~~~~~~~~~~~
2.302 /opt/drake/include/drake/geometry/internal_frame.h:138:5: error: template argument 1 is invalid
2.302   138 |     DRAKE_ASSERT(child_geometries_.contains(geometry_id));
2.302       |     ^~~~~~~~~~~~
2.302 /opt/drake/include/drake/geometry/internal_frame.h:138:5: error: 'Trait' is not a class, namespace, or enumeration
2.302   138 |     DRAKE_ASSERT(child_geometries_.contains(geometry_id));
2.302       |     ^~~~~~~~~~~~
2.302 /opt/drake/include/drake/geometry/internal_frame.h:138:5: error: 'class std::unordered_set<drake::geometry::GeometryId>' has no member named 'contains'
2.302   138 |     DRAKE_ASSERT(child_geometries_.contains(geometry_id));
2.302       |     ^~~~~~~~~~~~
2.302 /opt/drake/include/drake/geometry/internal_frame.h:138:5: error: 'class std::unordered_set<drake::geometry::GeometryId>' has no member named 'contains'
2.302 /opt/drake/include/drake/geometry/internal_frame.h:138:5: error: template argument 1 is invalid
2.302   138 |     DRAKE_ASSERT(child_geometries_.contains(geometry_id));
2.302       |     ^~~~~~~~~~~~
2.302 /opt/drake/include/drake/geometry/internal_frame.h:138:5: error: 'Trait' is not a class, namespace, or enumeration
2.302   138 |     DRAKE_ASSERT(child_geometries_.contains(geometry_id));
2.302       |     ^~~~~~~~~~~~
2.302 /opt/drake/include/drake/geometry/internal_frame.h:138:5: error: 'class std::unordered_set<drake::geometry::GeometryId>' has no member named 'contains'
2.302   138 |     DRAKE_ASSERT(child_geometries_.contains(geometry_id));
2.302       |     ^~~~~~~~~~~~
3.125 In file included from /opt/drake/include/drake/multibody/tree/acceleration_kinematics_cache.h:12,
3.125                  from /opt/drake/include/drake/multibody/tree/multibody_tree_system.h:12,
3.125                  from /opt/drake/include/drake/multibody/plant/force_density_field.h:12,
3.125                  from /opt/drake/include/drake/multibody/fem/fem_plant_data.h:6,
3.125                  from /opt/drake/include/drake/multibody/fem/fem_model.h:15,
3.125                  from /opt/drake/include/drake/multibody/fem/fem_solver.h:12,
3.125                  from /opt/drake/include/drake/multibody/plant/deformable_driver.h:14,
3.125                  from /opt/drake/include/drake/multibody/plant/discrete_update_manager.h:19,
3.125                  from /opt/drake/include/drake/multibody/plant/multibody_plant.h:27,
3.125                  from /home/test/test.cpp:1:
3.125 /opt/drake/include/drake/multibody/tree/multibody_tree_topology.h: In member function 'std::vector<drake::TypeSafeIndex<drake::multibody::BodyTag> > drake::multibody::internal::MultibodyTreeTopology::GetTransitiveOutboardBodies(std::vector<drake::TypeSafeIndex<drake::multibody::BodyTag> >) const':
3.125 /opt/drake/include/drake/multibody/tree/multibody_tree_topology.h:1016:28: error: 'class std::unordered_set<drake::TypeSafeIndex<drake::multibody::BodyTag> >' has no member named 'contains'
3.125  1016 |       if (!outboard_bodies.contains(body_index)) {
3.125       |                            ^~~~~~~~
3.481 In file included from /opt/drake/include/drake/multibody/plant/deformable_driver.h:16,
3.481                  from /opt/drake/include/drake/multibody/plant/discrete_update_manager.h:19,
3.481                  from /opt/drake/include/drake/multibody/plant/multibody_plant.h:27,
3.481                  from /home/test/test.cpp:1:
3.481 /opt/drake/include/drake/multibody/plant/deformable_model.h: In member function 'bool drake::multibody::DeformableModel<T>::HasConstraint(drake::multibody::DeformableBodyId) const':
3.481 /opt/drake/include/drake/multibody/plant/deformable_model.h:206:39: error: 'const class std::unordered_map<drake::Identifier<drake::multibody::DeformableBodyTag>, std::vector<drake::Identifier<drake::multibody::ConstraintTag> > >' has no member named 'contains'
3.481   206 |     return body_id_to_constraint_ids_.contains(id);
3.481       |                                       ^~~~~~~~
3.481 In file included from /opt/drake/include/drake/common/hash.h:16,
3.481                  from /opt/drake/include/drake/common/symbolic/expression/variable.h:18,
3.481                  from /opt/drake/include/drake/common/symbolic/expression/all.h:21,
3.481                  from /opt/drake/include/drake/common/symbolic/expression.h:10,
3.481                  from /opt/drake/include/drake/common/default_scalars.h:4,
3.481                  from /opt/drake/include/drake/multibody/plant/multibody_plant.h:17,
3.481                  from /home/test/test.cpp:1:
3.481 /opt/drake/include/drake/multibody/plant/deformable_model.h: In member function 'const drake::multibody::internal::DeformableRigidFixedConstraintSpec& drake::multibody::DeformableModel<T>::fixed_constraint_spec(drake::multibody::MultibodyConstraintId) const':
3.481 /opt/drake/include/drake/multibody/plant/deformable_model.h:214:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::DeformableRigidFixedConstraintSpec>' has no member named 'contains'
3.481   214 |     DRAKE_THROW_UNLESS(fixed_constraint_specs_.contains(id));
3.481       |     ^~~~~~~~~~~~~~~~~~
3.481 /opt/drake/include/drake/multibody/plant/deformable_model.h:214:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::DeformableRigidFixedConstraintSpec>' has no member named 'contains'
3.481 /opt/drake/include/drake/multibody/plant/deformable_model.h:214:5: error: template argument 1 is invalid
3.481   214 |     DRAKE_THROW_UNLESS(fixed_constraint_specs_.contains(id));
3.481       |     ^~~~~~~~~~~~~~~~~~
3.481 /opt/drake/include/drake/multibody/plant/deformable_model.h:214:5: error: template argument 1 is invalid
3.481   214 |     DRAKE_THROW_UNLESS(fixed_constraint_specs_.contains(id));
3.481       |     ^~~~~~~~~~~~~~~~~~
3.481 /opt/drake/include/drake/multibody/plant/deformable_model.h:214:5: error: 'Trait' is not a class, namespace, or enumeration
3.481   214 |     DRAKE_THROW_UNLESS(fixed_constraint_specs_.contains(id));
3.481       |     ^~~~~~~~~~~~~~~~~~
3.481 /opt/drake/include/drake/multibody/plant/deformable_model.h:214:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::DeformableRigidFixedConstraintSpec>' has no member named 'contains'
3.481   214 |     DRAKE_THROW_UNLESS(fixed_constraint_specs_.contains(id));
3.481       |     ^~~~~~~~~~~~~~~~~~
3.481 /opt/drake/include/drake/multibody/plant/deformable_model.h:214:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::DeformableRigidFixedConstraintSpec>' has no member named 'contains'
3.481 /opt/drake/include/drake/multibody/plant/deformable_model.h:214:5: error: 'Trait' is not a class, namespace, or enumeration
3.481   214 |     DRAKE_THROW_UNLESS(fixed_constraint_specs_.contains(id));
3.481       |     ^~~~~~~~~~~~~~~~~~
3.481 /opt/drake/include/drake/multibody/plant/deformable_model.h:214:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::DeformableRigidFixedConstraintSpec>' has no member named 'contains'
3.481   214 |     DRAKE_THROW_UNLESS(fixed_constraint_specs_.contains(id));
3.481       |     ^~~~~~~~~~~~~~~~~~
3.607 In file included from /opt/drake/include/drake/multibody/tree/multibody_tree-inl.h:33,
3.607                  from /opt/drake/include/drake/multibody/plant/multibody_plant.h:32,
3.607                  from /home/test/test.cpp:1:
3.607 /opt/drake/include/drake/multibody/tree/uniform_gravity_field_element.h: In member function 'bool drake::multibody::UniformGravityFieldElement<T>::is_enabled(drake::multibody::ModelInstanceIndex) const':
3.607 /opt/drake/include/drake/multibody/tree/uniform_gravity_field_element.h:63:39: error: 'const class std::set<drake::TypeSafeIndex<drake::multibody::ModelInstanceTag> >' has no member named 'contains'
3.607    63 |     return !disabled_model_instances_.contains(model_instance);
3.607       |                                       ^~~~~~~~
3.818 In file included from /opt/drake/include/drake/common/hash.h:16,
3.818                  from /opt/drake/include/drake/common/symbolic/expression/variable.h:18,
3.818                  from /opt/drake/include/drake/common/symbolic/expression/all.h:21,
3.818                  from /opt/drake/include/drake/common/symbolic/expression.h:10,
3.818                  from /opt/drake/include/drake/common/default_scalars.h:4,
3.818                  from /opt/drake/include/drake/multibody/plant/multibody_plant.h:17,
3.818                  from /home/test/test.cpp:1:
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h: In member function 'const drake::multibody::internal::CouplerConstraintSpec& drake::multibody::MultibodyPlant<T>::get_coupler_constraint_specs(drake::multibody::MultibodyConstraintId) const':
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1521:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::CouplerConstraintSpec>' has no member named 'contains'
3.818  1521 |     DRAKE_THROW_UNLESS(coupler_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1521:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::CouplerConstraintSpec>' has no member named 'contains'
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1521:5: error: template argument 1 is invalid
3.818  1521 |     DRAKE_THROW_UNLESS(coupler_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1521:5: error: template argument 1 is invalid
3.818  1521 |     DRAKE_THROW_UNLESS(coupler_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1521:5: error: 'Trait' is not a class, namespace, or enumeration
3.818  1521 |     DRAKE_THROW_UNLESS(coupler_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1521:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::CouplerConstraintSpec>' has no member named 'contains'
3.818  1521 |     DRAKE_THROW_UNLESS(coupler_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1521:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::CouplerConstraintSpec>' has no member named 'contains'
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1521:5: error: 'Trait' is not a class, namespace, or enumeration
3.818  1521 |     DRAKE_THROW_UNLESS(coupler_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1521:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::CouplerConstraintSpec>' has no member named 'contains'
3.818  1521 |     DRAKE_THROW_UNLESS(coupler_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h: In member function 'const drake::multibody::internal::DistanceConstraintSpec& drake::multibody::MultibodyPlant<T>::get_distance_constraint_specs(drake::multibody::MultibodyConstraintId) const':
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1530:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::DistanceConstraintSpec>' has no member named 'contains'
3.818  1530 |     DRAKE_THROW_UNLESS(distance_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1530:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::DistanceConstraintSpec>' has no member named 'contains'
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1530:5: error: template argument 1 is invalid
3.818  1530 |     DRAKE_THROW_UNLESS(distance_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1530:5: error: template argument 1 is invalid
3.818  1530 |     DRAKE_THROW_UNLESS(distance_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1530:5: error: 'Trait' is not a class, namespace, or enumeration
3.818  1530 |     DRAKE_THROW_UNLESS(distance_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1530:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::DistanceConstraintSpec>' has no member named 'contains'
3.818  1530 |     DRAKE_THROW_UNLESS(distance_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1530:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::DistanceConstraintSpec>' has no member named 'contains'
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1530:5: error: 'Trait' is not a class, namespace, or enumeration
3.818  1530 |     DRAKE_THROW_UNLESS(distance_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1530:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::DistanceConstraintSpec>' has no member named 'contains'
3.818  1530 |     DRAKE_THROW_UNLESS(distance_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h: In member function 'const drake::multibody::internal::BallConstraintSpec& drake::multibody::MultibodyPlant<T>::get_ball_constraint_specs(drake::multibody::MultibodyConstraintId) const':
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1539:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::BallConstraintSpec>' has no member named 'contains'
3.818  1539 |     DRAKE_THROW_UNLESS(ball_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1539:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::BallConstraintSpec>' has no member named 'contains'
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1539:5: error: template argument 1 is invalid
3.818  1539 |     DRAKE_THROW_UNLESS(ball_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1539:5: error: template argument 1 is invalid
3.818  1539 |     DRAKE_THROW_UNLESS(ball_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1539:5: error: 'Trait' is not a class, namespace, or enumeration
3.818  1539 |     DRAKE_THROW_UNLESS(ball_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1539:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::BallConstraintSpec>' has no member named 'contains'
3.818  1539 |     DRAKE_THROW_UNLESS(ball_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1539:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::BallConstraintSpec>' has no member named 'contains'
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1539:5: error: 'Trait' is not a class, namespace, or enumeration
3.818  1539 |     DRAKE_THROW_UNLESS(ball_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1539:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::BallConstraintSpec>' has no member named 'contains'
3.818  1539 |     DRAKE_THROW_UNLESS(ball_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h: In member function 'const drake::multibody::internal::WeldConstraintSpec& drake::multibody::MultibodyPlant<T>::get_weld_constraint_specs(drake::multibody::MultibodyConstraintId) const':
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1548:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::WeldConstraintSpec>' has no member named 'contains'
3.818  1548 |     DRAKE_THROW_UNLESS(weld_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1548:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::WeldConstraintSpec>' has no member named 'contains'
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1548:5: error: template argument 1 is invalid
3.818  1548 |     DRAKE_THROW_UNLESS(weld_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1548:5: error: template argument 1 is invalid
3.818  1548 |     DRAKE_THROW_UNLESS(weld_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.818 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1548:5: error: 'Trait' is not a class, namespace, or enumeration
3.818  1548 |     DRAKE_THROW_UNLESS(weld_constraints_specs_.contains(id));
3.818       |     ^~~~~~~~~~~~~~~~~~
3.819 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1548:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::WeldConstraintSpec>' has no member named 'contains'
3.819  1548 |     DRAKE_THROW_UNLESS(weld_constraints_specs_.contains(id));
3.819       |     ^~~~~~~~~~~~~~~~~~
3.819 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1548:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::WeldConstraintSpec>' has no member named 'contains'
3.819 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1548:5: error: 'Trait' is not a class, namespace, or enumeration
3.819  1548 |     DRAKE_THROW_UNLESS(weld_constraints_specs_.contains(id));
3.819       |     ^~~~~~~~~~~~~~~~~~
3.819 /opt/drake/include/drake/multibody/plant/multibody_plant.h:1548:5: error: 'const class std::map<drake::Identifier<drake::multibody::ConstraintTag>, drake::multibody::internal::WeldConstraintSpec>' has no member named 'contains'
3.819  1548 |     DRAKE_THROW_UNLESS(weld_constraints_specs_.contains(id));
3.819       |     ^~~~~~~~~~~~~~~~~~
5.558 make[2]: *** [CMakeFiles/test.dir/build.make:76: CMakeFiles/test.dir/test.cpp.o] Error 1
5.559 make[1]: *** [CMakeFiles/Makefile2:83: CMakeFiles/test.dir/all] Error 2
5.559 make: *** [Makefile:91: all] Error 2

This can be minimally reproduced using three files attached here: debug.zip.

For convenience, I'll also paste the contents of the files here, since they are short. The Dockerfile should be in the same directory as a folder called test with the below CMakeLists.txt and program named test.cpp.

The Dockerfile:

# syntax=docker/dockerfile:1

# essential
FROM ubuntu:22.04
SHELL ["/bin/bash", "-c"]
ENV TZ=America/Los_Angeles
RUN ln -snf /usr/share/zoneinfo/$TZ /etc/localtime && echo $TZ > /etc/timezone
RUN apt-get update -y
RUN apt-get install -y ca-certificates gnupg lsb-release wget cmake

# install drake
RUN wget -qO- https://drake-apt.csail.mit.edu/drake.asc | gpg --dearmor - \
    | tee /etc/apt/trusted.gpg.d/drake.gpg >/dev/null
RUN echo "deb [arch=amd64] https://drake-apt.csail.mit.edu/$(lsb_release -cs) $(lsb_release -cs) main" \
    | tee /etc/apt/sources.list.d/drake.list >/dev/null
RUN apt-get update
RUN apt-get install --no-install-recommends -y drake-dev

# adding drake to python path
ENV PATH="/opt/drake/bin${PATH:+:${PATH}}"
ENV PYTHONPATH="/opt/drake/lib/python$(python3 -c 'import sys; \
    print("{0}.{1}".format(*sys.version_info))')/site-packages${PYTHONPATH:+:${PYTHONPATH}}"

# ensuring that libdrake.so can be found
ENV LD_LIBRARY_PATH="$LD_LIBRARY_PATH:/opt/drake/lib"

# adding and building
ADD test /home/test
WORKDIR /home/test/build
RUN cmake -DCMAKE_PREFIX_PATH=/opt/drake .. && \
    make -j$(nproc)

The CMakeLists.txt:

cmake_minimum_required(VERSION 3.10.2)
project(test_proj)
find_package(drake REQUIRED)
add_executable(test test.cpp)
target_link_libraries(test drake::drake)

The file test.cpp:

#include <drake/multibody/plant/multibody_plant.h>

int main(int argc, char** argv) {
    return 0;
}

Version

1.27.0

What operating system are you using?

Ubuntu 22.04

What installation option are you using?

apt install drake

Relevant log output

No response

jwnimmer-tri commented 5 months ago

See https://drake.mit.edu/release_notes/v1.27.0.html:

As a result, we have some new lower bounds on supported tool versions: C++ standard >= 20

You need to tell CMake to use C++20, like this.

jwnimmer-tri commented 5 months ago

We found some places that still said C++17, so possibly as of #21247 this would be automatically fixed.