38 #include <urdf_parser/urdf_parser.h>
40 #include <gtest/gtest.h>
62 ASSERT_EQ(robot_model_->getURDF()->getName(),
"pr2");
63 ASSERT_EQ(robot_model_->getSRDF()->getName(),
"pr2");
70 const std::vector<const moveit::core::JointModel*>& joints = robot_model_->getJointModels();
71 for (std::size_t i = 0; i < joints.size(); ++i)
73 ASSERT_EQ(joints[i]->getJointIndex(), i);
74 ASSERT_EQ(robot_model_->getJointModel(joints[i]->getName()), joints[i]);
76 const std::vector<const moveit::core::LinkModel*>& links = robot_model_->getLinkModels();
77 for (std::size_t i = 0; i < links.size(); ++i)
79 ASSERT_EQ(links[i]->getLinkIndex(), i);
83 const std::string joint_name =
"fl_caster_rotation_joint";
84 const auto& joint = robot_model_->getJointModel(joint_name);
85 const auto& bounds = joint->getVariableBounds(joint->getName());
87 EXPECT_TRUE(bounds.velocity_bounded_);
88 EXPECT_EQ(bounds.max_velocity_, 10.0);
90 EXPECT_FALSE(bounds.position_bounded_);
91 EXPECT_FALSE(bounds.acceleration_bounded_);
92 EXPECT_FALSE(bounds.jerk_bounded_);
95 TEST(SiblingAssociateLinks, SimpleYRobot)
101 builder.
addChain(
"base_link->a",
"continuous");
102 builder.
addChain(
"a->b->c",
"fixed");
104 builder.
addChain(
"d->e",
"continuous");
106 builder.
addGroup({}, {
"base_joint" },
"base_joint");
107 ASSERT_TRUE(builder.
isValid());
108 moveit::core::RobotModelConstPtr robot_model = builder.
build();
110 const std::string
a =
"a", b =
"b",
c =
"c",
d =
"d";
111 auto connected = {
a, b,
c,
d };
114 for (
const std::string& root : connected)
116 SCOPED_TRACE(
"root: " + root);
117 std::set<std::string> expected_set(connected);
118 expected_set.erase(root);
119 std::set<std::string> actual_set;
120 for (
const auto& item : robot_model->getLinkModel(root)->getAssociatedFixedTransforms())
121 actual_set.insert(item.first->getName());
123 std::ostringstream expected, actual;
124 std::copy(expected_set.begin(), expected_set.end(), std::ostream_iterator<std::string>(expected,
" "));
125 std::copy(actual_set.begin(), actual_set.end(), std::ostream_iterator<std::string>(actual,
" "));
127 EXPECT_EQ(expected.str(), actual.str());
131 TEST(FloatingJointTest, interpolation_test)
141 bounds[0].max_position_ = 1.0;
142 bounds[1].min_position_ = -1.0;
143 bounds[1].max_position_ = 1.0;
144 bounds[2].min_position_ = -1.0;
145 bounds[2].max_position_ = 1.0;
150 random_numbers::RandomNumberGenerator rng;
152 for (
size_t i = 0; i < 1000; ++i)
159 double t = rng.uniformReal(0.0, 1.0);
165 double d1 = fjm.
distance(jv1, intp);
166 double d2 = fjm.
distance(jv2, intp);
167 double t_total = fjm.
distance(jv1, jv2);
170 EXPECT_NEAR(d1, t_total * t, 1e-6);
171 EXPECT_NEAR(d2, t_total * (1.0 - t), 1e-6);
175 int main(
int argc,
char** argv)
177 testing::InitGoogleTest(&argc, argv);
178 return RUN_ALL_TESTS();
moveit::core::RobotModelPtr robot_model_
moveit::core::RobotModelConstPtr robot_model_
void interpolate(const double *from, const double *to, const double t, double *state) const override
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state....
double distance(const double *values1, const double *values2) const override
Compute the distance between two joint states of the same model (represented by the variable values)
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds) const override
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to ...
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a variable. Throw an exception if the variable was not found.
Easily build different robot models for testing. Essentially a programmer-friendly light wrapper arou...
void addChain(const std::string §ion, const std::string &type, const std::vector< geometry_msgs::msg::Pose > &joint_origins={}, urdf::Vector3 joint_axis=urdf::Vector3(1.0, 0.0, 0.0))
Adds a chain of links and joints to the builder. The joint names are generated automatically as "<par...
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.
std::map< const LinkModel *, Eigen::Isometry3d, std::less< const LinkModel * >, Eigen::aligned_allocator< std::pair< const LinkModel *const, Eigen::Isometry3d > > > LinkTransformMap
Map from link model instances to Eigen transforms.
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
int main(int argc, char **argv)
TEST_F(LoadPlanningModelsPr2, InitOK)
TEST(SiblingAssociateLinks, SimpleYRobot)