moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <gtest/gtest.h>
#include <moveit/collision_detection/collision_common.h>
#include <moveit/robot_model/robot_model.h>
#include <moveit/robot_state/robot_state.h>
#include <moveit/utils/robot_model_test_utils.h>
#include <moveit/utils/logger.hpp>
#include <moveit/collision_detection_fcl/collision_common.h>
#include <moveit/collision_detection_fcl/collision_env_fcl.h>
#include <urdf_parser/urdf_parser.h>
#include <geometric_shapes/shape_operations.h>
Go to the source code of this file.
Classes | |
class | CollisionDetectionEnvTest |
Functions | |
void | setToHome (moveit::core::RobotState &panda_state) |
Brings the panda robot in user defined home position. | |
rclcpp::Logger | getLogger () |
TEST_F (CollisionDetectionEnvTest, InitOK) | |
Correct setup testing. | |
TEST_F (CollisionDetectionEnvTest, DefaultNotInCollision) | |
Tests the default values specified in the SRDF if they are collision free. | |
TEST_F (CollisionDetectionEnvTest, LinksInCollision) | |
A configuration where the robot should collide with itself. | |
TEST_F (CollisionDetectionEnvTest, RobotWorldCollision_1) | |
Adding obstacles to the world which are tested against the robot. Simple cases. | |
TEST_F (CollisionDetectionEnvTest, RobotWorldCollision_2) | |
Adding obstacles to the world which are tested against the robot. | |
TEST_F (CollisionDetectionEnvTest, PaddingTest) | |
Tests the padding through expanding the link geometry in such a way that a collision occurs. | |
TEST_F (CollisionDetectionEnvTest, DISABLED_ContinuousCollisionSelf) | |
Continuous self collision checks of the robot. | |
TEST_F (CollisionDetectionEnvTest, DISABLED_ContinuousCollisionWorld) | |
Two similar robot poses are used as start and end pose of a continuous collision check. | |
int | main (int argc, char **argv) |
rclcpp::Logger getLogger | ( | ) |
Definition at line 67 of file test_fcl_env.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 325 of file test_fcl_env.cpp.
|
inline |
Brings the panda robot in user defined home position.
Definition at line 53 of file test_fcl_env.cpp.
TEST_F | ( | CollisionDetectionEnvTest | , |
DefaultNotInCollision | |||
) |
Tests the default values specified in the SRDF if they are collision free.
Definition at line 126 of file test_fcl_env.cpp.
TEST_F | ( | CollisionDetectionEnvTest | , |
DISABLED_ContinuousCollisionSelf | |||
) |
Continuous self collision checks of the robot.
Functionality not supported yet.
Definition at line 233 of file test_fcl_env.cpp.
TEST_F | ( | CollisionDetectionEnvTest | , |
DISABLED_ContinuousCollisionWorld | |||
) |
Two similar robot poses are used as start and end pose of a continuous collision check.
Functionality not supported yet.
Definition at line 277 of file test_fcl_env.cpp.
TEST_F | ( | CollisionDetectionEnvTest | , |
InitOK | |||
) |
Correct setup testing.
Definition at line 120 of file test_fcl_env.cpp.
TEST_F | ( | CollisionDetectionEnvTest | , |
LinksInCollision | |||
) |
A configuration where the robot should collide with itself.
Definition at line 135 of file test_fcl_env.cpp.
TEST_F | ( | CollisionDetectionEnvTest | , |
PaddingTest | |||
) |
Tests the padding through expanding the link geometry in such a way that a collision occurs.
Definition at line 199 of file test_fcl_env.cpp.
TEST_F | ( | CollisionDetectionEnvTest | , |
RobotWorldCollision_1 | |||
) |
Adding obstacles to the world which are tested against the robot. Simple cases.
Definition at line 148 of file test_fcl_env.cpp.
TEST_F | ( | CollisionDetectionEnvTest | , |
RobotWorldCollision_2 | |||
) |
Adding obstacles to the world which are tested against the robot.
Definition at line 178 of file test_fcl_env.cpp.