Skip to content

Commit

Permalink
Add parameter to TrajectoryFollower stop rotation when bearing is rea…
Browse files Browse the repository at this point in the history
…ched (#1349)

* force stop rotation by setting ang vel to zero

Signed-off-by: Ian Chen <[email protected]>

* update example and bearing tol

Signed-off-by: Ian Chen <[email protected]>

* update tol check

Signed-off-by: Ian Chen <[email protected]>

* add note

Signed-off-by: Ian Chen <[email protected]>

* remove param from example world

Signed-off-by: Ian Chen <[email protected]>
  • Loading branch information
iche033 authored Feb 25, 2022
1 parent 8b8b9f6 commit d3a5015
Show file tree
Hide file tree
Showing 6 changed files with 85 additions and 2 deletions.
8 changes: 8 additions & 0 deletions include/ignition/gazebo/Link.hh
Original file line number Diff line number Diff line change
Expand Up @@ -227,6 +227,14 @@ namespace ignition
public: void SetLinearVelocity(EntityComponentManager &_ecm,
const math::Vector3d &_vel) const;


/// \brief Set the angular velocity on this link. If this is set, wrenches
/// on this link will be ignored for the current time step.
/// \param[in] _ecm Entity Component manager.
/// \param[in] _vel Angular velocity to set in Link's Frame.
public: void SetAngularVelocity(EntityComponentManager &_ecm,
const math::Vector3d &_vel) const;

/// \brief Get the angular acceleration of the body in the world frame.
/// \param[in] _ecm Entity-component manager.
/// \return Angular acceleration of the body in the world frame or
Expand Down
20 changes: 20 additions & 0 deletions src/Link.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

#include "ignition/gazebo/components/AngularAcceleration.hh"
#include "ignition/gazebo/components/AngularVelocity.hh"
#include "ignition/gazebo/components/AngularVelocityCmd.hh"
#include "ignition/gazebo/components/CanonicalLink.hh"
#include "ignition/gazebo/components/Collision.hh"
#include "ignition/gazebo/components/ExternalWorldWrenchCmd.hh"
Expand Down Expand Up @@ -266,6 +267,25 @@ void Link::SetLinearVelocity(EntityComponentManager &_ecm,
}
}

//////////////////////////////////////////////////
void Link::SetAngularVelocity(EntityComponentManager &_ecm,
const math::Vector3d &_vel) const
{
auto vel =
_ecm.Component<components::AngularVelocityCmd>(this->dataPtr->id);

if (vel == nullptr)
{
_ecm.CreateComponent(
this->dataPtr->id,
components::AngularVelocityCmd(_vel));
}
else
{
vel->Data() = _vel;
}
}

//////////////////////////////////////////////////
std::optional<math::Vector3d> Link::WorldAngularAcceleration(
const EntityComponentManager &_ecm) const
Expand Down
1 change: 0 additions & 1 deletion src/systems/physics/Physics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2150,7 +2150,6 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm)

worldAngularVelFeature->SetWorldAngularVelocity(
math::eigen3::convert(worldAngularVel));

return true;
});

Expand Down
35 changes: 34 additions & 1 deletion src/systems/trajectory_follower/TrajectoryFollower.cc
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
#include <sdf/sdf.hh>

#include "ignition/gazebo/components/Pose.hh"
#include "ignition/gazebo/components/AngularVelocityCmd.hh"
#include "ignition/gazebo/Link.hh"
#include "ignition/gazebo/Model.hh"
#include "ignition/gazebo/Util.hh"
Expand Down Expand Up @@ -109,6 +110,12 @@ class ignition::gazebo::systems::TrajectoryFollowerPrivate

/// \brief Whether the trajectory follower behavior should be paused or not.
public: bool paused = false;

/// \brief Angular velocity set to zero
public: bool zeroAngVelSet = false;

/// \brief Force angular velocity to be zero when bearing is reached
public: bool forceZeroAngVel = false;
};

//////////////////////////////////////////////////
Expand Down Expand Up @@ -249,6 +256,10 @@ void TrajectoryFollowerPrivate::Load(const EntityComponentManager &_ecm,
if (_sdf->HasElement("bearing_tolerance"))
this->bearingTolerance = _sdf->Get<double>("bearing_tolerance");

// Parse the optional <zero_vel_on_bearing_reached> element.
if (_sdf->HasElement("zero_vel_on_bearing_reached"))
this->forceZeroAngVel = _sdf->Get<bool>("zero_vel_on_bearing_reached");

// Parse the optional <topic> element.
this->topic = "/model/" + this->model.Name(_ecm) +
"/trajectory_follower/pause";
Expand Down Expand Up @@ -376,11 +387,33 @@ void TrajectoryFollower::PreUpdate(
{
forceWorld = (*comPose).Rot().RotateVector(
ignition::math::Vector3d(this->dataPtr->forceToApply, 0, 0));
}

// force angular velocity to be zero when bearing is reached
if (this->dataPtr->forceZeroAngVel && !this->dataPtr->zeroAngVelSet &&
math::equal (std::abs(bearing.Degree()), 0.0,
this->dataPtr->bearingTolerance * 0.5))
{
this->dataPtr->link.SetAngularVelocity(_ecm, math::Vector3d::Zero);
this->dataPtr->zeroAngVelSet = true;
}
}
ignition::math::Vector3d torqueWorld;
if (std::abs(bearing.Degree()) > this->dataPtr->bearingTolerance)
{
// remove angular velocity component otherwise the physics system will set
// the zero ang vel command every iteration
if (this->dataPtr->forceZeroAngVel && this->dataPtr->zeroAngVelSet)
{
auto angVelCmdComp = _ecm.Component<components::AngularVelocityCmd>(
this->dataPtr->link.Entity());
if (angVelCmdComp)
{
_ecm.RemoveComponent<components::AngularVelocityCmd>(
this->dataPtr->link.Entity());
this->dataPtr->zeroAngVelSet = false;
}
}

int sign = std::abs(bearing.Degree()) / bearing.Degree();
torqueWorld = (*comPose).Rot().RotateVector(
ignition::math::Vector3d(0, 0, sign * this->dataPtr->torqueToApply));
Expand Down
5 changes: 5 additions & 0 deletions src/systems/trajectory_follower/TrajectoryFollower.hh
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,11 @@ namespace systems
/// <bearing_tolerance>: If the bearing to the current waypoint is within
/// +- this tolerance, a torque won't be applied (degree)
/// The default value is 2 deg.
/// <zero_vel_on_bearing_reached>: Force angular velocity to be zero when
/// target bearing is reached.
/// Default is false.
/// Note: this is an experimental parameter
/// and may be removed in the future.
/// <force>: The force to apply at every plugin iteration in the X direction
/// of the link (N). The default value is 60.
/// <torque>: The torque to apply at every plugin iteration in the Yaw
Expand Down
18 changes: 18 additions & 0 deletions test/integration/link.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@

#include <ignition/gazebo/components/AngularAcceleration.hh>
#include <ignition/gazebo/components/AngularVelocity.hh>
#include <ignition/gazebo/components/AngularVelocityCmd.hh>
#include <ignition/gazebo/components/CanonicalLink.hh>
#include <ignition/gazebo/components/Collision.hh>
#include <ignition/gazebo/components/ExternalWorldWrenchCmd.hh>
Expand Down Expand Up @@ -500,6 +501,23 @@ TEST_F(LinkIntegrationTest, LinkSetVelocity)
link.SetLinearVelocity(ecm, linVel2);
EXPECT_EQ(linVel2,
ecm.Component<components::LinearVelocityCmd>(eLink)->Data());

// No AngularVelocityCmd should exist by default
EXPECT_EQ(nullptr, ecm.Component<components::AngularVelocityCmd>(eLink));

math::Vector3d angVel(0, 0, 1);
link.SetAngularVelocity(ecm, angVel);

// AngularVelocity cmd should exist
EXPECT_NE(nullptr, ecm.Component<components::AngularVelocityCmd>(eLink));
EXPECT_EQ(angVel,
ecm.Component<components::AngularVelocityCmd>(eLink)->Data());

// Make sure the angular velocity is updated
math::Vector3d angVel2(0, 0, 0);
link.SetAngularVelocity(ecm, angVel2);
EXPECT_EQ(angVel2,
ecm.Component<components::AngularVelocityCmd>(eLink)->Data());
}

//////////////////////////////////////////////////
Expand Down

0 comments on commit d3a5015

Please sign in to comment.