Skip to content

Commit

Permalink
more gz
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina committed Jun 26, 2022
1 parent e6c76d4 commit 1228f9c
Show file tree
Hide file tree
Showing 6 changed files with 8 additions and 8 deletions.
4 changes: 2 additions & 2 deletions dartsim/src/CustomFeatures.hh
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
*
*/

#ifndef IGNITION_PHYSICS_SRC_CUSTOMFEATURES_HH
#define IGNITION_PHYSICS_SRC_CUSTOMFEATURES_HH
#ifndef GZ_PHYSICS_SRC_CUSTOMFEATURES_HH
#define GZ_PHYSICS_SRC_CUSTOMFEATURES_HH

#include <gz/physics/Implements.hh>

Expand Down
2 changes: 1 addition & 1 deletion dartsim/worlds/falling.world
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<sdf version="1.6">
<world name="default">
<plugin
filename="libignition-gazebo-physics-system.so"
filename="libgz-sim-physics-system.so"
name="gz::gazebo::systems::v0::Physics">
</plugin>
<model name="sphere">
Expand Down
2 changes: 1 addition & 1 deletion include/gz/physics/FrameSemantics.hh
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ namespace gz
{
/////////////////////////////////////////////////
/// \brief FrameSemantics is an Interface that can be provided by
/// ignition-physics engines to provide users with easy ways to express
/// gz-physics engines to provide users with easy ways to express
/// kinematic quantities in terms of frames and compute their values in
/// terms of arbitrary frames of reference.
class GZ_PHYSICS_VISIBLE FrameSemantics : public virtual Feature
Expand Down
2 changes: 1 addition & 1 deletion include/gz/physics/Geometry.hh
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ namespace gz
{
namespace physics
{
/// \brief This is used by ignition-physics to represent rigid body
/// \brief This is used by gz-physics to represent rigid body
/// transforms in 2D or 3D simulations. The precision can be chosen as
/// float or scalar.
template <typename Scalar, std::size_t Dim>
Expand Down
2 changes: 1 addition & 1 deletion test/common_test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ foreach(test ${tests})
target_link_libraries(${TEST_TYPE}_${test}
PUBLIC
gz-plugin${GZ_PLUGIN_VER}::loader
gz-common5::gz-common5
gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER}
${PROJECT_LIBRARY_TARGET_NAME}
gtest
gtest_main
Expand Down
4 changes: 2 additions & 2 deletions tpe/plugin/src/CustomFeatures.hh
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
*
*/

#ifndef IGNITION_PHYSICS_TPE_PLUGIN_SRC_CUSTOMFEATURES_HH
#define IGNITION_PHYSICS_TPE_PLUGIN_SRC_CUSTOMFEATURES_HH
#ifndef GZ_PHYSICS_TPE_PLUGIN_SRC_CUSTOMFEATURES_HH
#define GZ_PHYSICS_TPE_PLUGIN_SRC_CUSTOMFEATURES_HH

#include <memory>

Expand Down

0 comments on commit 1228f9c

Please sign in to comment.