Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Respect joint axes' initial_position #2827

Open
wants to merge 6 commits into
base: gazebo11
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
46 changes: 38 additions & 8 deletions gazebo/physics/Model.cc
Original file line number Diff line number Diff line change
Expand Up @@ -269,6 +269,29 @@ void Model::LoadJoints()
}
}

void SetInitialPositionForAxis(JointPtr const& joint, unsigned int axisIdx, std::string const& axisElementName)
{
sdf::ElementPtr const jointSdf = joint->GetSDF();
if (joint->DOF() <= axisIdx || !jointSdf->HasElement(axisElementName))
return;

sdf::ElementPtr const axisElem = jointSdf->GetElement(axisElementName);
if (axisElem->HasElement("initial_position"))
{
double const initial_position = axisElem->Get<double>("initial_position");
if (!joint->SetPosition(axisIdx, initial_position))
{
gzerr << "Failed to set initial position " << initial_position << " for joint " << joint->GetScopedName() << std::endl;
}
}
}

void SetInitialPosition(JointPtr const& joint)
{
SetInitialPositionForAxis(joint, 0, "axis");
SetInitialPositionForAxis(joint, 1, "axis2");
}

//////////////////////////////////////////////////
void Model::Init()
{
Expand Down Expand Up @@ -314,6 +337,13 @@ void Model::Init()
this->jointPub->Publish(msg);
}

// This needs to be done after the whole kinematic chain has been initialized.
// Doing this in the joint's Init method completely messes up the setup.
for (auto& joint : this->joints)
{
SetInitialPosition(joint);
}

for (std::vector<GripperPtr>::iterator iter = this->grippers.begin();
iter != this->grippers.end(); ++iter)
{
Expand Down Expand Up @@ -1350,14 +1380,14 @@ void Model::SetState(const ModelState &_state)
gzerr << "Unable to find model[" << ms.first << "]\n";
}

// For now we don't use the joint state values to set the state of
// simulation.
// for (unsigned int i = 0; i < _state.GetJointStateCount(); ++i)
// {
// JointState jointState = _state.GetJointState(i);
// this->SetJointPosition(this->GetName() + "::" + jointState.GetName(),
// jointState.GetAngle(0).Radian());
// }
for (unsigned int i = 0; i < _state.GetJointStateCount(); ++i)
{
JointState const jointState = _state.GetJointState(i);
for (unsigned int k = 0; k < jointState.GetAngleCount(); ++k) {
this->SetJointPosition(this->GetName() + "::" + jointState.GetName(),
jointState.Position(k), k);
}
}
}

/////////////////////////////////////////////////
Expand Down
4 changes: 2 additions & 2 deletions gazebo/physics/ModelState.cc
Original file line number Diff line number Diff line change
Expand Up @@ -204,7 +204,7 @@ void ModelState::Load(const sdf::ElementPtr _elem)
}

// Set all the joints
/*this->jointStates.clear();
this->jointStates.clear();
if (_elem->HasElement("joint"))
{
sdf::ElementPtr childElem = _elem->GetElement("joint");
Expand All @@ -215,7 +215,7 @@ void ModelState::Load(const sdf::ElementPtr _elem)
JointState(childElem)));
childElem = childElem->GetNextElement("joint");
}
}*/
}
}

/////////////////////////////////////////////////
Expand Down
35 changes: 35 additions & 0 deletions gazebo/physics/ModelState_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -165,6 +165,41 @@ TEST_F(ModelStateTest, Nested)
}
}

TEST_F(ModelStateTest, JointState)
{
std::ostringstream sdfStr;
sdfStr << "<sdf version ='" << SDF_VERSION << "'>"
<< "<world name='default'>"
<< "<state world_name='default'>"
<< "<model name='model_00'>"
<< " <joint name='joint_00'>"
<< " <angle axis='0'>1.57</angle>"
<< " </joint>"
<< "</model>"
<< "</state>"
<< "</world>"
<< "</sdf>";
sdf::SDFPtr worldSDF(new sdf::SDF);
worldSDF->SetFromString(sdfStr.str());
EXPECT_TRUE(worldSDF->Root()->HasElement("world"));
sdf::ElementPtr worldElem = worldSDF->Root()->GetElement("world");
EXPECT_TRUE(worldElem->HasElement("state"));
sdf::ElementPtr stateElem = worldElem->GetElement("state");
EXPECT_TRUE(stateElem->HasElement("model"));
sdf::ElementPtr modelElem = stateElem->GetElement("model");
EXPECT_TRUE(modelElem != nullptr);

physics::ModelState const modelState(modelElem);

ASSERT_EQ(modelState.GetJointStateCount(), 1u);

physics::JointState const jointState = modelState.GetJointState(0);
EXPECT_EQ(1u, jointState.GetAngleCount());
EXPECT_EQ(1u, jointState.Positions().size());
EXPECT_DOUBLE_EQ(1.57, jointState.Position(0));
EXPECT_TRUE(ignition::math::isnan(jointState.Position(1)));
}

int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);
Expand Down
28 changes: 28 additions & 0 deletions test/integration/model.cc
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,34 @@ TEST_F(ModelTest, GetLinksV)
EXPECT_EQ(model->GetLinks().size(), 1u);
}

TEST_F(ModelTest, LoadJointState)
{
Load("worlds/joint_state_test.world");
physics::ModelPtr const model = GetModel("model_3");

ASSERT_EQ(model->GetJointCount(), 2u);

physics::JointPtr const joint_1 = model->GetJoint("joint_1");
EXPECT_NEAR(joint_1->Position(), 0.7854, 0.0001);

physics::JointPtr const joint_2 = model->GetJoint("joint_2");
EXPECT_NEAR(joint_2->Position(), 0.7854, 0.0001);
}

TEST_F(ModelTest, JointInitialPosition)
{
Load("worlds/joint_test.world");
physics::ModelPtr const model = GetModel("model_3");

ASSERT_EQ(model->GetJointCount(), 2u);

physics::JointPtr const joint_1 = model->GetJoint("joint_1");
EXPECT_NEAR(joint_1->Position(), 0.7854, 0.0001);

physics::JointPtr const joint_2 = model->GetJoint("joint_2");
EXPECT_NEAR(joint_2->Position(), 1.5707, 0.0001);
}

/////////////////////////////////////////////////
// This tests getting the scoped name of a model.
TEST_F(ModelTest, GetScopedName)
Expand Down
57 changes: 57 additions & 0 deletions test/worlds/joint_state_test.world
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
<?xml version="1.0" ?>
<sdf version="1.7">
<world name="default">
<!-- A global light source -->
<include>
<uri>model://sun</uri>
</include>
<model name="model_3">
<pose>0 0 0 0 0 0</pose>
<link name="link_1">
<visual name="link_1_box">
<pose>0 0.5 0 0 0 0</pose>
<geometry>
<box>
<size>0.125 0.95 0.125</size>
</box>
</geometry>
</visual>
</link>
<link name="link_2">
<visual name="link_2_visual">
<pose>0 1.5 0 0 0 0</pose>
<geometry>
<box>
<size>0.125 0.95 0.125</size>
</box>
</geometry>
</visual>
</link>
<joint name="joint_1" type="revolute">
<parent>world</parent>
<child>link_1</child>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="joint_2" type="revolute">
<parent>link_1</parent>
<child>link_2</child>
<axis>
<xyz>0 0 1</xyz>
</axis>
<pose>0 1 0 0 0 0</pose>
</joint>
</model>
<state world_name="default">
<model name="model_3">
<joint name="joint_1">
<angle axis=0>0.7854</angle>
</joint>
<joint name="joint_2">
<angle axis=0>0.7854</angle>
</joint>
</model>
</state>
</world>
</sdf>
40 changes: 40 additions & 0 deletions test/worlds/joint_test.world
Original file line number Diff line number Diff line change
Expand Up @@ -141,5 +141,45 @@
</joint>
<static>0</static>
</model>
<model name="model_3">
<pose>0 2 0 0 0 0</pose>
<link name="link_1">
<visual name="link_1_box">
<pose>0 0.5 0 0 0 0</pose>
<geometry>
<box>
<size>0.125 0.95 0.125</size>
</box>
</geometry>
</visual>
</link>
<link name="link_2">
<visual name="link_2_visual">
<pose>0 1.5 0 0 0 0</pose>
<geometry>
<box>
<size>0.125 0.95 0.125</size>
</box>
</geometry>
</visual>
</link>
<joint name="joint_1" type="revolute">
<parent>world</parent>
<child>link_1</child>
<axis>
<xyz>0 0 1</xyz>
<initial_position>0.7854</initial_position>
</axis>
</joint>
<joint name="joint_2" type="revolute">
<parent>link_1</parent>
<child>link_2</child>
<axis>
<xyz>0 0 1</xyz>
<initial_position>1.5707</initial_position>
</axis>
<pose>0 1 0 0 0 0</pose>
</joint>
</model>
</world>
</sdf>