forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
/
contact_results.h
55 lines (41 loc) · 1.59 KB
/
contact_results.h
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
#pragma once
#include <vector>
#include "drake/common/drake_copyable.h"
#include "drake/multibody/collision/element.h"
#include "drake/multibody/rigid_body_plant/contact_info.h"
namespace drake {
namespace systems {
// Forward declaration
template <typename T>
class RigidBodyPlant;
/**
A class containg the contact results (contact points and response spatial
forces for each colliding pair of collision elements).
@tparam T The scalar type. It must be a valid Eigen scalar.
Instantiated templates for the following ScalarTypes are provided:
- double
*/
template <typename T>
class ContactResults {
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(ContactResults)
ContactResults();
/** Returns the number of unique collision element pairs in contact. */
int get_num_contacts() const;
/** Retrieves the ith ContactInfo instance. No bounds checking will be done
in a release build (but will be done in debug). It is assumed the caller
will only use values in the range [0, get_num_contacts() -1], inclusive.
*/
const ContactInfo<T>& get_contact_info(int i) const;
// Clears the set of contact information for when the old data becomes
// invalid.
void Clear();
// Reports a contact between two elements and prepares a ContactInfo. The
// caller should populate the ContactInfo with the appropriate details.
ContactInfo<T>& AddContact(drake::multibody::collision::ElementId element_a,
drake::multibody::collision::ElementId element_b);
private:
std::vector<ContactInfo<T>> contacts_;
};
} // namespace systems
} // namespace drake