Go to the documentation of this file.
42 #include <urdf_parser/urdf_parser.h>
44 #include <ompl/util/Exception.h>
47 #include <gtest/gtest.h>
49 #include <boost/filesystem/path.hpp>
52 constexpr
double EPSILON = std::numeric_limits<double>::epsilon();
76 std::ofstream fout(
"ompl_interface_test_state_space_diagram1.dot");
84 catch (ompl::Exception& ex)
86 ROS_ERROR(
"Sanity checks did not pass: %s", ex.what());
109 std::ofstream fout(
"ompl_interface_test_state_space_diagram2.dot");
110 ompl::base::StateSpace::Diagram(fout);
118 joint_model_state_space.setup();
119 std::ofstream fout(
"ompl_interface_test_state_space_diagram1.dot");
120 joint_model_state_space.diagram(fout);
124 joint_model_state_space.sanityChecks();
127 catch (ompl::Exception& ex)
129 ROS_ERROR(
"Sanity checks did not pass: %s", ex.what());
136 ompl::base::State* state = joint_model_state_space.
allocState();
137 for (
int i = 0; i < 10; ++i)
156 for (
int i = 0; i < 10; ++i)
166 for (std::size_t joint_index = 0; joint_index < joint_model_group->
getVariableCount(); ++joint_index)
169 EXPECT_NE(joint_model,
nullptr);
184 joint_model_state_space.
freeState(state);
188 TEST(TestDiffDrive, TestStateSpace)
191 builder.
addVirtualJoint(
"odom_combined",
"base_link",
"planar",
"base_joint");
193 builder.
addGroup({}, {
"base_joint" },
"base");
194 ASSERT_TRUE(builder.
isValid());
196 auto robot_model = builder.
build();
204 int main(
int argc,
char** argv)
206 testing::InitGoogleTest(&argc, argv);
207 return RUN_ALL_TESTS();
const JointModel * getJointModel(const std::string &joint) const
double distance(const RobotState &other) const
void freeState(ompl::base::State *state) const override
void addJointProperty(const std::string &joint_name, const std::string &property_name, const std::string &value)
const std::vector< std::string > & getActiveJointModelNames() const
TEST(TestDiffDrive, TestStateSpace)
const std::string & getJointModelGroupName() const
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
void setToRandomPositions()
virtual void copyToOMPLState(ompl::base::State *state, const moveit::core::RobotState &rstate) const
Copy the data from a set of joint states to an OMPL state.
#define EXPECT_TRUE(args)
int main(int argc, char **argv)
TEST_F(LoadPlanningModelsPr2, StateSpace)
const RobotModelConstPtr & getRobotModel() const
moveit::core::RobotModelPtr build()
RobotModelBuilder & addVirtualJoint(const std::string &parent_frame, const std::string &child_link, const std::string &type, const std::string &name="")
moveit::core::RobotModelConstPtr robot_model_
virtual void copyToRobotState(moveit::core::RobotState &rstate, const ompl::base::State *state) const
Copy the data from an OMPL state to a set of joint states.
virtual void copyJointToOMPLState(ompl::base::State *state, const moveit::core::RobotState &robot_state, const moveit::core::JointModel *joint_model, int ompl_state_joint_index) const
Copy a single joint's values (which might have multiple variables) from a MoveIt robot_state to an OM...
RobotModelBuilder & addGroup(const std::vector< std::string > &links, const std::vector< std::string > &joints, const std::string &name)
unsigned int getVariableCount() const
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.
ompl::base::State * allocState() const override
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
ompl
Author(s): Ioan Sucan
autogenerated on Tue Dec 24 2024 03:28:10