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

Added world linear and angular velocity reset components for link to set_model_state plugin #2440

Open
wants to merge 25 commits into
base: scpeters/set_model_state_prototype
Choose a base branch
from

Conversation

yaswanth1701
Copy link
Contributor

@yaswanth1701 yaswanth1701 commented Jun 8, 2024

🎉 New feature

Follow up PR to #2359

Summary

This PR introduces WorldLinearVelocityReset and WorldAngularVelocityReset components for the LInk entity to set initial link velocities from SDF using set_model_state plugin. The link velocities are only set to root link of the FreeGroup for now.

Test it

gz sim -v 4 examples/worlds/set_model_state.sdf

Should see the red cube moving and rotating.

ezgif-3-6b40df0406

Checklist

  • Signed all commits for DCO
  • Added tests
  • Added example and/or tutorial
  • Updated documentation (as needed)
  • Updated migration guide (as needed)
  • Consider updating Python bindings (if the library has them)
  • codecheck passed (See contributing)
  • All tests passed (See test coverage)
  • While waiting for a review on your PR, please help review another open pull request to support the maintainers

Note to maintainers: Remember to use Squash-Merge and edit the commit message to match the pull request summary while retaining Signed-off-by messages.

Signed-off-by: yaswanth1701 <[email protected]>
Signed-off-by: yaswanth1701 <[email protected]>
Signed-off-by: yaswanth1701 <[email protected]>
Signed-off-by: yaswanth1701 <[email protected]>
Signed-off-by: yaswanth1701 <[email protected]>
Signed-off-by: yaswanth1701 <[email protected]>
@@ -0,0 +1,48 @@
/*
* Copyright (C) 2019 Open Source Robotics Foundation
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
* Copyright (C) 2019 Open Source Robotics Foundation
* Copyright (C) 2024 Open Source Robotics Foundation

*/
#ifndef GZ_SIM_COMPONENTS_WORLDANGULARVELOCITYRESET_HH_
#define GZ_SIM_COMPONENTS_WORLDANGULARELOCITYRESET_HH_
#include <vector>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

remove, this is not used in this header

@@ -0,0 +1,48 @@
/*
* Copyright (C) 2019 Open Source Robotics Foundation
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
* Copyright (C) 2019 Open Source Robotics Foundation
* Copyright (C) 2024 Open Source Robotics Foundation

*/
#ifndef GZ_SIM_COMPONENTS_WORLDLINEARVELOCITYRESET_HH_
#define GZ_SIM_COMPONENTS_WORLDLINEARVELOCITYRESET_HH_
#include <vector>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

remove, this is not used in this header

@@ -2591,7 +2593,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm)
return true;
});

// Update link linear velocity
// Update link linear velocity
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
// Update link linear velocity
// Update link linear velocity

return true;

auto rootLinkPtr = freeGroup->RootLink();
if(rootLinkPtr != linkPtrPhys){
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
if(rootLinkPtr != linkPtrPhys){
if(rootLinkPtr != linkPtrPhys)
{

Comment on lines 2726 to 2728
gzwarn << "Attempting to set angular velocity for link ["<< _entity
<<"] which is not root link of the FreeGroup."
<<"Velocity won't be set."<< std::endl;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
gzwarn << "Attempting to set angular velocity for link ["<< _entity
<<"] which is not root link of the FreeGroup."
<<"Velocity won't be set."<< std::endl;
gzwarn << "Attempting to set angular velocity for link [ " << _entity
<< " ] which is not root link of the FreeGroup."
<< "Velocity won't be set." << std::endl;

Comment on lines 2744 to 2747
gzdbg << "Attempting to set link angular velocity, but the "
<< "physics engine doesn't support velocity commands. "
<< "Velocity won't be set."
<< std::endl;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
gzdbg << "Attempting to set link angular velocity, but the "
<< "physics engine doesn't support velocity commands. "
<< "Velocity won't be set."
<< std::endl;
gzdbg << "Attempting to set link angular velocity, but the "
<< "physics engine doesn't support velocity commands. "
<< "Velocity won't be set."
<< std::endl;

Comment on lines 216 to 217


Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

remove

Comment on lines 281 to 284
}
}

}
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

wierd indentation

@yaswanth1701
Copy link
Contributor Author

Hi Alejandro, I have made the required changes, can you please review them again.

worldAngularVelFeature->SetWorldAngularVelocity(
math::eigen3::convert(worldAngularVel));
this->angularVelocityResetFlag = true;
}
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I see that this is your logic for ensuring that the VelocityReset components are only acted on a single time, but I recommend following the method used for the JointVelocityReset component, which is to delete the component after it has been acted on:

  • std::vector<Entity> entitiesVelocityReset;
    _ecm.Each<components::JointVelocityReset>(
    [&](const Entity &_entity, components::JointVelocityReset *) -> bool
    {
    entitiesVelocityReset.push_back(_entity);
    return true;
    });
    for (const auto entity : entitiesVelocityReset)
    {
    _ecm.RemoveComponent<components::JointVelocityReset>(entity);
    }

Copy link
Member

@scpeters scpeters left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

for consistency with the other component header files, we could name them simply AngularVelocityReset.hh and LinearVelocityReset.hh. The other header files also define components without the World prefix that refer to velocity in a body-fixed frame. We can leave a TODO comment for now if we don't want to implement that yet

<iyz>0</iyz>
<izz>5</izz>
</inertia>
<mass>120.0</mass>
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I updated #2359 to use auto-inertials in the example world in 7cab1bb

I think we should use a box with 3 different dimensions rather than a cube in order to visualize the Dzhanibekov effect. I think the dimensions from the boxes benchmark test (0.1, 0.4, 0.9) and initial angular velocity with largest component in Y (0.1, 5.0, 0.1) would work well. With the updated dimensions, we could use auto-inertials as well.

<model_state>
<link_state name="box_link">
<linear_velocity>0.1 -0.1 0.1</linear_velocity>
<angular_velocity>1 2 1</angular_velocity>
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I recommend adding a degrees boolean attribute to //link_state/angular_velocity to match the behavior of the //joint_state/position/@degrees and //joint_state/velocity/@degrees attributes. Then it would be nice to have pair of example boxes with angular velocity expressed in both deg/s and rad/s

Copy link
Contributor Author

@yaswanth1701 yaswanth1701 Jun 29, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

got it, I will make the changes

Signed-off-by: yaswanth1701 <[email protected]>
Signed-off-by: yaswanth1701 <[email protected]>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
Status: In review
Development

Successfully merging this pull request may close these issues.

None yet

3 participants