Skip to content

Commit

Permalink
resolved formatting comments
Browse files Browse the repository at this point in the history
Signed-off-by: yaswanth1701 <gonnayaswanth17@gmail.com>
  • Loading branch information
yaswanth1701 committed Jun 11, 2024
1 parent 8e730cc commit 3db0e98
Show file tree
Hide file tree
Showing 4 changed files with 29 additions and 27 deletions.
3 changes: 1 addition & 2 deletions include/gz/sim/components/WorldAngularVelocityReset.hh
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/*
* Copyright (C) 2019 Open Source Robotics Foundation
* Copyright (C) 2024 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.
Expand All @@ -16,7 +16,6 @@
*/
#ifndef GZ_SIM_COMPONENTS_WORLDANGULARVELOCITYRESET_HH_
#define GZ_SIM_COMPONENTS_WORLDANGULARELOCITYRESET_HH_
#include <vector>

#include <gz/math/Vector3.hh>
#include <gz/sim/components/Component.hh>
Expand Down
3 changes: 1 addition & 2 deletions include/gz/sim/components/WorldLinearVelocityReset.hh
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/*
* Copyright (C) 2019 Open Source Robotics Foundation
* Copyright (C) 2024 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.
Expand All @@ -16,7 +16,6 @@
*/
#ifndef GZ_SIM_COMPONENTS_WORLDLINEARVELOCITYRESET_HH_
#define GZ_SIM_COMPONENTS_WORLDLINEARVELOCITYRESET_HH_
#include <vector>

#include <gz/math/Vector3.hh>
#include <gz/sim/components/Component.hh>
Expand Down
37 changes: 20 additions & 17 deletions src/systems/physics/Physics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2593,7 +2593,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm)
return true;
});

// Update link linear velocity
// Update link linear velocity
_ecm.Each<components::Link, components::LinearVelocityCmd>(
[&](const Entity &_entity, const components::Link *,
const components::LinearVelocityCmd *_linearVelocityCmd)
Expand Down Expand Up @@ -2653,7 +2653,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm)
if (!this->entityLinkMap.HasEntity(_entity))
{
gzwarn << "Failed to find link [" << _entity
<< "]." << std::endl;
<< "]." << std::endl;
return true;
}

Expand All @@ -2666,13 +2666,15 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm)
return true;

auto rootLinkPtr = freeGroup->RootLink();
if(rootLinkPtr != linkPtrPhys){
gzwarn << "Attempting to set linear velocity for link ["<< _entity
<<"] which is not root link of the FreeGroup."
<<"Velocity won't be set."<< std::endl;
if(rootLinkPtr != linkPtrPhys)
{
gzwarn << "Attempting to set linear velocity for link [ " << _entity
<< " ] which is not root link of the FreeGroup."
<< "Velocity won't be set." << std::endl;

return true;
}

this->entityFreeGroupMap.AddEntity(_entity, freeGroup);

auto worldLinearVelFeature =
Expand All @@ -2684,9 +2686,9 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm)
if (!informed)
{
gzdbg << "Attempting to set link linear velocity, but the "
<< "physics engine doesn't support velocity commands. "
<< "Velocity won't be set."
<< std::endl;
<< "physics engine doesn't support velocity commands. "
<< "Velocity won't be set."
<< std::endl;
informed = true;
}
return true;
Expand All @@ -2709,7 +2711,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm)
if (!this->entityLinkMap.HasEntity(_entity))
{
gzwarn << "Failed to find link [" << _entity
<< "]." << std::endl;
<< "]." << std::endl;
return true;
}

Expand All @@ -2722,10 +2724,11 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm)
return true;

auto rootLinkPtr = freeGroup->RootLink();
if(rootLinkPtr != linkPtrPhys){
gzwarn << "Attempting to set angular velocity for link ["<< _entity
<<"] which is not root link of the FreeGroup."
<<"Velocity won't be set."<< std::endl;
if(rootLinkPtr != linkPtrPhys)
{
gzwarn << "Attempting to set angular velocity for link [ " << _entity
<< " ] which is not root link of the FreeGroup."
<< "Velocity won't be set." << std::endl;

return true;
}
Expand All @@ -2742,9 +2745,9 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm)
if (!informed)
{
gzdbg << "Attempting to set link angular velocity, but the "
<< "physics engine doesn't support velocity commands. "
<< "Velocity won't be set."
<< std::endl;
<< "physics engine doesn't support velocity commands. "
<< "Velocity won't be set."
<< std::endl;
informed = true;
}
return true;
Expand Down
13 changes: 7 additions & 6 deletions src/systems/set_model_state/SetModelState.cc
Original file line number Diff line number Diff line change
Expand Up @@ -213,8 +213,6 @@ void SetModelState::Configure(const Entity &_entity,
// }
}



if (jointPositionSet)
{
_ecm.SetComponentData<components::JointPositionReset>(jointEntity,
Expand All @@ -229,7 +227,8 @@ void SetModelState::Configure(const Entity &_entity,
}
for (auto linkStateElem = modelStateElem->FindElement("link_state");
linkStateElem != nullptr;
linkStateElem = linkStateElem->GetNextElement("link_state")){
linkStateElem = linkStateElem->GetNextElement("link_state"))
{

std::pair<std::string, bool> namePair =
linkStateElem->Get<std::string>("name", "");
Expand All @@ -248,6 +247,7 @@ void SetModelState::Configure(const Entity &_entity,
continue;
}

//default velocity is initialsed as zero vector.
math::Vector3d defaultVelocity;
math::Vector3d linearVelocity;
math::Vector3d angularVelocity;
Expand All @@ -273,15 +273,16 @@ void SetModelState::Configure(const Entity &_entity,
if(angularVelocityElem){
std::pair<math::Vector3d, bool> vectorPair =
angularVelocityElem->Get<math::Vector3d>("", defaultVelocity);
if(vectorPair.second){
if(vectorPair.second)
{
angularVelocity = vectorPair.first;
_ecm.SetComponentData<components::WorldAngularVelocityReset>(
linkEntity,
angularVelocity);

}
}

}
}
}

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

0 comments on commit 3db0e98

Please sign in to comment.