diff --git a/usv_gazebo_plugins/CMakeLists.txt b/usv_gazebo_plugins/CMakeLists.txt index 3bed368d1..911f76675 100644 --- a/usv_gazebo_plugins/CMakeLists.txt +++ b/usv_gazebo_plugins/CMakeLists.txt @@ -19,8 +19,8 @@ catkin_package( CATKIN_DEPENDS message_runtime gazebo_dev roscpp wave_gazebo_plugins ) -# Plugins require c++11 -set(CMAKE_CXX_FLAGS "-std=c++11 ${CMAKE_CXX_FLAGS}") +# Plugins require c++17 +set(CMAKE_CXX_FLAGS "-std=c++17 ${CMAKE_CXX_FLAGS}") include_directories( include ${catkin_INCLUDE_DIRS} diff --git a/usv_gazebo_plugins/include/usv_gazebo_plugins/usv_gazebo_dynamics_plugin.hh b/usv_gazebo_plugins/include/usv_gazebo_plugins/usv_gazebo_dynamics_plugin.hh index 98a58a682..598dcfe22 100644 --- a/usv_gazebo_plugins/include/usv_gazebo_plugins/usv_gazebo_dynamics_plugin.hh +++ b/usv_gazebo_plugins/include/usv_gazebo_plugins/usv_gazebo_dynamics_plugin.hh @@ -40,7 +40,7 @@ namespace gazebo /// : Horizontal surface area [m^2]. Default value is 0.48. /// : Boat length [m]. Default value is 1.35. /// : Boat width [m]. Default value is 1. - /// : Water density [kg/m^3]. Default value is 997.7735. + /// : Water density [kg/m^3]. Default value is 1000. /// : Water height [m]. Default value is 0.5. /// : Added mass coeff, surge. /// : Added mass coeff, sway. diff --git a/usv_gazebo_plugins/src/buoyancy_gazebo_plugin.cc b/usv_gazebo_plugins/src/buoyancy_gazebo_plugin.cc index 65f76a383..cb1606e5d 100644 --- a/usv_gazebo_plugins/src/buoyancy_gazebo_plugin.cc +++ b/usv_gazebo_plugins/src/buoyancy_gazebo_plugin.cc @@ -105,7 +105,7 @@ std::string BuoyancyObject::Disp() ///////////////////////////////////////////////// BuoyancyPlugin::BuoyancyPlugin() - : fluidDensity(997), + : fluidDensity(1000), fluidLevel(0.0), linearDrag(0.0), angularDrag(0.0), diff --git a/usv_gazebo_plugins/src/usv_gazebo_dynamics_plugin.cc b/usv_gazebo_plugins/src/usv_gazebo_dynamics_plugin.cc index 05aae52bc..6a4561bbc 100644 --- a/usv_gazebo_plugins/src/usv_gazebo_dynamics_plugin.cc +++ b/usv_gazebo_plugins/src/usv_gazebo_dynamics_plugin.cc @@ -88,7 +88,7 @@ void UsvDynamicsPlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf) } this->waterLevel = this->SdfParamDouble(_sdf, "waterLevel" , 0.5); - this->waterDensity = this->SdfParamDouble(_sdf, "waterDensity", 997.7735); + this->waterDensity = this->SdfParamDouble(_sdf, "waterDensity", 1000); this->paramXdotU = this->SdfParamDouble(_sdf, "xDotU" , 5); this->paramYdotV = this->SdfParamDouble(_sdf, "yDotV" , 5); this->paramZdotW = this->SdfParamDouble(_sdf, "zDotW" , 0.1); diff --git a/wamv_gazebo/urdf/dynamics/wamv_gazebo_dynamics_plugin.xacro b/wamv_gazebo/urdf/dynamics/wamv_gazebo_dynamics_plugin.xacro index 71eb2656a..dc6ed04e1 100644 --- a/wamv_gazebo/urdf/dynamics/wamv_gazebo_dynamics_plugin.xacro +++ b/wamv_gazebo/urdf/dynamics/wamv_gazebo_dynamics_plugin.xacro @@ -7,7 +7,7 @@ ${namespace}/base_link 0 - 997.8 + 1000 0.0 0.0 diff --git a/wave_gazebo_plugins/CMakeLists.txt b/wave_gazebo_plugins/CMakeLists.txt index 998674a3e..c9e04e0e1 100644 --- a/wave_gazebo_plugins/CMakeLists.txt +++ b/wave_gazebo_plugins/CMakeLists.txt @@ -2,21 +2,13 @@ cmake_minimum_required(VERSION 2.8.3) project(wave_gazebo_plugins) ############################################################################### -# Compile as C++11, supported in ROS Kinetic and newer -#set(CMAKE_CXX_STANDARD 11) -#set(CMAKE_CXX_STANDARD_REQUIRED ON) - -# For this package set as C++14 include(CheckCXXCompilerFlag) -CHECK_CXX_COMPILER_FLAG("-std=c++14" COMPILER_SUPPORTS_CXX14) -CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X) -if(COMPILER_SUPPORTS_CXX14) - set(CMAKE_CXX_FLAGS "-std=c++14") -elseif(COMPILER_SUPPORTS_CXX0X) - set(CMAKE_CXX_FLAGS "-std=c++0x") +CHECK_CXX_COMPILER_FLAG("-std=c++17" COMPILER_SUPPORTS_CXX17) +if(COMPILER_SUPPORTS_CXX17) + add_compile_options(-std=c++17) else() - message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++14 support. Please use a different C++ compiler.") + message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++17 support. Please use a different C++ compiler.") endif() # Set policy for CMake 3.1+. Use OLD policy to let FindBoost.cmake, dependency diff --git a/wave_gazebo_plugins/include/wave_gazebo_plugins/PhysicalConstants.hh b/wave_gazebo_plugins/include/wave_gazebo_plugins/PhysicalConstants.hh index eb991d3cc..b0e9f7498 100644 --- a/wave_gazebo_plugins/include/wave_gazebo_plugins/PhysicalConstants.hh +++ b/wave_gazebo_plugins/include/wave_gazebo_plugins/PhysicalConstants.hh @@ -43,7 +43,7 @@ namespace asv /// \brief Density of water. /// - /// \return 998.6 [kg m-3]. + /// \return 1000 [kg m-3]. public: static double WaterDensity(); /// \brief Kinematic viscosity of water at 18 dgree C. diff --git a/wave_gazebo_plugins/src/PhysicalConstants.cc b/wave_gazebo_plugins/src/PhysicalConstants.cc index 4d1ffee53..c1c0c1016 100644 --- a/wave_gazebo_plugins/src/PhysicalConstants.cc +++ b/wave_gazebo_plugins/src/PhysicalConstants.cc @@ -34,7 +34,7 @@ namespace asv ///////////////////////////////////////////////////////////////////////////// double PhysicalConstants::WaterDensity() { - return 998.6; + return 1000.; } /////////////////////////////////////////////////////////////////////////////