-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
unimplemented_collision_checker.h
70 lines (53 loc) · 2.43 KB
/
unimplemented_collision_checker.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
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
#pragma once
#include <memory>
#include <optional>
#include <string>
#include <vector>
#include "drake/planning/collision_checker.h"
#include "drake/planning/collision_checker_params.h"
namespace drake {
namespace planning {
/** A concrete collision checker implementation that throws an exception for
every virtual function hook. This might be useful for unit testing or for
deriving your own collision checker without providing for the full suite of
operations. */
class UnimplementedCollisionChecker : public CollisionChecker {
public:
/** Constructs a checker.
@param supports_parallel_checking will serve as the return value of the
CollisionChecker::SupportsParallelChecking() function. */
UnimplementedCollisionChecker(CollisionCheckerParams params,
bool supports_parallel_checking);
/** @name Does not allow copy, move, or assignment. */
/** @{ */
// N.B. The copy constructor is protected for use in implementing Clone().
UnimplementedCollisionChecker(UnimplementedCollisionChecker&&) = delete;
UnimplementedCollisionChecker& operator=(
const UnimplementedCollisionChecker&) = delete;
UnimplementedCollisionChecker& operator=(UnimplementedCollisionChecker&&) =
delete;
/** @} */
~UnimplementedCollisionChecker();
protected:
// To support Clone(), allow copying (but not move nor assign).
UnimplementedCollisionChecker(const UnimplementedCollisionChecker&);
std::unique_ptr<CollisionChecker> DoClone() const override;
void DoUpdateContextPositions(
CollisionCheckerContext* model_context) const override;
bool DoCheckContextConfigCollisionFree(
const CollisionCheckerContext&) const override;
std::optional<geometry::GeometryId> DoAddCollisionShapeToBody(
const std::string& group_name, const multibody::Body<double>& bodyA,
const geometry::Shape& shape,
const math::RigidTransform<double>& X_AG) override;
void RemoveAddedGeometries(
const std::vector<CollisionChecker::AddedShape>& shapes) override;
void UpdateCollisionFilters() override;
RobotClearance DoCalcContextRobotClearance(const CollisionCheckerContext&,
double) const override;
std::vector<RobotCollisionType> DoClassifyContextBodyCollisions(
const CollisionCheckerContext&) const override;
int DoMaxContextNumDistances(const CollisionCheckerContext&) const override;
};
} // namespace planning
} // namespace drake