Skip to content

Commit

Permalink
Add 2023 mwe starter image example (#72)
Browse files Browse the repository at this point in the history
* changing folder name for 2023 mwe to match 2022
  • Loading branch information
M1chaelM authored Sep 1, 2023
1 parent fb9af57 commit 1a6255d
Show file tree
Hide file tree
Showing 7 changed files with 235 additions and 2 deletions.
2 changes: 1 addition & 1 deletion mwes/2023/vrx_2023_simple/wamv_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -105,4 +105,4 @@ def main(args=None):


if __name__ == '__main__':
main()
main()
52 changes: 52 additions & 0 deletions mwes/2023/vrx_2023_starter/Dockerfile
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
# Note: you must first build the `dockwater:humble` image locally as described
# in the README
ARG BASEIMG=dockwater:humble
FROM $BASEIMG

# Set ROS/Gazebo distributions
ARG ROSDIST=humble
ARG GZDIST=garden

# Optional: Uncomment and customize to get whatever packages you need to build
# your software
#RUN apt update \
#&& apt install -y --no-install-recommends \
# ros-${ROSDIST}-actuator-msgs \
#&& rm -rf /var/lib/apt/lists/* \
#&& apt clean -qq

# Optional: Uncomment and customize to add dev. tools, applications, etc.
#RUN apt-get update && apt-get install -y --no-install-recommends \
# gdb \
# psmisc \
# vim \
# && rm -rf /var/lib/apt/lists/*

# Set up a colcon workspace
RUN mkdir -p /vrx_ws/src

# Here we use my_source as an example of a source code repository stored
# locally on the host. Depending on your solution, you may not
# necessarily need to build vrx. Modify the line below to indicate
# the source repository you want to copy into the workspace inside your
# image.
COPY my_source /vrx_ws/src/vrx

# By default, environment variables do not persist from one Docker
# command to the next, so it is necessary to source setup.sh and build
# the workspace in the same command.
RUN . /opt/ros/humble/setup.sh \
&& cd /vrx_ws \
&& colcon build --merge-install

# Copy startup scripts from host filesystem
COPY ros_entrypoint.sh run_my_system.bash wamv_demo.py /

## Customize your image here.
#
#
## ...

# Sets the entrypoint to your `/ros_entrypoint.sh` script. This is the default
# for this image unless you explicitly change it (not usually necessary).
ENTRYPOINT ["/ros_entrypoint.sh"]
60 changes: 60 additions & 0 deletions mwes/2023/vrx_2023_starter/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
# VRX 2023 Starter Image

## Summary
The intent of this image is to give an example of a Dockerfile that could be
used by competitors who want to copy custom source code into a workspace in
their image and build it.

### Note about this example:
* We use the `vrx` repository as an example of repository of custom source
code that you may want to build.
* In practice, your image may not need to build the `vrx` environment.
* If this is the case, simply replace the `vrx` repository with whatever you
do want to use, and update the `Dockerfile` to use the correct name.

## Preparation
Before building this image, first follow the [VRX Docker Installation
Tutorial](https://github.com/osrf/vrx/wiki/docker_install_tutorial).
The `Dockerfile` used in this example will expect you have already built the
`dockwater:humble` image locally according to the steps described in that tutorial.

## Build
* Clone the source repository into the directory that contains this
`Dockerfile` and the startup scripts:
```
cd vrx-docker/mwes/2023/vrx_2023_starter
git clone https://github.com/osrf/vrx my_source
```
* Make sure there is a `COPY` command in your `Dockerfile` that will put this
directory where it needs to go inside your image. For example:
```
COPY my_source /vrx_ws/src/vrx
```
* Build the docker image:
```
docker build -t <image_name> .
```
where `<image_name>` is a name of your choosing.

#### Note:
We are using the `my_source` directory to represent a temporary
copy of some code you want to develop. However, if you already have a copy
of the `vrx` repository in the same workspace, you will need to move or
delete the new copy you just created after building your Docker image to
avoid creating naming conflicts.

### Rebuilding your image
* If you change your source code and want the changes to be reflected in your
image, simply re-run the build command.
* The `COPY` command will detect any local changes and cause `docker` to copy
the updated file.
* This will also cause all subsequent commands in the `Dockerfile` to be re-run.
* This feature is the main reason to use `COPY` to copy files from a local
filesystem, rather than using `git clone` to pull directoy from a remote
repository.

### Run
To run your image, execute:
```
docker run -it <image_name>
```
7 changes: 7 additions & 0 deletions mwes/2023/vrx_2023_starter/ros_entrypoint.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
#!/bin/bash
set -e

# setup ros environment
source "/opt/ros/$ROS_DISTRO/setup.bash"

/run_my_system.bash
6 changes: 6 additions & 0 deletions mwes/2023/vrx_2023_starter/run_my_system.bash
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
#!/bin/bash

# Start ROS2 daemon for discovery if not already started
ros2 topic list

python3 wamv_demo.py
108 changes: 108 additions & 0 deletions mwes/2023/vrx_2023_starter/wamv_demo.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,108 @@
import rclpy
from rclpy.node import Node
from ros_gz_interfaces.msg import ParamVec
from std_msgs.msg import Float64
from rclpy.qos import QoSProfile, QoSDurabilityPolicy
from geometry_msgs.msg import PoseStamped

class GhostShip(Node):
def __init__(self):
print('Starting node...')
super().__init__('ghost_ship')
self.task_type = ""
self.task_state = ""
self.task_sub = self.create_subscription(ParamVec, '/vrx/task/info',
self.taskCB, 10)

pub_qos = QoSProfile(depth=1,
durability=QoSDurabilityPolicy.TRANSIENT_LOCAL)
self.right_thrust_pub = self.create_publisher(Float64,
'/wamv/thrusters/right/thrust',
qos_profile=pub_qos)
self.left_thrust_pub = self.create_publisher(Float64,
'/wamv/thrusters/left/thrust',
qos_profile=pub_qos)
self.thrust_msg = Float64()
self.thrust_msg.data = 30.0
self.loopCount = 0

self.landmark_pub = self.create_publisher(PoseStamped,
'/vrx/perception/landmark',
qos_profile=pub_qos)
self.landmark_msg = PoseStamped()
self.landmark_msg.header.stamp = self.get_clock().now().to_msg()
self.landmark_msg.header.frame_id = 'mb_marker_buoy_red'
self.landmark_msg.pose.position.x = -33.7227024
self.landmark_msg.pose.position.y = 150.67402097
self.landmark_msg.pose.position.z = 0.0

self.create_timer(0.5, self.sendCmds)

def taskCB(self, msg):
task_info = msg.params
for p in task_info:
if p.name == 'name':
self.task_type = p.value .string_value
if p.name == 'state':
self.task_state = p.value.string_value

def moveForward(self):
self.right_thrust_pub.publish(self.thrust_msg)
self.left_thrust_pub.publish(self.thrust_msg)
self.loopCount += 1

def stop(self):
self.thrust_msg.data = 0.0
self.right_thrust_pub.publish(self.thrust_msg)
self.left_thrust_pub.publish(self.thrust_msg)

def publishBuoyLoc(self):
if self.loopCount > 10:
self.landmark_pub.publish(self.landmark_msg)
self.loopCount = 0
self.loopCount += 1



def sendCmds(self):
if rclpy.ok():
match self.task_type:
case "perception":
if self.task_state == ("initial" or "ready"):
print("Waiting for perception task to start...")
elif self.task_state == "running":
self.publishBuoyLoc()
elif self.task_state == "finished":
print("Task ended...")
rclpy.shutdown()
case "stationkeeping":
if self.task_state == ("initial" or "ready"):
print("Waiting for stationkeeping task to start...")
elif self.task_state == "running":
if self.loopCount < 10:
self.moveForward()
else:
self.stop()
elif self.task_state == "finished":
print("Task ended...")
rclpy.shutdown()
case _:
print(self.task_state)
if self.task_state == ("initial" or "ready"):
print("Waiting for default task to start...")
elif self.task_state == "running":
self.right_thrust_pub.publish(self.thrust_msg)
self.left_thrust_pub.publish(self.thrust_msg)
elif self.task_state == "finished":
print("Task ended...")
rclpy.shutdown()

def main(args=None):
rclpy.init(args=args)

ghost_ship = GhostShip()
rclpy.spin(ghost_ship)


if __name__ == '__main__':
main()
2 changes: 1 addition & 1 deletion team_config/example_team/component_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -60,5 +60,5 @@ wamv_ball_shooter:
pitch: ${radians(-20)}
yaw: 0.0
wamv_pinger:
- name: pinger
- sensor_name: pinger
position: 1.0 0 -1.0

0 comments on commit 1a6255d

Please sign in to comment.