moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
locked_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 * Copyright (c) 2014, SRI International
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of Willow Garage nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *********************************************************************/
35
36/* Author: Acorn Pooley, Ioan Sucan */
37
38#include <gtest/gtest.h>
42#include <urdf_parser/urdf_parser.h>
43
44static const char* const URDF_STR =
45 "<?xml version=\"1.0\" ?>"
46 "<robot name=\"one_robot\">"
47 "<link name=\"base_link\">"
48 " <inertial>"
49 " <mass value=\"2.81\"/>"
50 " <origin rpy=\"0 0 0\" xyz=\"0.0 0.0 .0\"/>"
51 " <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>"
52 " </inertial>"
53 " <collision name=\"my_collision\">"
54 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
55 " <geometry>"
56 " <box size=\"1 2 1\" />"
57 " </geometry>"
58 " </collision>"
59 " <visual>"
60 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
61 " <geometry>"
62 " <box size=\"1 2 1\" />"
63 " </geometry>"
64 " </visual>"
65 "</link>"
66 "<joint name=\"joint_a\" type=\"continuous\">"
67 " <axis xyz=\"0 0 1\"/>"
68 " <parent link=\"base_link\"/>"
69 " <child link=\"link_a\"/>"
70 " <origin rpy=\" 0.0 0 0 \" xyz=\"0.0 0 0 \"/>"
71 "</joint>"
72 "<link name=\"link_a\">"
73 " <inertial>"
74 " <mass value=\"1.0\"/>"
75 " <origin rpy=\"0 0 0\" xyz=\"0.0 0.0 .0\"/>"
76 " <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>"
77 " </inertial>"
78 " <collision>"
79 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
80 " <geometry>"
81 " <box size=\"1 2 1\" />"
82 " </geometry>"
83 " </collision>"
84 " <visual>"
85 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
86 " <geometry>"
87 " <box size=\"1 2 1\" />"
88 " </geometry>"
89 " </visual>"
90 "</link>"
91 "<joint name=\"joint_b\" type=\"fixed\">"
92 " <parent link=\"link_a\"/>"
93 " <child link=\"link_b\"/>"
94 " <origin rpy=\" 0.0 -0.42 0 \" xyz=\"0.0 0.5 0 \"/>"
95 "</joint>"
96 "<link name=\"link_b\">"
97 " <inertial>"
98 " <mass value=\"1.0\"/>"
99 " <origin rpy=\"0 0 0\" xyz=\"0.0 0.0 .0\"/>"
100 " <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>"
101 " </inertial>"
102 " <collision>"
103 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
104 " <geometry>"
105 " <box size=\"1 2 1\" />"
106 " </geometry>"
107 " </collision>"
108 " <visual>"
109 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
110 " <geometry>"
111 " <box size=\"1 2 1\" />"
112 " </geometry>"
113 " </visual>"
114 "</link>"
115 " <joint name=\"joint_c\" type=\"prismatic\">"
116 " <axis xyz=\"1 0 0\"/>"
117 " <limit effort=\"100.0\" lower=\"0.0\" upper=\"0.09\" velocity=\"0.2\"/>"
118 " <safety_controller k_position=\"20.0\" k_velocity=\"500.0\" "
119 "soft_lower_limit=\"0.0\" soft_upper_limit=\"0.089\"/>"
120 " <parent link=\"link_b\"/>"
121 " <child link=\"link_c\"/>"
122 " <origin rpy=\" 0.0 0.42 0.0 \" xyz=\"0.0 -0.1 0 \"/>"
123 " </joint>"
124 "<link name=\"link_c\">"
125 " <inertial>"
126 " <mass value=\"1.0\"/>"
127 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 .0\"/>"
128 " <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>"
129 " </inertial>"
130 " <collision>"
131 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
132 " <geometry>"
133 " <box size=\"1 2 1\" />"
134 " </geometry>"
135 " </collision>"
136 " <visual>"
137 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
138 " <geometry>"
139 " <box size=\"1 2 1\" />"
140 " </geometry>"
141 " </visual>"
142 "</link>"
143 " <joint name=\"mim_f\" type=\"prismatic\">"
144 " <axis xyz=\"1 0 0\"/>"
145 " <limit effort=\"100.0\" lower=\"0.0\" upper=\"0.19\" velocity=\"0.2\"/>"
146 " <parent link=\"link_c\"/>"
147 " <child link=\"link_d\"/>"
148 " <origin rpy=\" 0.0 0.1 0.0 \" xyz=\"0.1 0.1 0 \"/>"
149 " <mimic joint=\"joint_f\" multiplier=\"1.5\" offset=\"0.1\"/>"
150 " </joint>"
151 " <joint name=\"joint_f\" type=\"prismatic\">"
152 " <axis xyz=\"1 0 0\"/>"
153 " <limit effort=\"100.0\" lower=\"0.0\" upper=\"0.19\" velocity=\"0.2\"/>"
154 " <parent link=\"link_d\"/>"
155 " <child link=\"link_e\"/>"
156 " <origin rpy=\" 0.0 0.1 0.0 \" xyz=\"0.1 0.1 0 \"/>"
157 " </joint>"
158 "<link name=\"link_d\">"
159 " <collision>"
160 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
161 " <geometry>"
162 " <box size=\"1 2 1\" />"
163 " </geometry>"
164 " </collision>"
165 " <visual>"
166 " <origin rpy=\"0 1 0\" xyz=\"0 0.1 0\"/>"
167 " <geometry>"
168 " <box size=\"1 2 1\" />"
169 " </geometry>"
170 " </visual>"
171 "</link>"
172 "<link name=\"link_e\">"
173 " <collision>"
174 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
175 " <geometry>"
176 " <box size=\"1 2 1\" />"
177 " </geometry>"
178 " </collision>"
179 " <visual>"
180 " <origin rpy=\"0 1 0\" xyz=\"0 0.1 0\"/>"
181 " <geometry>"
182 " <box size=\"1 2 1\" />"
183 " </geometry>"
184 " </visual>"
185 "</link>"
186 "</robot>";
187
188static const char* const SRDF_STR =
189 "<?xml version=\"1.0\" ?>"
190 "<robot name=\"one_robot\">"
191 "<virtual_joint name=\"base_joint\" child_link=\"base_link\" parent_frame=\"odom_combined\" type=\"planar\"/>"
192 "<group name=\"base_from_joints\">"
193 "<joint name=\"base_joint\"/>"
194 "<joint name=\"joint_a\"/>"
195 "<joint name=\"joint_c\"/>"
196 "</group>"
197 "<group name=\"mim_joints\">"
198 "<joint name=\"joint_f\"/>"
199 "<joint name=\"mim_f\"/>"
200 "</group>"
201 "<group name=\"base_with_subgroups\">"
202 "<group name=\"base_from_base_to_tip\"/>"
203 "<joint name=\"joint_c\"/>"
204 "</group>"
205 "<group name=\"base_from_base_to_tip\">"
206 "<chain base_link=\"base_link\" tip_link=\"link_b\"/>"
207 "<joint name=\"base_joint\"/>"
208 "</group>"
209 "</robot>";
210
211// index of joints from URDF
212enum
213{
216 MIM_F = 5,
217 JOINT_F = 6
219
220static moveit::core::RobotModelPtr getModel()
221{
222 static moveit::core::RobotModelPtr model;
223 if (!model)
224 {
225 urdf::ModelInterfaceSharedPtr urdf(urdf::parseURDF(URDF_STR));
226 auto srdf = std::make_shared<srdf::Model>();
227 srdf->initString(*urdf, SRDF_STR);
228 model = std::make_shared<moveit::core::RobotModel>(urdf, srdf);
229 }
230 return model;
231}
232
233// Test constructors and robot model loading
234TEST(LockedRobotState, load)
235{
236 moveit::core::RobotModelPtr model = getModel();
237
239
240 moveit::core::RobotState state2(model);
241 state2.setToDefaultValues();
243
244 auto ls4 = std::make_shared<robot_interaction::LockedRobotState>(model);
245}
246
247// sanity test the URDF and enum
248TEST(LockedRobotState, URDF_sanity)
249{
250 moveit::core::RobotModelPtr model = getModel();
252
253 EXPECT_EQ(ls1.getState()->getVariableNames()[JOINT_A], "joint_a");
254}
255
256// A superclass to test the robotStateChanged() virtual method
258{
259public:
260 Super1(const moveit::core::RobotModelPtr& model) : LockedRobotState(model), cnt_(0)
261 {
262 }
263
264 void robotStateChanged() override
265 {
266 cnt_++;
267 }
268
269 int cnt_;
270};
271
272static void modify1(moveit::core::RobotState* state)
273{
274 state->setVariablePosition(JOINT_A, 0.00006);
275}
276
277TEST(LockedRobotState, robotStateChanged)
278{
279 moveit::core::RobotModelPtr model = getModel();
280
281 Super1 ls1(model);
282
283 EXPECT_EQ(ls1.cnt_, 0);
284
286 cp1.setVariablePosition(JOINT_A, 0.00001);
287 cp1.setVariablePosition(JOINT_C, 0.00002);
288 cp1.setVariablePosition(JOINT_F, 0.00003);
289 ls1.setState(cp1);
290
291 EXPECT_EQ(ls1.cnt_, 1);
292
293 ls1.modifyState(modify1);
294 EXPECT_EQ(ls1.cnt_, 2);
295
296 ls1.modifyState(modify1);
297 EXPECT_EQ(ls1.cnt_, 3);
298}
299
300// Class for testing LockedRobotState in multithreaded environment.
301// Contains thread functions for modifying/checking a LockedRobotState.
303{
304public:
305 MyInfo() : quit_(false)
306 {
307 }
308
309 // Thread that repeatedly sets state to different values
310 void setThreadFunc(robot_interaction::LockedRobotState* locked_state, int* counter, double offset);
311
312 // Thread that repeatedly modifies state with different values
313 void modifyThreadFunc(robot_interaction::LockedRobotState* locked_state, int* counter, double offset);
314
315 // Thread that repeatedly checks that state is valid (not half-updated)
316 void checkThreadFunc(robot_interaction::LockedRobotState* locked_state, int* counter);
317
318 // Thread that waits for other threads to complete
319 void waitThreadFunc(robot_interaction::LockedRobotState* locked_state, int** counters, int max);
320
321private:
322 // helper function for modifyThreadFunc
323 void modifyFunc(moveit::core::RobotState& state, double val);
324
325 // Checks state for validity and self-consistancy.
326 void checkState(robot_interaction::LockedRobotState& locked_state);
327
328 // mutex protects quit_ and counter variables
329 std::mutex cnt_lock_;
330
331 // set to true by waitThreadFunc() when all counters have reached at least
332 // max.
333 bool quit_;
334};
335
336// Check the state. It should always be valid.
337void MyInfo::checkState(robot_interaction::LockedRobotState& locked_state)
338{
339 moveit::core::RobotStateConstPtr s = locked_state.getState();
340
342
343 // take some time
344 cnt_lock_.lock();
345 cnt_lock_.unlock();
346 cnt_lock_.lock();
347 cnt_lock_.unlock();
348 cnt_lock_.lock();
349 cnt_lock_.unlock();
350
351 // check mim_f == joint_f
352 EXPECT_EQ(s->getVariablePositions()[MIM_F], s->getVariablePositions()[JOINT_F] * 1.5 + 0.1);
353
355
356 EXPECT_NE(cp1.getVariablePositions(), cp2.getVariablePositions());
357 EXPECT_NE(cp1.getVariablePositions(), s->getVariablePositions());
358
359 int cnt = cp1.getVariableCount();
360 for (int i = 0; i < cnt; ++i)
361 {
362 EXPECT_EQ(cp1.getVariablePositions()[i], cp2.getVariablePositions()[i]);
363 EXPECT_EQ(cp1.getVariablePositions()[i], s->getVariablePositions()[i]);
364 }
365
366 // check mim_f == joint_f
367 EXPECT_EQ(s->getVariablePositions()[MIM_F], s->getVariablePositions()[JOINT_F] * 1.5 + 0.1);
368}
369
370// spin, checking the state
372{
373 bool go = true;
374 while (go)
375 {
376 for (int loops = 0; loops < 100; ++loops)
377 {
378 checkState(*locked_state);
379 }
380
381 cnt_lock_.lock();
382 go = !quit_;
383 ++*counter;
384 cnt_lock_.unlock();
385 }
386}
387
388// spin, setting the state to different values
389void MyInfo::setThreadFunc(robot_interaction::LockedRobotState* locked_state, int* counter, double offset)
390{
391 bool go = true;
392 while (go)
393 {
394 double val = offset;
395 for (int loops = 0; loops < 100; ++loops)
396 {
397 val += 0.0001;
398 moveit::core::RobotState cp1(*locked_state->getState());
399
400 cp1.setVariablePosition(JOINT_A, val + 0.00001);
401 cp1.setVariablePosition(JOINT_C, val + 0.00002);
402 cp1.setVariablePosition(JOINT_F, val + 0.00003);
403
404 locked_state->setState(cp1);
405 }
406
407 cnt_lock_.lock();
408 go = !quit_;
409 ++*counter;
410 cnt_lock_.unlock();
411
412 checkState(*locked_state);
413
414 val += 0.000001;
415 }
416}
417
418// modify the state in place. Used by MyInfo::modifyThreadFunc()
419void MyInfo::modifyFunc(moveit::core::RobotState& state, double val)
420{
421 state.setVariablePosition(JOINT_A, val + 0.00001);
422 state.setVariablePosition(JOINT_C, val + 0.00002);
423 state.setVariablePosition(JOINT_F, val + 0.00003);
424}
425
426// spin, modifying the state to different values
427void MyInfo::modifyThreadFunc(robot_interaction::LockedRobotState* locked_state, int* counter, double offset)
428{
429 bool go = true;
430 while (go)
431 {
432 double val = offset;
433 for (int loops = 0; loops < 100; ++loops)
434 {
435 val += 0.0001;
436
437 locked_state->modifyState([this, val](moveit::core::RobotState* state) { modifyFunc(*state, val); });
438 }
439
440 cnt_lock_.lock();
441 go = !quit_;
442 ++*counter;
443 cnt_lock_.unlock();
444
445 checkState(*locked_state);
446
447 val += 0.000001;
448 }
449}
450
451// spin until all counters reach at least max
452void MyInfo::waitThreadFunc(robot_interaction::LockedRobotState* locked_state, int** counters, int max)
453{
454 bool go = true;
455 while (go)
456 {
457 go = false;
458 cnt_lock_.lock();
459 for (int i = 0; counters[i]; ++i)
460 {
461 if (counters[i][0] < max)
462 go = true;
463 }
464 cnt_lock_.unlock();
465
466 checkState(*locked_state);
467 checkState(*locked_state);
468 }
469 cnt_lock_.lock();
470 quit_ = true;
471 cnt_lock_.unlock();
472}
473
474// Run several threads and ensure they modify the state consistently
475// ncheck - # of checkThreadFunc threads to run
476// nset - # of setThreadFunc threads to run
477// nmod - # of modifyThreadFunc threads to run
478static void runThreads(int ncheck, int nset, int nmod)
479{
480 MyInfo info;
481
482 moveit::core::RobotModelPtr model = getModel();
484
485 int num = ncheck + nset + nmod;
486
487 typedef int* int_ptr;
488 typedef std::thread* thread_ptr;
489 int* cnt = new int[num];
490 int_ptr* counters = new int_ptr[num + 1];
491 thread_ptr* threads = new thread_ptr[num];
492
493 int p = 0;
494 double val = 0.1;
495
496 // These threads check the validity of the RobotState
497 for (int i = 0; i < ncheck; ++i)
498 {
499 cnt[p] = 0;
500 counters[p] = &cnt[p];
501 threads[p] = new std::thread(&MyInfo::checkThreadFunc, &info, &ls1, &cnt[p]);
502 val += 0.1;
503 p++;
504 }
505
506 // These threads set the RobotState to new values
507 for (int i = 0; i < nset; ++i)
508 {
509 cnt[p] = 0;
510 counters[p] = &cnt[p];
511 threads[p] = new std::thread(&MyInfo::setThreadFunc, &info, &ls1, &cnt[p], val);
512 val += 0.1;
513 p++;
514 }
515
516 // These threads modify the RobotState in place
517 for (int i = 0; i < nmod; ++i)
518 {
519 cnt[p] = 0;
520 counters[p] = &cnt[p];
521 threads[p] = new std::thread(&MyInfo::modifyThreadFunc, &info, &ls1, &cnt[p], val);
522 val += 0.1;
523 p++;
524 }
525
526 ASSERT_EQ(p, num);
527 counters[p] = nullptr;
528
529 // this thread waits for all the other threads to make progress, then stops
530 // everything.
531 std::thread wthread(&MyInfo::waitThreadFunc, &info, &ls1, counters, 1000);
532
533 // wait for all threads to finish
534 for (int i = 0; i < p; ++i)
535 {
536 if (threads[i]->joinable())
537 {
538 threads[i]->join();
539 }
540 }
541 if (wthread.joinable())
542 {
543 wthread.join();
544 }
545
546 // clean up
547 for (int i = 0; i < p; ++i)
548 {
549 delete threads[i];
550 }
551 delete[] cnt;
552 delete[] counters;
553 delete[] threads;
554}
555
556TEST(LockedRobotState, set1)
557{
558 runThreads(1, 1, 0);
559}
560
561// skip all more complex locking checks when optimizations are disabled
562// they can easily outrun 20 minutes with Debug builds
563#ifdef NDEBUG
564#define OPT_TEST(F, N) TEST(F, N)
565#else
566#define OPT_TEST(F, N) TEST(F, DISABLED_##N)
567#endif
568
569OPT_TEST(LockedRobotState, set2)
570{
571 runThreads(1, 2, 0);
572}
573
574OPT_TEST(LockedRobotState, set3)
575{
576 runThreads(1, 3, 0);
577}
578
579OPT_TEST(LockedRobotState, mod1)
580{
581 runThreads(1, 0, 1);
582}
583
584OPT_TEST(LockedRobotState, mod2)
585{
586 runThreads(1, 0, 1);
587}
588
589OPT_TEST(LockedRobotState, mod3)
590{
591 runThreads(1, 0, 1);
592}
593
594OPT_TEST(LockedRobotState, set1mod1)
595{
596 runThreads(1, 1, 1);
597}
598
599OPT_TEST(LockedRobotState, set2mod1)
600{
601 runThreads(1, 2, 1);
602}
603
604OPT_TEST(LockedRobotState, set1mod2)
605{
606 runThreads(1, 1, 2);
607}
608
609OPT_TEST(LockedRobotState, set3mod1)
610{
611 runThreads(1, 3, 1);
612}
613
614OPT_TEST(LockedRobotState, set1mod3)
615{
616 runThreads(1, 1, 3);
617}
618
619OPT_TEST(LockedRobotState, set3mod3)
620{
621 runThreads(1, 3, 3);
622}
623
624OPT_TEST(LockedRobotState, set3mod3c3)
625{
626 runThreads(3, 3, 3);
627}
628
629int main(int argc, char** argv)
630{
631 testing::InitGoogleTest(&argc, argv);
632 return RUN_ALL_TESTS();
633}
void modifyThreadFunc(robot_interaction::LockedRobotState *locked_state, int *counter, double offset)
void waitThreadFunc(robot_interaction::LockedRobotState *locked_state, int **counters, int max)
void checkThreadFunc(robot_interaction::LockedRobotState *locked_state, int *counter)
void setThreadFunc(robot_interaction::LockedRobotState *locked_state, int *counter, double offset)
Super1(const moveit::core::RobotModelPtr &model)
void robotStateChanged() override
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
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 setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
Maintain a RobotState in a multithreaded environment.
moveit::core::RobotStateConstPtr getState() const
get read-only access to the state.
LockedRobotState(const moveit::core::RobotState &state)
void modifyState(const ModifyStateFunction &modify)
void setState(const moveit::core::RobotState &state)
Set the state to the new value.
int main(int argc, char **argv)
#define OPT_TEST(F, N)
TEST(LockedRobotState, load)