Skip to content

Commit

Permalink
3 ➡️ 4 (#253)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina authored Apr 29, 2021
2 parents b5e0511 + 809f338 commit ecd4692
Show file tree
Hide file tree
Showing 21 changed files with 306 additions and 198 deletions.
29 changes: 0 additions & 29 deletions .github/ISSUE_TEMPLATE/bug_report.md

This file was deleted.

23 changes: 0 additions & 23 deletions .github/ISSUE_TEMPLATE/feature_request.md

This file was deleted.

52 changes: 0 additions & 52 deletions .github/PULL_REQUEST_TEMPLATE.md

This file was deleted.

6 changes: 0 additions & 6 deletions .github/PULL_REQUEST_TEMPLATE/port.md

This file was deleted.

3 changes: 2 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,8 @@ find_package(ignition-cmake2 2.1.0 REQUIRED)
#============================================================================
# Configure the project
#============================================================================
ign_configure_project(VERSION_SUFFIX)
ign_configure_project()


#============================================================================
# Set project-specific options
Expand Down
98 changes: 98 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,62 @@

### Ignition Physics 3.x.x (20XX-XX-XX)

### Ignition Physics 3.2.0 (2021-04-28)

1. Infrastructure
* [Pull request #221](https://github.com/ignitionrobotics/ign-physics/pull/221)
* [Pull request #215](https://github.com/ignitionrobotics/ign-physics/pull/215)
* [Pull request #211](https://github.com/ignitionrobotics/ign-physics/pull/211)
* [Pull request #210](https://github.com/ignitionrobotics/ign-physics/pull/210)

1. Linters
* [Pull request #201](https://github.com/ignitionrobotics/ign-physics/pull/201)
* [Pull request #154](https://github.com/ignitionrobotics/ign-physics/pull/154)

1. Documentation
* [Pull request #164](https://github.com/ignitionrobotics/ign-physics/pull/164)
* [Pull request #163](https://github.com/ignitionrobotics/ign-physics/pull/163)
* [Pull request #187](https://github.com/ignitionrobotics/ign-physics/pull/187)
* [Pull request #162](https://github.com/ignitionrobotics/ign-physics/pull/162)
* [Pull request #120](https://github.com/ignitionrobotics/ign-physics/pull/120)
* [Pull request #144](https://github.com/ignitionrobotics/ign-physics/pull/144)
* [Pull request #131](https://github.com/ignitionrobotics/ign-physics/pull/131)
* [Pull request #128](https://github.com/ignitionrobotics/ign-physics/pull/128)
* [Pull request #115](https://github.com/ignitionrobotics/ign-physics/pull/115)
* [Pull request #104](https://github.com/ignitionrobotics/ign-physics/pull/104)
* [Pull request #105](https://github.com/ignitionrobotics/ign-physics/pull/105)
* [Pull request #106](https://github.com/ignitionrobotics/ign-physics/pull/106)

1. Add Windows installation
* [Pull request #194](https://github.com/ignitionrobotics/ign-physics/pull/194)

1. dartsim-plugin windows build fixes
* [Pull request #148](https://github.com/ignitionrobotics/ign-physics/pull/148)

1. [TPE] Skip computing collisions for static objects
* [Pull request #181](https://github.com/ignitionrobotics/ign-physics/pull/181)

1. [TPE] Update link pose and velocity
* [Pull request #179](https://github.com/ignitionrobotics/ign-physics/pull/179)

1. [TPE] Fix poseDirty getter
* [Pull request #182](https://github.com/ignitionrobotics/ign-physics/pull/182)

1. Add restitution coefficient support for bouncing
* [Pull request #139](https://github.com/ignitionrobotics/ign-physics/pull/139)

1. Fix compilation with gcc 10.2.0
* [Pull request #185](https://github.com/ignitionrobotics/ign-physics/pull/185)

1. Support setting canonical link
* [Pull request #142](https://github.com/ignitionrobotics/ign-physics/pull/142)

1. Ignore invalid joint commands
* [Pull request #137](https://github.com/ignitionrobotics/ign-physics/pull/137)

1. Fix CONFIG arg in ign_find_package(DART) call
* [Pull request #119](https://github.com/ignitionrobotics/ign-physics/pull/119)

### Ignition Physics 3.1.0 (2020-10-18)

1. Support for slip compliance in the dartsim-plugin.
Expand Down Expand Up @@ -114,6 +170,48 @@

### Ignition Physics 2.x.x (20XX-XX-XX)

### Ignition Physics 2.4.0 (2021-04-14)

1. [TPE] Update link pose and velocity
* [Pull request #179](https://github.com/ignitionrobotics/ign-physics/pull/179)

1. Infrastructure
* [Pull request #221](https://github.com/ignitionrobotics/ign-physics/pull/221)
* [Pull request #211](https://github.com/ignitionrobotics/ign-physics/pull/211)
* [Pull request #130](https://github.com/ignitionrobotics/ign-physics/pull/130)
* [Pull request #118](https://github.com/ignitionrobotics/ign-physics/pull/118)

1. Documentation
* [Pull request #187](https://github.com/ignitionrobotics/ign-physics/pull/187)
* [Pull request #194](https://github.com/ignitionrobotics/ign-physics/pull/194)

1. TPE: Skip computing collisions for static objects
* [Pull request #181](https://github.com/ignitionrobotics/ign-physics/pull/181)

1. Add restitution coefficient support for bouncing
* [Pull request #139](https://github.com/ignitionrobotics/ign-physics/pull/139)

1. Fix compilation with gcc 10.2.0
* [Pull request #185](https://github.com/ignitionrobotics/ign-physics/pull/185)

1. Fix TPE poseDirty getter
* [Pull request #182](https://github.com/ignitionrobotics/ign-physics/pull/182)

1. Support setting canonical link
* [Pull request #142](https://github.com/ignitionrobotics/ign-physics/pull/142)

1. Resolved codecheck issues
* [Pull request #154](https://github.com/ignitionrobotics/ign-physics/pull/154)

1. Ignore invalid joint commands
* [Pull request #137](https://github.com/ignitionrobotics/ign-physics/pull/137)

1. Support getting shape AABB in world frame
* [Pull request #127](https://github.com/ignitionrobotics/ign-physics/pull/127)

1. Fix CONFIG arg in `ign_find_package(DART)` call
* [Pull request #119](https://github.com/ignitionrobotics/ign-physics/pull/119)

### Ignition Physics 2.3.0 (2020-09-29)

1. Support for slip compliance in the dartsim-plugin.
Expand Down
10 changes: 5 additions & 5 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,9 +9,9 @@

Build | Status
-- | --
Test coverage | [![codecov](https://codecov.io/gh/ignitionrobotics/ign-physics/branch/main/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-physics)
Ubuntu Bionic | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_physics-ci-main-bionic-amd64)](https://build.osrfoundation.org/job/ignition_physics-ci-main-bionic-amd64)
Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_physics-ci-main-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_physics-ci-main-homebrew-amd64)
Test coverage | [![codecov](https://codecov.io/gh/ignitionrobotics/ign-physics/branch/ign-physics4/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-physics)
Ubuntu Bionic | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_physics-ci-ign-physics4-bionic-amd64)](https://build.osrfoundation.org/job/ignition_physics-ci-ign-physics4-bionic-amd64)
Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_physics-ci-ign-physics4-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_physics-ci-ign-physics4-homebrew-amd64)
Windows | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ign_physics-ci-win)](https://build.osrfoundation.org/job/ign_physics-ci-win)

Ignition Physics, a component of [Ignition
Expand Down Expand Up @@ -74,7 +74,7 @@ See the [installation tutorial](https://ignitionrobotics.org/api/physics/4.0/ins

# Usage

Please refer to the [examples directory](https://github.com/ignitionrobotics/ign-physics/raw/main/examples/).
Please refer to the [examples directory](https://github.com/ignitionrobotics/ign-physics/raw/ign-physics4/examples/).

# Documentation

Expand All @@ -91,7 +91,7 @@ You can also generate the documentation from a clone of this repository by follo
2. Clone the repository
```
git clone https://github.com/ignitionrobotics/ign-physics -b main
git clone https://github.com/ignitionrobotics/ign-physics -b ign-physics4
```
3. Configure and build the documentation.
Expand Down
2 changes: 1 addition & 1 deletion tpe/lib/src/Entity.hh
Original file line number Diff line number Diff line change
Expand Up @@ -173,7 +173,7 @@ class IGNITION_PHYSICS_TPELIB_VISIBLE Entity

/// \brief Get number of children
/// \return Map of child id's to child entities
protected: std::map<std::size_t, std::shared_ptr<Entity>> &GetChildren()
public: std::map<std::size_t, std::shared_ptr<Entity>> &GetChildren()
const;

/// \brief Update the entity bounding box
Expand Down
38 changes: 38 additions & 0 deletions tpe/lib/src/Link.cc
Original file line number Diff line number Diff line change
Expand Up @@ -42,3 +42,41 @@ Entity &Link::AddCollision()
this->ChildrenChanged();
return *it->second.get();
}

//////////////////////////////////////////////////
void Link::SetLinearVelocity(const math::Vector3d &_velocity)
{
this->linearVelocity = _velocity;
}

//////////////////////////////////////////////////
math::Vector3d Link::GetLinearVelocity() const
{
return this->linearVelocity;
}

//////////////////////////////////////////////////
void Link::SetAngularVelocity(const math::Vector3d &_velocity)
{
this->angularVelocity = _velocity;
}

//////////////////////////////////////////////////
math::Vector3d Link::GetAngularVelocity() const
{
return this->angularVelocity;
}

//////////////////////////////////////////////////
void Link::UpdatePose(double _timeStep)
{
if (this->linearVelocity == math::Vector3d::Zero &&
this->angularVelocity == math::Vector3d::Zero)
return;

math::Pose3d currentPose = this->GetPose();
math::Pose3d nextPose(
currentPose.Pos() + this->linearVelocity * _timeStep,
currentPose.Rot().Integrate(this->angularVelocity, _timeStep));
this->SetPose(nextPose);
}
30 changes: 30 additions & 0 deletions tpe/lib/src/Link.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@
#ifndef IGNITION_PHYSICS_TPE_LIB_SRC_LINK_HH_
#define IGNITION_PHYSICS_TPE_LIB_SRC_LINK_HH_

#include <ignition/utilities/SuppressWarning.hh>

#include "ignition/physics/tpelib/Export.hh"

#include "Entity.hh"
Expand All @@ -42,6 +44,34 @@ class IGNITION_PHYSICS_TPELIB_VISIBLE Link : public Entity
/// \brief Add a collision
/// \return Newly created Collision
public: Entity &AddCollision();

/// \brief Set the linear velocity of link relative to parent
/// \param[in] _velocity linear velocity in meters per second
public: void SetLinearVelocity(const math::Vector3d &_velocity);

/// \brief Get the linear velocity of link relative to parent
/// \return linear velocity of link in meters per second
public: math::Vector3d GetLinearVelocity() const;

/// \brief Set the angular velocity of link relative to parent
/// \param[in] _velocity angular velocity in radians per second
public: void SetAngularVelocity(const math::Vector3d &_velocity);

/// \brief Get the angular velocity of link relative to parent
/// \return angular velocity in radians per second
public: math::Vector3d GetAngularVelocity() const;

/// \brief Update the pose of the entity
/// \param[in] _timeStep current world timestep in seconds
public: virtual void UpdatePose(double _timeStep);

IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief linear velocity of link
protected: math::Vector3d linearVelocity;

/// \brief angular velocity of link
protected: math::Vector3d angularVelocity;
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};

}
Expand Down
Loading

0 comments on commit ecd4692

Please sign in to comment.