Skip to content

Commit

Permalink
fixing mavros launch
Browse files Browse the repository at this point in the history
  • Loading branch information
klaxalk committed Aug 8, 2023
1 parent dd2c81b commit bd06b2d
Show file tree
Hide file tree
Showing 10 changed files with 34 additions and 12 deletions.
5 changes: 5 additions & 0 deletions ros_packages/mrs_uav_gazebo_simulation/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,11 @@ install(DIRECTORY scripts/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/scripts
)

install(DIRECTORY tmux/
USE_SOURCE_PERMISSIONS
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/tmux
)

install(DIRECTORY ROMFS/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/ROMFS
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ def __init__(self, show_help=False, verbose=False):

self.path_to_launch_file_firmware = pkg_path + os.sep + 'launch' + os.sep + 'run_simulation_firmware.launch'
self.path_to_launch_file_spawn_model = pkg_path + os.sep + 'launch' + os.sep + 'spawn_simulation_model.launch'
self.path_to_launch_file_mavros = pkg_path + os.sep + 'launch' + os.sep + 'run_simulation_mavros.launch'
self.path_to_launch_file_mavros = "mrs_uav_px4_api" + os.sep + 'launch' + os.sep + 'mavros_gazebo_simulation.launch'

rospy.init_node('mrs_drone_spawner', anonymous=True)
rinfo('Node initialization started. All parameters loaded correctly.')
Expand Down
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
27 changes: 27 additions & 0 deletions ros_packages/mrs_uav_gazebo_simulation/tmux/one_drone/start.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
#!/bin/bash

# Absolute path to this script. /home/user/bin/foo.sh
SCRIPT=$(readlink -f $0)
# Absolute path this script is in. /home/user/bin
SCRIPTPATH=`dirname $SCRIPT`
cd "$SCRIPTPATH"

export TMUX_SESSION_NAME=simulation
export TMUX_SOCKET_NAME=mrs

# start tmuxinator
tmuxinator start -p ./session.yml

# if we are not in tmux
if [ -z $TMUX ]; then

# just attach to the session
tmux -L $TMUX_SOCKET_NAME a -t $TMUX_SESSION_NAME

# if we are in tmux
else

# switch to the newly-started session
tmux detach-client -E "tmux -L $TMUX_SOCKET_NAME a -t $TMUX_SESSION_NAME"

fi
1 change: 1 addition & 0 deletions tmux
11 changes: 0 additions & 11 deletions tmux/one_drone/start.sh

This file was deleted.

0 comments on commit bd06b2d

Please sign in to comment.