Go to the source code of this file.
◆ TRIGGERS_UPDATE
#define TRIGGERS_UPDATE |
( |
|
msg, |
|
|
|
expected_update_type |
|
) |
| |
Value: { \
planning_scene_monitor_->clearUpdateCallbacks(); \
auto received_update_type{ UpdateType::UPDATE_NONE }; \
planning_scene_monitor_->addUpdateCallback([&](
auto type) { received_update_type =
type; }); \
planning_scene_monitor_->newPlanningSceneMessage(msg); \
EXPECT_EQ(received_update_type, expected_update_type); \
}
Definition at line 103 of file planning_scene_monitor_test.cpp.
◆ UpdateType
◆ main()
int main |
( |
int |
argc, |
|
|
char ** |
argv |
|
) |
| |
◆ TEST_F() [1/2]
◆ TEST_F() [2/2]