diff --git a/uuv_gazebo_plugins/uuv_gazebo_plugins/CMakeLists.txt b/uuv_gazebo_plugins/uuv_gazebo_plugins/CMakeLists.txt index 16efc7ae3..32720ac2d 100644 --- a/uuv_gazebo_plugins/uuv_gazebo_plugins/CMakeLists.txt +++ b/uuv_gazebo_plugins/uuv_gazebo_plugins/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 2.8.3) project(uuv_gazebo_plugins) # Specify C++11 standard -add_definitions(-std=c++11) +add_definitions(-std=c++17) find_package(catkin REQUIRED COMPONENTS gazebo_dev) diff --git a/uuv_gazebo_plugins/uuv_gazebo_plugins/include/uuv_gazebo_plugins/BuoyantObject.hh b/uuv_gazebo_plugins/uuv_gazebo_plugins/include/uuv_gazebo_plugins/BuoyantObject.hh index 5802903e9..27ff1c965 100644 --- a/uuv_gazebo_plugins/uuv_gazebo_plugins/include/uuv_gazebo_plugins/BuoyantObject.hh +++ b/uuv_gazebo_plugins/uuv_gazebo_plugins/include/uuv_gazebo_plugins/BuoyantObject.hh @@ -74,7 +74,7 @@ class BuoyantObject public: double GetGravity(); /// \brief Sets bounding box - public: void SetBoundingBox(const ignition::math::Box &_bBox); + public: void SetBoundingBox(const ignition::math::AxisAlignedBox &_bBox); /// \brief Adds a field in the hydroWrench map public: void SetStoreVector(std::string _tag); @@ -120,7 +120,7 @@ class BuoyantObject /// \brief TEMP for calculation of the buoyancy /// force close to the surface - protected: ignition::math::Box boundingBox; + protected: ignition::math::AxisAlignedBox boundingBox; /// \brief Storage for hydrodynamic and hydrostatic forces and torques /// for debugging purposes diff --git a/uuv_gazebo_plugins/uuv_gazebo_plugins/src/BuoyantObject.cc b/uuv_gazebo_plugins/uuv_gazebo_plugins/src/BuoyantObject.cc index a206aeafc..319fd208e 100644 --- a/uuv_gazebo_plugins/uuv_gazebo_plugins/src/BuoyantObject.cc +++ b/uuv_gazebo_plugins/uuv_gazebo_plugins/src/BuoyantObject.cc @@ -52,7 +52,7 @@ BuoyantObject::BuoyantObject(physics::LinkPtr _link) this->boundingBox = link->BoundingBox(); #else math::Box bBox = link->GetBoundingBox(); - this->boundingBox = ignition::math::Box(bBox.min.x, bBox.min.y, bBox.min.z, + this->boundingBox = ignition::math::AxisAlignedBox(bBox.min.x, bBox.min.y, bBox.min.z, bBox.max.x, bBox.max.y, bBox.max.z); #endif // Set neutrally buoyant flag to false @@ -205,9 +205,9 @@ void BuoyantObject::ApplyBuoyancyForce() } ///////////////////////////////////////////////// -void BuoyantObject::SetBoundingBox(const ignition::math::Box &_bBox) +void BuoyantObject::SetBoundingBox(const ignition::math::AxisAlignedBox &_bBox) { - this->boundingBox = ignition::math::Box(_bBox); + this->boundingBox = ignition::math::AxisAlignedBox(_bBox); gzmsg << "New bounding box for " << this->link->GetName() << "::" << this->boundingBox << std::endl; diff --git a/uuv_gazebo_plugins/uuv_gazebo_plugins/src/HydrodynamicModel.cc b/uuv_gazebo_plugins/uuv_gazebo_plugins/src/HydrodynamicModel.cc index a4b49ad37..4e975a1e4 100644 --- a/uuv_gazebo_plugins/uuv_gazebo_plugins/src/HydrodynamicModel.cc +++ b/uuv_gazebo_plugins/uuv_gazebo_plugins/src/HydrodynamicModel.cc @@ -75,7 +75,7 @@ HydrodynamicModel::HydrodynamicModel(sdf::ElementPtr _sdf, double width = sdfModel->Get("width"); double length = sdfModel->Get("length"); double height = sdfModel->Get("height"); - ignition::math::Box boundingBox = ignition::math::Box( + ignition::math::AxisAlignedBox boundingBox = ignition::math::AxisAlignedBox( ignition::math::Vector3d(-width / 2, -length / 2, -height / 2), ignition::math::Vector3d(width / 2, length / 2, height / 2)); // Setting the the bounding box from the given dimensions diff --git a/uuv_gazebo_plugins/uuv_gazebo_ros_plugins/CMakeLists.txt b/uuv_gazebo_plugins/uuv_gazebo_ros_plugins/CMakeLists.txt index b79d5941a..7e3ba29e8 100644 --- a/uuv_gazebo_plugins/uuv_gazebo_ros_plugins/CMakeLists.txt +++ b/uuv_gazebo_plugins/uuv_gazebo_ros_plugins/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 2.8.3) project(uuv_gazebo_ros_plugins) # Specify C++11 standard -add_definitions(-std=c++11) +add_definitions(-std=c++17) find_package(catkin REQUIRED COMPONENTS uuv_gazebo_plugins diff --git a/uuv_sensor_plugins/uuv_sensor_ros_plugins/CMakeLists.txt b/uuv_sensor_plugins/uuv_sensor_ros_plugins/CMakeLists.txt index c12d8ffe0..3e823e4b0 100644 --- a/uuv_sensor_plugins/uuv_sensor_ros_plugins/CMakeLists.txt +++ b/uuv_sensor_plugins/uuv_sensor_ros_plugins/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 2.8.3) project(uuv_sensor_ros_plugins) -add_definitions(-std=c++11) +add_definitions(-std=c++17) # set(CMAKE_BUILD_TYPE RelWithDebInfo) diff --git a/uuv_sensor_plugins/uuv_sensor_ros_plugins/src/gazebo_ros_image_sonar.cpp b/uuv_sensor_plugins/uuv_sensor_ros_plugins/src/gazebo_ros_image_sonar.cpp index 6c3b7af9b..148e66842 100644 --- a/uuv_sensor_plugins/uuv_sensor_ros_plugins/src/gazebo_ros_image_sonar.cpp +++ b/uuv_sensor_plugins/uuv_sensor_ros_plugins/src/gazebo_ros_image_sonar.cpp @@ -942,9 +942,9 @@ cv::Mat GazeboRosImageSonar::ConstructVisualScanImage(cv::Mat& raw_scan) cv::Scalar white(255, 255, 255); cv::Size axes1(2./3.*scan.rows, 2./3.*scan.rows); cv::Size axes2(1./3.*scan.rows, 1./3.*scan.rows); - cv::ellipse(scan, center, axes, -90, -fov/2.-0.5, fov/2., white, 1, CV_AA); //, int lineType=LINE_8, 0); - cv::ellipse(scan, center, axes1, -90, -fov/2., fov/2., white, 1, CV_AA); //, int lineType=LINE_8, 0); - cv::ellipse(scan, center, axes2, -90, -fov/2., fov/2., white, 1, CV_AA); //, int lineType=LINE_8, 0); + cv::ellipse(scan, center, axes, -90, -fov/2.-0.5, fov/2., white, 1, cv::LINE_8, 0); //, int lineType=LINE_8, 0); + cv::ellipse(scan, center, axes1, -90, -fov/2., fov/2., white, 1, cv::LINE_8, 0); //, int lineType=LINE_8, 0); + cv::ellipse(scan, center, axes2, -90, -fov/2., fov/2., white, 1, cv::LINE_8, 0); //, int lineType=LINE_8, 0); for (int i = 0; i < 5; ++i) { float angle = -fov/2.-0.5 + (fov+0.5)*i/float(5-1); @@ -955,7 +955,7 @@ cv::Mat GazeboRosImageSonar::ConstructVisualScanImage(cv::Mat& raw_scan) cv::Point corner(scan.cols/2+cornerx, scan.rows-cornery); //cv::line(scan, center, left_corner, white, 2); //cv::line(scan, center, right_corner, white, 2); - cv::line(scan, center, corner, white, 1, CV_AA); + cv::line(scan, center, corner, white, 1, cv::LINE_8, 0); } cv_bridge::CvImage img_bridge; diff --git a/uuv_world_plugins/uuv_world_plugins/CMakeLists.txt b/uuv_world_plugins/uuv_world_plugins/CMakeLists.txt index b857d3a74..74e0aab7a 100644 --- a/uuv_world_plugins/uuv_world_plugins/CMakeLists.txt +++ b/uuv_world_plugins/uuv_world_plugins/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 2.8.3) project(uuv_world_plugins) # Specify C++11 standard -add_definitions(-std=c++11) +add_definitions(-std=c++17) ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) diff --git a/uuv_world_plugins/uuv_world_ros_plugins/CMakeLists.txt b/uuv_world_plugins/uuv_world_ros_plugins/CMakeLists.txt index 91c676553..efbfdee80 100644 --- a/uuv_world_plugins/uuv_world_ros_plugins/CMakeLists.txt +++ b/uuv_world_plugins/uuv_world_ros_plugins/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 2.8.3) project(uuv_world_ros_plugins) # Specify C++11 standard -add_definitions(-std=c++11) +add_definitions(-std=c++17) find_package(catkin REQUIRED COMPONENTS roscpp