moveit2
The MoveIt Motion Planning Framework for ROS 2.
robot_state_test.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
39 #include <urdf_parser/urdf_parser.h>
40 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
41 #include <gtest/gtest.h>
42 #include <sstream>
43 #include <algorithm>
44 #include <ctype.h>
45 
46 namespace
47 {
48 constexpr double EPSILON{ 1.e-9 };
49 }
50 
51 #if 0 // unused function
52 static bool sameStringIgnoringWS(const std::string& s1, const std::string& s2)
53 {
54  unsigned int i1 = 0;
55  unsigned int i2 = 0;
56  while (i1 < s1.size() && isspace(s1[i1]))
57  i1++;
58  while (i2 < s2.size() && isspace(s2[i2]))
59  i2++;
60  while (i1 < s1.size() && i2 < s2.size())
61  {
62  if (i1 < s1.size() && i2 < s2.size())
63  {
64  if (s1[i1] != s2[i2])
65  return false;
66  i1++;
67  i2++;
68  }
69  while (i1 < s1.size() && isspace(s1[i1]))
70  i1++;
71  while (i2 < s2.size() && isspace(s2[i2]))
72  i2++;
73  }
74  return i1 == s1.size() && i2 == s2.size();
75 }
76 #endif
77 
78 static void expect_near(const Eigen::MatrixXd& x, const Eigen::MatrixXd& y,
79  double eps = std::numeric_limits<double>::epsilon())
80 {
81  ASSERT_EQ(x.rows(), y.rows());
82  ASSERT_EQ(x.cols(), y.cols());
83  for (int r = 0; r < x.rows(); ++r)
84  for (int c = 0; c < x.cols(); ++c)
85  EXPECT_NEAR(x(r, c), y(r, c), eps) << "(r,c) = (" << r << "," << c << ")";
86 }
87 
88 // clang-format off
89 #define EXPECT_NEAR_TRACED(...) { \
90  SCOPED_TRACE("expect_near(" #__VA_ARGS__ ")"); \
91  expect_near(__VA_ARGS__); \
92 }
93 // clang-format on
94 
95 TEST(Loading, SimpleRobot)
96 {
97  moveit::core::RobotModelBuilder builder("myrobot", "base_link");
98  builder.addVirtualJoint("odom_combined", "base_link", "floating", "base_joint");
99  ASSERT_TRUE(builder.isValid());
100  moveit::core::RobotModelPtr model = builder.build();
101  moveit::core::RobotState state(model);
102 
103  state.setToDefaultValues();
104 
105  // make sure that this copy constructor works
106  moveit::core::RobotState new_state(state);
107 
108  EXPECT_EQ(new_state.getVariablePosition("base_joint/rot_w"), 1.0);
109 
110  EXPECT_EQ(std::string("myrobot"), model->getName());
111  EXPECT_EQ((unsigned int)7, new_state.getVariableCount());
112 
113  const std::vector<moveit::core::LinkModel*>& links = model->getLinkModels();
114  EXPECT_EQ((unsigned int)1, links.size());
115 
116  const std::vector<moveit::core::JointModel*>& joints = model->getJointModels();
117  EXPECT_EQ((unsigned int)1, joints.size());
118 
119  const std::vector<std::string>& pgroups = model->getJointModelGroupNames();
120  EXPECT_EQ((unsigned int)0, pgroups.size());
121 }
122 
123 TEST(LoadingAndFK, SimpleRobot)
124 {
125  moveit::core::RobotModelBuilder builder("myrobot", "base_link");
126  geometry_msgs::msg::Pose pose;
127  pose.position.x = -0.1;
128  pose.position.y = 0;
129  pose.position.z = 0;
130 
131  tf2::Quaternion q;
132  q.setRPY(0, 0, -1);
133  pose.orientation = tf2::toMsg(q);
134  builder.addCollisionBox("base_link", { 1, 2, 1 }, pose);
135  pose.position.x = 0;
136  pose.position.y = 0;
137  pose.position.z = 0;
138  q.setRPY(0, 0, 0);
139  pose.orientation = tf2::toMsg(q);
140  builder.addVisualBox("base_link", { 1, 2, 1 }, pose);
141  pose.position.x = 0;
142  pose.position.y = 0.099;
143  pose.position.z = 0;
144  q.setRPY(0, 0, 0);
145  pose.orientation = tf2::toMsg(q);
146  builder.addInertial("base_link", 2.81, pose, 0.1, -0.2, 0.5, -0.09, 1, 0.101);
147  builder.addVirtualJoint("odom_combined", "base_link", "planar", "base_joint");
148  builder.addGroup({}, { "base_joint" }, "base");
149 
150  ASSERT_TRUE(builder.isValid());
151  moveit::core::RobotModelPtr model = builder.build();
152  moveit::core::RobotState state(model);
153 
154  EXPECT_EQ((unsigned int)3, state.getVariableCount());
155 
156  state.setToDefaultValues();
157 
158  EXPECT_EQ((unsigned int)1, (unsigned int)model->getJointModelCount());
159  EXPECT_EQ((unsigned int)3, (unsigned int)model->getJointModels()[0]->getLocalVariableNames().size());
160 
161  std::map<std::string, double> joint_values;
162  joint_values["base_joint/x"] = 10.0;
163  joint_values["base_joint/y"] = 8.0;
164 
165  // testing incomplete state
166  std::vector<std::string> missing_states;
167  state.setVariablePositions(joint_values, missing_states);
168  ASSERT_EQ(missing_states.size(), 1u);
169  EXPECT_EQ(missing_states[0], std::string("base_joint/theta"));
170  joint_values["base_joint/theta"] = 0.1;
171 
172  state.setVariablePositions(joint_values, missing_states);
173  ASSERT_EQ(missing_states.size(), 0u);
174 
175  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("base_link").translation(), Eigen::Vector3d(10, 8, 0));
176 
177  state.setVariableAcceleration("base_joint/x", 0.0);
178 
179  const auto new_state = std::make_unique<moveit::core::RobotState>(state); // making sure that values get copied
180  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("base_link").translation(), Eigen::Vector3d(10, 8, 0));
181 
182  std::vector<double> jv(state.getVariableCount(), 0.0);
183  jv[state.getRobotModel()->getVariableIndex("base_joint/x")] = 5.0;
184  jv[state.getRobotModel()->getVariableIndex("base_joint/y")] = 4.0;
185  jv[state.getRobotModel()->getVariableIndex("base_joint/theta")] = 0.0;
186 
187  state.setVariablePositions(jv);
188  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("base_link").translation(), Eigen::Vector3d(5, 4, 0));
189 }
190 
191 class OneRobot : public testing::Test
192 {
193 protected:
194  void SetUp() override
195  {
196  static const std::string MODEL2 =
197  "<?xml version=\"1.0\" ?>"
198  "<robot name=\"one_robot\">"
199  "<link name=\"base_link\">"
200  " <inertial>"
201  " <mass value=\"2.81\"/>"
202  " <origin rpy=\"0 0 0\" xyz=\"0.0 0.0 .0\"/>"
203  " <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>"
204  " </inertial>"
205  " <collision name=\"my_collision\">"
206  " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
207  " <geometry>"
208  " <box size=\"1 2 1\" />"
209  " </geometry>"
210  " </collision>"
211  " <visual>"
212  " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
213  " <geometry>"
214  " <box size=\"1 2 1\" />"
215  " </geometry>"
216  " </visual>"
217  "</link>"
218  "<joint name=\"joint_a\" type=\"continuous\">"
219  " <axis xyz=\"0 0 1\"/>"
220  " <parent link=\"base_link\"/>"
221  " <child link=\"link_a\"/>"
222  " <origin rpy=\" 0.0 0 0 \" xyz=\"0.0 0 0 \"/>"
223  "</joint>"
224  "<link name=\"link_a\">"
225  " <inertial>"
226  " <mass value=\"1.0\"/>"
227  " <origin rpy=\"0 0 0\" xyz=\"0.0 0.0 .0\"/>"
228  " <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>"
229  " </inertial>"
230  " <collision>"
231  " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
232  " <geometry>"
233  " <box size=\"1 2 1\" />"
234  " </geometry>"
235  " </collision>"
236  " <visual>"
237  " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
238  " <geometry>"
239  " <box size=\"1 2 1\" />"
240  " </geometry>"
241  " </visual>"
242  "</link>"
243  "<joint name=\"joint_b\" type=\"fixed\">"
244  " <parent link=\"link_a\"/>"
245  " <child link=\"link_b\"/>"
246  " <origin rpy=\" 0.0 -0.42 0 \" xyz=\"0.0 0.5 0 \"/>"
247  "</joint>"
248  "<link name=\"link_b\">"
249  " <inertial>"
250  " <mass value=\"1.0\"/>"
251  " <origin rpy=\"0 0 0\" xyz=\"0.0 0.0 .0\"/>"
252  " <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>"
253  " </inertial>"
254  " <collision>"
255  " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
256  " <geometry>"
257  " <box size=\"1 2 1\" />"
258  " </geometry>"
259  " </collision>"
260  " <visual>"
261  " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
262  " <geometry>"
263  " <box size=\"1 2 1\" />"
264  " </geometry>"
265  " </visual>"
266  "</link>"
267  " <joint name=\"joint_c\" type=\"prismatic\">"
268  " <axis xyz=\"1 0 0\"/>"
269  " <limit effort=\"100.0\" lower=\"0.0\" upper=\"0.09\" velocity=\"0.2\"/>"
270  " <safety_controller k_position=\"20.0\" k_velocity=\"500.0\" soft_lower_limit=\"0.0\" "
271  "soft_upper_limit=\"0.089\"/>"
272  " <parent link=\"link_b\"/>"
273  " <child link=\"link_c\"/>"
274  " <origin rpy=\" 0.0 0.42 0.0 \" xyz=\"0.0 -0.1 0 \"/>"
275  " </joint>"
276  "<link name=\"link_c\">"
277  " <inertial>"
278  " <mass value=\"1.0\"/>"
279  " <origin rpy=\"0 0 0\" xyz=\"0.0 0 .0\"/>"
280  " <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>"
281  " </inertial>"
282  " <collision>"
283  " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
284  " <geometry>"
285  " <box size=\"1 2 1\" />"
286  " </geometry>"
287  " </collision>"
288  " <visual>"
289  " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
290  " <geometry>"
291  " <box size=\"1 2 1\" />"
292  " </geometry>"
293  " </visual>"
294  "</link>"
295  " <joint name=\"mim_f\" type=\"prismatic\">"
296  " <axis xyz=\"1 0 0\"/>"
297  " <limit effort=\"100.0\" lower=\"0.0\" upper=\"0.19\" velocity=\"0.2\"/>"
298  " <parent link=\"link_c\"/>"
299  " <child link=\"link_d\"/>"
300  " <origin rpy=\" 0.0 0.0 0.0 \" xyz=\"0.1 0.1 0 \"/>"
301  " <mimic joint=\"joint_f\" multiplier=\"1.5\" offset=\"0.1\"/>"
302  " </joint>"
303  " <joint name=\"joint_f\" type=\"prismatic\">"
304  " <axis xyz=\"1 0 0\"/>"
305  " <limit effort=\"100.0\" lower=\"0.0\" upper=\"0.19\" velocity=\"0.2\"/>"
306  " <parent link=\"link_d\"/>"
307  " <child link=\"link_e\"/>"
308  " <origin rpy=\" 0.0 0.0 0.0 \" xyz=\"0.1 0.1 0 \"/>"
309  " </joint>"
310  "<link name=\"link_d\">"
311  " <collision>"
312  " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
313  " <geometry>"
314  " <box size=\"1 2 1\" />"
315  " </geometry>"
316  " </collision>"
317  " <visual>"
318  " <origin rpy=\"0 1 0\" xyz=\"0 0.1 0\"/>"
319  " <geometry>"
320  " <box size=\"1 2 1\" />"
321  " </geometry>"
322  " </visual>"
323  "</link>"
324  "<link name=\"link_e\">"
325  " <collision>"
326  " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
327  " <geometry>"
328  " <box size=\"1 2 1\" />"
329  " </geometry>"
330  " </collision>"
331  " <visual>"
332  " <origin rpy=\"0 1 0\" xyz=\"0 0.1 0\"/>"
333  " <geometry>"
334  " <box size=\"1 2 1\" />"
335  " </geometry>"
336  " </visual>"
337  "</link>"
338  "</robot>";
339 
340  static const std::string SMODEL2 =
341  "<?xml version=\"1.0\" ?>"
342  "<robot name=\"one_robot\">"
343  "<virtual_joint name=\"base_joint\" child_link=\"base_link\" parent_frame=\"odom_combined\" type=\"planar\"/>"
344  "<group name=\"base_from_joints\">"
345  "<joint name=\"base_joint\"/>"
346  "<joint name=\"joint_a\"/>"
347  "<joint name=\"joint_c\"/>"
348  "</group>"
349  "<group name=\"mim_joints\">"
350  "<joint name=\"joint_f\"/>"
351  "<joint name=\"mim_f\"/>"
352  "</group>"
353  "<group name=\"base_with_subgroups\">"
354  "<group name=\"base_from_base_to_tip\"/>"
355  "<joint name=\"joint_c\"/>"
356  "</group>"
357  "<group name=\"base_from_base_to_tip\">"
358  "<chain base_link=\"base_link\" tip_link=\"link_b\"/>"
359  "<joint name=\"base_joint\"/>"
360  "</group>"
361  "<group name=\"base_from_base_to_e\">"
362  "<chain base_link=\"base_link\" tip_link=\"link_e\"/>"
363  "<joint name=\"base_joint\"/>"
364  "</group>"
365  "<group name=\"base_with_bad_subgroups\">"
366  "<group name=\"error\"/>"
367  "</group>"
368  "</robot>";
369 
370  urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDF(MODEL2);
371  auto srdf_model = std::make_shared<srdf::Model>();
372  srdf_model->initString(*urdf_model, SMODEL2);
373  robot_model_ = std::make_shared<moveit::core::RobotModel>(urdf_model, srdf_model);
374  }
375 
376  void TearDown() override
377  {
378  }
379 
380 protected:
381  moveit::core::RobotModelConstPtr robot_model_;
382 };
383 
385 {
386  moveit::core::RobotModelConstPtr model = robot_model_;
387 
388  // testing that the two planning groups are the same
389  const moveit::core::JointModelGroup* g_one = model->getJointModelGroup("base_from_joints");
390  const moveit::core::JointModelGroup* g_two = model->getJointModelGroup("base_from_base_to_tip");
391  const moveit::core::JointModelGroup* g_three = model->getJointModelGroup("base_with_subgroups");
392  const moveit::core::JointModelGroup* g_four = model->getJointModelGroup("base_with_bad_subgroups");
393  const moveit::core::JointModelGroup* g_mim = model->getJointModelGroup("mim_joints");
394 
395  ASSERT_TRUE(g_one != nullptr);
396  ASSERT_TRUE(g_two != nullptr);
397  ASSERT_TRUE(g_three != nullptr);
398  ASSERT_TRUE(g_four == nullptr);
399 
400  // joint_b is a fixed joint, so no one should have it
401  ASSERT_EQ(g_one->getJointModelNames().size(), 3u);
402  ASSERT_EQ(g_two->getJointModelNames().size(), 3u);
403  ASSERT_EQ(g_three->getJointModelNames().size(), 4u);
404  ASSERT_EQ(g_mim->getJointModelNames().size(), 2u);
405 
406  // only the links in between the joints, and the children of the leafs
407  ASSERT_EQ(g_one->getLinkModelNames().size(), 3u);
408  // g_two only has three links
409  ASSERT_EQ(g_two->getLinkModelNames().size(), 3u);
410  ASSERT_EQ(g_three->getLinkModelNames().size(), 4u);
411 
412  std::vector<std::string> jmn = g_one->getJointModelNames();
413  std::sort(jmn.begin(), jmn.end());
414  EXPECT_EQ(jmn[0], "base_joint");
415  EXPECT_EQ(jmn[1], "joint_a");
416  EXPECT_EQ(jmn[2], "joint_c");
417  jmn = g_two->getJointModelNames();
418  std::sort(jmn.begin(), jmn.end());
419  EXPECT_EQ(jmn[0], "base_joint");
420  EXPECT_EQ(jmn[1], "joint_a");
421  EXPECT_EQ(jmn[2], "joint_b");
422  jmn = g_three->getJointModelNames();
423  std::sort(jmn.begin(), jmn.end());
424  EXPECT_EQ(jmn[0], "base_joint");
425  EXPECT_EQ(jmn[1], "joint_a");
426  EXPECT_EQ(jmn[2], "joint_b");
427  EXPECT_EQ(jmn[3], "joint_c");
428 
429  // but they should have the same links to be updated
430  ASSERT_EQ(g_one->getUpdatedLinkModels().size(), 6u);
431  ASSERT_EQ(g_two->getUpdatedLinkModels().size(), 6u);
432  ASSERT_EQ(g_three->getUpdatedLinkModels().size(), 6u);
433 
434  EXPECT_EQ(g_one->getUpdatedLinkModels()[0]->getName(), "base_link");
435  EXPECT_EQ(g_one->getUpdatedLinkModels()[1]->getName(), "link_a");
436  EXPECT_EQ(g_one->getUpdatedLinkModels()[2]->getName(), "link_b");
437  EXPECT_EQ(g_one->getUpdatedLinkModels()[3]->getName(), "link_c");
438 
439  EXPECT_EQ(g_two->getUpdatedLinkModels()[0]->getName(), "base_link");
440  EXPECT_EQ(g_two->getUpdatedLinkModels()[1]->getName(), "link_a");
441  EXPECT_EQ(g_two->getUpdatedLinkModels()[2]->getName(), "link_b");
442  EXPECT_EQ(g_two->getUpdatedLinkModels()[3]->getName(), "link_c");
443 
444  EXPECT_EQ(g_three->getUpdatedLinkModels()[0]->getName(), "base_link");
445  EXPECT_EQ(g_three->getUpdatedLinkModels()[1]->getName(), "link_a");
446  EXPECT_EQ(g_three->getUpdatedLinkModels()[2]->getName(), "link_b");
447  EXPECT_EQ(g_three->getUpdatedLinkModels()[3]->getName(), "link_c");
448 
449  // bracketing so the state gets destroyed before we bring down the model
450 
451  moveit::core::RobotState state(model);
452 
453  EXPECT_EQ((unsigned int)7, state.getVariableCount());
454 
455  state.setToDefaultValues();
456 
457  std::map<std::string, double> joint_values;
458  joint_values["base_joint/x"] = 1.0;
459  joint_values["base_joint/y"] = 1.0;
460  joint_values["base_joint/theta"] = 0.5;
461  joint_values["joint_a"] = -0.5;
462  joint_values["joint_c"] = 0.08;
463  state.setVariablePositions(joint_values);
464 
465  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("base_link").translation(), Eigen::Vector3d(1, 1, 0));
466  EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("base_link").linear()).x(), 1e-5);
467  EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("base_link").linear()).y(), 1e-5);
468  EXPECT_NEAR(0.247404, Eigen::Quaterniond(state.getGlobalLinkTransform("base_link").linear()).z(), 1e-5);
469  EXPECT_NEAR(0.968912, Eigen::Quaterniond(state.getGlobalLinkTransform("base_link").linear()).w(), 1e-5);
470 
471  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_a").translation(), Eigen::Vector3d(1, 1, 0));
472  EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_a").linear()).x(), 1e-5);
473  EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_a").linear()).y(), 1e-5);
474  EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_a").linear()).z(), 1e-5);
475  EXPECT_NEAR(1.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_a").linear()).w(), 1e-5);
476 
477  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_b").translation(), Eigen::Vector3d(1, 1.5, 0));
478  EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_b").linear()).x(), 1e-5);
479  EXPECT_NEAR(-0.2084598, Eigen::Quaterniond(state.getGlobalLinkTransform("link_b").linear()).y(), 1e-5);
480  EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_b").linear()).z(), 1e-5);
481  EXPECT_NEAR(0.97803091, Eigen::Quaterniond(state.getGlobalLinkTransform("link_b").linear()).w(), 1e-5);
482 
483  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_c").translation(), Eigen::Vector3d(1.08, 1.4, 0));
484  EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_c").linear()).x(), 1e-5);
485  EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_c").linear()).y(), 1e-5);
486  EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_c").linear()).z(), 1e-5);
487  EXPECT_NEAR(1.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_c").linear()).w(), 1e-5);
488 
489  EXPECT_TRUE(state.satisfiesBounds());
490 
491  std::map<std::string, double> upd_a;
492  upd_a["joint_a"] = 0.2;
493  state.setVariablePositions(upd_a);
494  EXPECT_TRUE(state.satisfiesBounds(model->getJointModel("joint_a")));
495  EXPECT_NEAR(state.getVariablePosition("joint_a"), 0.2, 1e-3);
496  state.enforceBounds();
497  EXPECT_NEAR(state.getVariablePosition("joint_a"), 0.2, 1e-3);
498 
499  upd_a["joint_a"] = 3.2;
500  state.setVariablePositions(upd_a);
501  EXPECT_TRUE(state.satisfiesBounds(model->getJointModel("joint_a")));
502  EXPECT_NEAR(state.getVariablePosition("joint_a"), 3.2, 1e-3);
503  state.enforceBounds();
504  EXPECT_NEAR(state.getVariablePosition("joint_a"), -3.083185, 1e-3);
505  EXPECT_TRUE(state.satisfiesBounds(model->getJointModel("joint_a")));
506 
507  // mimic joints
508  state.setToDefaultValues();
509  EXPECT_TRUE(state.dirtyLinkTransforms());
510  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_c").translation(), Eigen::Vector3d(0.0, 0.4, 0));
511  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_d").translation(), Eigen::Vector3d(0.2, 0.5, 0));
512  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_e").translation(), Eigen::Vector3d(0.3, 0.6, 0));
513 
514  // setVariablePosition should update corresponding mimic joints too
515  state.setVariablePosition("joint_f", 1.0);
516  EXPECT_EQ(state.getVariablePosition("joint_f"), 1.0);
517  EXPECT_EQ(state.getVariablePosition("mim_f"), 1.6);
518  EXPECT_TRUE(state.dirtyLinkTransforms());
519  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_c").translation(), Eigen::Vector3d(0.0, 0.4, 0));
520  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_d").translation(), Eigen::Vector3d(1.7, 0.5, 0));
521  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_e").translation(), Eigen::Vector3d(2.8, 0.6, 0));
522 
523  ASSERT_EQ(g_mim->getVariableCount(), 2u);
524  double gstate[2];
525  state.copyJointGroupPositions(g_mim, gstate);
526 
527  // setToRandomPositions() uses a different mechanism to update mimic joints
528  state.setToRandomPositions(g_mim);
529  double joint_f = state.getVariablePosition("joint_f");
530  double mim_f = state.getVariablePosition("mim_f");
531  EXPECT_NEAR(mim_f, 1.5 * joint_f + 0.1, 1e-8);
532  EXPECT_TRUE(state.dirtyLinkTransforms());
533  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_c").translation(), Eigen::Vector3d(0.0, 0.4, 0));
534  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_d").translation(), Eigen::Vector3d(0.1 + mim_f, 0.5, 0));
535  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_e").translation(),
536  Eigen::Vector3d(0.1 + mim_f + joint_f + 0.1, 0.6, 0));
537 
538  // setJointGroupPositions() uses a different mechanism to update mimic joints
539  state.setJointGroupPositions(g_mim, gstate);
540  EXPECT_EQ(state.getVariablePosition("joint_f"), 1.0);
541  EXPECT_EQ(state.getVariablePosition("mim_f"), 1.6);
542  EXPECT_TRUE(state.dirtyLinkTransforms());
543  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_c").translation(), Eigen::Vector3d(0.0, 0.4, 0));
544  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_d").translation(), Eigen::Vector3d(1.7, 0.5, 0));
545  EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_e").translation(), Eigen::Vector3d(2.8, 0.6, 0));
546 }
547 
548 TEST_F(OneRobot, testPrintCurrentPositionWithJointLimits)
549 {
550  moveit::core::RobotState state(robot_model_);
551  const moveit::core::JointModelGroup* joint_model_group = robot_model_->getJointModelGroup("base_from_base_to_e");
552  ASSERT_TRUE(joint_model_group);
553 
554  state.setToDefaultValues();
555 
556  std::cout << "\nVisual inspection should show NO joints out of bounds:\n";
557  state.printStatePositionsWithJointLimits(joint_model_group);
558 
559  std::cout << "\nVisual inspection should show ONE joint out of bounds:\n";
560  std::vector<double> single_joint(1);
561  single_joint[0] = -1.0;
562  state.setJointPositions("joint_c", single_joint);
563  state.printStatePositionsWithJointLimits(joint_model_group);
564 
565  std::cout << "\nVisual inspection should show TWO joint out of bounds:\n";
566  single_joint[0] = 1.0;
567  state.setJointPositions("joint_f", single_joint);
568  state.printStatePositionsWithJointLimits(joint_model_group);
569 
570  std::cout << "\nVisual inspection should show ONE joint out of bounds:\n";
571  single_joint[0] = 0.19;
572  state.setJointPositions("joint_f", single_joint);
573  state.printStatePositionsWithJointLimits(joint_model_group);
574 }
575 
576 TEST_F(OneRobot, testInterpolation)
577 {
578  moveit::core::RobotState state_a(robot_model_);
579 
580  // Interpolate with itself
581  state_a.setToDefaultValues();
582  moveit::core::RobotState state_b(state_a);
583  moveit::core::RobotState interpolated_state(state_a);
584  for (size_t i = 0; i <= 10; ++i)
585  {
586  state_a.interpolate(state_b, static_cast<double>(i) / 10., interpolated_state,
587  robot_model_->getJointModelGroup("base_from_base_to_e"));
588  EXPECT_NEAR(state_a.distance(state_b), 0, EPSILON)
589  << "Interpolation between identical states yielded a different state.";
590 
591  for (const auto& link_name : robot_model_->getLinkModelNames())
592  {
593  EXPECT_FALSE(interpolated_state.getCollisionBodyTransform(link_name, 0).matrix().hasNaN())
594  << "Interpolation between identical states yielded NaN value.";
595  }
596  }
597 
598  // Some simple interpolation
599  std::map<std::string, double> joint_values;
600  joint_values["base_joint/x"] = 1.0;
601  joint_values["base_joint/y"] = 1.0;
602  state_a.setVariablePositions(joint_values);
603  joint_values["base_joint/x"] = 0.0;
604  joint_values["base_joint/y"] = 2.0;
605  state_b.setVariablePositions(joint_values);
606  EXPECT_NEAR(3 * std::sqrt(2), state_a.distance(state_b), EPSILON) << "Simple interpolation of base_joint failed.";
607 
608  state_a.interpolate(state_b, 0.5, interpolated_state, robot_model_->getJointModelGroup("base_from_base_to_e"));
609  EXPECT_NEAR(0., state_a.distance(interpolated_state) - state_b.distance(interpolated_state), EPSILON)
610  << "Simple interpolation of base_joint failed.";
611  EXPECT_NEAR(0.5, interpolated_state.getVariablePosition("base_joint/x"), EPSILON)
612  << "Simple interpolation of base_joint failed.";
613  EXPECT_NEAR(1.5, interpolated_state.getVariablePosition("base_joint/y"), EPSILON)
614  << "Simple interpolation of base_joint failed.";
615  state_a.interpolate(state_b, 0.1, interpolated_state, robot_model_->getJointModelGroup("base_from_base_to_e"));
616  EXPECT_NEAR(0.9, interpolated_state.getVariablePosition("base_joint/x"), EPSILON)
617  << "Simple interpolation of base_joint failed.";
618  EXPECT_NEAR(1.1, interpolated_state.getVariablePosition("base_joint/y"), EPSILON)
619  << "Simple interpolation of base_joint failed.";
620 
621  // Interpolate all the joints
622  joint_values["base_joint/x"] = 0.0;
623  joint_values["base_joint/y"] = 20.0;
624  joint_values["base_joint/theta"] = 3 * M_PI / 4;
625  joint_values["joint_a"] = -4 * M_PI / 5;
626  joint_values["joint_c"] = 0.0;
627  joint_values["joint_f"] = 1.0;
628  state_a.setVariablePositions(joint_values);
629 
630  joint_values["base_joint/x"] = 10.0;
631  joint_values["base_joint/y"] = 0.0;
632  joint_values["base_joint/theta"] = -3 * M_PI / 4;
633  joint_values["joint_a"] = 4 * M_PI / 5;
634  joint_values["joint_c"] = 0.07;
635  joint_values["joint_f"] = 0.0;
636  state_b.setVariablePositions(joint_values);
637 
638  for (size_t i = 0; i <= 5; ++i)
639  {
640  double t = static_cast<double>(i) / 5.;
641  state_a.interpolate(state_b, t, interpolated_state, robot_model_->getJointModelGroup("base_from_base_to_e"));
642  EXPECT_NEAR(10.0 * t, interpolated_state.getVariablePosition("base_joint/x"), EPSILON)
643  << "Base joint interpolation failed.";
644  EXPECT_NEAR(20.0 * (1 - t), interpolated_state.getVariablePosition("base_joint/y"), EPSILON)
645  << "Base joint interpolation failed.";
646  if (t < 0.5)
647  {
648  EXPECT_NEAR(3 * M_PI / 4 + (M_PI / 2) * t, interpolated_state.getVariablePosition("base_joint/theta"), EPSILON)
649  << "Base joint theta interpolation failed.";
650  EXPECT_NEAR(-4 * M_PI / 5 - (2 * M_PI / 5) * t, interpolated_state.getVariablePosition("joint_a"), EPSILON)
651  << "Continuous joint interpolation failed.";
652  }
653  else
654  {
655  EXPECT_NEAR(-3 * M_PI / 4 - (M_PI / 2) * (1 - t), interpolated_state.getVariablePosition("base_joint/theta"),
656  EPSILON)
657  << "Base joint theta interpolation failed.";
658  EXPECT_NEAR(4 * M_PI / 5 + (2 * M_PI / 5) * (1 - t), interpolated_state.getVariablePosition("joint_a"), EPSILON)
659  << "Continuous joint interpolation failed.";
660  }
661  EXPECT_NEAR(0.07 * t, interpolated_state.getVariablePosition("joint_c"), EPSILON)
662  << "Interpolation of joint_c failed.";
663  EXPECT_NEAR(1 - t, interpolated_state.getVariablePosition("joint_f"), EPSILON)
664  << "Interpolation of joint_f failed.";
665  EXPECT_NEAR(1.5 * (1 - t) + 0.1, interpolated_state.getVariablePosition("mim_f"), EPSILON)
666  << "Interpolation of mimic joint mim_f failed.";
667  }
668 
669  bool nan_exception = false;
670  try
671  {
672  state_a.interpolate(state_b, 1. / 0., interpolated_state, robot_model_->getJointModelGroup("base_from_base_to_e"));
673  }
674  catch (std::exception& e)
675  {
676  std::cout << "Caught expected exception: " << e.what() << '\n';
677  nan_exception = true;
678  }
679  EXPECT_TRUE(nan_exception) << "NaN interpolation parameter did not create expected exception.";
680 }
681 
682 TEST_F(OneRobot, rigidlyConnectedParent)
683 {
684  // link_e is its own rigidly-connected parent
685  const moveit::core::LinkModel* link_e{ robot_model_->getLinkModel("link_e") };
686  EXPECT_EQ(robot_model_->getRigidlyConnectedParentLinkModel(link_e), link_e);
687 
688  // link_b is rigidly connected to its parent link_a
689  const moveit::core::LinkModel* link_a{ robot_model_->getLinkModel("link_a") };
690  const moveit::core::LinkModel* link_b{ robot_model_->getLinkModel("link_b") };
691  EXPECT_EQ(robot_model_->getRigidlyConnectedParentLinkModel(link_b), link_a);
692 
693  moveit::core::RobotState state(robot_model_);
694  state.setToDefaultValues();
695  state.updateLinkTransforms();
696 
697  EXPECT_EQ(state.getRigidlyConnectedParentLinkModel("link_b"), link_a);
698 
699  // attach "object" with "subframe" to link_b
700  state.attachBody(std::make_unique<moveit::core::AttachedBody>(
701  link_b, "object", Eigen::Isometry3d::Identity(), std::vector<shapes::ShapeConstPtr>{},
702  EigenSTL::vector_Isometry3d{}, std::set<std::string>{}, trajectory_msgs::msg::JointTrajectory{},
703  moveit::core::FixedTransformsMap{ { "subframe", Eigen::Isometry3d::Identity() } }));
704 
705  // RobotState's version should resolve these too
706  EXPECT_EQ(link_a, state.getRigidlyConnectedParentLinkModel("object"));
707  EXPECT_EQ(link_a, state.getRigidlyConnectedParentLinkModel("object/subframe"));
708 
709  // test failure cases
710  EXPECT_EQ(nullptr, state.getRigidlyConnectedParentLinkModel("no_object"));
711  EXPECT_EQ(nullptr, state.getRigidlyConnectedParentLinkModel("object/no_subframe"));
712  EXPECT_EQ(nullptr, state.getRigidlyConnectedParentLinkModel(""));
713  EXPECT_EQ(nullptr, state.getRigidlyConnectedParentLinkModel("object/"));
714  EXPECT_EQ(nullptr, state.getRigidlyConnectedParentLinkModel("/"));
715 }
716 
717 int main(int argc, char** argv)
718 {
719  testing::InitGoogleTest(&argc, argv);
720  return RUN_ALL_TESTS();
721 }
void TearDown() override
void SetUp() override
moveit::core::RobotModelConstPtr robot_model_
const std::vector< std::string > & getLinkModelNames() const
Get the names of the links that are part of this joint group.
const std::vector< std::string > & getJointModelNames() const
Get the names of the joints in this group. These are the names of the joints returned by getJointMode...
const std::vector< const LinkModel * > & getUpdatedLinkModels() const
Get the names of the links that are to be updated when the state of this group changes....
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:72
Easily build different robot models for testing. Essentially a programmer-friendly light wrapper arou...
void addInertial(const std::string &link_name, double mass, geometry_msgs::msg::Pose origin, double ixx, double ixy, double ixz, double iyy, double iyz, double izz)
void addCollisionBox(const std::string &link_name, const std::vector< double > &dims, geometry_msgs::msg::Pose origin)
Adds a collision box to a specific link.
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.
void addVisualBox(const std::string &link_name, const std::vector< double > &size, geometry_msgs::msg::Pose origin)
Adds a visual box to a specific link.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state....
void setVariableAcceleration(const std::string &variable, double value)
Set the acceleration of a variable. If an unknown variable name is specified, an exception is thrown.
Definition: robot_state.h:381
const Eigen::Isometry3d & getCollisionBodyTransform(const std::string &link_name, std::size_t index)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
Definition: robot_state.h:1379
void attachBody(std::unique_ptr< AttachedBody > attached_body)
Add an attached body to this state.
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...
Definition: robot_state.h:1339
void setVariablePosition(const std::string &variable, double value)
Set the position of a single variable. An exception is thrown if the variable name is not known.
Definition: robot_state.h:188
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
Definition: robot_state.h:605
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
Definition: robot_state.h:691
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
Definition: robot_state.h:104
void printStatePositionsWithJointLimits(const moveit::core::JointModelGroup *jmg, std::ostream &out=std::cout) const
Output to console the current state of the robot's joint limits.
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
Definition: robot_state.h:134
void updateLinkTransforms()
Update the reference frame transforms for links. This call is needed before using the transforms of l...
void interpolate(const RobotState &to, double t, RobotState &state) const
double distance(const RobotState &other) const
Return the sum of joint distances to "other" state. An L1 norm. Only considers active joints.
Definition: robot_state.h:1457
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
bool satisfiesBounds(double margin=0.0) const
bool dirtyLinkTransforms() const
Definition: robot_state.h:1434
double getVariablePosition(const std::string &variable) const
Get the position of a particular variable. An exception is thrown if the variable is not known.
Definition: robot_state.h:207
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
std::size_t getVariableCount() const
Get the number of variables that make up this state.
Definition: robot_state.h:110
const moveit::core::LinkModel * getRigidlyConnectedParentLinkModel(const std::string &frame) const
Get the latest link upwards the kinematic tree which is only connected via fixed joints.
void setJointPositions(const std::string &joint_name, const double *position)
Definition: robot_state.h:515
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
std::map< std::string, Eigen::Isometry3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Isometry3d > > > FixedTransformsMap
Map frame names to the transformation matrix that can transform objects from the frame name to the pl...
Definition: transforms.h:53
x
Definition: pick.py:64
y
Definition: pick.py:65
r
Definition: plan.py:56
int main(int argc, char **argv)
TEST(Loading, SimpleRobot)
#define EXPECT_NEAR_TRACED(...)
TEST_F(OneRobot, FK)