moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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
46namespace
47{
48constexpr double EPSILON{ 1.e-9 };
49
50// Helper to create an Eigen::VectorXd from an initializer list, e.g.:
51// auto vector = makeVector({1.0, 2.0, 3.0});
52Eigen::VectorXd makeVector(const std::vector<double>& values)
53{
54 Eigen::VectorXd vector = Eigen::VectorXd::Zero(values.size());
55 for (std::size_t i = 0; i < values.size(); i++)
56 {
57 vector[i] = values[i];
58 }
59 return vector;
60}
61
62// Checks the validity of state.getJacobian() at the given 'joint_values' and 'joint_velocities'.
63void checkJacobian(moveit::core::RobotState& state, const moveit::core::JointModelGroup& joint_model_group,
64 const Eigen::VectorXd& joint_values, const Eigen::VectorXd& joint_velocities)
65{
66 // Using the Jacobian, compute the Cartesian velocity vector at which the end-effector would move, with the given
67 // joint velocities.
68 state.setToDefaultValues();
69 state.setJointGroupPositions(&joint_model_group, joint_values);
71
72 const moveit::core::JointModel* root_joint_model = joint_model_group.getJointModels().front();
73 const moveit::core::LinkModel* root_link_model = root_joint_model->getParentLinkModel();
74 const Eigen::Isometry3d root_pose_world = state.getGlobalLinkTransform(root_link_model).inverse();
75
76 const Eigen::Isometry3d tip_pose_initial =
77 root_pose_world * state.getGlobalLinkTransform(joint_model_group.getLinkModels().back());
78 const Eigen::MatrixXd jacobian = state.getJacobian(&joint_model_group);
79 const Eigen::VectorXd cartesian_velocity = jacobian * joint_velocities;
80
81 // Compute the instantaneous displacement that the end-effector would achieve if the given joint
82 // velocities were applied for a small amount of time.
83 constexpr double time_step = 1e-5;
84 const Eigen::VectorXd delta_joint_angles = time_step * joint_velocities;
85 state.setJointGroupPositions(&joint_model_group, joint_values + delta_joint_angles);
87 const Eigen::Isometry3d tip_pose_after_delta =
88 root_pose_world * state.getGlobalLinkTransform(joint_model_group.getLinkModels().back());
89 const Eigen::Vector3d displacement = tip_pose_after_delta.translation() - tip_pose_initial.translation();
90
91 // The Cartesian velocity vector obtained via the Jacobian should be aligned with the instantaneous robot motion, i.e.
92 // the angle between the vectors should be close to zero.
93 double angle = std::acos(displacement.dot(cartesian_velocity.head<3>()) /
94 (displacement.norm() * cartesian_velocity.head<3>().norm()));
95 EXPECT_NEAR(angle, 0.0, 1e-05) << "Angle between Cartesian velocity and Cartesian displacement larger than expected. "
96 "Angle: "
97 << angle << ". displacement: " << displacement.transpose()
98 << ". Cartesian velocity: " << cartesian_velocity.head<3>().transpose() << '\n';
99}
100} // namespace
101
102static void expect_near(const Eigen::MatrixXd& x, const Eigen::MatrixXd& y,
103 double eps = std::numeric_limits<double>::epsilon())
104{
105 ASSERT_EQ(x.rows(), y.rows());
106 ASSERT_EQ(x.cols(), y.cols());
107 for (int r = 0; r < x.rows(); ++r)
108 {
109 for (int c = 0; c < x.cols(); ++c)
110 EXPECT_NEAR(x(r, c), y(r, c), eps) << "(r,c) = (" << r << ',' << c << ')';
111 }
112}
113
114// clang-format off
115#define EXPECT_NEAR_TRACED(...) { \
116 SCOPED_TRACE("expect_near(" #__VA_ARGS__ ")"); \
117 expect_near(__VA_ARGS__); \
118}
119// clang-format on
120
122{
123 moveit::core::RobotModelBuilder builder("myrobot", "base_link");
124 builder.addVirtualJoint("odom_combined", "base_link", "floating", "base_joint");
125 ASSERT_TRUE(builder.isValid());
126 moveit::core::RobotModelPtr model = builder.build();
127 moveit::core::RobotState state(model);
128
129 state.setToDefaultValues();
130
131 // make sure that this copy constructor works
132 moveit::core::RobotState new_state(state);
133
134 EXPECT_EQ(new_state.getVariablePosition("base_joint/rot_w"), 1.0);
135
136 EXPECT_EQ(std::string("myrobot"), model->getName());
137 EXPECT_EQ(7u, new_state.getVariableCount());
138
139 const std::vector<moveit::core::LinkModel*>& links = model->getLinkModels();
140 EXPECT_EQ(1u, links.size());
141
142 const std::vector<moveit::core::JointModel*>& joints = model->getJointModels();
143 EXPECT_EQ(1u, joints.size());
144
145 const std::vector<std::string>& pgroups = model->getJointModelGroupNames();
146 EXPECT_EQ(0u, pgroups.size());
147}
148
149TEST(LoadingAndFK, SimpleRobot)
150{
151 moveit::core::RobotModelBuilder builder("myrobot", "base_link");
152 geometry_msgs::msg::Pose pose;
153 pose.position.x = -0.1;
154 pose.position.y = 0;
155 pose.position.z = 0;
156
157 tf2::Quaternion q;
158 q.setRPY(0, 0, -1);
159 pose.orientation = tf2::toMsg(q);
160 builder.addCollisionBox("base_link", { 1, 2, 1 }, pose);
161 pose.position.x = 0;
162 pose.position.y = 0;
163 pose.position.z = 0;
164 q.setRPY(0, 0, 0);
165 pose.orientation = tf2::toMsg(q);
166 builder.addVisualBox("base_link", { 1, 2, 1 }, pose);
167 pose.position.x = 0;
168 pose.position.y = 0.099;
169 pose.position.z = 0;
170 q.setRPY(0, 0, 0);
171 pose.orientation = tf2::toMsg(q);
172 builder.addInertial("base_link", 2.81, pose, 0.1, -0.2, 0.5, -0.09, 1, 0.101);
173 builder.addVirtualJoint("odom_combined", "base_link", "planar", "base_joint");
174 builder.addGroup({}, { "base_joint" }, "base");
175
176 ASSERT_TRUE(builder.isValid());
177 moveit::core::RobotModelPtr model = builder.build();
178 moveit::core::RobotState state(model);
179
180 EXPECT_EQ(3u, state.getVariableCount());
181
182 state.setToDefaultValues();
183
184 EXPECT_EQ(1u, static_cast<unsigned int>(model->getJointModelCount()));
185 EXPECT_EQ(3u, static_cast<unsigned int>(model->getJointModels()[0]->getLocalVariableNames().size()));
186
187 std::map<std::string, double> joint_values;
188 joint_values["base_joint/x"] = 10.0;
189 joint_values["base_joint/y"] = 8.0;
190
191 // testing incomplete state
192 std::vector<std::string> missing_states;
193 state.setVariablePositions(joint_values, missing_states);
194 ASSERT_EQ(missing_states.size(), 1u);
195 EXPECT_EQ(missing_states[0], std::string("base_joint/theta"));
196 joint_values["base_joint/theta"] = 0.1;
197
198 state.setVariablePositions(joint_values, missing_states);
199 ASSERT_EQ(missing_states.size(), 0u);
200
201 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("base_link").translation(), Eigen::Vector3d(10, 8, 0));
202
203 state.setVariableAcceleration("base_joint/x", 0.0);
204
205 const auto new_state = std::make_unique<moveit::core::RobotState>(state); // making sure that values get copied
206 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("base_link").translation(), Eigen::Vector3d(10, 8, 0));
207
208 std::vector<double> jv(state.getVariableCount(), 0.0);
209 jv[state.getRobotModel()->getVariableIndex("base_joint/x")] = 5.0;
210 jv[state.getRobotModel()->getVariableIndex("base_joint/y")] = 4.0;
211 jv[state.getRobotModel()->getVariableIndex("base_joint/theta")] = 0.0;
212
213 state.setVariablePositions(jv);
214 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("base_link").translation(), Eigen::Vector3d(5, 4, 0));
215}
216
217class OneRobot : public testing::Test
218{
219protected:
220 void SetUp() override
221 {
222 static const std::string MODEL2 = R"(
223 <?xml version="1.0" ?>
224 <robot name="one_robot">
225 <link name="base_link">
226 <inertial>
227 <mass value="2.81"/>
228 <origin rpy="0 0 0" xyz="0.0 0.0 .0"/>
229 <inertia ixx="0.1" ixy="-0.2" ixz="0.5" iyy="-.09" iyz="1" izz="0.101"/>
230 </inertial>
231 <collision name="my_collision">
232 <origin rpy="0 0 0" xyz="0 0 0"/>
233 <geometry>
234 <box size="1 2 1" />
235 </geometry>
236 </collision>
237 <visual>
238 <origin rpy="0 0 0" xyz="0.0 0 0"/>
239 <geometry>
240 <box size="1 2 1" />
241 </geometry>
242 </visual>
243 </link>
244 <joint name="joint_a" type="continuous">
245 <axis xyz="0 0 1"/>
246 <parent link="base_link"/>
247 <child link="link_a"/>
248 <origin rpy=" 0.0 0 0 " xyz="0.0 0 0 "/>
249 </joint>
250 <link name="link_a">
251 <inertial>
252 <mass value="1.0"/>
253 <origin rpy="0 0 0" xyz="0.0 0.0 .0"/>
254 <inertia ixx="0.1" ixy="-0.2" ixz="0.5" iyy="-.09" iyz="1" izz="0.101"/>
255 </inertial>
256 <collision>
257 <origin rpy="0 0 0" xyz="0 0 0"/>
258 <geometry>
259 <box size="1 2 1" />
260 </geometry>
261 </collision>
262 <visual>
263 <origin rpy="0 0 0" xyz="0.0 0 0"/>
264 <geometry>
265 <box size="1 2 1" />
266 </geometry>
267 </visual>
268 </link>
269 <joint name="joint_b" type="fixed">
270 <parent link="link_a"/>
271 <child link="link_b"/>
272 <origin rpy=" 0.0 -0.42 0 " xyz="0.0 0.5 0 "/>
273 </joint>
274 <link name="link_b">
275 <inertial>
276 <mass value="1.0"/>
277 <origin rpy="0 0 0" xyz="0.0 0.0 .0"/>
278 <inertia ixx="0.1" ixy="-0.2" ixz="0.5" iyy="-.09" iyz="1" izz="0.101"/>
279 </inertial>
280 <collision>
281 <origin rpy="0 0 0" xyz="0 0 0"/>
282 <geometry>
283 <box size="1 2 1" />
284 </geometry>
285 </collision>
286 <visual>
287 <origin rpy="0 0 0" xyz="0.0 0 0"/>
288 <geometry>
289 <box size="1 2 1" />
290 </geometry>
291 </visual>
292 </link>
293 <joint name="joint_c" type="prismatic">
294 <axis xyz="1 0 0"/>
295 <limit effort="100.0" lower="0.0" upper="0.09" velocity="0.2"/>
296 <safety_controller k_position="20.0" k_velocity="500.0" soft_lower_limit="0.0"
297 soft_upper_limit="0.089"/>
298 <parent link="link_b"/>
299 <child link="link_c"/>
300 <origin rpy=" 0.0 0.42 0.0 " xyz="0.0 -0.1 0 "/>
301 </joint>
302 <link name="link_c">
303 <inertial>
304 <mass value="1.0"/>
305 <origin rpy="0 0 0" xyz="0.0 0 .0"/>
306 <inertia ixx="0.1" ixy="-0.2" ixz="0.5" iyy="-.09" iyz="1" izz="0.101"/>
307 </inertial>
308 <collision>
309 <origin rpy="0 0 0" xyz="0 0 0"/>
310 <geometry>
311 <box size="1 2 1" />
312 </geometry>
313 </collision>
314 <visual>
315 <origin rpy="0 0 0" xyz="0.0 0 0"/>
316 <geometry>
317 <box size="1 2 1" />
318 </geometry>
319 </visual>
320 </link>
321 <joint name="mim_f" type="prismatic">
322 <axis xyz="1 0 0"/>
323 <limit effort="100.0" lower="0.0" upper="0.19" velocity="0.2"/>
324 <parent link="link_c"/>
325 <child link="link_d"/>
326 <origin rpy=" 0.0 0.0 0.0 " xyz="0.1 0.1 0 "/>
327 <mimic joint="joint_f" multiplier="1.5" offset="0.1"/>
328 </joint>
329 <joint name="joint_f" type="prismatic">
330 <axis xyz="1 0 0"/>
331 <limit effort="100.0" lower="0.0" upper="0.19" velocity="0.2"/>
332 <parent link="link_d"/>
333 <child link="link_e"/>
334 <origin rpy=" 0.0 0.0 0.0 " xyz="0.1 0.1 0 "/>
335 </joint>
336 <link name="link_d">
337 <collision>
338 <origin rpy="0 0 0" xyz="0 0 0"/>
339 <geometry>
340 <box size="1 2 1" />
341 </geometry>
342 </collision>
343 <visual>
344 <origin rpy="0 1 0" xyz="0 0.1 0"/>
345 <geometry>
346 <box size="1 2 1" />
347 </geometry>
348 </visual>
349 </link>
350 <link name="link_e">
351 <collision>
352 <origin rpy="0 0 0" xyz="0 0 0"/>
353 <geometry>
354 <box size="1 2 1" />
355 </geometry>
356 </collision>
357 <visual>
358 <origin rpy="0 1 0" xyz="0 0.1 0"/>
359 <geometry>
360 <box size="1 2 1" />
361 </geometry>
362 </visual>
363 </link>
364 </robot>
365 )";
366
367 static const std::string SMODEL2 = R"xml(
368 <?xml version="1.0" ?>
369 <robot name="one_robot">
370 <virtual_joint name="base_joint" child_link="base_link" parent_frame="odom_combined" type="planar"/>
371 <group name="base_from_joints">
372 <joint name="base_joint"/>
373 <joint name="joint_a"/>
374 <joint name="joint_c"/>
375 </group>
376 <group name="mim_joints">
377 <joint name="joint_f"/>
378 <joint name="mim_f"/>
379 </group>
380 <group name="base_with_subgroups">
381 <group name="base_from_base_to_tip"/>
382 <joint name="joint_c"/>
383 </group>
384 <group name="base_from_base_to_tip">
385 <chain base_link="base_link" tip_link="link_b"/>
386 <joint name="base_joint"/>
387 </group>
388 <group name="base_from_base_to_e">
389 <chain base_link="base_link" tip_link="link_e"/>
390 <joint name="base_joint"/>
391 </group>
392 <group name="base_with_bad_subgroups">
393 <group name="error"/>
394 </group>
395 </robot>
396 )xml";
397
398 urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDF(MODEL2);
399 auto srdf_model = std::make_shared<srdf::Model>();
400 srdf_model->initString(*urdf_model, SMODEL2);
401 robot_model_ = std::make_shared<moveit::core::RobotModel>(urdf_model, srdf_model);
402 }
403
404 void TearDown() override
405 {
406 }
407
408protected:
409 moveit::core::RobotModelConstPtr robot_model_;
410};
411
412TEST_F(OneRobot, setToDefaultValues)
413{
414 moveit::core::RobotState state(robot_model_);
415 state.setToDefaultValues();
416
417 // Get default values for joint_a.
418 double joint_a_default_position = state.getVariablePosition("joint_a");
419 double joint_a_default_velocity = state.getVariableVelocity("joint_a");
420 double joint_a_default_acceleration = state.getVariableAcceleration("joint_a");
421
422 // Set joint_a to some values.
423 state.setVariablePosition("joint_a", 1.0);
424 state.setVariableVelocity("joint_a", 2.0);
425 state.setVariableAcceleration("joint_a", 3.0);
426
427 // Check that joint_a has the right values.
428 EXPECT_EQ(state.getVariablePosition("joint_a"), 1.0);
429 EXPECT_EQ(state.getVariableVelocity("joint_a"), 2.0);
430 EXPECT_EQ(state.getVariableAcceleration("joint_a"), 3.0);
431
432 // Set to default values.
433 // Check that joint_a is back to the default values.
434 state.setToDefaultValues();
435 EXPECT_EQ(state.getVariablePosition("joint_a"), joint_a_default_position);
436 EXPECT_EQ(state.getVariableVelocity("joint_a"), joint_a_default_velocity);
437 EXPECT_EQ(state.getVariableAcceleration("joint_a"), joint_a_default_acceleration);
438}
439
441{
442 moveit::core::RobotModelConstPtr model = robot_model_;
443
444 // testing that the two planning groups are the same
445 const moveit::core::JointModelGroup* g_one = model->getJointModelGroup("base_from_joints");
446 const moveit::core::JointModelGroup* g_two = model->getJointModelGroup("base_from_base_to_tip");
447 const moveit::core::JointModelGroup* g_three = model->getJointModelGroup("base_with_subgroups");
448 const moveit::core::JointModelGroup* g_four = model->getJointModelGroup("base_with_bad_subgroups");
449 const moveit::core::JointModelGroup* g_mim = model->getJointModelGroup("mim_joints");
450
451 ASSERT_TRUE(g_one != nullptr);
452 ASSERT_TRUE(g_two != nullptr);
453 ASSERT_TRUE(g_three != nullptr);
454 ASSERT_TRUE(g_four == nullptr);
455
456 // joint_b is a fixed joint, so no one should have it
457 ASSERT_EQ(g_one->getJointModelNames().size(), 3u);
458 ASSERT_EQ(g_two->getJointModelNames().size(), 3u);
459 ASSERT_EQ(g_three->getJointModelNames().size(), 4u);
460 ASSERT_EQ(g_mim->getJointModelNames().size(), 2u);
461
462 // only the links in between the joints, and the children of the leafs
463 ASSERT_EQ(g_one->getLinkModelNames().size(), 3u);
464 // g_two only has three links
465 ASSERT_EQ(g_two->getLinkModelNames().size(), 3u);
466 ASSERT_EQ(g_three->getLinkModelNames().size(), 4u);
467
468 std::vector<std::string> jmn = g_one->getJointModelNames();
469 std::sort(jmn.begin(), jmn.end());
470 EXPECT_EQ(jmn[0], "base_joint");
471 EXPECT_EQ(jmn[1], "joint_a");
472 EXPECT_EQ(jmn[2], "joint_c");
473 jmn = g_two->getJointModelNames();
474 std::sort(jmn.begin(), jmn.end());
475 EXPECT_EQ(jmn[0], "base_joint");
476 EXPECT_EQ(jmn[1], "joint_a");
477 EXPECT_EQ(jmn[2], "joint_b");
478 jmn = g_three->getJointModelNames();
479 std::sort(jmn.begin(), jmn.end());
480 EXPECT_EQ(jmn[0], "base_joint");
481 EXPECT_EQ(jmn[1], "joint_a");
482 EXPECT_EQ(jmn[2], "joint_b");
483 EXPECT_EQ(jmn[3], "joint_c");
484
485 // but they should have the same links to be updated
486 ASSERT_EQ(g_one->getUpdatedLinkModels().size(), 6u);
487 ASSERT_EQ(g_two->getUpdatedLinkModels().size(), 6u);
488 ASSERT_EQ(g_three->getUpdatedLinkModels().size(), 6u);
489
490 EXPECT_EQ(g_one->getUpdatedLinkModels()[0]->getName(), "base_link");
491 EXPECT_EQ(g_one->getUpdatedLinkModels()[1]->getName(), "link_a");
492 EXPECT_EQ(g_one->getUpdatedLinkModels()[2]->getName(), "link_b");
493 EXPECT_EQ(g_one->getUpdatedLinkModels()[3]->getName(), "link_c");
494
495 EXPECT_EQ(g_two->getUpdatedLinkModels()[0]->getName(), "base_link");
496 EXPECT_EQ(g_two->getUpdatedLinkModels()[1]->getName(), "link_a");
497 EXPECT_EQ(g_two->getUpdatedLinkModels()[2]->getName(), "link_b");
498 EXPECT_EQ(g_two->getUpdatedLinkModels()[3]->getName(), "link_c");
499
500 EXPECT_EQ(g_three->getUpdatedLinkModels()[0]->getName(), "base_link");
501 EXPECT_EQ(g_three->getUpdatedLinkModels()[1]->getName(), "link_a");
502 EXPECT_EQ(g_three->getUpdatedLinkModels()[2]->getName(), "link_b");
503 EXPECT_EQ(g_three->getUpdatedLinkModels()[3]->getName(), "link_c");
504
505 // bracketing so the state gets destroyed before we bring down the model
506
507 moveit::core::RobotState state(model);
508
509 EXPECT_EQ(7u, state.getVariableCount());
510
511 state.setToDefaultValues();
512
513 std::map<std::string, double> joint_values;
514 joint_values["base_joint/x"] = 1.0;
515 joint_values["base_joint/y"] = 1.0;
516 joint_values["base_joint/theta"] = 0.5;
517 joint_values["joint_a"] = -0.5;
518 joint_values["joint_c"] = 0.08;
519 state.setVariablePositions(joint_values);
520
521 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("base_link").translation(), Eigen::Vector3d(1, 1, 0));
522 EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("base_link").linear()).x(), 1e-5);
523 EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("base_link").linear()).y(), 1e-5);
524 EXPECT_NEAR(0.247404, Eigen::Quaterniond(state.getGlobalLinkTransform("base_link").linear()).z(), 1e-5);
525 EXPECT_NEAR(0.968912, Eigen::Quaterniond(state.getGlobalLinkTransform("base_link").linear()).w(), 1e-5);
526
527 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_a").translation(), Eigen::Vector3d(1, 1, 0));
528 EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_a").linear()).x(), 1e-5);
529 EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_a").linear()).y(), 1e-5);
530 EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_a").linear()).z(), 1e-5);
531 EXPECT_NEAR(1.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_a").linear()).w(), 1e-5);
532
533 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_b").translation(), Eigen::Vector3d(1, 1.5, 0));
534 EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_b").linear()).x(), 1e-5);
535 EXPECT_NEAR(-0.2084598, Eigen::Quaterniond(state.getGlobalLinkTransform("link_b").linear()).y(), 1e-5);
536 EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_b").linear()).z(), 1e-5);
537 EXPECT_NEAR(0.97803091, Eigen::Quaterniond(state.getGlobalLinkTransform("link_b").linear()).w(), 1e-5);
538
539 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_c").translation(), Eigen::Vector3d(1.08, 1.4, 0));
540 EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_c").linear()).x(), 1e-5);
541 EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_c").linear()).y(), 1e-5);
542 EXPECT_NEAR(0.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_c").linear()).z(), 1e-5);
543 EXPECT_NEAR(1.0, Eigen::Quaterniond(state.getGlobalLinkTransform("link_c").linear()).w(), 1e-5);
544
545 EXPECT_TRUE(state.satisfiesBounds());
546
547 std::map<std::string, double> upd_a;
548 upd_a["joint_a"] = 0.2;
549 state.setVariablePositions(upd_a);
550 EXPECT_TRUE(state.satisfiesBounds(model->getJointModel("joint_a")));
551 EXPECT_NEAR(state.getVariablePosition("joint_a"), 0.2, 1e-3);
552 state.enforceBounds();
553 EXPECT_NEAR(state.getVariablePosition("joint_a"), 0.2, 1e-3);
554
555 upd_a["joint_a"] = 3.2;
556 state.setVariablePositions(upd_a);
557 EXPECT_TRUE(state.satisfiesBounds(model->getJointModel("joint_a")));
558 EXPECT_NEAR(state.getVariablePosition("joint_a"), 3.2, 1e-3);
559 state.enforceBounds();
560 EXPECT_NEAR(state.getVariablePosition("joint_a"), -3.083185, 1e-3);
561 EXPECT_TRUE(state.satisfiesBounds(model->getJointModel("joint_a")));
562
563 // mimic joints
564 state.setToDefaultValues();
565 EXPECT_TRUE(state.dirtyLinkTransforms());
566 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_c").translation(), Eigen::Vector3d(0.0, 0.4, 0));
567 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_d").translation(), Eigen::Vector3d(0.2, 0.5, 0));
568 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_e").translation(), Eigen::Vector3d(0.3, 0.6, 0));
569
570 // setVariablePosition should update corresponding mimic joints too
571 state.setVariablePosition("joint_f", 1.0);
572 EXPECT_EQ(state.getVariablePosition("joint_f"), 1.0);
573 EXPECT_EQ(state.getVariablePosition("mim_f"), 1.6);
574 EXPECT_TRUE(state.dirtyLinkTransforms());
575 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_c").translation(), Eigen::Vector3d(0.0, 0.4, 0));
576 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_d").translation(), Eigen::Vector3d(1.7, 0.5, 0));
577 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_e").translation(), Eigen::Vector3d(2.8, 0.6, 0));
578
579 ASSERT_EQ(g_mim->getVariableCount(), 2u);
580 double gstate[2];
581 state.copyJointGroupPositions(g_mim, gstate);
582
583 // setToRandomPositions() uses a different mechanism to update mimic joints
584 state.setToRandomPositions(g_mim);
585 double joint_f = state.getVariablePosition("joint_f");
586 double mim_f = state.getVariablePosition("mim_f");
587 EXPECT_NEAR(mim_f, 1.5 * joint_f + 0.1, 1e-8);
588 EXPECT_TRUE(state.dirtyLinkTransforms());
589 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_c").translation(), Eigen::Vector3d(0.0, 0.4, 0));
590 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_d").translation(), Eigen::Vector3d(0.1 + mim_f, 0.5, 0));
591 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_e").translation(),
592 Eigen::Vector3d(0.1 + mim_f + joint_f + 0.1, 0.6, 0));
593
594 // setJointGroupPositions() uses a different mechanism to update mimic joints
595 state.setJointGroupPositions(g_mim, gstate);
596 EXPECT_EQ(state.getVariablePosition("joint_f"), 1.0);
597 EXPECT_EQ(state.getVariablePosition("mim_f"), 1.6);
598 EXPECT_TRUE(state.dirtyLinkTransforms());
599 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_c").translation(), Eigen::Vector3d(0.0, 0.4, 0));
600 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_d").translation(), Eigen::Vector3d(1.7, 0.5, 0));
601 EXPECT_NEAR_TRACED(state.getGlobalLinkTransform("link_e").translation(), Eigen::Vector3d(2.8, 0.6, 0));
602}
603
604TEST_F(OneRobot, testPrintCurrentPositionWithJointLimits)
605{
606 moveit::core::RobotState state(robot_model_);
607 const moveit::core::JointModelGroup* joint_model_group = robot_model_->getJointModelGroup("base_from_base_to_e");
608 ASSERT_TRUE(joint_model_group);
609
610 state.setToDefaultValues();
611
612 std::cout << "\nVisual inspection should show NO joints out of bounds:\n";
613 state.printStatePositionsWithJointLimits(joint_model_group);
614
615 std::cout << "\nVisual inspection should show ONE joint out of bounds:\n";
616 std::vector<double> single_joint(1);
617 single_joint[0] = -1.0;
618 state.setJointPositions("joint_c", single_joint);
619 state.printStatePositionsWithJointLimits(joint_model_group);
620
621 std::cout << "\nVisual inspection should show TWO joint out of bounds:\n";
622 single_joint[0] = 1.0;
623 state.setJointPositions("joint_f", single_joint);
624 state.printStatePositionsWithJointLimits(joint_model_group);
625
626 std::cout << "\nVisual inspection should show ONE joint out of bounds:\n";
627 single_joint[0] = 0.19;
628 state.setJointPositions("joint_f", single_joint);
629 state.printStatePositionsWithJointLimits(joint_model_group);
630}
631
632TEST_F(OneRobot, testInterpolation)
633{
634 moveit::core::RobotState state_a(robot_model_);
635
636 // Interpolate with itself
637 state_a.setToDefaultValues();
638 moveit::core::RobotState state_b(state_a);
639 moveit::core::RobotState interpolated_state(state_a);
640 for (size_t i = 0; i <= 10; ++i)
641 {
642 state_a.interpolate(state_b, static_cast<double>(i) / 10., interpolated_state,
643 robot_model_->getJointModelGroup("base_from_base_to_e"));
644 EXPECT_NEAR(state_a.distance(state_b), 0, EPSILON) << "Interpolation between identical states yielded a different "
645 "state.";
646
647 for (const auto& link_name : robot_model_->getLinkModelNames())
648 {
649 EXPECT_FALSE(interpolated_state.getCollisionBodyTransform(link_name, 0).matrix().hasNaN()) << "Interpolation "
650 "between identical "
651 "states yielded "
652 "NaN value.";
653 }
654 }
655
656 // Some simple interpolation
657 std::map<std::string, double> joint_values;
658 joint_values["base_joint/x"] = 1.0;
659 joint_values["base_joint/y"] = 1.0;
660 state_a.setVariablePositions(joint_values);
661 joint_values["base_joint/x"] = 0.0;
662 joint_values["base_joint/y"] = 2.0;
663 state_b.setVariablePositions(joint_values);
664 EXPECT_NEAR(3 * std::sqrt(2), state_a.distance(state_b), EPSILON) << "Simple interpolation of base_joint failed.";
665
666 state_a.interpolate(state_b, 0.5, interpolated_state, robot_model_->getJointModelGroup("base_from_base_to_e"));
667 EXPECT_NEAR(0., state_a.distance(interpolated_state) - state_b.distance(interpolated_state), EPSILON) << "Simple "
668 "interpolati"
669 "on of "
670 "base_joint "
671 "failed.";
672 EXPECT_NEAR(0.5, interpolated_state.getVariablePosition("base_joint/x"), EPSILON) << "Simple interpolation of "
673 "base_joint failed.";
674 EXPECT_NEAR(1.5, interpolated_state.getVariablePosition("base_joint/y"), EPSILON) << "Simple interpolation of "
675 "base_joint failed.";
676 state_a.interpolate(state_b, 0.1, interpolated_state, robot_model_->getJointModelGroup("base_from_base_to_e"));
677 EXPECT_NEAR(0.9, interpolated_state.getVariablePosition("base_joint/x"), EPSILON) << "Simple interpolation of "
678 "base_joint failed.";
679 EXPECT_NEAR(1.1, interpolated_state.getVariablePosition("base_joint/y"), EPSILON) << "Simple interpolation of "
680 "base_joint failed.";
681
682 // Interpolate all the joints
683 joint_values["base_joint/x"] = 0.0;
684 joint_values["base_joint/y"] = 20.0;
685 joint_values["base_joint/theta"] = 3 * M_PI / 4;
686 joint_values["joint_a"] = -4 * M_PI / 5;
687 joint_values["joint_c"] = 0.0;
688 joint_values["joint_f"] = 1.0;
689 state_a.setVariablePositions(joint_values);
690
691 joint_values["base_joint/x"] = 10.0;
692 joint_values["base_joint/y"] = 0.0;
693 joint_values["base_joint/theta"] = -3 * M_PI / 4;
694 joint_values["joint_a"] = 4 * M_PI / 5;
695 joint_values["joint_c"] = 0.07;
696 joint_values["joint_f"] = 0.0;
697 state_b.setVariablePositions(joint_values);
698
699 for (size_t i = 0; i <= 5; ++i)
700 {
701 double t = static_cast<double>(i) / 5.;
702 state_a.interpolate(state_b, t, interpolated_state, robot_model_->getJointModelGroup("base_from_base_to_e"));
703 EXPECT_NEAR(10.0 * t, interpolated_state.getVariablePosition("base_joint/x"), EPSILON) << "Base joint "
704 "interpolation failed.";
705 EXPECT_NEAR(20.0 * (1 - t), interpolated_state.getVariablePosition("base_joint/y"), EPSILON) << "Base joint "
706 "interpolation "
707 "failed.";
708 if (t < 0.5)
709 {
710 EXPECT_NEAR(3 * M_PI / 4 + (M_PI / 2) * t, interpolated_state.getVariablePosition("base_joint/theta"), EPSILON)
711 << "Base joint theta interpolation failed.";
712 EXPECT_NEAR(-4 * M_PI / 5 - (2 * M_PI / 5) * t, interpolated_state.getVariablePosition("joint_a"), EPSILON)
713 << "Continuous joint interpolation failed.";
714 }
715 else
716 {
717 EXPECT_NEAR(-3 * M_PI / 4 - (M_PI / 2) * (1 - t), interpolated_state.getVariablePosition("base_joint/theta"),
718 EPSILON)
719 << "Base joint theta interpolation failed.";
720 EXPECT_NEAR(4 * M_PI / 5 + (2 * M_PI / 5) * (1 - t), interpolated_state.getVariablePosition("joint_a"), EPSILON)
721 << "Continuous joint interpolation failed.";
722 }
723 EXPECT_NEAR(0.07 * t, interpolated_state.getVariablePosition("joint_c"), EPSILON) << "Interpolation of joint_c "
724 "failed.";
725 EXPECT_NEAR(1 - t, interpolated_state.getVariablePosition("joint_f"), EPSILON) << "Interpolation of joint_f "
726 "failed.";
727 EXPECT_NEAR(1.5 * (1 - t) + 0.1, interpolated_state.getVariablePosition("mim_f"), EPSILON) << "Interpolation of "
728 "mimic joint mim_f "
729 "failed.";
730 }
731
732 bool nan_exception = false;
733 try
734 {
735 state_a.interpolate(state_b, 1. / 0., interpolated_state, robot_model_->getJointModelGroup("base_from_base_to_e"));
736 }
737 catch (std::exception& e)
738 {
739 std::cout << "Caught expected exception: " << e.what() << '\n';
740 nan_exception = true;
741 }
742 EXPECT_TRUE(nan_exception) << "NaN interpolation parameter did not create expected exception.";
743}
744
745TEST_F(OneRobot, rigidlyConnectedParent)
746{
747 // link_e is its own rigidly-connected parent
748 const moveit::core::LinkModel* link_e{ robot_model_->getLinkModel("link_e") };
749 EXPECT_EQ(robot_model_->getRigidlyConnectedParentLinkModel(link_e), link_e);
750
751 // link_b is rigidly connected to its parent link_a
752 const moveit::core::LinkModel* link_a{ robot_model_->getLinkModel("link_a") };
753 const moveit::core::LinkModel* link_b{ robot_model_->getLinkModel("link_b") };
754 EXPECT_EQ(robot_model_->getRigidlyConnectedParentLinkModel(link_b), link_a);
755
756 moveit::core::RobotState state(robot_model_);
757
758 EXPECT_EQ(state.getRigidlyConnectedParentLinkModel("link_b"), link_a);
759
760 // attach "object" with "subframe" to link_b
761 state.attachBody(std::make_unique<moveit::core::AttachedBody>(
762 link_b, "object", Eigen::Isometry3d::Identity(), std::vector<shapes::ShapeConstPtr>{},
763 EigenSTL::vector_Isometry3d{}, std::set<std::string>{}, trajectory_msgs::msg::JointTrajectory{},
764 moveit::core::FixedTransformsMap{ { "subframe", Eigen::Isometry3d::Identity() } }));
765
766 // RobotState's version should resolve these too
767 EXPECT_EQ(link_a, state.getRigidlyConnectedParentLinkModel("object"));
768 EXPECT_EQ(link_a, state.getRigidlyConnectedParentLinkModel("object/subframe"));
769
770 // test failure cases
771 EXPECT_EQ(nullptr, state.getRigidlyConnectedParentLinkModel("no_object"));
772 EXPECT_EQ(nullptr, state.getRigidlyConnectedParentLinkModel("object/no_subframe"));
773 EXPECT_EQ(nullptr, state.getRigidlyConnectedParentLinkModel(""));
774 EXPECT_EQ(nullptr, state.getRigidlyConnectedParentLinkModel("object/"));
775 EXPECT_EQ(nullptr, state.getRigidlyConnectedParentLinkModel("/"));
776}
777
778TEST(getJacobian, RevoluteJoints)
779{
780 // Robot URDF with four revolute joints.
781 constexpr char robot_urdf[] = R"(
782 <?xml version="1.0" ?>
783 <robot name="one_robot">
784 <link name="base_link"/>
785 <joint name="joint_a_revolute" type="revolute">
786 <axis xyz="0 0 1"/>
787 <parent link="base_link"/>
788 <child link="link_a"/>
789 <origin rpy="0 0 0" xyz="0 0 0"/>
790 <limit effort="100.0" lower="-3.14" upper="3.14" velocity="0.2"/>
791 </joint>
792 <link name="link_a"/>
793 <joint name="joint_b_revolute" type="revolute">
794 <axis xyz="0 0 1"/>
795 <parent link="link_a"/>
796 <child link="link_b"/>
797 <origin rpy="0 0 0" xyz="0.0 0.5 0"/>
798 <limit effort="100.0" lower="-3.14" upper="3.14" velocity="0.2"/>
799 </joint>
800 <link name="link_b"/>
801 <joint name="joint_c_revolute" type="revolute">
802 <axis xyz="0 1 0"/>
803 <parent link="link_b"/>
804 <child link="link_c"/>
805 <origin rpy="0 0 0" xyz="0.2 0.2 0"/>
806 <limit effort="100.0" lower="-3.14" upper="3.14" velocity="0.2"/>
807 </joint>
808 <link name="link_c"/>
809 <joint name="joint_d_revolute" type="revolute">
810 <axis xyz="1 0 0"/>
811 <parent link="link_c"/>
812 <child link="link_d"/>
813 <origin rpy="0 0 0" xyz="0.0 0.2 0.4"/>
814 <limit effort="100.0" lower="-3.14" upper="3.14" velocity="0.2"/>
815 </joint>
816 <link name="link_d"/>
817 </robot>
818 )";
819
820 constexpr char robot_srdf[] = R"xml(
821 <?xml version="1.0" ?>
822 <robot name="one_robot">
823 <group name="base_to_tip">
824 <joint name="joint_a_revolute"/>
825 <joint name="joint_b_revolute"/>
826 <joint name="joint_c_revolute"/>
827 <joint name="joint_d_revolute"/>
828 </group>
829 </robot>
830 )xml";
831
832 const urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDF(robot_urdf);
833 ASSERT_TRUE(urdf_model);
834 const auto srdf_model = std::make_shared<srdf::Model>();
835 ASSERT_TRUE(srdf_model->initString(*urdf_model, robot_srdf));
836 const auto robot_model = std::make_shared<moveit::core::RobotModel>(urdf_model, srdf_model);
837
838 moveit::core::RobotState state(robot_model);
839 const moveit::core::JointModelGroup* jmg = state.getJointModelGroup("base_to_tip");
840
841 // Some made-up numbers, at zero and non-zero robot configurations.
842 checkJacobian(state, *jmg, makeVector({ 0.0, 0.0, 0.0, 0.0 }), makeVector({ 0.1, 0.2, 0.3, 0.4 }));
843 checkJacobian(state, *jmg, makeVector({ 0.1, 0.2, 0.3, 0.4 }), makeVector({ 0.5, 0.3, 0.2, 0.1 }));
844}
845
846TEST(getJacobian, RevoluteAndPrismaticJoints)
847{
848 // Robot URDF with three revolute joints and one prismatic joint.
849 constexpr char robot_urdf[] = R"(
850 <?xml version="1.0" ?>
851 <robot name="one_robot">
852 <link name="base_link"/>
853 <joint name="joint_a_revolute" type="revolute">
854 <axis xyz="0 0 1"/>
855 <parent link="base_link"/>
856 <child link="link_a"/>
857 <origin rpy="0 0 0" xyz="0 0 0"/>
858 <limit effort="100.0" lower="-3.14" upper="3.14" velocity="0.2"/>
859 </joint>
860 <link name="link_a"/>
861 <joint name="joint_b_revolute" type="revolute">
862 <axis xyz="0 0 1"/>
863 <parent link="link_a"/>
864 <child link="link_b"/>
865 <origin rpy="0 0 0" xyz="0.0 0.5 0"/>
866 <limit effort="100.0" lower="-3.14" upper="3.14" velocity="0.2"/>
867 </joint>
868 <link name="link_b"/>
869 <joint name="joint_c_prismatic" type="prismatic">
870 <axis xyz="0 1 0"/>
871 <parent link="link_b"/>
872 <child link="link_c"/>
873 <origin rpy="0 0 0" xyz="0.2 0.2 0"/>
874 <limit effort="100.0" lower="-1.0" upper="1.0" velocity="0.2"/>
875 </joint>
876 <link name="link_c"/>
877 <joint name="joint_d_revolute" type="revolute">
878 <axis xyz="1 0 0"/>
879 <parent link="link_c"/>
880 <child link="link_d"/>
881 <origin rpy="0 0 0" xyz="0.0 0.2 0.4"/>
882 <limit effort="100.0" lower="-3.14" upper="3.14" velocity="0.2"/>
883 </joint>
884 <link name="link_d"/>
885 </robot>
886 )";
887
888 constexpr char robot_srdf[] = R"xml(
889 <?xml version="1.0" ?>
890 <robot name="one_robot">
891 <group name="base_to_tip">
892 <joint name="joint_a_revolute"/>
893 <joint name="joint_b_revolute"/>
894 <joint name="joint_c_prismatic"/>
895 <joint name="joint_d_revolute"/>
896 </group>
897 </robot>
898 )xml";
899
900 const urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDF(robot_urdf);
901 ASSERT_TRUE(urdf_model);
902 const auto srdf_model = std::make_shared<srdf::Model>();
903 ASSERT_TRUE(srdf_model->initString(*urdf_model, robot_srdf));
904 const auto robot_model = std::make_shared<moveit::core::RobotModel>(urdf_model, srdf_model);
905
906 moveit::core::RobotState state(robot_model);
907 const moveit::core::JointModelGroup* jmg = state.getJointModelGroup("base_to_tip");
908
909 // Some made-up numbers, at zero and non-zero robot configurations.
910 checkJacobian(state, *jmg, makeVector({ 0.0, 0.0, 0.0, 0.0 }), makeVector({ 0.1, 0.2, 0.3, 0.4 }));
911 checkJacobian(state, *jmg, makeVector({ 0.1, 0.2, 0.3, 0.4 }), makeVector({ 0.5, 0.3, 0.2, 0.1 }));
912}
913
914TEST(getJacobian, RevoluteAndFixedJoints)
915{
916 // Robot URDF with two revolute joints and two fixed joints.
917 constexpr char robot_urdf[] = R"(
918 <?xml version="1.0" ?>
919 <robot name="one_robot">
920 <link name="base_link"/>
921 <joint name="joint_a_revolute" type="revolute">
922 <axis xyz="0 0 1"/>
923 <parent link="base_link"/>
924 <child link="link_a"/>
925 <origin rpy="0 0 0" xyz="0 0 0"/>
926 <limit effort="100.0" lower="-3.14" upper="3.14" velocity="0.2"/>
927 </joint>
928 <link name="link_a"/>
929 <joint name="joint_b_fixed" type="fixed">
930 <parent link="link_a"/>
931 <child link="link_b"/>
932 </joint>
933 <link name="link_b"/>
934 <joint name="joint_c_fixed" type="fixed">
935 <parent link="link_b"/>
936 <child link="link_c"/>
937 </joint>
938 <link name="link_c"/>
939 <joint name="joint_d_revolute" type="revolute">
940 <axis xyz="1 0 0"/>
941 <parent link="link_c"/>
942 <child link="link_d"/>
943 <origin rpy="0 0 0" xyz="0.0 0.2 0.4"/>
944 <limit effort="100.0" lower="-3.14" upper="3.14" velocity="0.2"/>
945 </joint>
946 <link name="link_d"/>
947 </robot>
948 )";
949
950 constexpr char robot_srdf[] = R"xml(
951 <?xml version="1.0" ?>
952 <robot name="one_robot">
953 <group name="base_to_tip">
954 <joint name="joint_a_revolute"/>
955 <joint name="joint_b_fixed"/>
956 <joint name="joint_c_fixed"/>
957 <joint name="joint_d_revolute"/>
958 </group>
959 </robot>
960 )xml";
961
962 const urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDF(robot_urdf);
963 ASSERT_TRUE(urdf_model);
964 const auto srdf_model = std::make_shared<srdf::Model>();
965 ASSERT_TRUE(srdf_model->initString(*urdf_model, robot_srdf));
966 const auto robot_model = std::make_shared<moveit::core::RobotModel>(urdf_model, srdf_model);
967
968 moveit::core::RobotState state(robot_model);
969 const moveit::core::JointModelGroup* jmg = state.getJointModelGroup("base_to_tip");
970
971 // Some made-up numbers, at zero and non-zero robot configurations.
972 checkJacobian(state, *jmg, makeVector({ 0.0, 0.0 }), makeVector({ 0.1, 0.4 }));
973 checkJacobian(state, *jmg, makeVector({ 0.1, 0.4 }), makeVector({ 0.5, 0.1 }));
974}
975
976TEST(getJacobian, RevolutePlanarAndPrismaticJoints)
977{
978 // Robot URDF with two revolute joints, one planar joint and one prismatic.
979 constexpr char robot_urdf[] = R"(
980 <?xml version="1.0" ?>
981 <robot name="one_robot">
982 <link name="base_link"/>
983 <joint name="joint_a_planar" type="planar">
984 <axis xyz="0 0 1"/>
985 <parent link="base_link"/>
986 <child link="link_a"/>
987 <origin rpy="0 0 0" xyz="0 0 0"/>
988 <limit effort="100.0" lower="-1.0" upper="1.0" velocity="0.2"/>
989 </joint>
990 <link name="link_a"/>
991 <joint name="joint_b_revolute" type="revolute">
992 <axis xyz="0 0 1"/>
993 <parent link="link_a"/>
994 <child link="link_b"/>
995 <origin rpy="0 0 0" xyz="0.0 0.5 0"/>
996 <limit effort="100.0" lower="-3.14" upper="3.14" velocity="0.2"/>
997 </joint>
998 <link name="link_b"/>
999 <joint name="joint_c_prismatic" type="prismatic">
1000 <axis xyz="0 1 0"/>
1001 <parent link="link_b"/>
1002 <child link="link_c"/>
1003 <origin rpy="0 0 0" xyz="0.2 0.2 0"/>
1004 <limit effort="100.0" lower="-1.0" upper="1.0" velocity="0.2"/>
1005 </joint>
1006 <link name="link_c"/>
1007 <joint name="joint_d_revolute" type="revolute">
1008 <axis xyz="1 0 0"/>
1009 <parent link="link_c"/>
1010 <child link="link_d"/>
1011 <origin rpy="0 0 0" xyz="0.0 0.2 0.4"/>
1012 <limit effort="100.0" lower="-3.14" upper="3.14" velocity="0.2"/>
1013 </joint>
1014 <link name="link_d"/>
1015 </robot>
1016 )";
1017
1018 constexpr char robot_srdf[] = R"xml(
1019 <?xml version="1.0" ?>
1020 <robot name="one_robot">
1021 <group name="base_to_tip">
1022 <joint name="joint_a_planar"/>
1023 <joint name="joint_b_revolute"/>
1024 <joint name="joint_c_prismatic"/>
1025 <joint name="joint_d_revolute"/>
1026 </group>
1027 </robot>
1028 )xml";
1029
1030 const urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDF(robot_urdf);
1031 ASSERT_TRUE(urdf_model);
1032 const auto srdf_model = std::make_shared<srdf::Model>();
1033 ASSERT_TRUE(srdf_model->initString(*urdf_model, robot_srdf));
1034 const auto robot_model = std::make_shared<moveit::core::RobotModel>(urdf_model, srdf_model);
1035
1036 moveit::core::RobotState state(robot_model);
1037 const moveit::core::JointModelGroup* jmg = state.getJointModelGroup("base_to_tip");
1038
1039 checkJacobian(state, *jmg, makeVector({ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 }),
1040 makeVector({ 0.2, 0.05, 0.1, 0.2, 0.3, 0.4 }));
1041}
1042
1043TEST(getJacobian, GroupNotAtOrigin)
1044{
1045 // URDF with a 3 DOF robot not at the URDF origin.
1046 constexpr char robot_urdf[] = R"(
1047 <?xml version="1.0" ?>
1048 <robot name="one_robot">
1049 <link name="origin"/>
1050 <joint name="fixed_offset" type="fixed">
1051 <parent link="origin"/>
1052 <child link="link_a"/>
1053 <origin rpy="0 0 1.5707" xyz="0.0 0.0 0.0"/>
1054 </joint>
1055 <link name="link_a"/>
1056 <joint name="joint_a_revolute" type="revolute">
1057 <axis xyz="1 0 0"/>
1058 <parent link="link_a"/>
1059 <child link="link_b"/>
1060 <origin rpy="0 0 0" xyz="0.0 0.2 0.4"/>
1061 <limit effort="100.0" lower="-3.14" upper="3.14" velocity="0.2"/>
1062 </joint>
1063 <link name="link_b"/>
1064 <joint name="joint_b_revolute" type="revolute">
1065 <axis xyz="1 0 0"/>
1066 <parent link="link_b"/>
1067 <child link="link_c"/>
1068 <origin rpy="0 0 0" xyz="0.0 0.2 0.4"/>
1069 <limit effort="100.0" lower="-3.14" upper="3.14" velocity="0.2"/>
1070 </joint>
1071 <link name="link_c"/>
1072 <joint name="joint_c_revolute" type="revolute">
1073 <axis xyz="1 0 0"/>
1074 <parent link="link_c"/>
1075 <child link="link_d"/>
1076 <origin rpy="0 0 0" xyz="0.0 0.2 0.4"/>
1077 <limit effort="100.0" lower="-3.14" upper="3.14" velocity="0.2"/>
1078 </joint>
1079 <link name="link_d"/>
1080 </robot>
1081 )";
1082
1083 constexpr char robot_srdf[] = R"xml(
1084 <?xml version="1.0" ?>
1085 <robot name="one_robot">
1086 <group name="base_to_tip">
1087 <joint name="joint_a_revolute"/>
1088 <joint name="joint_b_revolute"/>
1089 <joint name="joint_c_revolute"/>
1090 </group>
1091 </robot>
1092 )xml";
1093
1094 const urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDF(robot_urdf);
1095 ASSERT_TRUE(urdf_model);
1096 const auto srdf_model = std::make_shared<srdf::Model>();
1097 ASSERT_TRUE(srdf_model->initString(*urdf_model, robot_srdf));
1098 const auto robot_model = std::make_shared<moveit::core::RobotModel>(urdf_model, srdf_model);
1099
1100 moveit::core::RobotState state(robot_model);
1101 const moveit::core::JointModelGroup* jmg = state.getJointModelGroup("base_to_tip");
1102
1103 // Some made-up numbers, at zero and non-zero robot configurations.
1104 checkJacobian(state, *jmg, makeVector({ 0.0, 0.0, 0.0 }), makeVector({ 0.1, 0.4, 0.2 }));
1105 checkJacobian(state, *jmg, makeVector({ 0.1, 0.4, 0.3 }), makeVector({ 0.5, 0.1, 0.2 }));
1106}
1107
1108TEST(getJointPositions, getFixedJointValue)
1109{
1110 // Robot URDF with two revolute joints and a final fixed joint.
1111 // Trying to get the value of the fixed joint should work and return nullptr.
1112 constexpr char robot_urdf[] = R"(
1113 <?xml version="1.0" ?>
1114 <robot name="one_robot">
1115 <link name="base_link"/>
1116 <joint name="joint_a_revolute" type="revolute">
1117 <axis xyz="0 0 1"/>
1118 <parent link="base_link"/>
1119 <child link="link_a"/>
1120 <origin rpy="0 0 0" xyz="0 0 0"/>
1121 <limit effort="100.0" lower="-3.14" upper="3.14" velocity="0.2"/>
1122 </joint>
1123 <link name="link_a"/>
1124 <joint name="joint_b_revolute" type="revolute">
1125 <axis xyz="0 0 1"/>
1126 <parent link="link_a"/>
1127 <child link="link_b"/>
1128 <origin rpy="0 0 0" xyz="0 0 0"/>
1129 <limit effort="100.0" lower="-3.14" upper="3.14" velocity="0.2"/>
1130 </joint>
1131 <link name="link_b"/>
1132 <joint name="joint_c_fixed" type="fixed">
1133 <parent link="link_b"/>
1134 <child link="link_c"/>
1135 </joint>
1136 <link name="link_c"/>
1137 </robot>
1138 )";
1139
1140 constexpr char robot_srdf[] = R"xml(
1141 <?xml version="1.0" ?>
1142 <robot name="one_robot">
1143 <group name="base_to_tip">
1144 <joint name="joint_a_revolute"/>
1145 <joint name="joint_b_revolute"/>
1146 <joint name="joint_c_fixed"/>
1147 </group>
1148 </robot>
1149 )xml";
1150
1151 const urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDF(robot_urdf);
1152 ASSERT_TRUE(urdf_model);
1153 const auto srdf_model = std::make_shared<srdf::Model>();
1154 ASSERT_TRUE(srdf_model->initString(*urdf_model, robot_srdf));
1155 const auto robot_model = std::make_shared<moveit::core::RobotModel>(urdf_model, srdf_model);
1156
1157 // Getting the value of the last fixed joint should return nullptr, since it doesn't have an active variable.
1158 moveit::core::RobotState state(robot_model);
1159 state.setToDefaultValues();
1160 const double* joint_value = state.getJointPositions("joint_c_fixed");
1161 ASSERT_EQ(joint_value, nullptr);
1162}
1163
1164int main(int argc, char** argv)
1165{
1166 testing::InitGoogleTest(&argc, argv);
1167 return RUN_ALL_TESTS();
1168}
void TearDown() override
void SetUp() override
moveit::core::RobotModelConstPtr robot_model_
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 * > & getLinkModels() const
Get the links that are part of this joint 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 > & getLinkModelNames() const
Get the names of the links that are part of this joint group.
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....
const std::vector< const JointModel * > & getJointModels() const
Get all the joints in this group (including fixed and mimic joints).
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
const LinkModel * getParentLinkModel() const
Get the link that this joint connects to. The robot is assumed to start with a joint,...
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.
double getVariableAcceleration(const std::string &variable) const
Get the acceleration of a particular variable. An exception is thrown if the variable is not known.
void attachBody(std::unique_ptr< AttachedBody > attached_body)
Add an attached body to this state.
bool getJacobian(const JointModelGroup *group, const LinkModel *link, const Eigen::Vector3d &reference_point_position, Eigen::MatrixXd &jacobian, bool use_quaternion_representation=false) const
Compute the Jacobian with reference to a particular point on a given link, for a specified group.
const double * getJointPositions(const std::string &joint_name) const
void setVariableVelocity(const std::string &variable, double value)
Set the velocity of a variable. If an unknown variable name is specified, an exception is thrown.
double getVariableVelocity(const std::string &variable) const
Get the velocity of a particular variable. An exception is thrown if the variable is not known.
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.
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...
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...
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
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 RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
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
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...
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.
bool satisfiesBounds(double margin=0.0) const
bool dirtyLinkTransforms() const
double getVariablePosition(const std::string &variable) const
Get the position of a particular variable. An exception is thrown if the variable is not known.
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.
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 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)
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
int main(int argc, char **argv)
TEST(Loading, SimpleRobot)
#define EXPECT_NEAR_TRACED(...)
TEST_F(OneRobot, setToDefaultValues)