Skip to content

Commit

Permalink
fix codecheck errors
Browse files Browse the repository at this point in the history
Signed-off-by: claireyywang <[email protected]>
  • Loading branch information
claireyywang committed Jun 1, 2020
1 parent cb10101 commit 4863437
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 8 deletions.
4 changes: 2 additions & 2 deletions include/ignition/gazebo/components/AngularVelocityCmd.hh
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,8 @@ namespace components
IGN_GAZEBO_REGISTER_COMPONENT(
"ign_gazebo_components.AngularVelocityCmd", AngularVelocityCmd)

/// \brief A component type that contains angular velocity cmd of an entity in the
/// world frame represented by ignition::math::Vector3d.
/// \brief A component type that contains angular velocity cmd
/// of an entity in the world frame represented by ignition::math::Vector3d.
using WorldAngularVelocityCmd =
Component<math::Vector3d, class WorldAngularVelocityCmdTag>;
IGN_GAZEBO_REGISTER_COMPONENT(
Expand Down
3 changes: 2 additions & 1 deletion include/ignition/gazebo/components/LinearVelocityCmd.hh
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,8 @@ namespace components
{
/// \brief A component type that contains linear velocity of an entity
/// represented by ignition::math::Vector3d.
using LinearVelocityCmd = Component<math::Vector3d, class LinearVelocityCmdTag>;
using LinearVelocityCmd = Component<
math::Vector3d, class LinearVelocityCmdTag>;
IGN_GAZEBO_REGISTER_COMPONENT(
"ign_gazebo_components.LinearVelocityCmd", LinearVelocityCmd)

Expand Down
11 changes: 6 additions & 5 deletions src/systems/physics/Physics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -416,9 +416,10 @@ class ignition::gazebo::systems::PhysicsPrivate
ignition::physics::FeaturePolicy3d,
WorldVelocityCommandFeatureList>;

/// \brief A map between free group entity ids in the ECM to FreeGroup Entities in
/// ign-physics, with velocity command feature.
/// All FreeGroup on this map are casted for `WorldVelocityCommandFeatureList`.
/// \brief A map between free group entity ids in the ECM
/// to FreeGroup Entities in ign-physics, with velocity command feature.
/// All FreeGroup on this map are casted for
/// `WorldVelocityCommandFeatureList`.
public: std::unordered_map<Entity, FreeGroupVelocityCmdPtrType>
entityWorldVelocityCommandMap;

Expand Down Expand Up @@ -1296,7 +1297,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm)

return true;
});

// Update model pose
_ecm.Each<components::Model, components::WorldPoseCmd>(
[&](const Entity &_entity, const components::Model *,
Expand Down Expand Up @@ -1371,7 +1372,7 @@ void PhysicsPrivate::UpdatePhysics(EntityComponentManager &_ecm)

return true;
});

// Update model linear velocity
_ecm.Each<components::Model, components::LinearVelocityCmd>(
[&](const Entity &_entity, const components::Model *,
Expand Down

0 comments on commit 4863437

Please sign in to comment.