Skip to content
Commits on Source (31)
cmake_minimum_required(VERSION 3.8)
project(waterstridergazebo)
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(uuv_gazebo_ros_plugins_msgs REQUIRED)
find_package(Eigen3 REQUIRED COMPONENTS system)
include_directories(
# include
${EIGEN3_INCLUDE_DIRS}
)
install(DIRECTORY launch meshes robots urdf
DESTINATION share/${PROJECT_NAME}
PATTERN "*~"
EXCLUDE)
add_executable(thrusters_controller_node src/thrusters_controller_node.cpp)
ament_target_dependencies(thrusters_controller_node
rclcpp
std_msgs
geometry_msgs
uuv_gazebo_ros_plugins_msgs)
install(TARGETS thrusters_controller_node
DESTINATION lib/${PROJECT_NAME})
install(DIRECTORY config
DESTINATION share/${PROJECT_NAME}
PATTERN "*~"
EXCLUDE)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
set(ament_cmake_copyright_FOUND TRUE)
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
set(DESCRIPTIONS_PYTHON_TESTS
test/test_urdf_files.py
)
foreach(T ${DESCRIPTIONS_PYTHON_TESTS})
get_filename_component(_test_name ${T} NAME_WE)
ament_add_pytest_test(${_test_name} ${T}
PYTHON_EXECUTABLE "${PYTHON_EXECUTABLE}"
APPEND_ENV AMENT_PREFIX_PATH=${ament_index_build_path}
PYTHONPATH=${CMAKE_CURRENT_BINARY_DIR}
TIMEOUT 120
)
endforeach()
endif()
ament_export_dependencies(EIGEN3)
ament_package()
# VaterstriderGazebo # Waterstrider simulation
## Launch robot
Setup source:
```bash
## Getting started source /opt/ros/iron/setup.bash
source $HOME/ros2_ws/install/setup.bash
To make it easy for you to get started with GitLab, here's a list of recommended next steps. source /usr/share/gazebo/setup.sh
Already a pro? Just edit this README.md and make it your own. Want to make it easy? [Use the template at the bottom](#editing-this-readme)!
## Add your files
- [ ] [Create](https://docs.gitlab.com/ee/user/project/repository/web_editor.html#create-a-file) or [upload](https://docs.gitlab.com/ee/user/project/repository/web_editor.html#upload-a-file) files
- [ ] [Add files using the command line](https://docs.gitlab.com/ee/gitlab-basics/add-file.html#add-a-file-using-the-command-line) or push an existing Git repository with the following command:
``` ```
cd existing_repo Launch an ocean world (Plankton package):
git remote add origin https://gitlab.dnouglublenie.ru/skb/vaterstridergazebo.git ```bash
git branch -M master ros2 launch uuv_gazebo_worlds lake.launch
git push -uf origin master
``` ```
Launch a robot in the world
## Integrate with your tools ```bash
ros2 launch waterstridergazebo upload_waterstrider_launch.py
- [ ] [Set up project integrations](https://gitlab.dnouglublenie.ru/skb/vaterstridergazebo/-/settings/integrations) ```
## Teleoperation
## Collaborate with your team Launch thrusters controller for any type of teleoperation
```bash
- [ ] [Invite team members and collaborators](https://docs.gitlab.com/ee/user/project/members/) ros2 launch waterstridergazebo thrusters_controller_launch.py
- [ ] [Create a new merge request](https://docs.gitlab.com/ee/user/project/merge_requests/creating_merge_requests.html) ```
- [ ] [Automatically close issues from merge requests](https://docs.gitlab.com/ee/user/project/issues/managing_issues.html#closing-issues-automatically) Keyboard teleoperation
- [ ] [Enable merge request approvals](https://docs.gitlab.com/ee/user/project/merge_requests/approvals/) ```bash
- [ ] [Set auto-merge](https://docs.gitlab.com/ee/user/project/merge_requests/merge_when_pipeline_succeeds.html) ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args --remap cmd_vel:=waterstrider/twist_command
```
## Test and Deploy Joystick teleoperation
```bash
Use the built-in continuous integration in GitLab. ros2 launch waterstridergazebo joy_teleop.launch
```
- [ ] [Get started with GitLab CI/CD](https://docs.gitlab.com/ee/ci/quick_start/index.html) \ No newline at end of file
- [ ] [Analyze your code for known vulnerabilities with Static Application Security Testing (SAST)](https://docs.gitlab.com/ee/user/application_security/sast/)
- [ ] [Deploy to Kubernetes, Amazon EC2, or Amazon ECS using Auto Deploy](https://docs.gitlab.com/ee/topics/autodevops/requirements.html)
- [ ] [Use pull-based deployments for improved Kubernetes management](https://docs.gitlab.com/ee/user/clusters/agent/)
- [ ] [Set up protected environments](https://docs.gitlab.com/ee/ci/environments/protected_environments.html)
***
# Editing this README
When you're ready to make this README your own, just edit this file and use the handy template below (or feel free to structure it however you want - this is just a starting point!). Thanks to [makeareadme.com](https://www.makeareadme.com/) for this template.
## Suggestions for a good README
Every project is different, so consider which of these sections apply to yours. The sections used in the template are suggestions for most open source projects. Also keep in mind that while a README can be too long and detailed, too long is better than too short. If you think your README is too long, consider utilizing another form of documentation rather than cutting out information.
## Name
Choose a self-explaining name for your project.
## Description
Let people know what your project can do specifically. Provide context and add a link to any reference visitors might be unfamiliar with. A list of Features or a Background subsection can also be added here. If there are alternatives to your project, this is a good place to list differentiating factors.
## Badges
On some READMEs, you may see small images that convey metadata, such as whether or not all the tests are passing for the project. You can use Shields to add some to your README. Many services also have instructions for adding a badge.
## Visuals
Depending on what you are making, it can be a good idea to include screenshots or even a video (you'll frequently see GIFs rather than actual videos). Tools like ttygif can help, but check out Asciinema for a more sophisticated method.
## Installation
Within a particular ecosystem, there may be a common way of installing things, such as using Yarn, NuGet, or Homebrew. However, consider the possibility that whoever is reading your README is a novice and would like more guidance. Listing specific steps helps remove ambiguity and gets people to using your project as quickly as possible. If it only runs in a specific context like a particular programming language version or operating system or has dependencies that have to be installed manually, also add a Requirements subsection.
## Usage
Use examples liberally, and show the expected output if you can. It's helpful to have inline the smallest example of usage that you can demonstrate, while providing links to more sophisticated examples if they are too long to reasonably include in the README.
## Support
Tell people where they can go to for help. It can be any combination of an issue tracker, a chat room, an email address, etc.
## Roadmap
If you have ideas for releases in the future, it is a good idea to list them in the README.
## Contributing
State if you are open to contributions and what your requirements are for accepting them.
For people who want to make changes to your project, it's helpful to have some documentation on how to get started. Perhaps there is a script that they should run or some environment variables that they need to set. Make these steps explicit. These instructions could also be useful to your future self.
You can also document commands to lint the code or run tests. These steps help to ensure high code quality and reduce the likelihood that the changes inadvertently break something. Having instructions for running tests is especially helpful if it requires external setup, such as starting a Selenium server for testing in a browser.
## Authors and acknowledgment
Show your appreciation to those who have contributed to the project.
## License
For open source projects, say how it is licensed.
## Project status
If you have run out of energy or time for your project, put a note at the top of the README saying that development has slowed down or stopped completely. Someone may choose to fork your project or volunteer to step in as a maintainer or owner, allowing your project to keep going. You can also make an explicit request for maintainers.
/**:
ros__parameters:
qos_overrides:
/parameter_events:
publisher:
depth: 1000
durability: volatile
history: keep_last
reliability: reliable
start_type_description_service: true
use_sim_time: false
thrusters:
controller_output_0:
enabled: true
f: [ -0.99, 0.01, 0.00]
r: [ -2.2795, -1.50, -0.8897]
input: [-1.0, 0.0, 1.0]
output: [-700.0, 0.0, 700.0]
controller_output_1:
enabled: true
f: [ -0.99, -0.01, 0.00]
r: [ -2.2795, 1.50, -0.8897]
input: [-1.0, 0.0, 1.0]
output: [-700.0, 0.0, 700.0]
import os
from ament_index_python import get_package_share_directory
from launch import LaunchDescription
from launch.actions import GroupAction, IncludeLaunchDescription
from launch_ros.actions import Node, PushRosNamespace
from launch_xml.launch_description_sources import XMLLaunchDescriptionSource
from launch.launch_description_sources import PythonLaunchDescriptionSource
def generate_launch_description():
ld = LaunchDescription()
gazebo = IncludeLaunchDescription(XMLLaunchDescriptionSource(os.path.join(get_package_share_directory('uuv_gazebo_worlds'), 'launch/ocean_waves.launch')))
ld.add_action(gazebo)
waterstider = IncludeLaunchDescription(PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('waterstridergazebo'), 'launch/upload_waterstrider_launch.py')))
ld.add_action(waterstider)
thruster_controller = IncludeLaunchDescription(PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('waterstridergazebo'), 'launch/thrusters_controller_launch.py')))
ld.add_action(thruster_controller)
return ld
\ No newline at end of file
<?xml version="1.0"?>
<launch>
<include file="$(find-pkg-share uuv_teleop)/launch/uuv_teleop.launch">
<arg name="uuv_name" value="waterstrider"/>
<arg name="joy_id" value="0"/>
<arg name="output_topic" value="twist_command"/>
<arg name="message_type" value="twist"/>
<arg name="gain_roll" value="0.0"/>
<arg name="gain_pitch" value="1.0"/>
<arg name="gain_yaw" value="0.6"/>
<arg name="gain_x" value="1.0"/>
<arg name="gain_y" value="1.0"/>
<arg name="gain_z" value="1.0"/>
</include>
</launch>
ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args --remap cmd_vel:=waterstrider/twist_command
import os
from ament_index_python import get_package_share_directory
from launch import LaunchDescription
from launch.actions import GroupAction
from launch_ros.actions import Node, PushRosNamespace
from launch.substitutions import LaunchConfiguration as Lc
from launch.actions import DeclareLaunchArgument
from launch.actions import OpaqueFunction
def to_bool(value: str):
if isinstance(value, bool):
return value
if not isinstance(value, str):
raise ValueError('String to bool, invalid type ' + str(value))
valid = {'true': True, '1': True,
'false': False, '0': False}
if value.lower() in valid:
return valid[value]
raise ValueError('String to bool, invalid value: %s' % value)
def launch_setup(context, *args, **kwargs):
namespace = Lc('namespace').perform(context)
is_use_namespace = to_bool(Lc("is_use_namespace").perform(context))
if is_use_namespace:
return [GroupAction([
PushRosNamespace(namespace),
Node(
package='waterstridergazebo',
executable='thrusters_controller_node',
output='screen',
parameters=[os.path.join(
get_package_share_directory('waterstridergazebo'),
'config',
'waterstrider_thrusters.yaml'
)],
remappings=[
('thrusters/controller_output_0', 'thrusters/id_0/input'),
('thrusters/controller_output_1', 'thrusters/id_1/input'),
]
)
])]
return [GroupAction([
Node(
package='waterstridergazebo',
executable='thrusters_controller_node',
output='screen',
parameters=[os.path.join(
get_package_share_directory('waterstridergazebo'),
'config',
'waterstrider_thrusters.yaml'
)],
remappings=[
('thrusters/controller_output_0', 'thrusters/id_0/input'),
('thrusters/controller_output_1', 'thrusters/id_1/input'),
]
)
])]
def generate_launch_description():
return LaunchDescription([
DeclareLaunchArgument('namespace', default_value='waterstrider'),
DeclareLaunchArgument('is_use_namespace', default_value='true'),
OpaqueFunction(function=launch_setup)
])
# Copyright (c) 2020 The Plankton Authors.
# All rights reserved.
#
# This source code is derived from UUV Simulator
# (https://github.com/uuvsimulator/uuv_simulator)
# Copyright (c) 2016-2019 The UUV Simulator Authors
# licensed under the Apache license, Version 2.0
# cf. 3rd-party-licenses.txt file in the root directory of this source tree.
#
from launch import LaunchDescription
from launch.launch_description_sources import AnyLaunchDescriptionSource
from launch_ros.actions import Node, PushRosNamespace
from launch.actions import DeclareLaunchArgument
from launch.actions import GroupAction
from launch.actions import OpaqueFunction
from launch.actions import IncludeLaunchDescription
from launch.substitutions import LaunchConfiguration as Lc
import launch_testing.actions
from ament_index_python.packages import get_package_share_directory
import os
import pathlib
import xacro
from plankton_utils.time import is_sim_time
def to_bool(value: str):
if isinstance(value, bool):
return value
if not isinstance(value, str):
raise ValueError('String to bool, invalid type ' + str(value))
valid = {'true': True, '1': True,
'false': False, '0': False}
if value.lower() in valid:
return valid[value]
raise ValueError('String to bool, invalid value: %s' % value)
# =============================================================================
def launch_setup(context, *args, **kwargs):
# Perform substitutions
debug = Lc('debug').perform(context)
namespace = Lc('namespace').perform(context)
x = Lc('x').perform(context)
y = Lc('y').perform(context)
z = Lc('z').perform(context)
roll = Lc('roll').perform(context)
pitch = Lc('pitch').perform(context)
yaw = Lc('yaw').perform(context)
# use_sim_time = Lc('use_sim_time').perform(context)
use_world_ned = Lc('use_ned_frame').perform(context)
is_write_on_disk = Lc('write_file_on_disk').perform(context)
# Request sim time value to the global node
res = is_sim_time(return_param=False, use_subprocess=True)
# Xacro
xacro_file = os.path.join(
get_package_share_directory('waterstridergazebo'),
'robots',
'waterstrider_' + (Lc('mode')).perform(context) + '.xacro'
)
# Build the directories, check for existence
path = os.path.join(
get_package_share_directory('uuv_descriptions'),
'robots',
'generated',
namespace,
)
if not pathlib.Path(path).exists():
try:
# Create directory if required and sub-directory
os.makedirs(path)
except OSError:
print("Creation of the directory %s failed" % path)
output = os.path.join(
path,
'robot_description.urdf'
)
if not pathlib.Path(xacro_file).exists():
exc = 'Launch file ' + xacro_file + ' does not exist'
raise Exception(exc)
if to_bool(use_world_ned):
mappings = {'debug': debug, 'namespace': namespace, 'inertial_reference_frame': 'world_ned'}
else:
mappings = {'debug': debug, 'namespace': namespace, 'inertial_reference_frame': 'world'}
doc = xacro.process(xacro_file, mappings=mappings)
if is_write_on_disk:
with open(output, 'w') as file_out:
file_out.write(doc)
# URDF spawner
args = ('-x %s -y %s -z %s -R %s -P %s -Y %s -entity %s -topic robot_description'
% (x, y, z, roll, pitch, yaw, namespace)).split()
# Urdf spawner. NB: node namespace does not prefix the spawning service,
# as using a leading /
# NB 2: node namespace prefixes the robot_description topic
urdf_spawner = Node(
name='urdf_spawner',
package='gazebo_ros',
executable='spawn_entity.py',
output='screen',
parameters=[{'use_sim_time': res}],
arguments=args,
)
# A joint state publisher plugin already is started with the model, no need to use the default joint state publisher
# N.B.: alternative way to generate a robot_description string:
# string = str('ros2 run xacro xacro ' + xacro_file + ' debug:=false namespace:=' + namespace + ' inertial_reference_frame:=world')
# cmd = Command(string)
# but it currently yields yaml parsing error due to ":" in the comments of the xacro description files
robot_state_publisher = Node(
name='robot_state_publisher',
package='robot_state_publisher',
executable='robot_state_publisher',
output='screen',
parameters=[{'use_sim_time': res}, {'robot_description': doc}], # Use subst here
)
# Thrusters remapings
thrusters_transformers = [Node(package='topic_tools',
executable='transform',
arguments=[f'/waterstrider/thrusters/controller_output_{i}',
f'/waterstrider/thrusters/id_{i}/input',
'uuv_gazebo_ros_plugins_msgs/FloatStamped',
'uuv_gazebo_ros_plugins_msgs.msg.FloatStamped(data=m.data)',
'--wait-for-start',
'--import',
'uuv_gazebo_ros_plugins_msgs'
]) for i in range(8)]
# Message to tf
message_to_tf_launch = os.path.join(
get_package_share_directory('uuv_assistants'),
'launch',
'message_to_tf.launch'
)
if not pathlib.Path(message_to_tf_launch).exists():
exc = 'Launch file ' + message_to_tf_launch + ' does not exist'
raise Exception(exc)
launch_args = [('namespace', namespace), ('world_frame', 'world'),
('child_frame_id', '/' + namespace + '/base_link'), ('use_sim_time', str(res).lower()), ]
message_to_tf_launch = IncludeLaunchDescription(
AnyLaunchDescriptionSource(message_to_tf_launch), launch_arguments=launch_args)
group = GroupAction([
PushRosNamespace(namespace),
urdf_spawner,
robot_state_publisher,
*thrusters_transformers
])
return [group, message_to_tf_launch]
# =============================================================================
def generate_launch_description():
# TODO Try LaunchContext ?
return LaunchDescription([
DeclareLaunchArgument('debug', default_value='0'),
DeclareLaunchArgument('x', default_value='0'),
DeclareLaunchArgument('y', default_value='0'),
DeclareLaunchArgument('z', default_value='0'),
DeclareLaunchArgument('roll', default_value='0.0'),
DeclareLaunchArgument('pitch', default_value='0.0'),
DeclareLaunchArgument('yaw', default_value='3.1415926'),
DeclareLaunchArgument('mode', default_value='default'),
DeclareLaunchArgument('namespace', default_value='waterstrider'),
DeclareLaunchArgument('use_ned_frame', default_value='false'),
DeclareLaunchArgument('write_file_on_disk', default_value='false'),
# DeclareLaunchArgument('use_sim_time', default_value='true'),
OpaqueFunction(function=launch_setup)
])
# Blender 4.3.2 MTL File: 'None'
# www.blender.org
newmtl mat_1
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_10
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_11
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_12
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_13
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_14
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_15
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_2
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_3
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_4
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_5
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_6
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_7
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_8
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_9
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
This diff is collapsed.
# Blender 4.3.2 MTL File: 'None'
# www.blender.org
newmtl mat_1
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_10
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_11
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_12
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_13
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_14
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_15
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_2
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_3
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_4
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_5
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_6
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_7
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_8
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
newmtl mat_9
Ns 0.000000
Ka 1.000000 1.000000 1.000000
Kd 0.800000 0.800000 0.800000
Ks 0.000000 0.000000 0.000000
Ke 0.000000 0.000000 0.000000
Ni 1.500000
d 1.000000
illum 1
This diff is collapsed.
source diff could not be displayed: it is too large. Options to address this: view the blob.
This diff is collapsed.
# Blender 4.3.2 MTL File: 'None'
# www.blender.org
# Blender 4.3.2
# www.blender.org
mtllib untitled.mtl
# Exported by Open CASCADE Technology [dev.opencascade.org]
newmtl mat_1
Ka 0.220168 0.537099 0.394040
Kd 0.435294 1.000000 0.745098
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_2
Ka 0.537099 0.537099 0.537099
Kd 1.000000 1.000000 1.000000
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_3
Ka 0.352223 0.537099 0.528295
Kd 0.670588 1.000000 0.984314
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_4
Ka 0.272990 0.537099 0.407245
Kd 0.529412 1.000000 0.768627
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_5
Ka 0.398442 0.398442 0.398442
Kd 0.752941 0.752941 0.752941
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_6
Ka 0.272990 0.283995 0.283995
Kd 0.529412 0.549020 0.549020
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_7
Ka 0.101319 0.101319 0.101319
Kd 0.223529 0.223529 0.223529
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_8
Ka 0.420451 0.435857 0.499683
Kd 0.792157 0.819608 0.933333
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_9
Ka 0.000000 0.352223 0.510688
Kd 0.000000 0.670588 0.952941
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_10
Ka 0.000000 0.334615 0.484277
Kd 0.000000 0.639216 0.905882
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_11
Ka 0.482076 0.493081 0.493081
Kd 0.901961 0.921569 0.921569
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_12
Ka 0.411647 0.400643 0.389638
Kd 0.776471 0.756863 0.737255
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_13
Ka 0.255383 0.255383 0.255383
Kd 0.498039 0.498039 0.498039
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_14
Ka 0.479875 0.490880 0.497482
Kd 0.898039 0.917647 0.929412
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
newmtl mat_15
Ka 0.385236 0.308205 0.000000
Kd 0.729412 0.592157 0.000000
Ks 0.484529 0.484529 0.484529
Ns 1000.000000
This diff is collapsed.
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>waterstridergazebo</name>
<version>1.0.0</version>
<description>The waterstrider description package</description>
<maintainer email="seawolfy60@gmail.com">Arina Aleevskaia</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<depend>rclcpp</depend>
<depend>std_msgs</depend>
<depend>geometry_msgs</depend>
<depend>uuv_gazebo_ros_plugins_msgs</depend>
<build_depend>eigen</build_depend>
<exec_depend>rclpy</exec_depend>
<exec_depend>gazebo_ros</exec_depend>
<exec_depend>plankton_utils</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>uuv_assistants</exec_depend>
<exec_depend>uuv_gazebo_ros_plugins</exec_depend>
<exec_depend>uuv_sensor_ros_plugins</exec_depend>
<exec_depend>xacro</exec_depend>
<exec_depend>ros2launch</exec_depend>
<exec_depend>topic_tools</exec_depend>
<test_depend>ament_cmake_pytest</test_depend>
<test_depend>xacro</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>
<?xml version="1.0"?>
<!-- Copyright (c) 2020 The Plankton Authors.
All rights reserved.
This source code is derived from UUV Simulator
(https://github.com/uuvsimulator/uuv_simulator)
Copyright (c) 2016-2019 The UUV Simulator Authors
licensed under the Apache license, Version 2.0
cf. 3rd-party-licenses.txt file in the root directory of this source tree.
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
-->
<robot name="waterstrider" xmlns:xacro="http://www.ros.org/wiki/xacro" >
<xacro:arg name="debug" default="0"/>
<xacro:arg name="namespace" default="waterstrider"/>
<xacro:arg name="inertial_reference_frame" default="world"/>
<!-- Include the ROV macro file -->
<xacro:include filename="$(find waterstridergazebo)/urdf/waterstrider_base.xacro"/>
<xacro:include filename="$(find waterstridergazebo)/urdf/waterstrider.gazebo.xacro"/>
<!-- Create the waterstrider -->
<xacro:waterstrider_base
namespace="$(arg namespace)"
inertial_reference_frame="$(arg inertial_reference_frame)">
<!-- The underwater object plugin is given as an input block parameter to
allow the addition of external models of manipulator units -->
<gazebo>
<plugin name="$(arg namespace)_uuv_plugin" filename="libuuv_underwater_object_ros_plugin.so">
<fluid_density>1028.0</fluid_density>
<flow_velocity_topic>hydrodynamics/current_velocity</flow_velocity_topic>
<debug>$(arg debug)</debug>
<!-- Adding the hydrodynamic and hydrostatic parameters for the vehicle-->
<xacro:waterstrider_hydro_model namespace="$(arg namespace)"/>
</plugin>
</gazebo>
</xacro:waterstrider_base>
<!-- Joint state publisher plugin -->
<xacro:default_joint_state_publisher namespace="$(arg namespace)" update_rate="50"/>
</robot>