Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

2023 minimum working example #60

Merged
merged 10 commits into from
Jun 28, 2023
108 changes: 108 additions & 0 deletions mwes/2023/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()
6 changes: 6 additions & 0 deletions mwes/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -19,3 +19,9 @@ This directory contains Dockerfiles for building example competitor Docker image
* Provides a starting point for competitors who expect to build a workspace using custom source code.
* Because the Dockerfile expects to copy source code from the local file system, it is not self-contained.
* Please see the `2022/vrx_2022_starter/README.md` for build instructions.

## 2023

### `vrx_2023_simple` (in work)
* Dockerfile pending
* The python script corresponds to the behavior in `jessicaherman/vrx-competitor-example`
14 changes: 3 additions & 11 deletions replay_trial.bash
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ NOCOLOR='\033[0m'
# Define usage function.
usage()
{
echo "Usage: $0 [-n --nvidia] [--keep-docker] [--manual-play] [--keep-gz] <team_name> <task_name> <trial_num>"
echo "Usage: $0 [--keep-docker] [--manual-play] [--keep-gz] <team_name> <task_name> <trial_num>"
echo "--keep-docker: Keep Gazebo window open and Docker container running after playback ends."
echo " By default, everything is terminated automatically."
echo "--manual-play: Do not automatically start playback. Wait for user to click in GUI."
Expand All @@ -31,8 +31,6 @@ usage()
}

# Parse arguments
nvidia_arg=""
image_nvidia=""
keep_docker=1

# Args to pass to script internal to Docker container
Expand All @@ -45,12 +43,6 @@ do
key="$1"

case $key in
-n|--nvidia)
nvidia_arg="-n"
image_nvidia="-nvidia"
shift
;;

--keep-docker)
keep_docker=1
shift
Expand Down Expand Up @@ -166,8 +158,8 @@ y=$y" > ${HOST_GZ_GUI_CONFIG_DIR}/gui.ini

# Run Gazebo simulation server container
SERVER_CMD="/play_vrx_log.sh ${LOG_FILE} ${OUTPUT} ${manual_play} ${keep_gz}"
SERVER_IMG="vrx-server-${ROS_DISTRO}${image_nvidia}:latest"
${DIR}/vrx_server/run_container.bash $nvidia_arg ${SERVER_CONTAINER_NAME} $SERVER_IMG \
SERVER_IMG="vrx-server-${ROS_DISTRO}:latest"
${DIR}/vrx_server/run_container.bash ${SERVER_CONTAINER_NAME} $SERVER_IMG \
"--net ${NETWORK} \
--ip ${SERVER_ROS_IP} \
-v ${HOST_LOG_DIR}:${LOG_DIR} \
Expand Down
51 changes: 14 additions & 37 deletions run_trial.bash
Original file line number Diff line number Diff line change
Expand Up @@ -19,36 +19,10 @@ NOCOLOR='\033[0m'
# Define usage function.
usage()
{
echo "Usage: $0 [-n --nvidia] <team_name> <task_name> <trial_num>"
echo "Usage: $0 <team_name> <task_name> <trial_num>"
exit 1
}

# Parse arguments
RUNTIME="runc"
nvidia_arg=""
image_nvidia=""

POSITIONAL=()
while [[ $# -gt 0 ]]
do
key="$1"

case $key in
-n|--nvidia)
RUNTIME="nvidia"
nvidia_arg="-n"
image_nvidia="-nvidia"
shift
;;
*) # unknown option
POSITIONAL+=("$1")
shift
;;
esac
done

set -- "${POSITIONAL[@]}"

# Call usage() function if arguments not supplied.
[[ $# -ne 3 ]] && usage

Expand All @@ -65,7 +39,9 @@ fi

# Constants for containers
SERVER_CONTAINER_NAME=vrx-server-system
ROS_DISTRO=noetic
SERVER_USER=developer
ROS_DISTRO=humble
SERVER_IMG="vrx-server-${ROS_DISTRO}:latest"
LOG_DIR=/vrx/logs
NETWORK=vrx-network
NETWORK_SUBNET="172.16.0.10/16" # subnet mask allows communication between IP addresses with 172.16.xx.xx (xx = any)
Expand Down Expand Up @@ -97,7 +73,7 @@ chmod 777 ${HOST_LOG_DIR}
echo -e "${GREEN}Done.${NOCOLOR}\n"

# Find wamv urdf and task world files
echo "Looking for generated files"
echo "Looking for WAM-V urdf file (generated)"
TEAM_GENERATED_DIR=${DIR}/generated/team_generated/${TEAM_NAME}
if [ -f "${TEAM_GENERATED_DIR}/${TEAM_NAME}.urdf" ]; then
echo "Successfully found: ${TEAM_GENERATED_DIR}/${TEAM_NAME}.urdf"
Expand All @@ -106,9 +82,11 @@ else
echo -e "${RED}Err: ${TEAM_GENERATED_DIR}/${TEAM_NAME}.urdf not found."; exit 1;
fi

echo "Looking for task sdf file (generated/copied)"
COMP_GENERATED_DIR=${DIR}/generated/task_generated/${TASK_NAME}
if [ -f "${COMP_GENERATED_DIR}/worlds/${TASK_NAME}${TRIAL_NUM}.sdf" ]; then
echo "Successfully found: ${COMP_GENERATED_DIR}/worlds/${TASK_NAME}${TRIAL_NUM}.sdf"
echo -e "${GREEN}Done.${NOCOLOR}\n"
else
echo -e "${RED}Err: ${COMP_GENERATED_DIR}/worlds/${TASK_NAME}${TRIAL_NUM}.sdf not found."; exit 1;
fi
Expand Down Expand Up @@ -142,9 +120,8 @@ echo "---------------------------------"
# simulation doesn't start too early, but may have issues if competitior
# container waiting for ROS master and has error before server is created.
# Run Gazebo simulation server container
SERVER_CMD="/run_vrx_trial.sh /team_generated/${TEAM_NAME}.urdf /task_generated/worlds/${TASK_NAME}${TRIAL_NUM}.world ${LOG_DIR}"
SERVER_IMG="vrx-server-${ROS_DISTRO}${image_nvidia}:latest"
${DIR}/vrx_server/run_container.bash $nvidia_arg ${SERVER_CONTAINER_NAME} $SERVER_IMG \
SERVER_CMD="/run_vrx_trial.sh /team_generated/${TEAM_NAME}.urdf /task_generated/worlds/${TASK_NAME}${TRIAL_NUM} ${LOG_DIR}"
${DIR}/vrx_server/run_container.bash ${SERVER_CONTAINER_NAME} $SERVER_IMG \
"--net ${NETWORK} \
--ip ${SERVER_ROS_IP} \
-v ${TEAM_GENERATED_DIR}:/team_generated \
Expand Down Expand Up @@ -172,8 +149,8 @@ docker run \
--env ROS_MASTER_URI=${ROS_MASTER_URI} \
--env ROS_IP=${COMPETITOR_ROS_IP} \
--ip ${COMPETITOR_ROS_IP} \
--gpus all \
--privileged \
--runtime=$RUNTIME \
${DOCKERHUB_IMAGE} &

# Run competition until server is ended
Expand All @@ -183,10 +160,10 @@ echo "---------------------------------"

# Copy the ROS log files from the server's container.
echo "Copying ROS log files from server container..."
docker cp --follow-link ${SERVER_CONTAINER_NAME}:/home/$USER/.ros/log/latest $HOST_LOG_DIR/ros-server-latest
docker cp --follow-link ${SERVER_CONTAINER_NAME}:/home/$USER/.gazebo/ $HOST_LOG_DIR/gazebo-server
docker cp --follow-link ${SERVER_CONTAINER_NAME}:/home/$USER/vrx_rostopics.bag $HOST_LOG_DIR/
docker cp --follow-link ${SERVER_CONTAINER_NAME}:/home/$USER/verbose_output.txt $HOST_LOG_DIR/
#docker cp --follow-link ${SERVER_CONTAINER_NAME}:/home/$SERVER_USER/.ros/log/latest $HOST_LOG_DIR/ros-server-latest
docker cp --follow-link ${SERVER_CONTAINER_NAME}:/home/$SERVER_USER/.gz/ $HOST_LOG_DIR/gz-server
docker cp --follow-link ${SERVER_CONTAINER_NAME}:/home/$SERVER_USER/vrx_rostopics.bag $HOST_LOG_DIR/
docker cp --follow-link ${SERVER_CONTAINER_NAME}:/home/$SERVER_USER/verbose_output.txt $HOST_LOG_DIR/

echo -e "${GREEN}OK${NOCOLOR}\n"

Expand Down
2 changes: 1 addition & 1 deletion team_config/example_team/dockerhub_image.txt
Original file line number Diff line number Diff line change
@@ -1 +1 @@
crvogt/vrx_2022_simple
jessicaherman/vrx-competitor-example:2023.v2
64 changes: 64 additions & 0 deletions team_config/example_team_2022/component_config.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
wamv_camera:
- name: front_left_camera
visualize: False
x: 0.75
y: 0.1
z: 1.5
R: 0.0
P: ${radians(15)}
Y: 0.0
post_Y: 0.0
- name: front_right_camera
visualize: False
x: 0.75
y: -0.1
z: 1.5
R: 0.0
P: ${radians(15)}
Y: 0.0
post_Y: 0.0
- name: far_left_camera
visualize: False
x: 0.75
y: 0.3
z: 1.5
R: 0.0
P: ${radians(15)}
Y: 0.0
post_Y: 0.0
wamv_gps:
- name: gps_wamv
x: -0.85
y: 0.0
z: 1.3
R: 0.0
P: 0.0
Y: 0.0
wamv_imu:
- name: imu_wamv
x: 0.3
y: -0.2
z: 1.3
R: 0.0
P: 0.0
Y: 0.0
lidar:
- name: lidar_wamv
type: 16_beam
x: 0.7
y: 0.0
z: 1.8
R: 0.0
P: ${radians(8)}
Y: 0.0
post_Y: 0.0
wamv_ball_shooter:
- name: ball_shooter
x: 0.55
y: -0.3
z: 1.3
pitch: ${radians(-20)}
yaw: 0.0
wamv_pinger:
- name: pinger
position: 1.0 0 -1.0
1 change: 1 addition & 0 deletions team_config/example_team_2022/dockerhub_image.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
crvogt/vrx_2022_simple
10 changes: 10 additions & 0 deletions team_config/example_team_2022/thruster_config.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
engine:
- prefix: "left"
position: "-2.373776 1.027135 0.318237"
orientation: "0.0 0.0 0.0"
- prefix: "right"
position: "-2.373776 -1.027135 0.318237"
orientation: "0.0 0.0 0.0"
- prefix: "middle"
position: "0 0 0.318237"
orientation: "0.0 0.0 0.0"
Loading