$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00037 #include <planning_models/kinematic_model.h> 00038 #include <planning_models/kinematic_state.h> 00039 #include <gtest/gtest.h> 00040 #include <sstream> 00041 #include <ctype.h> 00042 00043 static bool sameStringIgnoringWS(const std::string &s1, const std::string &s2) 00044 { 00045 unsigned int i1 = 0; 00046 unsigned int i2 = 0; 00047 while (i1 < s1.size() && isspace(s1[i1])) i1++; 00048 while (i2 < s2.size() && isspace(s2[i2])) i2++; 00049 while (i1 < s1.size() && i2 < s2.size()) 00050 { 00051 if (i1 < s1.size() && i2 < s2.size()) 00052 { 00053 if (s1[i1] != s2[i2]) 00054 return false; 00055 i1++; 00056 i2++; 00057 } 00058 while (i1 < s1.size() && isspace(s1[i1])) i1++; 00059 while (i2 < s2.size() && isspace(s2[i2])) i2++; 00060 } 00061 return i1 == s1.size() && i2 == s2.size(); 00062 } 00063 00064 TEST(Loading, SimpleRobot) 00065 { 00066 static const std::string MODEL0 = 00067 "<?xml version=\"1.0\" ?>" 00068 "<robot name=\"myrobot\">" 00069 " <link name=\"base_link\">" 00070 " <collision name=\"base_collision\">" 00071 " <origin rpy=\"0 0 0\" xyz=\"0 0 0.165\"/>" 00072 " <geometry name=\"base_collision_geom\">" 00073 " <box size=\"0.65 0.65 0.23\"/>" 00074 " </geometry>" 00075 " </collision>" 00076 " </link>" 00077 "</robot>"; 00078 00079 std::vector<planning_models::KinematicModel::MultiDofConfig> multi_dof_configs; 00080 planning_models::KinematicModel::MultiDofConfig config("base_joint"); 00081 config.type = "Floating"; 00082 config.parent_frame_id = "odom_combined"; 00083 config.child_frame_id = "base_link"; 00084 multi_dof_configs.push_back(config); 00085 00086 urdf::Model urdfModel; 00087 urdfModel.initString(MODEL0); 00088 00089 std::vector<planning_models::KinematicModel::GroupConfig> gcs; 00090 planning_models::KinematicModel* model = new planning_models::KinematicModel(urdfModel,gcs,multi_dof_configs); 00091 00092 //bracketing so the state gets destroyed before we bring down the model 00093 { 00094 planning_models::KinematicState state(model); 00095 00096 state.setKinematicStateToDefault(); 00097 00098 //make sure that this copy constructor works 00099 planning_models::KinematicState new_state(state); 00100 00101 //(0,0,0,0) isn't a valid quaternion, so the w should be 1 00102 std::map<std::string, double> state_values; 00103 new_state.getKinematicStateValues(state_values); 00104 00105 EXPECT_EQ(state_values["floating_rot_w"], 1.0); 00106 00107 EXPECT_EQ(std::string("myrobot"), model->getName()); 00108 EXPECT_EQ((unsigned int)7, new_state.getDimension()); 00109 00110 const std::vector<planning_models::KinematicModel::LinkModel*>& links = model->getLinkModels(); 00111 EXPECT_EQ((unsigned int)1, links.size()); 00112 00113 const std::vector<planning_models::KinematicModel::JointModel*>& joints = model->getJointModels(); 00114 EXPECT_EQ((unsigned int)1, joints.size()); 00115 00116 std::vector<std::string> pgroups; 00117 model->getModelGroupNames(pgroups); 00118 EXPECT_EQ((unsigned int)0, pgroups.size()); 00119 } 00120 00121 delete model; 00122 } 00123 00124 TEST(LoadingAndFK, SimpleRobot) 00125 { 00126 static const std::string MODEL1 = 00127 "<?xml version=\"1.0\" ?>" 00128 "<robot name=\"myrobot\">" 00129 "<link name=\"base_link\">" 00130 " <inertial>" 00131 " <mass value=\"2.81\"/>" 00132 " <origin rpy=\"0 0 0\" xyz=\"0.0 0.099 .0\"/>" 00133 " <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>" 00134 " </inertial>" 00135 " <collision name=\"my_collision\">" 00136 " <origin rpy=\"0 0 -1\" xyz=\"-0.1 0 0\"/>" 00137 " <geometry>" 00138 " <box size=\"1 2 1\" />" 00139 " </geometry>" 00140 " </collision>" 00141 " <visual>" 00142 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>" 00143 " <geometry>" 00144 " <box size=\"1 2 1\" />" 00145 " </geometry>" 00146 " </visual>" 00147 "</link>" 00148 "</robot>"; 00149 00150 static const std::string MODEL1_INFO = 00151 "Complete model state dimension = 3\n" 00152 "State bounds: [-3.14159, 3.14159] [-DBL_MAX, DBL_MAX] [-DBL_MAX, DBL_MAX]\n" 00153 "Root joint : base_joint \n" 00154 "Available groups: base \n" 00155 "Group base has 1 roots: base_joint \n"; 00156 00157 std::vector<planning_models::KinematicModel::MultiDofConfig> multi_dof_configs; 00158 planning_models::KinematicModel::MultiDofConfig config("base_joint"); 00159 config.type = "Planar"; 00160 config.parent_frame_id = "odom_combined"; 00161 config.child_frame_id = "base_link"; 00162 multi_dof_configs.push_back(config); 00163 00164 urdf::Model urdfModel; 00165 urdfModel.initString(MODEL1); 00166 00167 std::vector<std::string> gc_joints; 00168 gc_joints.push_back("base_joint"); 00169 std::vector<std::string> empty; 00170 std::vector<planning_models::KinematicModel::GroupConfig> gcs; 00171 gcs.push_back(planning_models::KinematicModel::GroupConfig("base", gc_joints, empty)); 00172 00173 planning_models::KinematicModel* model(new planning_models::KinematicModel(urdfModel,gcs,multi_dof_configs)); 00174 00175 //bracketing so the state gets destroyed before we bring down the model 00176 { 00177 planning_models::KinematicState state(model); 00178 00179 EXPECT_EQ((unsigned int)3, state.getDimension()); 00180 00181 state.setKinematicStateToDefault(); 00182 00183 const std::vector<planning_models::KinematicState::JointState*>& joint_states = state.getJointStateVector(); 00184 EXPECT_EQ((unsigned int)1, joint_states.size()); 00185 EXPECT_EQ((unsigned int)3, joint_states[0]->getJointStateValues().size()); 00186 00187 std::stringstream ssi; 00188 state.printStateInfo(ssi); 00189 EXPECT_TRUE(sameStringIgnoringWS(MODEL1_INFO, ssi.str())) << ssi.str(); 00190 00191 00192 std::map<std::string, double> joint_values; 00193 joint_values["planar_x"]=10.0; 00194 joint_values["planar_y"]=8.0; 00195 00196 //testing incomplete state 00197 std::vector<std::string> missing_states; 00198 EXPECT_FALSE(state.setKinematicState(joint_values, 00199 missing_states)); 00200 ASSERT_EQ(missing_states.size(),1); 00201 EXPECT_EQ(missing_states[0],std::string("planar_th")); 00202 joint_values["planar_th"]=0.0; 00203 00204 EXPECT_TRUE(state.setKinematicState(joint_values, 00205 missing_states)); 00206 ASSERT_EQ(missing_states.size(),0); 00207 00208 EXPECT_NEAR(10.0, state.getLinkState("base_link")->getGlobalLinkTransform().getOrigin().x(), 1e-5); 00209 EXPECT_NEAR(8.0, state.getLinkState("base_link")->getGlobalLinkTransform().getOrigin().y(), 1e-5); 00210 EXPECT_NEAR(0.0, state.getLinkState("base_link")->getGlobalLinkTransform().getOrigin().z(), 1e-5); 00211 00212 //making sure that values get copied 00213 planning_models::KinematicState new_state(state); 00214 EXPECT_NEAR(10.0, new_state.getLinkState("base_link")->getGlobalLinkTransform().getOrigin().x(), 1e-5); 00215 EXPECT_NEAR(8.0, new_state.getLinkState("base_link")->getGlobalLinkTransform().getOrigin().y(), 1e-5); 00216 EXPECT_NEAR(0.0, new_state.getLinkState("base_link")->getGlobalLinkTransform().getOrigin().z(), 1e-5); 00217 00218 const std::map<std::string, unsigned int>& ind_map = state.getKinematicStateIndexMap(); 00219 std::vector<double> jv(state.getDimension(), 0.0); 00220 jv[ind_map.at("planar_x")] = 10.0; 00221 jv[ind_map.at("planar_y")] = 8.0; 00222 jv[ind_map.at("planar_th")] = 0.0; 00223 00224 state.setKinematicState(jv); 00225 EXPECT_NEAR(10.0, state.getLinkState("base_link")->getGlobalLinkTransform().getOrigin().x(), 1e-5); 00226 EXPECT_NEAR(8.0, state.getLinkState("base_link")->getGlobalLinkTransform().getOrigin().y(), 1e-5); 00227 EXPECT_NEAR(0.0, state.getLinkState("base_link")->getGlobalLinkTransform().getOrigin().z(), 1e-5); 00228 } 00229 delete model; 00230 } 00231 00232 TEST(FK, OneRobot) 00233 { 00234 static const std::string MODEL2 = 00235 "<?xml version=\"1.0\" ?>" 00236 "<robot name=\"one_robot\">" 00237 "<link name=\"base_link\">" 00238 " <inertial>" 00239 " <mass value=\"2.81\"/>" 00240 " <origin rpy=\"0 0 0\" xyz=\"0.0 0.0 .0\"/>" 00241 " <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>" 00242 " </inertial>" 00243 " <collision name=\"my_collision\">" 00244 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>" 00245 " <geometry>" 00246 " <box size=\"1 2 1\" />" 00247 " </geometry>" 00248 " </collision>" 00249 " <visual>" 00250 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>" 00251 " <geometry>" 00252 " <box size=\"1 2 1\" />" 00253 " </geometry>" 00254 " </visual>" 00255 "</link>" 00256 "<joint name=\"joint_a\" type=\"continuous\">" 00257 " <axis xyz=\"0 0 1\"/>" 00258 " <parent link=\"base_link\"/>" 00259 " <child link=\"link_a\"/>" 00260 " <origin rpy=\" 0.0 0 0 \" xyz=\"0.0 0 0 \"/>" 00261 "</joint>" 00262 "<link name=\"link_a\">" 00263 " <inertial>" 00264 " <mass value=\"1.0\"/>" 00265 " <origin rpy=\"0 0 0\" xyz=\"0.0 0.0 .0\"/>" 00266 " <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>" 00267 " </inertial>" 00268 " <collision>" 00269 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>" 00270 " <geometry>" 00271 " <box size=\"1 2 1\" />" 00272 " </geometry>" 00273 " </collision>" 00274 " <visual>" 00275 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>" 00276 " <geometry>" 00277 " <box size=\"1 2 1\" />" 00278 " </geometry>" 00279 " </visual>" 00280 "</link>" 00281 "<joint name=\"joint_b\" type=\"fixed\">" 00282 " <parent link=\"link_a\"/>" 00283 " <child link=\"link_b\"/>" 00284 " <origin rpy=\" 0.0 -0.42 0 \" xyz=\"0.0 0.5 0 \"/>" 00285 "</joint>" 00286 "<link name=\"link_b\">" 00287 " <inertial>" 00288 " <mass value=\"1.0\"/>" 00289 " <origin rpy=\"0 0 0\" xyz=\"0.0 0.0 .0\"/>" 00290 " <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>" 00291 " </inertial>" 00292 " <collision>" 00293 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>" 00294 " <geometry>" 00295 " <box size=\"1 2 1\" />" 00296 " </geometry>" 00297 " </collision>" 00298 " <visual>" 00299 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>" 00300 " <geometry>" 00301 " <box size=\"1 2 1\" />" 00302 " </geometry>" 00303 " </visual>" 00304 "</link>" 00305 " <joint name=\"joint_c\" type=\"prismatic\">" 00306 " <axis xyz=\"1 0 0\"/>" 00307 " <limit effort=\"100.0\" lower=\"0.0\" upper=\"0.09\" velocity=\"0.2\"/>" 00308 " <safety_controller k_position=\"20.0\" k_velocity=\"500.0\" soft_lower_limit=\"0.0\" soft_upper_limit=\"0.089\"/>" 00309 " <parent link=\"link_b\"/>" 00310 " <child link=\"link_c\"/>" 00311 " <origin rpy=\" 0.0 0.42 0.0 \" xyz=\"0.0 -0.1 0 \"/>" 00312 " </joint>" 00313 "<link name=\"link_c\">" 00314 " <inertial>" 00315 " <mass value=\"1.0\"/>" 00316 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 .0\"/>" 00317 " <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>" 00318 " </inertial>" 00319 " <collision>" 00320 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>" 00321 " <geometry>" 00322 " <box size=\"1 2 1\" />" 00323 " </geometry>" 00324 " </collision>" 00325 " <visual>" 00326 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>" 00327 " <geometry>" 00328 " <box size=\"1 2 1\" />" 00329 " </geometry>" 00330 " </visual>" 00331 "</link>" 00332 "</robot>"; 00333 00334 static const std::string MODEL2_INFO = 00335 "Complete model state dimension = 5\n" 00336 "State bounds: [-3.14159, 3.14159] [-DBL_MAX, DBL_MAX] [-DBL_MAX, DBL_MAX] [-3.14159, 3.14159] [0.00000, 0.08900]\n" 00337 "Root joint : base_joint \n" 00338 "Available groups: base_from_base_to_tip base_from_joints base_with_subgroups \n" 00339 "Group base_from_base_to_tip has 1 roots: base_joint \n" 00340 "Group base_from_joints has 1 roots: base_joint \n" 00341 "Group base_with_subgroups has 1 roots: base_joint \n"; 00342 00343 00344 urdf::Model urdfModel; 00345 urdfModel.initString(MODEL2); 00346 00347 std::vector<std::string> gc_joints; 00348 gc_joints.push_back("base_joint"); 00349 gc_joints.push_back("joint_a"); 00350 gc_joints.push_back("joint_c"); 00351 std::vector<std::string> subgroups; 00352 std::vector<planning_models::KinematicModel::GroupConfig> gcs; 00353 gcs.push_back(planning_models::KinematicModel::GroupConfig("base_from_joints", gc_joints, subgroups)); 00354 00355 //defining this in the list before the actual subgroup to make sure that works 00356 std::vector<std::string> extra_joint; 00357 extra_joint.push_back("joint_c"); 00358 subgroups.push_back("base_from_base_to_tip"); 00359 gcs.push_back(planning_models::KinematicModel::GroupConfig("base_with_subgroups", extra_joint, subgroups)); 00360 00361 //not making this all the way to joint_c intentionally 00362 gcs.push_back(planning_models::KinematicModel::GroupConfig("base_from_base_to_tip","odom_combined","link_b")); 00363 00364 //now adding a fake one 00365 subgroups.push_back("monkey_group"); 00366 gcs.push_back(planning_models::KinematicModel::GroupConfig("base_with_bad_subgroups", extra_joint, subgroups)); 00367 00368 std::vector<planning_models::KinematicModel::MultiDofConfig> multi_dof_configs; 00369 planning_models::KinematicModel::MultiDofConfig config("base_joint"); 00370 config.type = "Planar"; 00371 config.parent_frame_id = "odom_combined"; 00372 config.child_frame_id = "base_link"; 00373 multi_dof_configs.push_back(config); 00374 00375 planning_models::KinematicModel* model = new planning_models::KinematicModel(urdfModel,gcs,multi_dof_configs); 00376 00377 //testing that the two planning groups are the same 00378 const planning_models::KinematicModel::JointModelGroup* g_one = model->getModelGroup("base_from_joints"); 00379 const planning_models::KinematicModel::JointModelGroup* g_two = model->getModelGroup("base_from_base_to_tip"); 00380 const planning_models::KinematicModel::JointModelGroup* g_three = model->getModelGroup("base_with_subgroups"); 00381 const planning_models::KinematicModel::JointModelGroup* g_four = model->getModelGroup("base_with_bad_subgroups"); 00382 00383 ASSERT_TRUE(g_one != NULL); 00384 ASSERT_TRUE(g_two != NULL); 00385 ASSERT_TRUE(g_three != NULL); 00386 ASSERT_TRUE(g_four == NULL); 00387 00388 //joint_b is a fixed joint, so no one should have it 00389 ASSERT_EQ(g_one->getJointModelNames().size(), 3); 00390 ASSERT_EQ(g_two->getJointModelNames().size(), 2); 00391 ASSERT_EQ(g_three->getJointModelNames().size(), 3); 00392 00393 //only the links in between the joints, and the children of the leafs 00394 ASSERT_EQ(g_one->getGroupLinkModels().size(), 4); 00395 //g_two only has three links 00396 ASSERT_EQ(g_two->getGroupLinkModels().size(), 3); 00397 ASSERT_EQ(g_three->getGroupLinkModels().size(), 4); 00398 00399 EXPECT_EQ(g_one->getJointModelNames()[0],"base_joint"); 00400 EXPECT_EQ(g_one->getJointModelNames()[1],"joint_a"); 00401 EXPECT_EQ(g_one->getJointModelNames()[2],"joint_c"); 00402 EXPECT_EQ(g_two->getJointModelNames()[0],"base_joint"); 00403 EXPECT_EQ(g_two->getJointModelNames()[1],"joint_a"); 00404 EXPECT_EQ(g_three->getJointModelNames()[0],"base_joint"); 00405 EXPECT_EQ(g_three->getJointModelNames()[1],"joint_a"); 00406 EXPECT_EQ(g_three->getJointModelNames()[2],"joint_c"); 00407 00408 //but they should have the same links to be updated 00409 ASSERT_EQ(g_one->getUpdatedLinkModels().size(), 4); 00410 ASSERT_EQ(g_two->getUpdatedLinkModels().size(), 4); 00411 ASSERT_EQ(g_three->getUpdatedLinkModels().size(), 4); 00412 00413 EXPECT_EQ(g_one->getUpdatedLinkModels()[0]->getName(),"base_link"); 00414 EXPECT_EQ(g_one->getUpdatedLinkModels()[1]->getName(),"link_a"); 00415 EXPECT_EQ(g_one->getUpdatedLinkModels()[2]->getName(),"link_b"); 00416 EXPECT_EQ(g_one->getUpdatedLinkModels()[3]->getName(),"link_c"); 00417 00418 EXPECT_EQ(g_two->getUpdatedLinkModels()[0]->getName(),"base_link"); 00419 EXPECT_EQ(g_two->getUpdatedLinkModels()[1]->getName(),"link_a"); 00420 EXPECT_EQ(g_two->getUpdatedLinkModels()[2]->getName(),"link_b"); 00421 EXPECT_EQ(g_two->getUpdatedLinkModels()[3]->getName(),"link_c"); 00422 00423 EXPECT_EQ(g_three->getUpdatedLinkModels()[0]->getName(),"base_link"); 00424 EXPECT_EQ(g_three->getUpdatedLinkModels()[1]->getName(),"link_a"); 00425 EXPECT_EQ(g_three->getUpdatedLinkModels()[2]->getName(),"link_b"); 00426 EXPECT_EQ(g_three->getUpdatedLinkModels()[3]->getName(),"link_c"); 00427 00428 //bracketing so the state gets destroyed before we bring down the model 00429 { 00430 planning_models::KinematicState state(model); 00431 00432 EXPECT_EQ((unsigned int)5, state.getDimension()); 00433 00434 state.setKinematicStateToDefault(); 00435 00436 std::map<std::string, double> joint_values; 00437 joint_values["planar_x"]=1.0; 00438 joint_values["planar_y"]=1.0; 00439 joint_values["planar_th"]=0.5; 00440 joint_values["joint_a"] = -0.5; 00441 joint_values["joint_c"] = 0.1; 00442 state.getJointStateGroup("base_from_joints")->setKinematicState(joint_values); 00443 00444 //double param[5] = { 1, 1, 0.5, -0.5, 0.1 }; 00445 //model->getGroup("base")->computeTransforms(param); 00446 00447 std::stringstream ss1; 00448 state.printStateInfo(ss1); 00449 EXPECT_TRUE(sameStringIgnoringWS(MODEL2_INFO, ss1.str())) << MODEL2_INFO << "\n" << ss1.str(); 00450 state.printTransforms(ss1); 00451 00452 //make sure it works the same way for the whole robot 00453 state.setKinematicState(joint_values); 00454 std::stringstream ss2; 00455 state.printStateInfo(ss2); 00456 state.printTransforms(ss2); 00457 00458 EXPECT_EQ(ss1.str(), ss2.str()); 00459 00460 EXPECT_NEAR(1.0, state.getLinkState("base_link")->getGlobalLinkTransform().getOrigin().x(), 1e-5); 00461 EXPECT_NEAR(1.0, state.getLinkState("base_link")->getGlobalLinkTransform().getOrigin().y(), 1e-5); 00462 EXPECT_NEAR(0.0, state.getLinkState("base_link")->getGlobalLinkTransform().getOrigin().z(), 1e-5); 00463 EXPECT_NEAR(0.0, state.getLinkState("base_link")->getGlobalLinkTransform().getRotation().x(), 1e-5); 00464 EXPECT_NEAR(0.0, state.getLinkState("base_link")->getGlobalLinkTransform().getRotation().y(), 1e-5); 00465 EXPECT_NEAR(0.247404, state.getLinkState("base_link")->getGlobalLinkTransform().getRotation().z(), 1e-5); 00466 EXPECT_NEAR(0.968912, state.getLinkState("base_link")->getGlobalLinkTransform().getRotation().w(), 1e-5); 00467 00468 EXPECT_NEAR(1.0, state.getLinkState("link_a")->getGlobalLinkTransform().getOrigin().x(), 1e-5); 00469 EXPECT_NEAR(1.0, state.getLinkState("link_a")->getGlobalLinkTransform().getOrigin().y(), 1e-5); 00470 EXPECT_NEAR(0.0, state.getLinkState("link_a")->getGlobalLinkTransform().getOrigin().z(), 1e-5); 00471 EXPECT_NEAR(0.0, state.getLinkState("link_a")->getGlobalLinkTransform().getRotation().x(), 1e-5); 00472 EXPECT_NEAR(0.0, state.getLinkState("link_a")->getGlobalLinkTransform().getRotation().y(), 1e-5); 00473 EXPECT_NEAR(0.0, state.getLinkState("link_a")->getGlobalLinkTransform().getRotation().z(), 1e-5); 00474 EXPECT_NEAR(1.0, state.getLinkState("link_a")->getGlobalLinkTransform().getRotation().w(), 1e-5); 00475 00476 EXPECT_NEAR(1.0, state.getLinkState("link_b")->getGlobalLinkTransform().getOrigin().x(), 1e-5); 00477 EXPECT_NEAR(1.5, state.getLinkState("link_b")->getGlobalLinkTransform().getOrigin().y(), 1e-5); 00478 EXPECT_NEAR(0.0, state.getLinkState("link_b")->getGlobalLinkTransform().getOrigin().z(), 1e-5); 00479 EXPECT_NEAR(0.0, state.getLinkState("link_b")->getGlobalLinkTransform().getRotation().x(), 1e-5); 00480 EXPECT_NEAR(-0.20846, state.getLinkState("link_b")->getGlobalLinkTransform().getRotation().y(), 1e-5); 00481 EXPECT_NEAR(0.0, state.getLinkState("link_b")->getGlobalLinkTransform().getRotation().z(), 1e-5); 00482 EXPECT_NEAR(0.978031, state.getLinkState("link_b")->getGlobalLinkTransform().getRotation().w(), 1e-5); 00483 00484 EXPECT_NEAR(1.1, state.getLinkState("link_c")->getGlobalLinkTransform().getOrigin().x(), 1e-5); 00485 EXPECT_NEAR(1.4, state.getLinkState("link_c")->getGlobalLinkTransform().getOrigin().y(), 1e-5); 00486 EXPECT_NEAR(0.0, state.getLinkState("link_c")->getGlobalLinkTransform().getOrigin().z(), 1e-5); 00487 EXPECT_NEAR(0.0, state.getLinkState("link_c")->getGlobalLinkTransform().getRotation().x(), 1e-5); 00488 EXPECT_NEAR(0.0, state.getLinkState("link_c")->getGlobalLinkTransform().getRotation().y(), 1e-5); 00489 EXPECT_NEAR(0.0, state.getLinkState("link_c")->getGlobalLinkTransform().getRotation().z(), 1e-5); 00490 EXPECT_NEAR(1.0, state.getLinkState("link_c")->getGlobalLinkTransform().getRotation().w(), 1e-5); 00491 00492 //bonus bounds lookup test 00493 std::vector<std::string> jn; 00494 jn.push_back("planar_x"); 00495 jn.push_back("planar_th"); 00496 jn.push_back("base_joint"); 00497 EXPECT_TRUE(state.areJointsWithinBounds(jn)); 00498 00499 jn.push_back("monkey"); 00500 EXPECT_FALSE(state.areJointsWithinBounds(jn)); 00501 } 00502 00503 delete model; 00504 } 00505 int main(int argc, char **argv) 00506 { 00507 testing::InitGoogleTest(&argc, argv); 00508 return RUN_ALL_TESTS(); 00509 }