38 #include <rclcpp/logger.hpp>
39 #include <rclcpp/logging.hpp>
45 const std::pair<std::string, std::string>& key,
bool found)
56 RCLCPP_DEBUG_STREAM(
getLogger(),
"Contact btw " << key.first <<
" and " << key.second <<
" dist: " << contact.
depth);
60 if (contact.
depth <= 0)
65 std::vector<collision_detection::Contact> data;
79 data.emplace_back(contact);
96 return &(cdata.
res.
contacts.insert(std::make_pair(key, data)).first->second.back());
100 std::vector<collision_detection::Contact>& dr = cdata.
res.
contacts[key];
101 dr.emplace_back(contact);
129 btConvexHullComputer conv;
130 btAlignedObjectArray<btVector3> points;
131 points.reserve(
static_cast<int>(
input.size()));
134 points.push_back(btVector3(
static_cast<btScalar
>(v[0]),
static_cast<btScalar
>(v[1]),
static_cast<btScalar
>(v[2])));
137 btScalar val = conv.compute(&points[0].getX(),
sizeof(btVector3), points.size(),
static_cast<btScalar
>(shrink),
138 static_cast<btScalar
>(shrinkClamp));
141 RCLCPP_ERROR(
getLogger(),
"Failed to create convex hull");
145 int num_verts = conv.vertices.size();
146 vertices.reserve(
static_cast<size_t>(num_verts));
147 for (
int i = 0; i < num_verts; ++i)
149 btVector3& v = conv.vertices[i];
153 int num_faces = conv.faces.size();
154 faces.reserve(
static_cast<size_t>(3 * num_faces));
155 for (
int i = 0; i < num_faces; ++i)
157 std::vector<int> face;
160 const btConvexHullComputer::Edge* source_edge = &(conv.edges[conv.faces[i]]);
161 int a = source_edge->getSourceVertex();
164 int b = source_edge->getTargetVertex();
167 const btConvexHullComputer::Edge* edge = source_edge->getNextEdgeOfFace();
168 int c = edge->getTargetVertex();
171 edge = edge->getNextEdgeOfFace();
172 c = edge->getTargetVertex();
177 edge = edge->getNextEdgeOfFace();
178 c = edge->getTargetVertex();
180 faces.push_back(
static_cast<int>(face.size()));
181 faces.insert(faces.end(), face.begin(), face.end());
rclcpp::Logger getLogger()
collision_detection::Contact * processResult(ContactTestData &cdata, collision_detection::Contact &contact, const std::pair< std::string, std::string > &key, bool found)
Stores a single contact result in the requested way.
std::vector< T, Eigen::aligned_allocator< T > > AlignedVector
int createConvexHull(AlignedVector< Eigen::Vector3d > &vertices, std::vector< int > &faces, const AlignedVector< Eigen::Vector3d > &input, double shrink=-1, double shrinkClamp=-1)
Create a convex hull from vertices using Bullet Convex Hull Computer.
Vec3fX< details::Vec3Data< double > > Vector3d
bool contacts
If true, compute contacts. Otherwise only a binary collision yes/no is reported.
std::size_t max_contacts
Overall maximum number of contacts to compute.
std::size_t max_contacts_per_pair
Maximum number of contacts to compute per pair of bodies (multiple bodies may be in contact at differ...
bool distance
If true, compute proximity distance.
double distance
Closest distance between two bodies.
bool collision
True if collision was found, false otherwise.
std::size_t contact_count
Number of contacts returned.