Skip to content
This repository was archived by the owner on Feb 6, 2023. It is now read-only.

Commit 66474bd

Browse files
author
Thomas Denewiler
committed
Add Noetic support. Set compiler flags based on CMake version. Add conditional code to support Gazebo 11.
Signed-off-by: Thomas Denewiler <[email protected]>
1 parent bfb40cb commit 66474bd

6 files changed

Lines changed: 44 additions & 6 deletions

File tree

uuv_control/uuv_thruster_manager/src/uuv_thrusters/models/thruster_proportional.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414
# limitations under the License.
1515
import rospy
1616
import numpy
17-
from thruster import Thruster
17+
from .thruster import Thruster
1818

1919

2020
class ThrusterProportional(Thruster):

uuv_gazebo_plugins/uuv_gazebo_plugins/CMakeLists.txt

Lines changed: 19 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,13 @@
1-
cmake_minimum_required(VERSION 2.8.3)
1+
cmake_minimum_required(VERSION 3.0.2)
22
project(uuv_gazebo_plugins)
33

44
# Specify C++11 standard
5-
add_definitions(-std=c++11)
5+
if(NOT "${CMAKE_VERSION}" VERSION_LESS "3.16")
6+
set(CMAKE_CXX_STANDARD 17)
7+
set(CMAKE_CXX_STANDARD_REQUIRED ON)
8+
else()
9+
set(LOCAL_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
10+
endif()
611

712
find_package(catkin REQUIRED COMPONENTS
813
gazebo_dev)
@@ -72,6 +77,11 @@ add_library(uuv_dynamics
7277
src/Dynamics.cc
7378
)
7479
list(APPEND UUV_GAZEBO_PLUGINS_LIST uuv_dynamics)
80+
set_target_properties(uuv_dynamics
81+
PROPERTIES
82+
COMPILE_FLAGS
83+
"${LOCAL_CXX_FLAGS}"
84+
)
7585

7686
add_library(uuv_fin_plugin
7787
src/LiftDragModel.cc
@@ -97,6 +107,11 @@ target_link_libraries(uuv_underwater_object_plugin
97107
${EIGEN3_LIBRARIES}
98108
)
99109
list(APPEND UUV_GAZEBO_PLUGINS_LIST uuv_underwater_object_plugin)
110+
set_target_properties(uuv_underwater_object_plugin
111+
PROPERTIES
112+
COMPILE_FLAGS
113+
"${LOCAL_CXX_FLAGS}"
114+
)
100115

101116
add_library(uuv_thruster_plugin
102117
src/ThrusterConversionFcn.cc
@@ -136,8 +151,8 @@ install(DIRECTORY include/${PROJECT_NAME}/
136151
)
137152

138153
install(DIRECTORY include/
139-
DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}
140-
FILES_MATCHING PATTERN ".hh"
154+
DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}
155+
FILES_MATCHING PATTERN ".hh"
141156
)
142157

143158
install(DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/

uuv_gazebo_plugins/uuv_gazebo_plugins/include/uuv_gazebo_plugins/BuoyantObject.hh

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,11 @@ class BuoyantObject
7474
public: double GetGravity();
7575

7676
/// \brief Sets bounding box
77+
#if GAZEBO_MAJOR_VERSION >= 11
78+
public: void SetBoundingBox(const ignition::math::AxisAlignedBox &_bBox);
79+
#else
7780
public: void SetBoundingBox(const ignition::math::Box &_bBox);
81+
#endif
7882

7983
/// \brief Adds a field in the hydroWrench map
8084
public: void SetStoreVector(std::string _tag);
@@ -120,7 +124,11 @@ class BuoyantObject
120124

121125
/// \brief TEMP for calculation of the buoyancy
122126
/// force close to the surface
127+
#if GAZEBO_MAJOR_VERSION >= 11
128+
protected: ignition::math::AxisAlignedBox boundingBox;
129+
#else
123130
protected: ignition::math::Box boundingBox;
131+
#endif
124132

125133
/// \brief Storage for hydrodynamic and hydrostatic forces and torques
126134
/// for debugging purposes

uuv_gazebo_plugins/uuv_gazebo_plugins/src/BuoyantObject.cc

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -205,9 +205,17 @@ void BuoyantObject::ApplyBuoyancyForce()
205205
}
206206

207207
/////////////////////////////////////////////////
208+
#if GAZEBO_MAJOR_VERSION >= 11
209+
void BuoyantObject::SetBoundingBox(const ignition::math::AxisAlignedBox &_bBox)
210+
#else
208211
void BuoyantObject::SetBoundingBox(const ignition::math::Box &_bBox)
212+
#endif
209213
{
214+
#if GAZEBO_MAJOR_VERSION >= 11
215+
this->boundingBox = ignition::math::AxisAlignedBox(_bBox);
216+
#else
210217
this->boundingBox = ignition::math::Box(_bBox);
218+
#endif
211219

212220
gzmsg << "New bounding box for " << this->link->GetName() << "::"
213221
<< this->boundingBox << std::endl;

uuv_gazebo_plugins/uuv_gazebo_plugins/src/HydrodynamicModel.cc

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -75,9 +75,15 @@ HydrodynamicModel::HydrodynamicModel(sdf::ElementPtr _sdf,
7575
double width = sdfModel->Get<double>("width");
7676
double length = sdfModel->Get<double>("length");
7777
double height = sdfModel->Get<double>("height");
78+
#if GAZEBO_MAJOR_VERSION >= 11
79+
ignition::math::AxisAlignedBox boundingBox = ignition::math::AxisAlignedBox(
80+
ignition::math::Vector3d(-width / 2, -length / 2, -height / 2),
81+
ignition::math::Vector3d(width / 2, length / 2, height / 2));
82+
#else
7883
ignition::math::Box boundingBox = ignition::math::Box(
7984
ignition::math::Vector3d(-width / 2, -length / 2, -height / 2),
8085
ignition::math::Vector3d(width / 2, length / 2, height / 2));
86+
#endif
8187
// Setting the the bounding box from the given dimensions
8288
this->SetBoundingBox(boundingBox);
8389
}

uuv_sensor_plugins/uuv_sensor_ros_plugins/src/gazebo_ros_image_sonar.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,7 @@
4949
#include <sensor_msgs/image_encodings.h>
5050
#include <cv_bridge/cv_bridge.h>
5151
#include <opencv2/core/core.hpp>
52+
#include <opencv2/imgproc/imgproc_c.h>
5253

5354
namespace gazebo
5455
{
@@ -1054,4 +1055,4 @@ void GazeboRosImageSonar::PublishDisparityImage(const DepthImage& depth, ros::Ti
10541055
*/
10551056

10561057

1057-
}
1058+
}

0 commit comments

Comments
 (0)