diff --git a/tmux/config/custom_config.yaml b/tmux/config/custom_config.yaml index 8632257..a3263ef 100644 --- a/tmux/config/custom_config.yaml +++ b/tmux/config/custom_config.yaml @@ -13,7 +13,7 @@ mrs_uav_managers: # "dummy" ] - initial_state_estimator: "gps_baro" # will be used as the first state estimator + initial_state_estimator: "gps_garmin" # will be used as the first state estimator agl_height_estimator: "garmin_agl" # only slightly filtered height for checking min height (not used in control feedback) control_manager: @@ -29,10 +29,10 @@ mrs_uav_managers: controller: "Se3Controller" horizontal: - threshold_distance: 2.5 # [m] + threshold_distance: 1.2 # [m] vertical: - threshold_distance: 1.5 # [m] + threshold_distance: 1.2 # [m] uav_manager: diff --git a/tmux/config/m690.yaml b/tmux/config/m690.yaml deleted file mode 100644 index 4a2d81c..0000000 --- a/tmux/config/m690.yaml +++ /dev/null @@ -1,62 +0,0 @@ -uav_mass: 4.65 - -motor_params: - n_motors: 4 - a: 0.18452 - b: -0.15 - -# these model parameters can be used when -# - 'control group', and/or -# - 'actuator control' -# are accepted by the HW API. -model_params: - - arm_length: 0.345 # [m] - body_height: 0.20 # [m] - - propulsion: - - # force [N] = force_constant * rpm^2 - force_constant: 0.0000010312 - - # torque [Nm] = torque_constant * force [N] - torque_constant: 0.07 - - prop_radius: 0.2286 # [m] - - # allocation motors -> torques - - # quadrotor X configuration - # [roll torque, [ [RPM_1^2, - # pitch torque, = Alloc * RPM_2^2, - # yaw torque, Matrix ... - # thrust force] ] RPM_n_motors^2] - allocation_matrix: [ - -0.707, 0.707, 0.707, -0.707, # *= force_constant*arm_length - -0.707, 0.707, -0.707, 0.707, # *= force_constant*arm_length - -1, -1, 1, 1, # *= torque_constant*force_constant - 1, 1, 1, 1, # *= force_constant - ] - - # The UAV's inertia is approximated as a cilinder using the parameters above - # Alternatively, you can provide inertia matrix directly using the following parameter: - # inertia_matrix: [] - - rpm: - min: 801.55 # [revolutions/minute] - max: 5337.0 # [revolutions/minute] - -mrs_uav_managers: - - constraint_manager: - - default_constraints: - gps_garmin: "medium" - gps_baro: "medium" - rtk: "medium" - aloam: "slow" - hector_garmin: "slow" - vio: "slow" - optflow: "slow" - other: "slow" - ground_truth: "medium" diff --git a/tmux/config/world_config.yaml b/tmux/config/world_config.yaml index 2700a72..cb6b16c 100644 --- a/tmux/config/world_config.yaml +++ b/tmux/config/world_config.yaml @@ -7,7 +7,7 @@ world_origin: safety_area: - enabled: true + enabled: false horizontal: diff --git a/tmux/session.yml b/tmux/session.yml index 6c8ee65..d279864 100644 --- a/tmux/session.yml +++ b/tmux/session.yml @@ -5,7 +5,7 @@ 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=m690 +pre_window: export UAV_NAME=uav1; export RUN_TYPE=simulation; export UAV_TYPE=x500 startup_window: control windows: - roscore: @@ -26,7 +26,7 @@ windows: - spawn: layout: tiled panes: - - waitForGazebo; rosservice call /mrs_drone_spawner/spawn "1 $UAV_TYPE --enable-rangefinder --enable-ouster --use-gpu-ray" + - waitForGazebo; rosservice call /mrs_drone_spawner/spawn "1 $UAV_TYPE --enable-rangefinder --enable-ouster use_gpu:=True" # - waitForGazebo; rosservice call /mrs_drone_spawner/spawn "1 $UAV_TYPE --enable-rangefinder --enable-rplidar" - takeoff: layout: tiled @@ -44,8 +44,7 @@ windows: - control: layout: tiled panes: - # - waitForTime; 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 - - waitForTime; roslaunch mrs_uav_core core.launch platform_config:=./config/m690.yaml custom_config:=./config/custom_config.yaml world_config:=./config/world_config.yaml network_config:=./config/network_config.yaml + - waitForTime; 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 - gazebo_camera_follow: layout: tiled panes: