moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Classes | Macros | Functions
test_planning_scene.cpp File Reference
#include <gtest/gtest.h>
#include <moveit/collision_detection_fcl/collision_detector_allocator_fcl.h>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit/utils/message_checks.h>
#include <moveit/utils/robot_model_test_utils.h>
#include <urdf_parser/urdf_parser.h>
#include <fstream>
#include <sstream>
#include <string>
#include <tf2_eigen/tf2_eigen.hpp>
#include <octomap_msgs/conversions.h>
#include <octomap/octomap.h>
#include <moveit/collision_detection/collision_common.h>
#include <moveit/collision_detection/collision_plugin_cache.h>
Include dependency graph for test_planning_scene.cpp:

Go to the source code of this file.

Classes

class  CollisionDetectorTests
 

Macros

#define INSTANTIATE_TEST_SUITE_P(...)   INSTANTIATE_TEST_CASE_P(__VA_ARGS__)
 

Functions

 TEST (PlanningScene, TestOneShapeObjectPose)
 
 TEST (PlanningScene, LoadRestore)
 
 TEST (PlanningScene, LoadOctomap)
 
 TEST (PlanningScene, LoadRestoreDiff)
 
 TEST (PlanningScene, MakeAttachedDiff)
 
 TEST (PlanningScene, isStateValid)
 
 TEST (PlanningScene, loadGoodSceneGeometryNewFormat)
 
 TEST (PlanningScene, loadGoodSceneGeometryOldFormat)
 
 TEST (PlanningScene, loadBadSceneGeometry)
 
 TEST (PlanningScene, switchCollisionDetectorType)
 
 TEST (PlanningScene, FailRetrievingNonExistentObject)
 
 TEST_P (CollisionDetectorTests, ClearDiff)
 
moveit_msgs::msg::PlanningScene createPlanningSceneDiff (const planning_scene::PlanningScene &ps, const std::string &object_name, const int8_t operation, const bool attach_object=false, const bool create_object=true)
 
std::set< std::string > getCollisionObjectsNames (const planning_scene::PlanningScene &ps)
 
std::set< std::string > getAttachedCollisionObjectsNames (const planning_scene::PlanningScene &ps)
 
 TEST (PlanningScene, RobotStateDiffBug)
 
 INSTANTIATE_TEST_SUITE_P (PluginTests, CollisionDetectorTests, testing::Values("FCL", "Bullet"))
 
int main (int argc, char **argv)
 

Macro Definition Documentation

◆ INSTANTIATE_TEST_SUITE_P

#define INSTANTIATE_TEST_SUITE_P (   ...)    INSTANTIATE_TEST_CASE_P(__VA_ARGS__)

Definition at line 594 of file test_planning_scene.cpp.

Function Documentation

◆ createPlanningSceneDiff()

moveit_msgs::msg::PlanningScene createPlanningSceneDiff ( const planning_scene::PlanningScene ps,
const std::string &  object_name,
const int8_t  operation,
const bool  attach_object = false,
const bool  create_object = true 
)

Definition at line 450 of file test_planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getAttachedCollisionObjectsNames()

std::set< std::string > getAttachedCollisionObjectsNames ( const planning_scene::PlanningScene ps)

Definition at line 507 of file test_planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getCollisionObjectsNames()

std::set< std::string > getCollisionObjectsNames ( const planning_scene::PlanningScene ps)

Definition at line 496 of file test_planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ INSTANTIATE_TEST_SUITE_P()

INSTANTIATE_TEST_SUITE_P ( PluginTests  ,
CollisionDetectorTests  ,
testing::Values("FCL", "Bullet")   
)

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 600 of file test_planning_scene.cpp.

◆ TEST() [1/12]

TEST ( PlanningScene  ,
FailRetrievingNonExistentObject   
)

Definition at line 353 of file test_planning_scene.cpp.

Here is the call graph for this function:

◆ TEST() [2/12]

TEST ( PlanningScene  ,
isStateValid   
)

Definition at line 238 of file test_planning_scene.cpp.

Here is the call graph for this function:

◆ TEST() [3/12]

TEST ( PlanningScene  ,
loadBadSceneGeometry   
)

Definition at line 310 of file test_planning_scene.cpp.

Here is the call graph for this function:

◆ TEST() [4/12]

TEST ( PlanningScene  ,
loadGoodSceneGeometryNewFormat   
)

Definition at line 249 of file test_planning_scene.cpp.

Here is the call graph for this function:

◆ TEST() [5/12]

TEST ( PlanningScene  ,
loadGoodSceneGeometryOldFormat   
)

Definition at line 284 of file test_planning_scene.cpp.

Here is the call graph for this function:

◆ TEST() [6/12]

TEST ( PlanningScene  ,
LoadOctomap   
)

Definition at line 94 of file test_planning_scene.cpp.

Here is the call graph for this function:

◆ TEST() [7/12]

TEST ( PlanningScene  ,
LoadRestore   
)

Definition at line 80 of file test_planning_scene.cpp.

Here is the call graph for this function:

◆ TEST() [8/12]

TEST ( PlanningScene  ,
LoadRestoreDiff   
)

Definition at line 147 of file test_planning_scene.cpp.

Here is the call graph for this function:

◆ TEST() [9/12]

TEST ( PlanningScene  ,
MakeAttachedDiff   
)

Definition at line 207 of file test_planning_scene.cpp.

Here is the call graph for this function:

◆ TEST() [10/12]

TEST ( PlanningScene  ,
RobotStateDiffBug   
)

Definition at line 517 of file test_planning_scene.cpp.

Here is the call graph for this function:

◆ TEST() [11/12]

TEST ( PlanningScene  ,
switchCollisionDetectorType   
)

Definition at line 336 of file test_planning_scene.cpp.

Here is the call graph for this function:

◆ TEST() [12/12]

TEST ( PlanningScene  ,
TestOneShapeObjectPose   
)

Definition at line 54 of file test_planning_scene.cpp.

Here is the call graph for this function:

◆ TEST_P()

TEST_P ( CollisionDetectorTests  ,
ClearDiff   
)

Definition at line 364 of file test_planning_scene.cpp.

Here is the call graph for this function: