Skip to content

Commit

Permalink
Browse files Browse the repository at this point in the history
  • Loading branch information
Mokaz committed Aug 6, 2024
2 parents e6eb05f + ae68f2d commit bc9a8ae
Show file tree
Hide file tree
Showing 8 changed files with 1,824 additions and 46 deletions.
2 changes: 1 addition & 1 deletion run_sim.sh
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ tmux rename-window -t $SESSION_NAME:0 'asv_setup'
tmux send-keys -t $SESSION_NAME:0 'ros2 launch asv_setup sim_freya.launch.py' C-m

tmux new-window -t $SESSION_NAME:1 -n 'vrx_gz'
tmux send-keys -t $SESSION_NAME:1 'ros2 launch vrx_gz competition.launch.py world:=sydney_regatta' C-m
tmux send-keys -t $SESSION_NAME:1 'ros2 launch vrx_gz competition.launch.py world:=Njord_maneuvering' C-m

tmux attach-session -t $SESSION_NAME

Expand Down
4 changes: 2 additions & 2 deletions vortex_sim_interface/src/vortex_sim_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,8 @@ class VortexSimInterface : public rclcpp::Node

pcl_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("/ouster/points", qos_sensor_data);

map_origin_lat_ = -33.72242824301795;
map_origin_lon_ = 150.6740063854522;
map_origin_lat_ = -33.72213988382845;
map_origin_lon_ = 150.67413500672993;

gps_sub_ = this->create_subscription<sensor_msgs::msg::NavSatFix>(
"/wamv/sensors/gps/gps/fix", qos_sensor_data,
Expand Down
4 changes: 2 additions & 2 deletions vrx_gz/launch/njord_colav_with_otter.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ def launch(context, *args, **kwargs):
with open(config_file, 'r') as stream:
models = Model.FromConfig(stream)
else:
m = Model('wamv', 'wam-v', [-535, 197, 0, 0, 0, 0])
m = Model('wamv', 'wam-v', [-535, 197.5, 0, 0, 0, 0])
if robot_urdf and robot_urdf != '':
m.set_urdf(robot_urdf)
models.append(m)
Expand Down Expand Up @@ -73,7 +73,7 @@ def generate_launch_description():
# Launch Arguments
DeclareLaunchArgument(
'world',
default_value='sydney_regatta',
default_value='njord_colav_tasks',
description='Name of world'),
DeclareLaunchArgument(
'sim_mode',
Expand Down
Loading

0 comments on commit bc9a8ae

Please sign in to comment.