41#include <gtest/gtest.h>
55 for (
unsigned int i = 0; i < trials; ++i)
89 collision_detection::CollisionEnvPtr
cenv_;
91 collision_detection::AllowedCollisionMatrixPtr
acm_;
101 const std::string plugin_name = GetParam();
102 SCOPED_TRACE(plugin_name);
104 std::vector<moveit::core::RobotState> states;
105 std::vector<std::thread> threads;
106 std::vector<bool> collisions;
109 if (!loader.
activate(plugin_name, planning_scene_))
111#if defined(GTEST_SKIP_)
112 GTEST_SKIP_(
"Failed to load collision plugin");
118 for (
unsigned int i = 0; i <
THREADS; ++i)
122 state.setToRandomPositions();
125 states.push_back(std::move(state));
128 for (
unsigned int i = 0; i <
THREADS; ++i)
130 threads.emplace_back(std::thread([i, &scene = *planning_scene_, &state = states[i], expected = collisions[i]] {
135 for (
unsigned int i = 0; i < states.size(); ++i)
141 planning_scene_.reset();
144#ifndef INSTANTIATE_TEST_SUITE_P
145#define INSTANTIATE_TEST_SUITE_P(...) INSTANTIATE_TEST_CASE_P(__VA_ARGS__)
153 ::testing::InitGoogleTest(&argc, argv);
154 return RUN_ALL_TESTS();
collision_detection::CollisionEnvPtr cenv_
moveit::core::RobotModelPtr robot_model_
planning_scene::PlanningScenePtr planning_scene_
moveit::core::RobotStatePtr robot_state_
collision_detection::AllowedCollisionMatrixPtr acm_
bool activate(const std::string &name, const planning_scene::PlanningScenePtr &scene)
Activate a specific collision plugin for the given planning scene instance.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
This class maintains the representation of the environment as seen by a planning instance....
void checkCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res)
Check whether the current state is in collision, and if needed, updates the collision transforms of t...
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &package_name, const std::string &urdf_relative_path, const std::string &srdf_relative_path)
Loads a robot model given a URDF and SRDF file in a package.
Representation of a collision checking request.
Representation of a collision checking result.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void clear()
Clear a previously stored result.
bool collision
True if collision was found, false otherwise.
int main(int argc, char **argv)
#define INSTANTIATE_TEST_SUITE_P(...)
bool runCollisionDetection(unsigned int, unsigned int trials, const planning_scene::PlanningScene &scene, const moveit::core::RobotState &state)
void runCollisionDetectionAssert(unsigned int id, unsigned int trials, const planning_scene::PlanningScene &scene, const moveit::core::RobotState &state, bool expected_result)
TEST_P(CollisionDetectorTests, Threaded)
Tests the collision detector in multiple threads.