18 #ifndef _JOINT_TEST_HH_
19 #define _JOINT_TEST_HH_
24 #include "test/ServerFixture.hh"
27 #include "gazebo/physics/physics.hh"
29 using namespace gazebo;
31 typedef std::tr1::tuple<const char *, const char *>
std_string2;
34 public ::testing::WithParamInterface<std_string2>
43 public:
void ForceTorque1(
const std::string &_physicsEngine);
51 public:
void ForceTorque2(
const std::string &_physicsEngine);
57 public:
void GetForceTorqueWithAppliedForce(
58 const std::string &_physicsEngine);
63 public:
void JointTorqueTest(
const std::string &_physicsEngine);
67 public:
void JointCreationDestructionTest(
const std::string &_physicsEngine);
69 public:
virtual void SetUp()
71 const ::testing::TestInfo *
const test_info =
72 ::testing::UnitTest::GetInstance()->current_test_info();
73 if (test_info->value_param())
75 gzdbg <<
"Params: " << test_info->value_param() << std::endl;
76 std::tr1::tie(this->physicsEngine, this->jointType) = GetParam();
83 public:
void SpawnJointTypes(
const std::string &_physicsEngine,
84 const std::string &_jointType);
90 public:
void SpawnJointRotational(
const std::string &_physicsEngine,
91 const std::string &_jointType);
97 public:
void SpawnJointRotationalWorld(
const std::string &_physicsEngine,
98 const std::string &_jointType);
105 axis(math::Vector3(1, 0, 0))
154 bool _worldChild =
false,
155 bool _worldParent =
false,
163 return SpawnJoint(opt);
175 std::ostringstream modelStr;
176 std::ostringstream modelName;
177 modelName <<
"joint_model" << this->spawnCount++;
180 <<
"<sdf version='" << SDF_VERSION <<
"'>"
181 <<
"<model name ='" << modelName.str() <<
"'>"
182 <<
" <pose>" << _opt.
modelPose <<
"</pose>";
186 <<
" <link name='parent'>"
193 <<
" <link name='child'>"
198 <<
" <joint name='joint' type='" << _opt.
type <<
"'>"
199 <<
" <pose>" << _opt.
jointPose <<
"</pose>";
201 modelStr <<
" <parent>world</parent>";
203 modelStr <<
" <parent>parent</parent>";
205 modelStr <<
" <child>world</child>";
207 modelStr <<
" <child>child</child>";
210 <<
" <xyz>" << _opt.
axis <<
"</xyz>"
216 msg.set_sdf(modelStr.str());
217 this->factoryPub->Publish(msg);
223 unsigned int waitCount = 0;
225 !this->HasEntity(modelName.str()))
228 if (++waitCount % 10 == 0)
230 gzwarn <<
"Waiting " << waitCount / 10 <<
" seconds for "
231 << _opt.
type <<
" joint to spawn." << std::endl;
234 if (this->HasEntity(modelName.str()) && waitCount >= 10)
235 gzwarn << _opt.
type <<
" joint has spawned." << std::endl;
242 joint = model->GetJoint(
"joint");
255 private:
unsigned int spawnCount;