42 #include <urdf_parser/urdf_parser.h>
44 #include <ompl/util/Exception.h>
47 #include <gtest/gtest.h>
50 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit.ompl_planning.test.test_state_space");
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 RCLCPP_ERROR(LOGGER,
"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 RCLCPP_ERROR(LOGGER,
"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();
208 catch (ompl::Exception& ex)
210 RCLCPP_ERROR(LOGGER,
"Sanity checks did not pass: %s", ex.what());
215 int main(
int argc,
char** argv)
217 testing::InitGoogleTest(&argc, argv);
218 return RUN_ALL_TESTS();
moveit::core::RobotModelPtr robot_model_
const JointModel * getJointModel(const std::string &joint) const
Get a joint by its name. Throw an exception if the joint is not part of this group.
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
const std::vector< std::string > & getActiveJointModelNames() const
Get the names of the active joints in this group. These are the names of the joints returned by getJo...
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Easily build different robot models for testing. Essentially a programmer-friendly light wrapper arou...
void addJointProperty(const std::string &joint_name, const std::string &property_name, const std::string &value)
Adds a new joint property.
bool isValid()
Returns true if the building process so far has been valid.
void addGroup(const std::vector< std::string > &links, const std::vector< std::string > &joints, const std::string &name)
Adds a new group using a list of links and a list of joints.
moveit::core::RobotModelPtr build()
Builds and returns the robot model added to the builder.
void addVirtualJoint(const std::string &parent_frame, const std::string &child_link, const std::string &type, const std::string &name="")
Adds a virtual joint to the SRDF.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
double distance(const RobotState &other) const
Return the sum of joint distances to "other" state. An L1 norm. Only considers active joints.
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
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...
const std::string & getJointModelGroupName() const
ompl::base::State * allocState() const override
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 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.
void freeState(ompl::base::State *state) const override
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.
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
int main(int argc, char **argv)
TEST_F(LoadPlanningModelsPr2, StateSpace)
TEST(TestDiffDrive, TestStateSpace)