40 #include <urdf_parser/urdf_parser.h>
42 #include <gtest/gtest.h>
43 #include <geometric_shapes/shapes.h>
48 constexpr
double M_TAU = 2 * M_PI;
55 const std::string robot_name =
"pr2";
73 ASSERT_EQ(urdf_model_->getName(),
"pr2");
74 ASSERT_EQ(srdf_model_->getName(),
"pr2");
79 auto srdf_model = std::make_shared<srdf::Model>();
85 static const std::string SMODEL1 =
"<?xml version=\"1.0\" ?>"
86 "<robot name=\"pr2\">"
87 "<virtual_joint name=\"base_joint\" child_link=\"base_footprint\" "
88 "parent_frame=\"base_footprint\" type=\"planar\"/>"
90 srdf_model->initString(*urdf_model_, SMODEL1);
96 static const std::string SMODEL2 =
"<?xml version=\"1.0\" ?>"
97 "<robot name=\"pr2\">"
98 "<virtual_joint name=\"world_joint\" child_link=\"base_footprint\" "
99 "parent_frame=\"odom_combined\" type=\"floating\"/>"
101 srdf_model->initString(*urdf_model_, SMODEL2);
110 static const std::string SMODEL1 =
"<?xml version=\"1.0\" ?>"
111 "<robot name=\"pr2\">"
112 "<virtual_joint name=\"base_joint\" child_link=\"base_footprint\" "
113 "parent_frame=\"base_footprint\" type=\"planar\"/>"
114 "<group name=\"left_arm_base_tip\">"
115 "<chain base_link=\"monkey_base\" tip_link=\"monkey_tip\"/>"
117 "<group name=\"left_arm_joints\">"
118 "<joint name=\"l_monkey_pan_joint\"/>"
119 "<joint name=\"l_monkey_fles_joint\"/>"
123 auto srdf_model = std::make_shared<srdf::Model>();
124 srdf_model->initString(*urdf_model_, SMODEL1);
128 ASSERT_TRUE(left_arm_base_tip_group ==
nullptr);
131 ASSERT_TRUE(left_arm_joints_group ==
nullptr);
133 static const std::string SMODEL2 =
"<?xml version=\"1.0\" ?>"
134 "<robot name=\"pr2\">"
135 "<virtual_joint name=\"base_joint\" child_link=\"base_footprint\" "
136 "parent_frame=\"base_footprint\" type=\"planar\"/>"
137 "<group name=\"left_arm_base_tip\">"
138 "<chain base_link=\"torso_lift_link\" tip_link=\"l_wrist_roll_link\"/>"
140 "<group name=\"left_arm_joints\">"
141 "<joint name=\"l_shoulder_pan_joint\"/>"
142 "<joint name=\"l_shoulder_lift_joint\"/>"
143 "<joint name=\"l_upper_arm_roll_joint\"/>"
144 "<joint name=\"l_elbow_flex_joint\"/>"
145 "<joint name=\"l_forearm_roll_joint\"/>"
146 "<joint name=\"l_wrist_flex_joint\"/>"
147 "<joint name=\"l_wrist_roll_joint\"/>"
150 srdf_model->initString(*urdf_model_, SMODEL2);
152 auto robot_model2 = std::make_shared<moveit::core::RobotModel>(urdf_model_, srdf_model);
154 left_arm_base_tip_group = robot_model2->getJointModelGroup(
"left_arm_base_tip");
155 ASSERT_TRUE(left_arm_base_tip_group !=
nullptr);
157 left_arm_joints_group = robot_model2->getJointModelGroup(
"left_arm_joints");
158 ASSERT_TRUE(left_arm_joints_group !=
nullptr);
166 EXPECT_EQ(robot_model2->getVariableNames().size(), robot_model2->getVariableCount());
168 bool found_shoulder_pan_link =
false;
169 bool found_wrist_roll_link =
false;
172 if (link_model->getName() ==
"l_shoulder_pan_link")
174 EXPECT_TRUE(!found_shoulder_pan_link);
175 found_shoulder_pan_link =
true;
177 if (link_model->getName() ==
"l_wrist_roll_link")
179 EXPECT_TRUE(!found_wrist_roll_link);
180 found_wrist_roll_link =
true;
182 EXPECT_TRUE(link_model->getName() !=
"torso_lift_link");
184 EXPECT_TRUE(found_shoulder_pan_link);
185 EXPECT_TRUE(found_wrist_roll_link);
189 std::map<std::string, double> jv;
190 jv[
"base_joint/x"] = 0.433;
191 jv[
"base_joint/theta"] = -0.5;
193 moveit_msgs::msg::RobotState robot_state;
202 EXPECT_NEAR(v1[i], v2[i], 1e-5);
221 auto model = std::make_shared<moveit::core::RobotModel>(urdf_model_, srdf_model_);
222 EXPECT_TRUE(model->getLinkModel(
"r_gripper_palm_link")->getAssociatedFixedTransforms().size() > 1);
227 auto robot_model = std::make_shared<moveit::core::RobotModel>(urdf_model_, srdf_model_);
235 const auto identity = Eigen::Isometry3d::Identity();
236 std::vector<shapes::ShapeConstPtr>
shapes;
237 EigenSTL::vector_Isometry3d poses;
238 shapes::Shape* shape =
new shapes::Box(.1, .1, .1);
239 shapes.push_back(shapes::ShapeConstPtr(shape));
240 poses.push_back(identity);
241 std::set<std::string> touch_links;
243 trajectory_msgs::msg::JointTrajectory empty_state;
245 ks.
attachBody(std::make_unique<moveit::core::AttachedBody>(robot_model->getLinkModel(
"r_gripper_palm_link"),
"box",
246 identity,
shapes, poses, touch_links, empty_state));
248 std::vector<const moveit::core::AttachedBody*> attached_bodies_1;
250 ASSERT_EQ(attached_bodies_1.size(), 1u);
252 std::vector<const moveit::core::AttachedBody*> attached_bodies_2;
255 ASSERT_EQ(attached_bodies_2.size(), 1u);
258 attached_bodies_1.clear();
260 ASSERT_EQ(attached_bodies_1.size(), 0u);
263 attached_bodies_2.clear();
265 ASSERT_EQ(attached_bodies_2.size(), 0u);
270 auto robot_model = std::make_shared<moveit::core::RobotModel>(urdf_model_, srdf_model_);
275 std::vector<shapes::ShapeConstPtr>
shapes;
276 EigenSTL::vector_Isometry3d poses;
277 shapes::Shape* shape =
new shapes::Box(.1, .1, .1);
278 shapes.push_back(shapes::ShapeConstPtr(shape));
279 poses.push_back(Eigen::Isometry3d::Identity());
280 std::set<std::string> touch_links;
281 Eigen::Isometry3d pose_a = Eigen::Isometry3d::Identity();
282 Eigen::Isometry3d pose_b = Eigen::Isometry3d(Eigen::Translation3d(0, 0, 1));
284 subframes[
"frame1"] = Eigen::Isometry3d(Eigen::Translation3d(0, 0, 1));
286 trajectory_msgs::msg::JointTrajectory empty_state;
287 ks.
attachBody(std::make_unique<moveit::core::AttachedBody>(robot_model->getLinkModel(
"r_gripper_palm_link"),
"boxA",
288 pose_a,
shapes, poses, touch_links, empty_state,
290 ks.
attachBody(std::make_unique<moveit::core::AttachedBody>(robot_model->getLinkModel(
"r_gripper_palm_link"),
"boxB",
291 pose_b,
shapes, poses, touch_links, empty_state,
297 EXPECT_EQ(0.0,
p(2, 3));
299 EXPECT_EQ(1.0,
p(2, 3));
302 Eigen::Isometry3d p2;
306 EXPECT_TRUE(
p.isApprox(p2,
EPSILON));
309 moveit_msgs::msg::RobotState msg;
315 Eigen::Isometry3d pose_c = Eigen::Isometry3d(Eigen::Translation3d(0.1, 0.2, 0.3)) *
316 Eigen::AngleAxisd(0.1 *
M_TAU, Eigen::Vector3d::UnitX()) *
317 Eigen::AngleAxisd(0.2 *
M_TAU, Eigen::Vector3d::UnitY()) *
318 Eigen::AngleAxisd(0.4 *
M_TAU, Eigen::Vector3d::UnitZ());
319 Eigen::Quaterniond q(pose_c.linear());
320 moveit_msgs::msg::AttachedCollisionObject new_aco = msg.attached_collision_objects[0];
321 new_aco.object.id =
"boxC";
322 new_aco.object.header.frame_id =
"r_shoulder_pan_link";
323 new_aco.object.pose.position.x = pose_c.translation()[0];
324 new_aco.object.pose.position.y = pose_c.translation()[1];
325 new_aco.object.pose.position.z = pose_c.translation()[2];
326 new_aco.object.pose.orientation.x = q.vec()[0];
327 new_aco.object.pose.orientation.y = q.vec()[1];
328 new_aco.object.pose.orientation.z = q.vec()[2];
329 new_aco.object.pose.orientation.w = q.w();
330 msg.attached_collision_objects.push_back(new_aco);
335 Eigen::Isometry3d p_original, p_reconverted;
338 EXPECT_TRUE(p_original.isApprox(p_reconverted,
EPSILON));
341 Eigen::Isometry3d p_link, p_header_frame;
345 p = p_header_frame * pose_c;
347 EXPECT_TRUE(
p.isApprox(p2,
EPSILON));
349 p = p_link.inverse() * p_header_frame * pose_c;
351 EXPECT_TRUE(
p.isApprox(p2,
EPSILON));
354 int main(
int argc,
char** argv)
356 testing::InitGoogleTest(&argc, argv);
357 return RUN_ALL_TESTS();
moveit::core::RobotModelPtr robot_model_
urdf::ModelInterfaceSharedPtr urdf_model_
srdf::ModelSharedPtr srdf_model_
const Eigen::Isometry3d & getGlobalPose() const
Get the pose of the attached body, relative to the world.
const EigenSTL::vector_Isometry3d & getShapePosesInLinkFrame() const
Get the fixed transforms (the transforms to the shapes of this body, relative to the link)....
const Eigen::Isometry3d & getPose() const
Get the pose of the attached body relative to the parent link.
const std::vector< const JointModel * > & getJointModels() const
Get all the joints in this group (including fixed and mimic joints).
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 > & getVariableNames() const
Get the names of the variables that make up the joints included in this group. The number of returned...
const std::vector< std::string > & getSubgroupNames() const
Get the names of the groups that are subsets of this one (in terms of joints set)
bool isSubgroup(const std::string &group) const
Check if the joints of group group are a subset of the joints in this group.
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
const std::string & getModelFrame() const
Get the frame in which the transforms for this model are computed (when using a RobotState)....
const JointModel * getRootJoint() const
Get the root joint. There will be one root joint unless the model is empty. This is either extracted ...
const JointModelGroup * getJointModelGroup(const std::string &name) const
Get a joint group from this model (by name)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state....
void attachBody(std::unique_ptr< AttachedBody > attached_body)
Add an attached body to this state.
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
bool clearAttachedBody(const std::string &id)
Remove the attached body named id. Return false if the object was not found (and thus not removed)....
double * getVariablePositions()
Get a raw pointer to the positions of the variables stored in this state. Use carefully....
const Eigen::Isometry3d & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
const AttachedBody * getAttachedBody(const std::string &name) const
Get the attached body named name. Return nullptr if not found.
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.
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
srdf::ModelSharedPtr loadSRDFModel(const std::string &robot_name)
Loads an SRDF Model from moveit_resources.
urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string &robot_name)
Loads a URDF Model Interface from moveit_resources.
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...
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
int main(int argc, char **argv)
TEST_F(LoadPlanningModelsPr2, InitOK)