Skip to content
This repository was archived by the owner on Feb 3, 2025. It is now read-only.

Commit

Permalink
Merged in issue_2239 (pull request #3024)
Browse files Browse the repository at this point in the history
Fix Issue 2239: All links teleport to origin if model has a revolute2 joint.

Approved-by: Steven Peters <scpeters@osrfoundation.org>
Approved-by: Shane Loretz <sloretz@osrfoundation.org>
  • Loading branch information
azeey committed Oct 18, 2018
2 parents 157b27e + d80afcb commit 8abbfa6
Show file tree
Hide file tree
Showing 8 changed files with 184 additions and 11 deletions.
4 changes: 4 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,10 @@

## Gazebo 9.X.X (20XX-XX-XX)

1. Fix for revolute2 joints that prevents links from teleporting to origin
* [Pull request 3024](https://bitbucket.org/osrf/gazebo/pull-request/3024)
* [Issue 2239](https://bitbucket.org/osrf/gazebo/issues/2239)

1. Fix for BulletFixedJoint when used with inertial matrices with non-zero values on their off-diagonal
* [Pull request 3010](https://bitbucket.org/osrf/gazebo/pull-request/3010)

Expand Down
6 changes: 6 additions & 0 deletions deps/opende/include/gazebo/ode/objects.h
Original file line number Diff line number Diff line change
Expand Up @@ -3012,6 +3012,12 @@ ODE_API dReal dJointGetHinge2Param (dJointID, int parameter);
*/
ODE_API dReal dJointGetHinge2Angle1 (dJointID);

/**
* @brief Get angle
* @ingroup joints
*/
ODE_API dReal dJointGetHinge2Angle2 (dJointID);

/**
* @brief Get time derivative of angle
* @ingroup joints
Expand Down
90 changes: 81 additions & 9 deletions deps/opende/src/joints/hinge2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,13 +32,42 @@
// hinge 2. note that this joint must be attached to two bodies for it to work

dReal
dxJointHinge2::measureAngle() const
dxJointHinge2::measureAngle1() const
{
dVector3 a1, a2;
dMultiply0_331( a1, node[1].body->posr.R, axis2 );
dMultiply1_331( a2, node[0].body->posr.R, a1 );
dReal x = dCalcVectorDot3( v1, a2 );
dReal y = dCalcVectorDot3( v2, a2 );
// bring axis 2 into first body's reference frame
dVector3 p, q;
if (node[1].body)
dMultiply0_331( p, node[1].body->posr.R, axis2 );
else
dCopyVector3(p, axis2);

if (node[0].body)
dMultiply1_331( q, node[0].body->posr.R, p );
else
dCopyVector3(q, p);

dReal x = dCalcVectorDot3( v1, q );
dReal y = dCalcVectorDot3( v2, q );
return -dAtan2( y, x );
}

dReal
dxJointHinge2::measureAngle2() const
{
// bring axis 1 into second body's reference frame
dVector3 p, q;
if (node[0].body)
dMultiply0_331( p, node[0].body->posr.R, axis1 );
else
dCopyVector3(p, axis1);

if (node[1].body)
dMultiply1_331( q, node[1].body->posr.R, p );
else
dCopyVector3(q, p);

dReal x = dCalcVectorDot3( w1, q );
dReal y = dCalcVectorDot3( w2, q );
return -dAtan2( y, x );
}

Expand Down Expand Up @@ -88,7 +117,7 @@ dxJointHinge2::getInfo1( dxJoint::Info1 *info )
if (( limot1.lostop >= -M_PI || limot1.histop <= M_PI ) &&
limot1.lostop <= limot1.histop )
{
dReal angle = measureAngle();
dReal angle = measureAngle1();
limot1.testRotationalLimit( angle );
}
if ( limot1.limit || limot1.fmax > 0 ) info->m++;
Expand Down Expand Up @@ -224,6 +253,36 @@ dxJointHinge2::makeV1andV2()
}
}

// same as above, but for the second axis

void
dxJointHinge2::makeW1andW2()
{
if ( node[1].body )
{
// get axis 1 and 2 in global coords
dVector3 ax1, ax2, w;
dMultiply0_331( ax1, node[0].body->posr.R, axis1 );
dMultiply0_331( ax2, node[1].body->posr.R, axis2 );

// don't do anything if the axis1 or axis2 vectors are zero or the same
if ((_dequal(ax1[0], 0.0) && _dequal(ax1[1], 0.0) && _dequal(ax1[2], 0.0)) ||
(_dequal(ax2[0], 0.0) && _dequal(ax2[1], 0.0) && _dequal(ax2[2], 0.0)) ||
(_dequal(ax1[0], ax2[0]) && _dequal(ax1[1], ax2[1]) && _dequal(ax1[2], ax2[2])))
return;

// modify axis 1 so it's perpendicular to axis 2
dReal k = dCalcVectorDot3( ax2, ax1 );
for ( int i = 0; i < 3; i++ ) ax1[i] -= k * ax2[i];
dNormalize3( ax1 );

// make w1 = modified axis1, w2 = axis2 x (modified axis1)
dCalcVectorCross3( w, ax2, ax1 );
dMultiply1_331( w1, node[1].body->posr.R, ax1 );
dMultiply1_331( w2, node[1].body->posr.R, w );
}
}


void dJointSetHinge2Anchor( dJointID j, dReal x, dReal y, dReal z )
{
Expand All @@ -232,6 +291,7 @@ void dJointSetHinge2Anchor( dJointID j, dReal x, dReal y, dReal z )
checktype( joint, Hinge2 );
setAnchors( joint, x, y, z, joint->anchor1, joint->anchor2 );
joint->makeV1andV2();
joint->makeW1andW2();
}


Expand All @@ -249,6 +309,7 @@ void dJointSetHinge2Axis1( dJointID j, dReal x, dReal y, dReal z )
joint->getAxisInfo( ax1, ax2, ax, joint->s0, joint->c0 );
}
joint->makeV1andV2();
joint->makeW1andW2();
}


Expand All @@ -267,6 +328,7 @@ void dJointSetHinge2Axis2( dJointID j, dReal x, dReal y, dReal z )
joint->getAxisInfo( ax1, ax2, ax, joint->s0, joint->c0 );
}
joint->makeV1andV2();
joint->makeW1andW2();
}


Expand Down Expand Up @@ -390,11 +452,20 @@ dReal dJointGetHinge2Angle1( dJointID j )
dxJointHinge2* joint = ( dxJointHinge2* )j;
dUASSERT( joint, "bad joint argument" );
checktype( joint, Hinge2 );
if ( joint->node[0].body ) return joint->measureAngle();
else return 0;
return joint->measureAngle1();
}


dReal dJointGetHinge2Angle2( dJointID j )
{
dxJointHinge2* joint = ( dxJointHinge2* )j;
dUASSERT( joint, "bad joint argument" );
checktype( joint, Hinge2 );
return joint->measureAngle2();
}



dReal dJointGetHinge2Angle1Rate( dJointID j )
{
dxJointHinge2* joint = ( dxJointHinge2* )j;
Expand Down Expand Up @@ -490,4 +561,5 @@ dxJointHinge2::setRelativeValues()
getAxisInfo( ax1, ax2, axis, s0, c0 );

makeV1andV2();
makeW1andW2();
}
6 changes: 5 additions & 1 deletion deps/opende/src/joints/hinge2.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,13 +36,17 @@ struct dxJointHinge2 : public dxJoint
dVector3 axis2; // axis 2 w.r.t second body
dReal c0, s0; // cos,sin of desired angle between axis 1,2
dVector3 v1, v2; // angle ref vectors embedded in first body
dVector3 w1, w2; // angle ref vectors embedded in second body
dxJointLimitMotor limot1; // limit+motor info for axis 1
dxJointLimitMotor limot2; // limit+motor info for axis 2
dReal susp_erp, susp_cfm; // suspension parameters (erp,cfm)


dReal measureAngle() const;
dReal measureAngle1() const;
dReal measureAngle2() const;
void makeV1andV2();
void makeW1andW2();

void getAxisInfo(dVector3 ax1, dVector3 ax2, dVector3 axis,
dReal &sin_angle, dReal &cos_Angle) const;

Expand Down
2 changes: 2 additions & 0 deletions gazebo/physics/ode/ODEHinge2Joint.cc
Original file line number Diff line number Diff line change
Expand Up @@ -150,6 +150,8 @@ double ODEHinge2Joint::PositionImpl(const unsigned int _index) const
/// \todo Return position of axis 1
if (_index == 0)
result = dJointGetHinge2Angle1(this->jointId);
else
result = dJointGetHinge2Angle2(this->jointId);
}
else
gzerr << "ODE Joint ID is invalid\n";
Expand Down
2 changes: 1 addition & 1 deletion test/integration/joint_test.hh
Original file line number Diff line number Diff line change
Expand Up @@ -216,7 +216,7 @@ class JointTest : public ServerFixture,
axis->set_use_parent_model_frame(_opt.useParentModelFrame);
}
// Hack: hardcode a second axis for universal joints
if (_opt.type == "universal")
if (_opt.type == "universal" || _opt.type == "revolute2")
{
auto axis2 = jointMsg->mutable_axis2();
msgs::Set(axis2->mutable_xyz(),
Expand Down
84 changes: 84 additions & 0 deletions test/regression/2239_revolute2_teleport.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
/*
* Copyright (C) 2018 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#include <ignition/math/Pose3.hh>

#include "gazebo/test/ServerFixture.hh"
#include "gazebo/test/helper_physics_generator.hh"
#include "test/integration/joint_test.hh"

using namespace gazebo;

class Issue2239Test: public JointTest
{
/// \brief Spawn a revolute2 joint and test whether the model teleports
public: void TestRevolute2JointTeleport(const std::string &_physicsEngine);
};

/////////////////////////////////////////////////
void Issue2239Test::TestRevolute2JointTeleport(
const std::string &_physicsEngine)
{
this->Load("worlds/empty.world", true, _physicsEngine);
physics::WorldPtr world = physics::get_world("default");
ASSERT_NE(nullptr, world);

// Verify the physics engine
physics::PhysicsEnginePtr physics = world->Physics();
ASSERT_NE(nullptr, physics);
EXPECT_EQ(physics->GetType(), _physicsEngine);

// disable gravity
physics->SetGravity(ignition::math::Vector3d::Zero);

SpawnJointOptions opt;
opt.type = "revolute2";
opt.parentLinkPose.Set(0, 0.1, 0.1, 0, 0, 0);
opt.childLinkPose.Set(0.1, 0.2, 0.1, 0, 0, 0);
opt.axis.Set(1, 0, 0);
opt.wait = common::Time(99, 0);
physics::JointPtr joint = SpawnJoint(opt);
ASSERT_NE(nullptr, joint);

physics::LinkPtr childLink = joint->GetChild();
ASSERT_NE(nullptr, childLink);

world->Step(1);

const auto childPos = childLink->WorldCoGPose().Pos();
const double tolerance = 1e-4;
// We expect the child link to be in the same position as it was when it was
// created. The regression is that the child link teleports to the origin.
EXPECT_NEAR(childPos.X(), opt.childLinkPose.Pos().X(), tolerance);
EXPECT_NEAR(childPos.Y(), opt.childLinkPose.Pos().Y(), tolerance);
EXPECT_NEAR(childPos.Z(), opt.childLinkPose.Pos().Z(), tolerance);
}

TEST_P(Issue2239Test, TestRevolute2JointTeleport)
{
this->TestRevolute2JointTeleport(this->physicsEngine);
}

INSTANTIATE_TEST_CASE_P(PhysicsEngines, Issue2239Test,
::testing::Combine(::testing::Values("ode", "dart"), ::testing::Values("")));

/////////////////////////////////////////////////
int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
1 change: 1 addition & 0 deletions test/regression/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ set(tests
2297_log_insertions_paused.cc
2428_log_insertions.cc
2430_revolute_joint_SetPosition.cc
2239_revolute2_teleport.cc
)
gz_build_tests(${tests} EXTRA_LIBS gazebo_test_fixture)

Expand Down

0 comments on commit 8abbfa6

Please sign in to comment.