37 #include <gtest/gtest.h> 39 #include <urdf_parser/urdf_parser.h> 42 #include <boost/filesystem/path.hpp> 43 #include <moveit_resources/config.h> 49 boost::filesystem::path res_path(MOVEIT_TEST_RESOURCES_DIR);
51 std::fstream xml_file((res_path / filename).
string().c_str(), std::fstream::in);
53 while (xml_file.good())
56 std::getline(xml_file, line);
57 xml_string += (line +
"\n");
60 file_content = xml_string;
67 robot_model_out = urdf::parseURDF(xml_string);
74 srdf_model_out->initString(*robot_model_out, xml_string);
77 TEST(PlanningScene, LoadRestore)
79 urdf::ModelInterfaceSharedPtr urdf_model;
83 moveit_msgs::PlanningScene ps_msg;
92 TEST(PlanningScene, LoadRestoreDiff)
94 urdf::ModelInterfaceSharedPtr urdf_model;
101 Eigen::Affine3d
id = Eigen::Affine3d::Identity();
104 moveit_msgs::PlanningScene ps_msg;
105 ps_msg.robot_state.is_diff =
true;
107 ps->getPlanningSceneMsg(ps_msg);
108 ps->setPlanningSceneMsg(ps_msg);
112 planning_scene::PlanningScenePtr next = ps->diff();
113 EXPECT_TRUE(next->getWorld()->hasObject(
"sphere"));
117 next->getPlanningSceneDiffMsg(ps_msg);
118 EXPECT_EQ(ps_msg.world.collision_objects.size(), 1);
119 next->decoupleParent();
120 moveit_msgs::PlanningScene ps_msg2;
121 next->getPlanningSceneDiffMsg(ps_msg2);
122 EXPECT_EQ(ps_msg2.world.collision_objects.size(), 0);
123 next->getPlanningSceneMsg(ps_msg);
124 EXPECT_EQ(ps_msg.world.collision_objects.size(), 2);
125 ps->setPlanningSceneMsg(ps_msg);
129 TEST(PlanningScene, MakeAttachedDiff)
132 urdf::ModelInterfaceSharedPtr urdf_model;
138 Eigen::Affine3d
id = Eigen::Affine3d::Identity();
141 planning_scene::PlanningScenePtr attached_object_diff_scene = ps->diff();
143 moveit_msgs::AttachedCollisionObject att_obj;
144 att_obj.link_name =
"r_wrist_roll_link";
145 att_obj.object.operation = moveit_msgs::CollisionObject::ADD;
146 att_obj.object.id =
"sphere";
151 attached_object_diff_scene->processAttachedCollisionObjectMsg(att_obj);
152 attached_object_diff_scene->checkCollision(req, res);
153 ps->checkCollision(req, res);
156 TEST(PlanningScene, isStateValid)
159 urdf::ModelInterfaceSharedPtr urdf_model;
164 if (ps->isStateColliding(current_state,
"left_arm"))
166 EXPECT_FALSE(ps->isStateValid(current_state,
"left_arm"));
170 int main(
int argc,
char** argv)
172 testing::InitGoogleTest(&argc, argv);
173 return RUN_ALL_TESTS();
Representation of a collision checking request.
const std::string & getName() const
Get the name of the planning scene. This is empty by default.
static bool isEmpty(const moveit_msgs::PlanningScene &msg)
Check if a message includes any information about a planning scene, or it is just a default...
void loadRobotModel(urdf::ModelInterfaceSharedPtr &robot_model_out)
int main(int argc, char **argv)
Maintain a representation of the environment.
Representation of a collision checking result.
void addToObject(const std::string &id, const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Affine3d &poses)
Add shapes to an object in the map. This function makes repeated calls to addToObjectInternal() to ad...
TEST(PlanningScene, LoadRestore)
bool hasObject(const std::string &id) const
Check if a particular object exists in the collision world.
#define EXPECT_FALSE(args)
This class maintains the representation of the environment as seen by a planning instance. The environment geometry, the robot geometry and state are maintained.
const robot_model::RobotModelConstPtr & getRobotModel() const
Get the kinematic model for which the planning scene is maintained.
void loadModelFile(std::string filename, std::string &file_content)
def xml_string(rootXml, addHeader=True)
bool setPlanningSceneMsg(const moveit_msgs::PlanningScene &scene)
Set this instance of a planning scene to be the same as the one serialized in the scene message...
void loadRobotModels(urdf::ModelInterfaceSharedPtr &robot_model_out, srdf::ModelSharedPtr &srdf_model_out)
Representation of a robot's state. This includes position, velocity, acceleration and effort...
#define EXPECT_TRUE(args)
void getPlanningSceneMsg(moveit_msgs::PlanningScene &scene) const
Construct a message (scene) with all the necessary data so that the scene can be later reconstructed ...
std::shared_ptr< const Shape > ShapeConstPtr