38#include <gtest/gtest.h>
42#include <urdf_parser/urdf_parser.h>
44static const char*
const URDF_STR =
45 "<?xml version=\"1.0\" ?>"
46 "<robot name=\"one_robot\">"
47 "<link name=\"base_link\">"
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\"/>"
53 " <collision name=\"my_collision\">"
54 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
56 " <box size=\"1 2 1\" />"
60 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
62 " <box size=\"1 2 1\" />"
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 \"/>"
72 "<link name=\"link_a\">"
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\"/>"
79 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
81 " <box size=\"1 2 1\" />"
85 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
87 " <box size=\"1 2 1\" />"
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 \"/>"
96 "<link name=\"link_b\">"
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\"/>"
103 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
105 " <box size=\"1 2 1\" />"
109 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
111 " <box size=\"1 2 1\" />"
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 \"/>"
124 "<link name=\"link_c\">"
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\"/>"
131 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
133 " <box size=\"1 2 1\" />"
137 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
139 " <box size=\"1 2 1\" />"
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\"/>"
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 \"/>"
158 "<link name=\"link_d\">"
160 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
162 " <box size=\"1 2 1\" />"
166 " <origin rpy=\"0 1 0\" xyz=\"0 0.1 0\"/>"
168 " <box size=\"1 2 1\" />"
172 "<link name=\"link_e\">"
174 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
176 " <box size=\"1 2 1\" />"
180 " <origin rpy=\"0 1 0\" xyz=\"0 0.1 0\"/>"
182 " <box size=\"1 2 1\" />"
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\"/>"
197 "<group name=\"mim_joints\">"
198 "<joint name=\"joint_f\"/>"
199 "<joint name=\"mim_f\"/>"
201 "<group name=\"base_with_subgroups\">"
202 "<group name=\"base_from_base_to_tip\"/>"
203 "<joint name=\"joint_c\"/>"
205 "<group name=\"base_from_base_to_tip\">"
206 "<chain base_link=\"base_link\" tip_link=\"link_b\"/>"
207 "<joint name=\"base_joint\"/>"
220static moveit::core::RobotModelPtr getModel()
222 static moveit::core::RobotModelPtr model;
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);
236 moveit::core::RobotModelPtr model = getModel();
244 auto ls4 = std::make_shared<robot_interaction::LockedRobotState>(model);
248TEST(LockedRobotState, URDF_sanity)
250 moveit::core::RobotModelPtr model = getModel();
277TEST(LockedRobotState, robotStateChanged)
279 moveit::core::RobotModelPtr model = getModel();
283 EXPECT_EQ(ls1.
cnt_, 0);
291 EXPECT_EQ(ls1.
cnt_, 1);
294 EXPECT_EQ(ls1.
cnt_, 2);
297 EXPECT_EQ(ls1.
cnt_, 3);
329 std::mutex cnt_lock_;
339 moveit::core::RobotStateConstPtr s = locked_state.
getState();
352 EXPECT_EQ(s->getVariablePositions()[
MIM_F], s->getVariablePositions()[
JOINT_F] * 1.5 + 0.1);
356 EXPECT_NE(cp1.getVariablePositions(), cp2.getVariablePositions());
357 EXPECT_NE(cp1.getVariablePositions(), s->getVariablePositions());
359 int cnt = cp1.getVariableCount();
360 for (
int i = 0; i < cnt; ++i)
362 EXPECT_EQ(cp1.getVariablePositions()[i], cp2.getVariablePositions()[i]);
363 EXPECT_EQ(cp1.getVariablePositions()[i], s->getVariablePositions()[i]);
367 EXPECT_EQ(s->getVariablePositions()[
MIM_F], s->getVariablePositions()[
JOINT_F] * 1.5 + 0.1);
376 for (
int loops = 0; loops < 100; ++loops)
378 checkState(*locked_state);
395 for (
int loops = 0; loops < 100; ++loops)
412 checkState(*locked_state);
433 for (
int loops = 0; loops < 100; ++loops)
445 checkState(*locked_state);
459 for (
int i = 0; counters[i]; ++i)
461 if (counters[i][0] < max)
466 checkState(*locked_state);
467 checkState(*locked_state);
478static void runThreads(
int ncheck,
int nset,
int nmod)
482 moveit::core::RobotModelPtr model = getModel();
485 int num = ncheck + nset + nmod;
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];
497 for (
int i = 0; i < ncheck; ++i)
500 counters[p] = &cnt[p];
507 for (
int i = 0; i < nset; ++i)
510 counters[p] = &cnt[p];
517 for (
int i = 0; i < nmod; ++i)
520 counters[p] = &cnt[p];
527 counters[p] =
nullptr;
534 for (
int i = 0; i < p; ++i)
536 if (threads[i]->joinable())
541 if (wthread.joinable())
547 for (
int i = 0; i < p; ++i)
564#define OPT_TEST(F, N) TEST(F, N)
566#define OPT_TEST(F, N) TEST(F, DISABLED_##N)
631 testing::InitGoogleTest(&argc, argv);
632 return RUN_ALL_TESTS();
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.
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)
TEST(LockedRobotState, load)