39 #include <moveit_resources/config.h> 41 #include <urdf_parser/urdf_parser.h> 43 #include <ompl/util/Exception.h> 45 #include <gtest/gtest.h> 47 #include <boost/filesystem/path.hpp> 54 boost::filesystem::path res_path(MOVEIT_TEST_RESOURCES_DIR);
58 std::fstream xml_file((res_path /
"pr2_description/urdf/robot.xml").
string().c_str(), std::fstream::in);
59 if (xml_file.is_open())
61 while (xml_file.good())
64 std::getline(xml_file, line);
65 xml_string += (line +
"\n");
79 robot_model::RobotModelPtr robot_model_;
92 std::ofstream fout(
"ompl_interface_test_state_space_diagram1.dot");
100 catch (ompl::Exception& ex)
102 ROS_ERROR(
"Sanity checks did not pass: %s", ex.what());
125 std::ofstream fout(
"ompl_interface_test_state_space_diagram2.dot");
126 ompl::base::StateSpace::Diagram(fout);
135 std::ofstream fout(
"ompl_interface_test_state_space_diagram1.dot");
143 catch (ompl::Exception& ex)
145 ROS_ERROR(
"Sanity checks did not pass: %s", ex.what());
149 robot_state::RobotState kstate(robot_model_);
150 kstate.setToRandomPositions();
151 EXPECT_TRUE(kstate.distance(kstate) < 1e-12);
153 for (
int i = 0; i < 10; ++i)
155 robot_state::RobotState kstate2(kstate);
156 EXPECT_TRUE(kstate.distance(kstate2) < 1e-12);
159 std::cout << (kstate.getGlobalLinkTransform(
"r_wrist_roll_link").translation() -
160 kstate2.getGlobalLinkTransform(
"r_wrist_roll_link").translation())
162 EXPECT_TRUE(kstate.distance(kstate2) > 1e-12);
164 std::cout << (kstate.getGlobalLinkTransform(
"r_wrist_roll_link").translation() -
165 kstate2.getGlobalLinkTransform(
"r_wrist_roll_link").translation())
167 EXPECT_TRUE(kstate.distance(kstate2) < 1e-12);
173 int main(
int argc,
char** argv)
175 testing::InitGoogleTest(&argc, argv);
176 return RUN_ALL_TESTS();
urdf::ModelInterfaceSharedPtr urdf_model_
virtual void copyToRobotState(robot_state::RobotState &rstate, const ompl::base::State *state) const
Copy the data from an OMPL state to a set of joint states.
virtual void copyToOMPLState(ompl::base::State *state, const robot_state::RobotState &rstate) const
Copy the data from a set of joint states to an OMPL state.
virtual void setPlanningVolume(double minX, double maxX, double minY, double maxY, double minZ, double maxZ)
Set the planning volume for the possible SE2 and/or SE3 components of the state space.
virtual ompl::base::State * allocState() const
def xml_string(rootXml, addHeader=True)
virtual void freeState(ompl::base::State *state) const
srdf::ModelSharedPtr srdf_model_
#define EXPECT_TRUE(args)
TEST_F(LoadPlanningModelsPr2, StateSpace)
int main(int argc, char **argv)
const std::string & getJointModelGroupName() const