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

noetic compatible #445

Open
wants to merge 4 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 3 additions & 2 deletions uuv_control/uuv_control_utils/package.xml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<package format="2">
<package format="3">
<name>uuv_control_utils</name>
<version>0.6.13</version>
<description>The uuv_control_utils package</description>
Expand All @@ -24,7 +24,8 @@
<exec_depend>python-numpy</exec_depend>
<exec_depend>uuv_control_msgs</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>python-yaml</exec_depend>
<exec_depend condition="$ROS_PYTHON_VERSION == 2">python-yaml</exec_depend>
<exec_depend condition="$ROS_PYTHON_VERSION == 3">python3-yaml</exec_depend>
<exec_depend>visualization_msgs</exec_depend>
<exec_depend>nav_msgs</exec_depend>
<exec_depend>uuv_trajectory_control</exec_depend>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#!/usr/bin/env python
#!/usr/bin/env python3
# Copyright (c) 2016 The UUV Simulator Authors.
# All rights reserved.
#
Expand Down
8 changes: 5 additions & 3 deletions uuv_control/uuv_thruster_manager/package.xml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<package format="2">
<package format="3">
<name>uuv_thruster_manager</name>
<version>0.6.13</version>
<description>The thruster manager package</description>
Expand All @@ -22,7 +22,10 @@
<exec_depend>message_runtime</exec_depend>
<exec_depend>tf</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>python-yaml</exec_depend>
<exec_depend condition="$ROS_PYTHON_VERSION == 2">python-empy</exec_depend>
<exec_depend condition="$ROS_PYTHON_VERSION == 3">python3-empy</exec_depend>
<exec_depend condition="$ROS_PYTHON_VERSION == 2">python-yaml</exec_depend>
<exec_depend condition="$ROS_PYTHON_VERSION == 3">python3-yaml</exec_depend>
<exec_depend>uuv_gazebo_ros_plugins_msgs</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>uuv_assistants</exec_depend>
Expand All @@ -37,4 +40,3 @@
<test_depend>xacro</test_depend>

</package>

Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
# limitations under the License.
import rospy
import numpy
from thruster import Thruster
from .thruster import Thruster


class ThrusterProportional(Thruster):
Expand Down
11 changes: 7 additions & 4 deletions uuv_control/uuv_trajectory_control/package.xml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<package format="2">
<package format="3">
<name>uuv_trajectory_control</name>
<version>0.6.13</version>
<description>The uuv_trajectory_control package</description>
Expand All @@ -15,9 +15,12 @@
<exec_depend>rospy</exec_depend>
<exec_depend>roslib</exec_depend>
<exec_depend>python-numpy</exec_depend>
<exec_depend>python-matplotlib</exec_depend>
<exec_depend>python-yaml</exec_depend>
<exec_depend>python-scipy</exec_depend>
<exec_depend condition="$ROS_PYTHON_VERSION == 2">python-matplotlib</exec_depend>
<exec_depend condition="$ROS_PYTHON_VERSION == 3">python3-matplotlib</exec_depend>
<exec_depend condition="$ROS_PYTHON_VERSION == 2">python-yaml</exec_depend>
<exec_depend condition="$ROS_PYTHON_VERSION == 3">python3-yaml</exec_depend>
<exec_depend condition="$ROS_PYTHON_VERSION == 2">python-scipy</exec_depend>
<exec_depend condition="$ROS_PYTHON_VERSION == 3">python3-scipy</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>uuv_control_msgs</exec_depend>
<exec_depend>tf</exec_depend>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#!/usr/bin/env python
#!/usr/bin/env python3
# Copyright (c) 2016-2019 The UUV Simulator Authors.
# All rights reserved.
#
Expand Down
24 changes: 19 additions & 5 deletions uuv_gazebo_plugins/uuv_gazebo_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,8 +1,13 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 3.0.2)
project(uuv_gazebo_plugins)

# Specify C++11 standard
add_definitions(-std=c++11)
if(NOT "${CMAKE_VERSION}" VERSION_LESS "3.16")
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
else()
set(LOCAL_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
endif()

find_package(catkin REQUIRED COMPONENTS
gazebo_dev)
Expand Down Expand Up @@ -72,7 +77,11 @@ add_library(uuv_dynamics
src/Dynamics.cc
)
list(APPEND UUV_GAZEBO_PLUGINS_LIST uuv_dynamics)

set_target_properties(uuv_dynamics
PROPERTIES
COMPILE_FLAGS
"${LOCAL_CXX_FLAGS}"
)
add_library(uuv_fin_plugin
src/LiftDragModel.cc
src/FinPlugin.cc
Expand All @@ -97,6 +106,11 @@ target_link_libraries(uuv_underwater_object_plugin
${EIGEN3_LIBRARIES}
)
list(APPEND UUV_GAZEBO_PLUGINS_LIST uuv_underwater_object_plugin)
set_target_properties(uuv_underwater_object_plugin
PROPERTIES
COMPILE_FLAGS
"${LOCAL_CXX_FLAGS}"
)

add_library(uuv_thruster_plugin
src/ThrusterConversionFcn.cc
Expand Down Expand Up @@ -136,8 +150,8 @@ install(DIRECTORY include/${PROJECT_NAME}/
)

install(DIRECTORY include/
DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}
FILES_MATCHING PATTERN ".hh"
DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}
FILES_MATCHING PATTERN ".hh"
)

install(DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,11 @@ class BuoyantObject
public: double GetGravity();

/// \brief Sets bounding box
#if GAZEBO_MAJOR_VERSION >= 11
public: void SetBoundingBox(const ignition::math::AxisAlignedBox &_bBox);
#else
public: void SetBoundingBox(const ignition::math::Box &_bBox);
#endif

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

/// \brief TEMP for calculation of the buoyancy
/// force close to the surface
#if GAZEBO_MAJOR_VERSION >= 11
protected: ignition::math::AxisAlignedBox boundingBox;
#else
protected: ignition::math::Box boundingBox;
#endif

/// \brief Storage for hydrodynamic and hydrostatic forces and torques
/// for debugging purposes
Expand Down
10 changes: 9 additions & 1 deletion uuv_gazebo_plugins/uuv_gazebo_plugins/src/BuoyantObject.cc
Original file line number Diff line number Diff line change
Expand Up @@ -205,10 +205,18 @@ void BuoyantObject::ApplyBuoyancyForce()
}

/////////////////////////////////////////////////
#if GAZEBO_MAJOR_VERSION >= 11
void BuoyantObject::SetBoundingBox(const ignition::math::AxisAlignedBox &_bBox)
#else
void BuoyantObject::SetBoundingBox(const ignition::math::Box &_bBox)
#endif
{
#if GAZEBO_MAJOR_VERSION >= 11
this->boundingBox = ignition::math::AxisAlignedBox(_bBox);
#else
this->boundingBox = ignition::math::Box(_bBox);

#endif

gzmsg << "New bounding box for " << this->link->GetName() << "::"
<< this->boundingBox << std::endl;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,9 +75,15 @@ HydrodynamicModel::HydrodynamicModel(sdf::ElementPtr _sdf,
double width = sdfModel->Get<double>("width");
double length = sdfModel->Get<double>("length");
double height = sdfModel->Get<double>("height");
ignition::math::Box boundingBox = ignition::math::Box(
#if GAZEBO_MAJOR_VERSION >= 11
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));
#else
ignition::math::Box boundingBox = ignition::math::Box(
ignition::math::Vector3d(-width / 2, -length / 2, -height / 2),
ignition::math::Vector3d(width / 2, length / 2, height / 2));
#endif
// Setting the the bounding box from the given dimensions
this->SetBoundingBox(boundingBox);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -149,6 +149,7 @@ bool MagnetometerROSPlugin::OnUpdate(const common::UpdateInfo& _info)
this->rosMsg.magnetic_field.z = this->measMagneticField.Z();

this->rosSensorOutputPub.publish(this->rosMsg);
return true;
}

/////////////////////////////////////////////////
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -141,6 +141,7 @@ bool ROSBasePlugin::InitBasePlugin(sdf::ElementPtr _sdf)

// Add a default Gaussian noise model
this->AddNoiseModel("default", this->noiseSigma);
return true;
}

/////////////////////////////////////////////////
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@
#include <sensor_msgs/image_encodings.h>
#include <cv_bridge/cv_bridge.h>
#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc_c.h>

namespace gazebo
{
Expand Down
117 changes: 0 additions & 117 deletions uuv_simulator/CHANGELOG.rst

This file was deleted.

4 changes: 0 additions & 4 deletions uuv_simulator/CMakeLists.txt

This file was deleted.

44 changes: 0 additions & 44 deletions uuv_simulator/package.xml

This file was deleted.

Loading