diff --git a/README.md b/README.md index 2010d86..6fa0d16 100644 --- a/README.md +++ b/README.md @@ -15,6 +15,10 @@ This repository includes Core ROS examples for the [MRS UAV System](https://gith ## Python * [sweeping_generator](./python/sweeping_generator) - Minimalistic Python Example that generates sweeping path for the UAV + +## tmux + +* [passthrough_estimator](./tmux/passthrough_estimator) - tmux simulation session that shows how to run the simulation with passthrough estimator # Disclaimer diff --git a/tmux/passthrough_estimator/config/custom_config.yaml b/tmux/passthrough_estimator/config/custom_config.yaml new file mode 100644 index 0000000..acc2191 --- /dev/null +++ b/tmux/passthrough_estimator/config/custom_config.yaml @@ -0,0 +1,71 @@ +mrs_uav_managers: + + estimation_manager: + + # loaded state estimator plugins + state_estimators: [ + "passthrough", + ] + + initial_state_estimator: "passthrough" # will be used as the first state estimator + agl_height_estimator: "" # only slightly filtered height for checking min height (not used in control feedback) + + passthrough: + max_flight_z: 100.0 # [m] maximum allowed flight Z (in the estimator frame) + kickoff: false # do not wait until desired Hz is achieved (set to true if kickoff estimator is used) + message: + topic: "hw_api/odometry" + + uav_manager: + + takeoff: + + during_takeoff: + controller: "MpcController" + tracker: "LandoffTracker" + + after_takeoff: + controller: "MpcController" # more robust + # controller: "Se3Controller" # more precise + tracker: "MpcTracker" + + constraint_manager: + + estimator_types: [ + "passthrough" + ] + + constraints: [ + "slow", + "medium", + "fast" + ] + + # list of allowed gains per odometry mode + allowed_constraints: + passthrough: ["slow", "medium", "fast"] + + # those gains will be used automatically when a localization mode switches + # and the current gains are not in the allowed list (next paragraphs) + default_constraints: + passthrough: "slow" + + gain_manager: + + estimator_types: [ + "passthrough" + ] + + gains: [ + "soft" + ] + + # list of allowed gains per odometry mode + allowed_gains: + passthrough: ["soft"] + + # those gains will be used automatically when a localization mode switches + # and the current gains are not in the allowed list (next paragraphs) + default_gains: + passthrough: "soft" + diff --git a/tmux/passthrough_estimator/config/network_config.yaml b/tmux/passthrough_estimator/config/network_config.yaml new file mode 100644 index 0000000..08f370d --- /dev/null +++ b/tmux/passthrough_estimator/config/network_config.yaml @@ -0,0 +1,15 @@ +# 1. This list is used by NimbroNetwork for mutual communication of the UAVs +# The names of the robots have to match hostnames described in /etc/hosts. +# +# 2. This list is used by MpcTracker for mutual collision avoidance of the UAVs. +# The names should match the true "UAV_NAMES" (the topic prefixes). +# +# network_config:=~/config/network_config.yaml +# +# to the core.launch and nimbro.launch. + +network: + + robot_names: [ + uav1, + ] diff --git a/tmux/passthrough_estimator/config/rviz/passthrough.rviz b/tmux/passthrough_estimator/config/rviz/passthrough.rviz new file mode 100644 index 0000000..84492fc --- /dev/null +++ b/tmux/passthrough_estimator/config/rviz/passthrough.rviz @@ -0,0 +1,533 @@ +Panels: + - Class: rviz/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /TF1/Frames1 + - /TF1/Tree1 + Splitter Ratio: 0.6970587968826294 + Tree Height: 361 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + - /Plan path1 + - /Custom Goal1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Name: Time + SyncMode: 0 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.20000000298023224 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 100 + Reference Frame: + Value: true + - Alpha: 0.5 + Cell Size: 5 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 100 + Reference Frame: + Value: true + - Class: rviz/TF + Enabled: false + Filter (blacklist): "" + Filter (whitelist): "" + Frame Timeout: 15 + Frames: + All Enabled: false + Marker Alpha: 1 + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + {} + Update Interval: 0 + Value: false + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + uav1/fcu: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + uav1/fcu/arms_red: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: UAVModel + Robot Description: /uav1/robot_model + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz/Group + Displays: + - Background color: 204; 204; 204 + Class: mrs_rviz_plugins/Status + Computer load: true + Control manager: true + Custom strings: true + Enabled: true + Hw api state: true + Name: Status + Node stats list: false + Odometry: true + Text color: 0; 0; 0 + Top Line: true + Topic rates: true + UAV name: uav1 + Value: true + - Class: rviz/InteractiveMarkers + Enable Transparency: true + Enabled: true + Name: Control Display + Show Axes: false + Show Descriptions: true + Show Visual Aids: false + Update Topic: control/update + Value: true + Enabled: true + Name: Status + - Class: rviz/Group + Displays: + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 6.5032958984375 + Min Value: -0.6449446678161621 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: AxisColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: ouster_raw + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.10000000149011612 + Style: Spheres + Topic: /uav1/os_cloud_nodelet/points + Unreliable: true + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 0; 0; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: rplidar + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.10000000149011612 + Style: Flat Squares + Topic: /uav1/rplidar/scan + Unreliable: true + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/Image + Enabled: false + Image Topic: /uav1/vio/camera/image_raw + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: vio_camera + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: false + Enabled: true + Name: Sensors + - Class: rviz/Group + Displays: + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /uav1/control_manager/safety_area_markers + Name: SafetyhArea + Namespaces: + "": true + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /uav1/control_manager/safety_area_coordinates_markers + Name: SafetyAreaCoordinates + Namespaces: + "": true + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /uav1/control_manager/disturbances_markers + Name: Disturbances + Namespaces: + control_manager: true + Queue Size: 100 + Value: true + - Angle Tolerance: 0.009999999776482582 + Class: rviz/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Keep: 1 + Name: control_reference + Position Tolerance: 0.009999999776482582 + Queue Size: 10 + Shape: + Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Color: 255; 25; 0 + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Value: Axes + Topic: /uav1/control_manager/control_reference + Unreliable: true + Value: true + - Class: rviz/Group + Displays: + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.30000001192092896 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 0; 170; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: Poses + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Arrow (Flat) + Topic: /uav1/control_manager/trajectory_original/poses + Unreliable: true + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /uav1/control_manager/trajectory_original/markers + Name: Markers + Namespaces: + {} + Queue Size: 100 + Value: true + Enabled: true + Name: OriginalTrajectory + - Alpha: 0.10000000149011612 + Class: mrs_rviz_plugins/Bumper + Collision alpha: 0.5 + Collision color: 255; 0; 0 + Color: 204; 51; 204 + Colorize collisions: true + Display mode: sensor types + Enabled: true + History Length: 1 + Horizontal collision threshold: 1 + Name: Bumper + Queue Size: 10 + Show sectors with no data: false + Show undetected obstacles: true + Topic: /uav1/bumper/obstacle_sectors + Unreliable: true + Value: true + Vertical collision threshold: 1 + Enabled: true + Name: ControlManager + - Class: rviz/Group + Displays: + - Angle Tolerance: 0.009999999776482582 + Class: rviz/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: false + Enabled: true + Keep: 1 + Name: odom_main + Position Tolerance: 0.009999999776482582 + Queue Size: 10 + Shape: + Alpha: 1 + Axes Length: 0.5 + Axes Radius: 0.10000000149011612 + Color: 0; 25; 255 + Head Length: 1 + Head Radius: 0.30000001192092896 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Value: Axes + Topic: /uav1/estimation_manager/odom_main + Unreliable: true + Value: true + Enabled: true + Name: EstimationManager + - Class: rviz/Group + Displays: + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.30000001192092896 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 0; 0; 255 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: MpcPredictionTrajectory + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Arrow (Flat) + Topic: /uav1/control_manager/mpc_tracker/predicted_trajectory_debugging + Unreliable: true + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.10000000149011612 + Axes Radius: 0.05000000074505806 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: MpcInnerReference + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Axes + Topic: /uav1/control_manager/mpc_tracker/mpc_reference_debugging + Unreliable: true + Value: true + - Class: rviz/Group + Displays: + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.30000001192092896 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: Poses + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Arrow (Flat) + Topic: /uav1/control_manager/mpc_tracker/trajectory_processed/poses + Unreliable: true + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /uav1/control_manager/mpc_tracker/trajectory_processed/markers + Name: Markers + Namespaces: + {} + Queue Size: 100 + Value: true + Enabled: true + Name: PostprocessedTrajectory + Enabled: true + Name: MpcTracker + - Class: rviz/Group + Displays: + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /uav1/trajectory_generation/markers/final + Name: final + Namespaces: + {} + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /uav1/trajectory_generation/markers/original + Name: original + Namespaces: + {} + Queue Size: 100 + Value: true + Enabled: true + Name: TrajectoryGeneration + Enabled: true + Global Options: + Background Color: 255; 255; 255 + Default Light: true + Fixed Frame: uav1/local_origin + Frame Rate: 60 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + - Class: mrs_rviz_plugins/ControlTool + - Class: mrs_rviz_plugins/WaypointPlanner + Drone name: uav1 + Fly now: true + Height offset: 0 + Loop: false + Shape: Axes + Stop at waypoints: false + Topic: trajectory_generation/path + Use heading: true + - Class: mrs_rviz_plugins/NamedSetGoal + Name: name + Topic: goal + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 8.42684555053711 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: -0.012971354648470879 + Y: -0.16276033222675323 + Z: 1.279098391532898 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.3653985559940338 + Target Frame: uav1/fcu + Yaw: 3.0853917598724365 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 506 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd000000040000000000000156000001a4fc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001a4000000c700fffffffb0000001400760069006f005f00630061006d0065007200610000000122000000bd0000000000000000fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000001400000009f0000000000000000fb0000001400760069006f005f00630061006d00650072006100000001400000009f0000001600ffffff0000000100000116000001a4fc0200000004fb0000001e0054006f006f006c002000500072006f0070006500720074006900650073000000003b000000e40000005c00fffffffb0000000a005600690065007700730000000125000000ba000000a000fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073000000016d0000016e0000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000038f0000003efc0100000002fb0000000800540069006d006500000000000000038f0000030200fffffffb0000000800540069006d0065010000000000000450000000000000000000000606000001a400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: true + Views: + collapsed: true + Width: 1890 + X: 3852 + Y: 32 + vio_camera: + collapsed: false diff --git a/tmux/passthrough_estimator/config/world_config.yaml b/tmux/passthrough_estimator/config/world_config.yaml new file mode 100644 index 0000000..d9aa1b5 --- /dev/null +++ b/tmux/passthrough_estimator/config/world_config.yaml @@ -0,0 +1,34 @@ +world_origin: + + units: "LATLON" # {"UTM, "LATLON"} + + origin_x: 47.397743 + origin_y: 8.545594 + +safety_area: + + enabled: true + + horizontal: + + # the frame of reference in which the points are expressed + frame_name: "local_origin" + + # polygon + # + # x, y [m] for any frame_name except latlon_origin + # x = latitude, y = longitude [deg] for frame_name=="latlon_origin" + points: [ + -50, -50, + 50, -50, + 50, 50, + -50, 50, + ] + + vertical: + + # the frame of reference in which the max&min z is expressed + frame_name: "local_origin" + + max_z: 30.0 + min_z: 0.5 diff --git a/tmux/passthrough_estimator/kill.sh b/tmux/passthrough_estimator/kill.sh new file mode 100755 index 0000000..28d50b0 --- /dev/null +++ b/tmux/passthrough_estimator/kill.sh @@ -0,0 +1,14 @@ +#!/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 + +# just attach to the session +tmux -L $TMUX_SOCKET_NAME split-window -t $TMUX_SESSION_NAME +tmux -L $TMUX_SOCKET_NAME send-keys -t $TMUX_SESSION_NAME "sleep 1; tmux list-panes -s -F \"#{pane_pid} #{pane_current_command}\" | grep -v tmux | cut -d\" \" -f1 | while read in; do killp \$in; done; exit" ENTER diff --git a/tmux/passthrough_estimator/layout.json b/tmux/passthrough_estimator/layout.json new file mode 100644 index 0000000..3b10030 --- /dev/null +++ b/tmux/passthrough_estimator/layout.json @@ -0,0 +1,105 @@ +[ + { + "border": "normal", + "floating": "auto_off", + "fullscreen_mode": 0, + "layout": "splith", + "percent": 0.5, + "type": "con", + "nodes": [ + { + "border": "normal", + "floating": "auto_off", + "layout": "splith", + "percent": 1, + "type": "con", + "nodes": [ + { + "border": "normal", + "floating": "auto_off", + "layout": "splitv", + "percent": 1, + "type": "con", + "nodes": [ + { + "border": "normal", + "floating": "auto_off", + "layout": "splith", + "percent": 0.5, + "type": "con", + "nodes": [ + { + "border": "pixel", + "current_border_width": 3, + "floating": "auto_off", + "geometry": { + "height": 460, + "width": 724, + "x": 0, + "y": 0 + }, + "name": "Gazebo", + "percent": 0.5, + "swallows": [ + { + "instance": "^gazebo$" + } + ], + "type": "con" + }, + { + "border": "pixel", + "current_border_width": 3, + "floating": "auto_off", + "geometry": { + "height": 460, + "width": 724, + "x": 0, + "y": 0 + }, + "name": "default_simulation.rviz* - RViz", + "percent": 0.5, + "swallows": [ + { + "instance": "^rviz$" + } + ], + "type": "con" + } + ] + }, + { + "border": "normal", + "floating": "auto_off", + "layout": "splith", + "percent": 0.5, + "type": "con", + "nodes": [ + { + "border": "pixel", + "current_border_width": 3, + "floating": "auto_off", + "geometry": { + "height": 460, + "width": 724, + "x": 0, + "y": 0 + }, + "name": "./start.sh", + "percent": 1, + "swallows": [ + { + "instance": "^urxvt$" + } + ], + "type": "con" + } + ] + } + ] + } + ] + } + ] + } +] diff --git a/tmux/passthrough_estimator/session.yml b/tmux/passthrough_estimator/session.yml new file mode 100644 index 0000000..8e50092 --- /dev/null +++ b/tmux/passthrough_estimator/session.yml @@ -0,0 +1,55 @@ +# do not modify these +root: ./ +name: simulation +socket_name: mrs +attach: false +tmux_options: -f /etc/ctu-mrs/tmux.conf +# you can modify these +pre_window: export UAV_NAME=uav1; export RUN_TYPE=simulation; export UAV_TYPE=x500 +startup_window: status +windows: + - roscore: + layout: tiled + panes: + - roscore + - gazebo: + layout: tiled + panes: + - waitForRos; roslaunch mrs_uav_gazebo_simulation simulation.launch world_name:=grass_plane gui:=true + - waitForGazebo; rosservice call /mrs_drone_spawner/spawn "1 --$UAV_TYPE" + - waitForControl; gz camera -c gzclient_camera -f $UAV_NAME; history -s gz camera -c gzclient_camera -f $UAV_NAME + - status: + layout: tiled + panes: + - waitForHw; roslaunch mrs_uav_status status.launch + - hw_api: + layout: tiled + panes: + - waitForTime; roslaunch mrs_uav_px4_api api.launch + - core: + layout: tiled + panes: + - waitForHw; roslaunch mrs_uav_core core.launch + platform_config:=`rospack find mrs_uav_gazebo_simulation`/config/mrs_uav_system/$UAV_TYPE.yaml + custom_config:=./config/custom_config.yaml + world_config:=./config/world_config.yaml + network_config:=./config/network_config.yaml + - takeoff: + layout: tiled + panes: + - waitForHw; roslaunch mrs_uav_autostart automatic_start.launch + - 'waitForControl; rosservice call /$UAV_NAME/hw_api/arming 1; sleep 2; rosservice call /$UAV_NAME/hw_api/offboard' + - goto: + layout: tiled + panes: + - 'history -s rosservice call /$UAV_NAME/control_manager/goto \"goal: \[0.0, 10.0, 1.5, 0.0\]\"' + - rviz: + layout: tiled + panes: + - waitForControl; rviz -d ./config/rviz/passthrough.rviz + - waitForControl; roslaunch mrs_rviz_plugins load_robot.launch + - waitForControl; roslaunch mrs_rviz_plugins rviz_interface.launch + - layout: + layout: tiled + panes: + - waitForControl; sleep 3; ~/.i3/layout_manager.sh ./layout.json diff --git a/tmux/passthrough_estimator/start.sh b/tmux/passthrough_estimator/start.sh new file mode 100755 index 0000000..5bb2275 --- /dev/null +++ b/tmux/passthrough_estimator/start.sh @@ -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