From d0e17d381d8c6f08a6cc8fb08383b07191b32c36 Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Wed, 26 Jul 2023 20:25:32 +0800 Subject: [PATCH 01/34] Tweaking UI Signed-off-by: Michael X. Grey --- rmf_site_editor/src/widgets/create.rs | 58 +++++++++------------------ 1 file changed, 20 insertions(+), 38 deletions(-) diff --git a/rmf_site_editor/src/widgets/create.rs b/rmf_site_editor/src/widgets/create.rs index 26dad371..4bd588ba 100644 --- a/rmf_site_editor/src/widgets/create.rs +++ b/rmf_site_editor/src/widgets/create.rs @@ -85,6 +85,26 @@ impl<'a, 'w, 's> CreateWidget<'a, 'w, 's> { SelectAnchor::create_one_new_edge().for_constraint().into(), )); } + CollapsingHeader::new("New drawing") + .default_open(false) + .show(ui, |ui| { + if let Some(new_asset_source) = InspectAssetSource::new( + source, &RecallAssetSource::default() + ).show(ui) { + self.events + .change + .asset_source + .send(Change::new(new_asset_source, e)); + } + ui.add_space(5.0); + if ui.button("Add Drawing").clicked() { + let drawing = Drawing { + source: source.clone(), + ..default() + }; + self.events.commands.spawn(DrawingBundle::new(&drawing)); + } + }); } AppState::SiteDrawingEditor => { if ui.button("Fiducial").clicked() { @@ -193,44 +213,6 @@ impl<'a, 'w, 's> CreateWidget<'a, 'w, 's> { } } } - if let Ok((e, source)) = self.events.pending_drawings.get_single() { - ui.add_space(10.0); - CollapsingHeader::new("New drawing") - .default_open(false) - .show(ui, |ui| { - if let Some(new_asset_source) = - InspectAssetSource::new(source, &RecallAssetSource::default()).show(ui) - { - self.events - .change - .asset_source - .send(Change::new(new_asset_source, e)); - } - ui.add_space(5.0); - match self.events.app_state.current() { - AppState::SiteEditor => { - if ui.button("Add Drawing").clicked() { - let drawing = Drawing { - source: source.clone(), - ..default() - }; - self.events.commands.spawn(DrawingBundle::new(&drawing)); - } - ui.add_space(10.0); - } - _ => {} - } - }); - } else if self.events.pending_drawings.is_empty() { - // Spawn one - let source = AssetSource::Local("clinic.png".to_string()); - self.events - .commands - .spawn(source.clone()) - .insert(DrawingMarker) - .insert(SuppressRecencyRank) - .insert(Pending); - } }); } } From a5636fcc0c63693c5b03f1bc8d365f75c6cb6c9f Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Wed, 26 Jul 2023 21:35:35 +0800 Subject: [PATCH 02/34] Clean up drawing creation Signed-off-by: Michael X. Grey --- rmf_site_editor/src/widgets/create.rs | 160 +++++++++---------- rmf_site_editor/src/widgets/inspector/mod.rs | 9 -- rmf_site_editor/src/widgets/mod.rs | 28 ++-- rmf_site_format/src/misc.rs | 2 +- 4 files changed, 94 insertions(+), 105 deletions(-) diff --git a/rmf_site_editor/src/widgets/create.rs b/rmf_site_editor/src/widgets/create.rs index 4bd588ba..68c9ad59 100644 --- a/rmf_site_editor/src/widgets/create.rs +++ b/rmf_site_editor/src/widgets/create.rs @@ -18,7 +18,7 @@ use crate::{ inspector::{InspectAssetSource, InspectScale}, interaction::{ChangeMode, SelectAnchor, SelectAnchor3D}, - site::{Change, DrawingBundle, DrawingMarker}, + site::{Change, DrawingBundle, DrawingMarker, Recall}, AppEvents, AppState, SuppressRecencyRank, }; use bevy::prelude::*; @@ -85,21 +85,24 @@ impl<'a, 'w, 's> CreateWidget<'a, 'w, 's> { SelectAnchor::create_one_new_edge().for_constraint().into(), )); } + + ui.add_space(10.0); CollapsingHeader::new("New drawing") .default_open(false) .show(ui, |ui| { if let Some(new_asset_source) = InspectAssetSource::new( - source, &RecallAssetSource::default() + &self.events.pending_drawings.source, + &self.events.pending_drawings.recall_source, ).show(ui) { - self.events - .change - .asset_source - .send(Change::new(new_asset_source, e)); + self.events.pending_drawings.recall_source.remember( + &new_asset_source + ); + self.events.pending_drawings.source = new_asset_source; } ui.add_space(5.0); if ui.button("Add Drawing").clicked() { let drawing = Drawing { - source: source.clone(), + source: self.events.pending_drawings.source.clone(), ..default() }; self.events.commands.spawn(DrawingBundle::new(&drawing)); @@ -129,89 +132,76 @@ impl<'a, 'w, 's> CreateWidget<'a, 'w, 's> { match self.events.app_state.current() { AppState::MainMenu | AppState::SiteDrawingEditor | AppState::SiteVisualizer => {} AppState::SiteEditor | AppState::WorkcellEditor => { - if let Ok((e, source, scale)) = self.events.pending_models.get_single() { - ui.add_space(10.0); - CollapsingHeader::new("New model") - .default_open(false) - .show(ui, |ui| { - if let Some(new_asset_source) = - InspectAssetSource::new(source, &RecallAssetSource::default()) - .show(ui) - { - self.events - .change - .asset_source - .send(Change::new(new_asset_source, e)); - } - ui.add_space(5.0); - if let Some(new_scale) = InspectScale::new(scale).show(ui) { - self.events - .workcell_change - .scale - .send(Change::new(new_scale, e)); + ui.add_space(10.0); + CollapsingHeader::new("New model") + .default_open(false) + .show(ui, |ui| { + if let Some(new_asset_source) = InspectAssetSource::new( + &self.events.pending_model.source, + &self.events.pending_model.recall_source, + ).show(ui) { + self.events.pending_model.recall_source.remember(&new_asset_source); + self.events.pending_model.source = new_asset_source; + } + ui.add_space(5.0); + if let Some(new_scale) = InspectScale::new( + &self.events.pending_model.scale, + ).show(ui) { + self.events.pending_model.scale = new_scale; + } + ui.add_space(5.0); + match self.events.app_state.current() { + AppState::MainMenu + | AppState::SiteDrawingEditor + | AppState::SiteVisualizer => {} + AppState::SiteEditor => { + if ui.button("Spawn model").clicked() { + let model = Model { + source: self.events.pending_model.source.clone(), + scale: self.events.pending_model.scale, + ..default() + }; + self.events.request.change_mode.send(ChangeMode::To( + SelectAnchor3D::create_new_point() + .for_model(model) + .into(), + )); + } } - ui.add_space(5.0); - match self.events.app_state.current() { - AppState::MainMenu - | AppState::SiteDrawingEditor - | AppState::SiteVisualizer => {} - AppState::SiteEditor => { - if ui.button("Spawn model").clicked() { - let model = Model { - source: source.clone(), - ..default() - }; - self.events.request.change_mode.send(ChangeMode::To( - SelectAnchor3D::create_new_point() - .for_model(model) - .into(), - )); - } + AppState::WorkcellEditor => { + if ui.button("Spawn visual").clicked() { + let workcell_model = WorkcellModel { + geometry: Geometry::Mesh { + filename: (&self.events.pending_model.source).into(), + scale: Some(*self.events.pending_model.scale), + }, + ..default() + }; + self.events.request.change_mode.send(ChangeMode::To( + SelectAnchor3D::create_new_point() + .for_visual(workcell_model) + .into(), + )); } - AppState::WorkcellEditor => { - if ui.button("Spawn visual").clicked() { - let workcell_model = WorkcellModel { - geometry: Geometry::Mesh { - filename: source.into(), - scale: Some(**scale), - }, - ..default() - }; - self.events.request.change_mode.send(ChangeMode::To( - SelectAnchor3D::create_new_point() - .for_visual(workcell_model) - .into(), - )); - } - if ui.button("Spawn collision").clicked() { - let workcell_model = WorkcellModel { - geometry: Geometry::Mesh { - filename: source.into(), - scale: Some(**scale), - }, - ..default() - }; - self.events.request.change_mode.send(ChangeMode::To( - SelectAnchor3D::create_new_point() - .for_collision(workcell_model) - .into(), - )); - } - ui.add_space(10.0); + if ui.button("Spawn collision").clicked() { + let workcell_model = WorkcellModel { + geometry: Geometry::Mesh { + filename: (&self.events.pending_model.source).into(), + scale: Some(*self.events.pending_model.scale), + }, + ..default() + }; + self.events.request.change_mode.send(ChangeMode::To( + SelectAnchor3D::create_new_point() + .for_collision(workcell_model) + .into(), + )); } + ui.add_space(10.0); } - }); - } else if self.events.pending_models.is_empty() { - // Spawn one - let source = AssetSource::Search("OpenRobotics/AdjTable".to_string()); - self.events - .commands - .spawn(source.clone()) - .insert(Scale::default()) - .insert(ModelMarker) - .insert(Pending); + } + }); } - } } }); } diff --git a/rmf_site_editor/src/widgets/inspector/mod.rs b/rmf_site_editor/src/widgets/inspector/mod.rs index 1295399c..79324920 100644 --- a/rmf_site_editor/src/widgets/inspector/mod.rs +++ b/rmf_site_editor/src/widgets/inspector/mod.rs @@ -409,15 +409,6 @@ impl<'a, 'w1, 'w2, 's1, 's2> InspectorWidget<'a, 'w1, 'w2, 's1, 's2> { ui.add_space(10.0); } - if let Ok(is_primary) = self.params.drawing.is_primary.get(selection) { - if let Some(new_is_primary) = InspectIsPrimary::new(is_primary).show(ui) { - self.events - .is_primary - .send(Change::new(new_is_primary, selection)); - } - ui.add_space(10.0); - } - if let Ok(distance) = self.params.drawing.distance.get(selection) { if let Some(new_distance) = InspectOptionF32::new("Distance".to_string(), distance.0, 10.0) diff --git a/rmf_site_editor/src/widgets/mod.rs b/rmf_site_editor/src/widgets/mod.rs index 1f4b8902..e359a27f 100644 --- a/rmf_site_editor/src/widgets/mod.rs +++ b/rmf_site_editor/src/widgets/mod.rs @@ -33,7 +33,7 @@ use crate::{ }; use bevy::{ecs::system::SystemParam, prelude::*}; use bevy_egui::{ - egui::{self, Button, CollapsingHeader, Sense}, + egui::{self, Button, CollapsingHeader}, EguiContext, }; use rmf_site_format::*; @@ -76,6 +76,19 @@ pub enum UiUpdateLabel { DrawUi, } +#[derive(Resource, Clone, Default)] +pub struct PendingDrawing { + pub source: AssetSource, + pub recall_source: RecallAssetSource, +} + +#[derive(Resource, Clone, Default)] +pub struct PendingModel { + pub source: AssetSource, + pub recall_source: RecallAssetSource, + pub scale: Scale, +} + #[derive(Default)] pub struct StandardUiLayout; @@ -86,6 +99,8 @@ impl Plugin for StandardUiLayout { .init_resource::() .init_resource::() .init_resource::() + .init_resource::() + .init_resource::() .add_system_set(SystemSet::on_enter(AppState::MainMenu).with_system(init_ui_style)) .add_system_set( SystemSet::on_update(AppState::SiteEditor) @@ -239,16 +254,9 @@ pub struct AppEvents<'w, 's> { pub layers: LayerEvents<'w, 's>, pub app_state: ResMut<'w, State>, pub visibility_parameters: VisibilityParameters<'w, 's>, - pub pending_models: Query< - 'w, - 's, - (Entity, &'static AssetSource, &'static Scale), - (With, With), - >, - pub pending_drawings: - Query<'w, 's, (Entity, &'static AssetSource), (With, With)>, + pub pending_model: ResMut<'w, PendingModel>, + pub pending_drawings: ResMut<'w, PendingDrawing>, // TODO(luca) put this into change once the 16 size limit is lifted in bevy 0.10 - pub is_primary: EventWriter<'w, 's, Change>, pub distance: EventWriter<'w, 's, Change>, pub scale_drawing: EventWriter<'w, 's, ScaleDrawing>, pub align_drawings: EventWriter<'w, 's, AlignLevelDrawings>, diff --git a/rmf_site_format/src/misc.rs b/rmf_site_format/src/misc.rs index fb8f8b6c..5b211724 100644 --- a/rmf_site_format/src/misc.rs +++ b/rmf_site_format/src/misc.rs @@ -125,7 +125,7 @@ impl RectFace { } } -#[derive(Serialize, Deserialize, Deref, DerefMut, PartialEq, Clone, Debug)] +#[derive(Serialize, Deserialize, Deref, DerefMut, PartialEq, Clone, Copy, Debug)] #[cfg_attr(feature = "bevy", derive(Component))] pub struct Scale(pub Vec3); From 3585ab503c09f5a5c9e172140bedbe5659595b10 Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Wed, 26 Jul 2023 23:04:21 +0800 Subject: [PATCH 03/34] Use events to start and stop editing drawings Signed-off-by: Michael X. Grey --- .../src/site/drawing_editor/mod.rs | 10 +++++- rmf_site_editor/src/widgets/create.rs | 34 +++++++++---------- rmf_site_editor/src/widgets/inspector/mod.rs | 5 ++- rmf_site_editor/src/widgets/mod.rs | 9 +++-- 4 files changed, 36 insertions(+), 22 deletions(-) diff --git a/rmf_site_editor/src/site/drawing_editor/mod.rs b/rmf_site_editor/src/site/drawing_editor/mod.rs index e19b1e29..3f38c116 100644 --- a/rmf_site_editor/src/site/drawing_editor/mod.rs +++ b/rmf_site_editor/src/site/drawing_editor/mod.rs @@ -28,6 +28,12 @@ use crate::{AppState, VisibilityEvents}; use std::collections::HashSet; +#[derive(Clone, Copy)] +pub struct BeginEditDrawing(pub Entity); + +#[derive(Clone, Copy)] +pub struct FinishEditDrawing; + #[derive(Default)] pub struct DrawingEditorPlugin; @@ -166,7 +172,9 @@ fn make_drawing_default_selected( impl Plugin for DrawingEditorPlugin { fn build(&self, app: &mut App) { - app.add_event::() + app + .add_event::() + .add_event::() .add_system_set( SystemSet::on_enter(AppState::SiteDrawingEditor) .with_system(hide_level_entities) diff --git a/rmf_site_editor/src/widgets/create.rs b/rmf_site_editor/src/widgets/create.rs index 68c9ad59..6a62c42a 100644 --- a/rmf_site_editor/src/widgets/create.rs +++ b/rmf_site_editor/src/widgets/create.rs @@ -91,18 +91,18 @@ impl<'a, 'w, 's> CreateWidget<'a, 'w, 's> { .default_open(false) .show(ui, |ui| { if let Some(new_asset_source) = InspectAssetSource::new( - &self.events.pending_drawings.source, - &self.events.pending_drawings.recall_source, + &self.events.display.pending_drawings.source, + &self.events.display.pending_drawings.recall_source, ).show(ui) { - self.events.pending_drawings.recall_source.remember( + self.events.display.pending_drawings.recall_source.remember( &new_asset_source ); - self.events.pending_drawings.source = new_asset_source; + self.events.display.pending_drawings.source = new_asset_source; } ui.add_space(5.0); if ui.button("Add Drawing").clicked() { let drawing = Drawing { - source: self.events.pending_drawings.source.clone(), + source: self.events.display.pending_drawings.source.clone(), ..default() }; self.events.commands.spawn(DrawingBundle::new(&drawing)); @@ -137,17 +137,17 @@ impl<'a, 'w, 's> CreateWidget<'a, 'w, 's> { .default_open(false) .show(ui, |ui| { if let Some(new_asset_source) = InspectAssetSource::new( - &self.events.pending_model.source, - &self.events.pending_model.recall_source, + &self.events.display.pending_model.source, + &self.events.display.pending_model.recall_source, ).show(ui) { - self.events.pending_model.recall_source.remember(&new_asset_source); - self.events.pending_model.source = new_asset_source; + self.events.display.pending_model.recall_source.remember(&new_asset_source); + self.events.display.pending_model.source = new_asset_source; } ui.add_space(5.0); if let Some(new_scale) = InspectScale::new( - &self.events.pending_model.scale, + &self.events.display.pending_model.scale, ).show(ui) { - self.events.pending_model.scale = new_scale; + self.events.display.pending_model.scale = new_scale; } ui.add_space(5.0); match self.events.app_state.current() { @@ -157,8 +157,8 @@ impl<'a, 'w, 's> CreateWidget<'a, 'w, 's> { AppState::SiteEditor => { if ui.button("Spawn model").clicked() { let model = Model { - source: self.events.pending_model.source.clone(), - scale: self.events.pending_model.scale, + source: self.events.display.pending_model.source.clone(), + scale: self.events.display.pending_model.scale, ..default() }; self.events.request.change_mode.send(ChangeMode::To( @@ -172,8 +172,8 @@ impl<'a, 'w, 's> CreateWidget<'a, 'w, 's> { if ui.button("Spawn visual").clicked() { let workcell_model = WorkcellModel { geometry: Geometry::Mesh { - filename: (&self.events.pending_model.source).into(), - scale: Some(*self.events.pending_model.scale), + filename: (&self.events.display.pending_model.source).into(), + scale: Some(*self.events.display.pending_model.scale), }, ..default() }; @@ -186,8 +186,8 @@ impl<'a, 'w, 's> CreateWidget<'a, 'w, 's> { if ui.button("Spawn collision").clicked() { let workcell_model = WorkcellModel { geometry: Geometry::Mesh { - filename: (&self.events.pending_model.source).into(), - scale: Some(*self.events.pending_model.scale), + filename: (&self.events.display.pending_model.source).into(), + scale: Some(*self.events.display.pending_model.scale), }, ..default() }; diff --git a/rmf_site_editor/src/widgets/inspector/mod.rs b/rmf_site_editor/src/widgets/inspector/mod.rs index 79324920..0d5f1ff1 100644 --- a/rmf_site_editor/src/widgets/inspector/mod.rs +++ b/rmf_site_editor/src/widgets/inspector/mod.rs @@ -92,6 +92,7 @@ use crate::{ site::{ Category, Change, DrawingMarker, DrawingSemiTransparency, EdgeLabels, FloorSemiTransparency, LayerVisibility, Original, ScaleDrawing, SiteID, + BeginEditDrawing, }, widgets::AppEvents, AppState, @@ -442,7 +443,9 @@ impl<'a, 'w1, 'w2, 's1, 's2> InspectorWidget<'a, 'w1, 'w2, 's1, 's2> { match self.events.app_state.current() { AppState::SiteEditor => { if ui.add(Button::new("Drawing editor")).clicked() { - self.events.app_state.set(AppState::SiteDrawingEditor).ok(); + self.events.layers.begin_edit_drawing.send( + BeginEditDrawing(selection) + ); } } AppState::SiteDrawingEditor => { diff --git a/rmf_site_editor/src/widgets/mod.rs b/rmf_site_editor/src/widgets/mod.rs index e359a27f..4da0d44b 100644 --- a/rmf_site_editor/src/widgets/mod.rs +++ b/rmf_site_editor/src/widgets/mod.rs @@ -28,6 +28,7 @@ use crate::{ ConsiderLocationTag, CurrentLevel, Delete, DrawingMarker, ExportLights, GlobalDrawingVisibility, GlobalFloorVisibility, LayerVisibility, PhysicalLightToggle, SaveNavGraphs, ScaleDrawing, SiteState, ToggleLiftDoorAvailability, + BeginEditDrawing, FinishEditDrawing, }, AppState, CreateNewWorkspace, CurrentWorkspace, LoadWorkspace, SaveWorkspace, }; @@ -169,6 +170,8 @@ pub struct PanelResources<'w, 's> { pub light: ResMut<'w, LightDisplay>, pub occupancy: ResMut<'w, OccupancyDisplay>, pub log_history: ResMut<'w, LogHistory>, + pub pending_model: ResMut<'w, PendingModel>, + pub pending_drawings: ResMut<'w, PendingDrawing>, _ignore: Query<'w, 's, ()>, } @@ -200,6 +203,8 @@ pub struct LayerEvents<'w, 's> { pub change_layer_vis: EventWriter<'w, 's, Change>, pub global_floor_vis: ResMut<'w, GlobalFloorVisibility>, pub global_drawing_vis: ResMut<'w, GlobalDrawingVisibility>, + pub begin_edit_drawing: EventWriter<'w, 's, BeginEditDrawing>, + pub finish_edit_drawing: EventWriter<'w, 's, FinishEditDrawing>, } #[derive(SystemParam)] @@ -254,8 +259,6 @@ pub struct AppEvents<'w, 's> { pub layers: LayerEvents<'w, 's>, pub app_state: ResMut<'w, State>, pub visibility_parameters: VisibilityParameters<'w, 's>, - pub pending_model: ResMut<'w, PendingModel>, - pub pending_drawings: ResMut<'w, PendingDrawing>, // TODO(luca) put this into change once the 16 size limit is lifted in bevy 0.10 pub distance: EventWriter<'w, 's, Change>, pub scale_drawing: EventWriter<'w, 's, ScaleDrawing>, @@ -458,7 +461,7 @@ fn site_visualizer_ui_layout( )); } if ui.add(Button::new("Return to site editor")).clicked() { - events.app_state.set(AppState::SiteEditor).ok(); + events.layers.begin_edit_drawing.send(FinishEditDrawing); } }); }); From 224201152113ade0d350b0e0434178a6230d0ffa Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Thu, 27 Jul 2023 16:01:29 +0800 Subject: [PATCH 04/34] Bug: ComputedVisibility is turning out false for drawing while it is being edited Signed-off-by: Michael X. Grey --- .../src/site/drawing_editor/mod.rs | 245 ++++++++++++------ rmf_site_editor/src/site/load.rs | 5 +- rmf_site_editor/src/site/save.rs | 28 +- rmf_site_editor/src/widgets/mod.rs | 4 +- rmf_site_editor/src/workcell/load.rs | 14 +- rmf_site_editor/src/workspace.rs | 6 + 6 files changed, 209 insertions(+), 93 deletions(-) diff --git a/rmf_site_editor/src/site/drawing_editor/mod.rs b/rmf_site_editor/src/site/drawing_editor/mod.rs index 3f38c116..ea282d39 100644 --- a/rmf_site_editor/src/site/drawing_editor/mod.rs +++ b/rmf_site_editor/src/site/drawing_editor/mod.rs @@ -15,24 +15,46 @@ * */ -use bevy::prelude::*; +use bevy::{prelude::*, render::view::visibility::RenderLayers}; pub mod optimizer; pub use optimizer::*; -use crate::interaction::{CameraControls, HeadlightToggle, Selection}; -use crate::site::{ - Anchor, DrawingMarker, Edge, FiducialMarker, MeasurementMarker, Pending, PixelsPerMeter, Point, +use crate::{ + interaction::{CameraControls, HeadlightToggle, Selection}, + site::{ + Anchor, DrawingMarker, Edge, FiducialMarker, MeasurementMarker, Pending, + PixelsPerMeter, Point, PreventDeletion, SiteProperties, WorkcellProperties, + }, + WorkspaceMarker, CurrentWorkspace, }; -use crate::{AppState, VisibilityEvents}; +use crate::AppState; use std::collections::HashSet; #[derive(Clone, Copy)] pub struct BeginEditDrawing(pub Entity); +/// Command to finish editing a drawing. Use None to command any drawing to finish. #[derive(Clone, Copy)] -pub struct FinishEditDrawing; +pub struct FinishEditDrawing(pub Option); + +#[derive(Clone, Copy)] +pub struct EditDrawing { + /// What drawing is being edited + pub drawing: Entity, + /// What is the original parent level for the drawing + pub level: Entity, +} + +#[derive(Clone, Copy, Default, Resource, Deref)] +pub struct CurrentEditDrawing(Option); + +impl CurrentEditDrawing { + pub fn get(&self) -> &Option { + &self.0 + } +} #[derive(Default)] pub struct DrawingEditorPlugin; @@ -50,81 +72,147 @@ pub struct AlignLevelDrawings(pub Entity); #[derive(Deref, DerefMut)] pub struct AlignSiteDrawings(pub Entity); -fn hide_level_entities( - mut visibilities: Query<&mut Visibility>, - mut camera_controls: ResMut, - mut cameras: Query<&mut Camera>, - headlight_toggle: Res, - mut visibility_events: VisibilityEvents, +fn switch_edit_drawing_mode( + mut commands: Commands, + mut begin: EventReader, + mut finish: EventReader, + mut current: ResMut, + mut workspace_visibility: Query<&mut Visibility, With>, + mut app_state: ResMut>, + current_workspace: Res, + parent: Query<&Parent, With>, + is_site: Query<(), With>, + is_workcell: Query<(), With>, + global_tf: Query<&GlobalTransform>, + vis: Query<(&Visibility, &ComputedVisibility, Option<&RenderLayers>), Without>, ) { - camera_controls.use_orthographic(true, &mut cameras, &mut visibilities, headlight_toggle.0); - visibility_events.constraints.send(false.into()); - visibility_events.doors.send(false.into()); - visibility_events.lanes.send(false.into()); - visibility_events.lift_cabins.send(false.into()); - visibility_events.lift_cabin_doors.send(false.into()); - visibility_events.locations.send(false.into()); - visibility_events.floors.send(false.into()); - visibility_events.models.send(false.into()); - visibility_events.walls.send(false.into()); -} + if let CurrentEditDrawing(Some(e)) = *current { + if let Ok((v, cv, r)) = vis.get(e.drawing) { + println!("Visibility of drawing: {} -> {}", v.is_visible, cv.is_visible_in_view()); + println!("Render layers of drawing: {r:?}"); + } else { + println!("No visibility information for drawing"); + } -fn hide_non_drawing_entities( - mut anchors: Query<(Entity, &mut Visibility), (With, Without)>, - parents: Query<&Parent>, - mut drawings: Query<(Entity, &mut Visibility), (Without, With)>, - mut anchor_set: ResMut, - selection: Res, -) { - for (e, mut vis) in &mut anchors { - if let Ok(parent) = parents.get(e) { - if drawings.get(**parent).is_err() { - if vis.is_visible { - vis.is_visible = false; - anchor_set.insert(e); - } - } + if let Ok(tf) = global_tf.get(e.drawing) { + println!("Global tf of drawing: {tf:?}"); } } - for (e, mut vis) in &mut drawings { - if **selection != Some(e) { - if vis.is_visible { - vis.is_visible = false; - anchor_set.insert(e); + + // TODO(@mxgrey): We can make this implementation much cleaner after we + // update to the latest version of bevy that distinguishes between inherited + // vs independent visibility. + // + // We should also consider using an edit mode stack instead of simply + // CurrentWorkspace and AppState. + 'handle_begin: { + if let Some(BeginEditDrawing(e)) = begin.iter().last() { + dbg!(); + if current.get().is_some_and(|c| c.drawing == *e) { + dbg!(); + break 'handle_begin; + } + + if let Some(c) = current.get() { + dbg!(); + // A drawing was being edited and now we're switching to a + // different drawing, so we need to reset the previous drawing. + commands.entity(c.drawing) + .set_parent(c.level) + .remove::(); + } + + let level = if let Ok(p) = parent.get(*e) { + p.get() + } else { + error!("Cannot edit {e:?} as a drawing"); + *current = CurrentEditDrawing(None); + break 'handle_begin; + }; + + if let Ok(tf) = global_tf.get(level) { + println!("Level global transform: {tf:?}"); + } else { + println!("Could not find global transform of level"); + } + + if let Ok(tf) = global_tf.get(*e) { + println!("Drawing global transform: {tf:?}"); + } + + if let Ok((v, cv, r)) = vis.get(*e) { + println!("Visibility of drawing: {} -> {}", v.is_visible, cv.is_visible_in_view()); + println!("Drawing render layers: {r:?}"); + } + + dbg!(); + *current = CurrentEditDrawing(Some(EditDrawing { drawing: *e, level })); + commands.entity(*e) + .remove_parent() + .insert(Visibility { is_visible: true }) + .insert(PreventDeletion::because( + "Cannot delete a drawing that is currently being edited" + .to_owned() + )); + if let Some(err) = app_state.set(AppState::SiteDrawingEditor).err() { + error!("Unable to switch to drawing editor mode: {err:?}"); + } + + dbg!(); + for mut v in &mut workspace_visibility { + v.is_visible = false; } } } -} -fn restore_non_drawing_entities( - mut visibilities: Query<&mut Visibility>, - mut anchor_set: ResMut, -) { - for e in anchor_set.drain() { - visibilities - .get_mut(e) - .map(|mut vis| vis.is_visible = true) - .ok(); - } -} + for FinishEditDrawing(finish) in finish.iter() { + dbg!(); + let c = if let Some(c) = current.get() { + if finish.is_some_and(|e| e != c.drawing) { + dbg!(); + continue; + } + c + } else { + dbg!(); + continue; + }; -fn restore_level_entities( - mut visibilities: Query<&mut Visibility>, - mut camera_controls: ResMut, - mut cameras: Query<&mut Camera>, - headlight_toggle: Res, - mut visibility_events: VisibilityEvents, -) { - camera_controls.use_perspective(true, &mut cameras, &mut visibilities, headlight_toggle.0); - visibility_events.constraints.send(true.into()); - visibility_events.doors.send(true.into()); - visibility_events.lanes.send(true.into()); - visibility_events.lift_cabins.send(true.into()); - visibility_events.lift_cabin_doors.send(true.into()); - visibility_events.locations.send(true.into()); - visibility_events.floors.send(true.into()); - visibility_events.models.send(true.into()); - visibility_events.walls.send(true.into()); + commands.entity(c.drawing) + .set_parent(c.level) + .remove::(); + *current = CurrentEditDrawing(None); + + dbg!(¤t_workspace); + if let Some(w) = current_workspace.root { + if let Ok(mut v) = workspace_visibility.get_mut(w) { + v.is_visible = current_workspace.display; + } + + dbg!(); + if is_site.contains(w) { + dbg!(); + if let Some(err) = app_state.set(AppState::SiteEditor).err() { + error!("Failed to switch back to site editing mode: {err:?}"); + } + } else if is_workcell.contains(w) { + dbg!(); + if let Some(err) = app_state.set(AppState::WorkcellEditor).err() { + error!("Failed to switch back to workcell editing mode: {err:?}"); + } + } else { + dbg!(); + // This logic can probably be improved with an editor mode stack + error!( + "Unable to identify the type for the current workspace \ + {w:?}, so we will default to site editing mode", + ); + if let Some(err) = app_state.set(AppState::SiteEditor).err() { + error!("Failed to switch back to site editing mode: {err:?}"); + } + } + } + } } fn assign_drawing_parent_to_new_measurements_and_fiducials( @@ -175,16 +263,9 @@ impl Plugin for DrawingEditorPlugin { app .add_event::() .add_event::() - .add_system_set( - SystemSet::on_enter(AppState::SiteDrawingEditor) - .with_system(hide_level_entities) - .with_system(hide_non_drawing_entities), - ) - .add_system_set( - SystemSet::on_exit(AppState::SiteDrawingEditor) - .with_system(restore_level_entities) - .with_system(restore_non_drawing_entities), - ) + .add_event::() + .init_resource::() + .add_system(switch_edit_drawing_mode) .add_system_set( SystemSet::on_update(AppState::SiteDrawingEditor) .with_system(assign_drawing_parent_to_new_measurements_and_fiducials) diff --git a/rmf_site_editor/src/site/load.rs b/rmf_site_editor/src/site/load.rs index 57090cf9..a1984963 100644 --- a/rmf_site_editor/src/site/load.rs +++ b/rmf_site_editor/src/site/load.rs @@ -15,7 +15,9 @@ * */ -use crate::{recency::RecencyRanking, site::*, Autoload, CurrentWorkspace}; +use crate::{ + recency::RecencyRanking, site::*, Autoload, CurrentWorkspace, WorkspaceMarker, +}; use bevy::{ecs::system::SystemParam, prelude::*, tasks::AsyncComputeTaskPool}; use futures_lite::future; use rmf_site_format::legacy::building_map::BuildingMap; @@ -52,6 +54,7 @@ fn generate_site_entities(commands: &mut Commands, site_data: &rmf_site_format:: site_cmd .insert(Category::Site) .insert(site_data.properties.clone()) + .insert(WorkspaceMarker) .with_children(|site| { for (anchor_id, anchor) in &site_data.anchors { let anchor_entity = site diff --git a/rmf_site_editor/src/site/save.rs b/rmf_site_editor/src/site/save.rs index f90aa874..53863b15 100644 --- a/rmf_site_editor/src/site/save.rs +++ b/rmf_site_editor/src/site/save.rs @@ -58,6 +58,25 @@ pub enum SiteGenerationError { InvalidLiftDoorReference { door: Entity, anchor: Entity }, } +/// This is used when a drawing is being edited to fix its parenting before we +/// attempt to save the site. +// TODO(@mxgrey): Remove this when we no longer need to de-parent drawings while +// editing them. +fn assemble_edited_drawing(world: &mut World) { + let Some(c) = world.get_resource::().copied() else { return }; + let Some(c) = c.get() else { return }; + let Some(mut level) = world.get_entity_mut(c.level) else { return }; + level.push_children(&[c.drawing]); +} + +/// Revert the drawing back to the root so it can continue to be edited. +fn disassemble_edited_drawing(world: &mut World) { + let Some(c) = world.get_resource::().copied() else { return }; + let Some(c) = c.get() else { return }; + let Some(mut level) = world.get_entity_mut(c.level) else { return }; + level.remove_children(&[c.drawing]); +} + /// Look through all the elements that we will be saving and assign a SiteID /// component to any elements that do not have one already. fn assign_site_ids(world: &mut World, site: Entity) -> Result<(), SiteGenerationError> { @@ -901,6 +920,8 @@ pub fn generate_site( world: &mut World, site: Entity, ) -> Result { + assemble_edited_drawing(world); + assign_site_ids(world, site)?; let anchors = collect_site_anchors(world, site); let levels = generate_levels(world, site)?; @@ -910,17 +931,18 @@ pub fn generate_site( let locations = generate_locations(world, site)?; let graph_ranking = generate_graph_rankings(world, site)?; - let props = match world.get::(site) { - Some(props) => props, + let properties = match world.get::(site) { + Some(props) => props.clone(), None => { return Err(SiteGenerationError::InvalidSiteEntity(site)); } }; + disassemble_edited_drawing(world); return Ok(Site { format_version: rmf_site_format::SemVer::default(), anchors, - properties: props.clone(), + properties, levels, lifts, navigation: Navigation { diff --git a/rmf_site_editor/src/widgets/mod.rs b/rmf_site_editor/src/widgets/mod.rs index 4da0d44b..19733c9a 100644 --- a/rmf_site_editor/src/widgets/mod.rs +++ b/rmf_site_editor/src/widgets/mod.rs @@ -395,7 +395,7 @@ fn site_drawing_ui_layout( }); ui.separator(); if ui.add(Button::new("Return to site editor")).clicked() { - events.app_state.set(AppState::SiteEditor).ok(); + events.layers.finish_edit_drawing.send(FinishEditDrawing(None)); } }); }); @@ -461,7 +461,7 @@ fn site_visualizer_ui_layout( )); } if ui.add(Button::new("Return to site editor")).clicked() { - events.layers.begin_edit_drawing.send(FinishEditDrawing); + events.app_state.set(AppState::SiteEditor); } }); }); diff --git a/rmf_site_editor/src/workcell/load.rs b/rmf_site_editor/src/workcell/load.rs index abc40a34..87ad64f9 100644 --- a/rmf_site_editor/src/workcell/load.rs +++ b/rmf_site_editor/src/workcell/load.rs @@ -18,19 +18,22 @@ use std::collections::HashMap; use std::path::PathBuf; -use crate::site::{AnchorBundle, DefaultFile, Dependents, PreventDeletion, SiteState}; -use crate::workcell::ChangeCurrentWorkcell; +use crate::{ + site::{AnchorBundle, DefaultFile, Dependents, PreventDeletion, SiteState}, + workcell::ChangeCurrentWorkcell, + WorkspaceMarker, +}; use bevy::prelude::*; use std::collections::HashSet; use rmf_site_format::{ Category, ConstraintDependents, MeshConstraint, NameInWorkcell, SiteID, - WorkcellCollisionMarker, WorkcellVisualMarker, + WorkcellCollisionMarker, WorkcellVisualMarker, Workcell, }; pub struct LoadWorkcell { /// The site data to load - pub workcell: rmf_site_format::Workcell, + pub workcell: Workcell, /// Should the application switch focus to this new site pub focus: bool, /// Set if the workcell was loaded from a file @@ -39,7 +42,7 @@ pub struct LoadWorkcell { fn generate_workcell_entities( commands: &mut Commands, - workcell: &rmf_site_format::Workcell, + workcell: &Workcell, ) -> Entity { // Create hashmap of ids to entity to correctly generate hierarchy let mut id_to_entity = HashMap::new(); @@ -54,6 +57,7 @@ fn generate_workcell_entities( .insert(NameInWorkcell(workcell.properties.name.clone())) .insert(SiteID(workcell.id)) .insert(Category::Workcell) + .insert(WorkspaceMarker) .insert(PreventDeletion::because( "Workcell root cannot be deleted".to_string(), )) diff --git a/rmf_site_editor/src/workspace.rs b/rmf_site_editor/src/workspace.rs index a18c7151..9f308dbb 100644 --- a/rmf_site_editor/src/workspace.rs +++ b/rmf_site_editor/src/workspace.rs @@ -40,6 +40,10 @@ pub struct ChangeCurrentWorkspace { /// what app mode the editor is currently in pub struct CreateNewWorkspace; +/// Apply this component to all workspace types +#[derive(Component)] +pub struct WorkspaceMarker; + /// Used as an event to command that a workspace should be loaded. This will spawn a file open /// dialog (in non-wasm) with allowed extensions depending on the app state // TODO(luca) Encapsulate a list of optional filters, for example to allow users to only load @@ -75,6 +79,8 @@ impl WorkspaceData { } /// Used as a resource that keeps track of the current workspace +// TODO(@mxgrey): Consider a workspace stack, e.g. so users can temporarily edit +// a workcell inside of a site and then revert back into the site. #[derive(Clone, Copy, Debug, Default, Resource)] pub struct CurrentWorkspace { pub root: Option, From 02da9a41f20938b89254eed822a0829e7c8c79c1 Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Thu, 27 Jul 2023 18:12:22 +0800 Subject: [PATCH 05/34] Fix the switch in and out of drawing editor Signed-off-by: Michael X. Grey --- .../src/interaction/camera_controls.rs | 36 +++++++ rmf_site_editor/src/keyboard.rs | 11 +-- .../src/site/drawing_editor/mod.rs | 97 ++++++++----------- rmf_site_editor/src/site/save.rs | 4 +- 4 files changed, 84 insertions(+), 64 deletions(-) diff --git a/rmf_site_editor/src/interaction/camera_controls.rs b/rmf_site_editor/src/interaction/camera_controls.rs index 0350c610..2f27ecdc 100644 --- a/rmf_site_editor/src/interaction/camera_controls.rs +++ b/rmf_site_editor/src/interaction/camera_controls.rs @@ -78,6 +78,18 @@ impl ProjectionMode { } } +pub struct ChangeProjectionMode(pub ProjectionMode); + +impl ChangeProjectionMode { + pub fn to_perspective() -> ChangeProjectionMode { + ChangeProjectionMode(ProjectionMode::Perspective) + } + + pub fn to_orthographic() -> ChangeProjectionMode { + ChangeProjectionMode(ProjectionMode::Orthographic) + } +} + #[derive(Debug, Clone, Reflect, Resource)] pub struct CameraControls { mode: ProjectionMode, @@ -152,6 +164,23 @@ impl CameraControls { self.use_perspective(!choice, cameras, visibilities, headlights_on); } + pub fn use_mode( + &mut self, + mode: ProjectionMode, + cameras: &mut Query<&mut Camera>, + visibilities: &mut Query<&mut Visibility>, + headlights_on: bool, + ) { + match mode { + ProjectionMode::Perspective => { + self.use_perspective(true, cameras, visibilities, headlights_on); + } + ProjectionMode::Orthographic => { + self.use_orthographic(true, cameras, visibilities, headlights_on); + } + } + } + pub fn mode(&self) -> ProjectionMode { self.mode } @@ -329,10 +358,16 @@ fn camera_controls( mut previous_mouse_location: ResMut, mut controls: ResMut, mut cameras: Query<(&mut Projection, &mut Transform)>, + mut bevy_cameras: Query<&mut Camera>, mut visibility: Query<&mut Visibility>, headlight_toggle: Res, picking_blockers: Res, + mut change_mode: EventReader, ) { + if let Some(mode) = change_mode.iter().last() { + controls.use_mode(mode.0, &mut bevy_cameras, &mut visibility, headlight_toggle.0); + } + if headlight_toggle.is_changed() { controls.toggle_lights(headlight_toggle.0, &mut visibility); } @@ -488,6 +523,7 @@ impl Plugin for CameraControlsPlugin { app.insert_resource(MouseLocation::default()) .init_resource::() .init_resource::() + .add_event::() .add_system(camera_controls); } } diff --git a/rmf_site_editor/src/keyboard.rs b/rmf_site_editor/src/keyboard.rs index d9a948e1..d7e5a331 100644 --- a/rmf_site_editor/src/keyboard.rs +++ b/rmf_site_editor/src/keyboard.rs @@ -18,7 +18,7 @@ use crate::{ interaction::{ camera_controls::{CameraControls, HeadlightToggle}, - ChangeMode, InteractionMode, Selection, + ChangeMode, InteractionMode, Selection, ChangeProjectionMode, }, site::{AlignLevelDrawings, AlignSiteDrawings, CurrentLevel, Delete}, CreateNewWorkspace, CurrentWorkspace, LoadWorkspace, SaveWorkspace, @@ -56,17 +56,14 @@ fn handle_keyboard_input( keyboard_input: Res>, selection: Res, current_mode: Res, - mut camera_controls: ResMut, - mut cameras: Query<&mut Camera>, - mut visibilities: Query<&mut Visibility>, mut egui_context: ResMut, mut change_mode: EventWriter, mut delete: EventWriter, mut save_workspace: EventWriter, mut new_workspace: EventWriter, mut load_workspace: EventWriter, + mut change_camera_mode: EventWriter, current_level: Res, - headlight_toggle: Res, mut debug_mode: ResMut, mut params: KeyboardParams, ) { @@ -80,11 +77,11 @@ fn handle_keyboard_input( } if keyboard_input.just_pressed(KeyCode::F2) { - camera_controls.use_orthographic(true, &mut cameras, &mut visibilities, headlight_toggle.0); + change_camera_mode.send(ChangeProjectionMode::to_perspective()); } if keyboard_input.just_pressed(KeyCode::F3) { - camera_controls.use_perspective(true, &mut cameras, &mut visibilities, headlight_toggle.0); + change_camera_mode.send(ChangeProjectionMode::to_orthographic()); } if keyboard_input.just_pressed(KeyCode::Escape) { diff --git a/rmf_site_editor/src/site/drawing_editor/mod.rs b/rmf_site_editor/src/site/drawing_editor/mod.rs index ea282d39..6dc0e98e 100644 --- a/rmf_site_editor/src/site/drawing_editor/mod.rs +++ b/rmf_site_editor/src/site/drawing_editor/mod.rs @@ -21,7 +21,7 @@ pub mod optimizer; pub use optimizer::*; use crate::{ - interaction::{CameraControls, HeadlightToggle, Selection}, + interaction::{CameraControls, HeadlightToggle, Selection, ChangeProjectionMode}, site::{ Anchor, DrawingMarker, Edge, FiducialMarker, MeasurementMarker, Pending, PixelsPerMeter, Point, PreventDeletion, SiteProperties, WorkcellProperties, @@ -47,12 +47,22 @@ pub struct EditDrawing { pub level: Entity, } -#[derive(Clone, Copy, Default, Resource, Deref)] -pub struct CurrentEditDrawing(Option); +#[derive(Clone, Copy, Resource)] +pub struct CurrentEditDrawing { + editor: Entity, + target: Option, +} + +impl FromWorld for CurrentEditDrawing { + fn from_world(world: &mut World) -> Self { + let editor = world.spawn(SpatialBundle::default()).id(); + Self { editor, target: None } + } +} impl CurrentEditDrawing { - pub fn get(&self) -> &Option { - &self.0 + pub fn target(&self) -> &Option { + &self.target } } @@ -79,26 +89,14 @@ fn switch_edit_drawing_mode( mut current: ResMut, mut workspace_visibility: Query<&mut Visibility, With>, mut app_state: ResMut>, + mut local_tf: Query<&mut Transform>, + mut change_camera_mode: EventWriter, + global_tf: Query<&GlobalTransform>, current_workspace: Res, parent: Query<&Parent, With>, is_site: Query<(), With>, is_workcell: Query<(), With>, - global_tf: Query<&GlobalTransform>, - vis: Query<(&Visibility, &ComputedVisibility, Option<&RenderLayers>), Without>, ) { - if let CurrentEditDrawing(Some(e)) = *current { - if let Ok((v, cv, r)) = vis.get(e.drawing) { - println!("Visibility of drawing: {} -> {}", v.is_visible, cv.is_visible_in_view()); - println!("Render layers of drawing: {r:?}"); - } else { - println!("No visibility information for drawing"); - } - - if let Ok(tf) = global_tf.get(e.drawing) { - println!("Global tf of drawing: {tf:?}"); - } - } - // TODO(@mxgrey): We can make this implementation much cleaner after we // update to the latest version of bevy that distinguishes between inherited // vs independent visibility. @@ -107,14 +105,11 @@ fn switch_edit_drawing_mode( // CurrentWorkspace and AppState. 'handle_begin: { if let Some(BeginEditDrawing(e)) = begin.iter().last() { - dbg!(); - if current.get().is_some_and(|c| c.drawing == *e) { - dbg!(); + if current.target().is_some_and(|c| c.drawing == *e) { break 'handle_begin; } - if let Some(c) = current.get() { - dbg!(); + if let Some(c) = current.target() { // A drawing was being edited and now we're switching to a // different drawing, so we need to reset the previous drawing. commands.entity(c.drawing) @@ -126,39 +121,36 @@ fn switch_edit_drawing_mode( p.get() } else { error!("Cannot edit {e:?} as a drawing"); - *current = CurrentEditDrawing(None); + current.target = None; break 'handle_begin; }; - if let Ok(tf) = global_tf.get(level) { - println!("Level global transform: {tf:?}"); - } else { - println!("Could not find global transform of level"); - } - - if let Ok(tf) = global_tf.get(*e) { - println!("Drawing global transform: {tf:?}"); - } - - if let Ok((v, cv, r)) = vis.get(*e) { - println!("Visibility of drawing: {} -> {}", v.is_visible, cv.is_visible_in_view()); - println!("Drawing render layers: {r:?}"); - } - - dbg!(); - *current = CurrentEditDrawing(Some(EditDrawing { drawing: *e, level })); + current.target = Some(EditDrawing { drawing: *e, level }); commands.entity(*e) - .remove_parent() + .set_parent(current.editor) .insert(Visibility { is_visible: true }) + .insert(ComputedVisibility::default()) .insert(PreventDeletion::because( "Cannot delete a drawing that is currently being edited" .to_owned() )); + + change_camera_mode.send(ChangeProjectionMode::to_orthographic()); + + if let Ok(mut editor_tf) = local_tf.get_mut(current.editor) { + if let Ok(mut level_tf) = global_tf.get(level) { + *editor_tf = level_tf.compute_transform(); + } else { + error!("Cannot get transform of current level"); + } + } else { + error!("Cannot change transform of drawing editor view"); + } + if let Some(err) = app_state.set(AppState::SiteDrawingEditor).err() { error!("Unable to switch to drawing editor mode: {err:?}"); } - dbg!(); for mut v in &mut workspace_visibility { v.is_visible = false; } @@ -166,42 +158,37 @@ fn switch_edit_drawing_mode( } for FinishEditDrawing(finish) in finish.iter() { - dbg!(); - let c = if let Some(c) = current.get() { + let c = if let Some(c) = current.target() { if finish.is_some_and(|e| e != c.drawing) { - dbg!(); continue; } c } else { - dbg!(); continue; }; commands.entity(c.drawing) .set_parent(c.level) .remove::(); - *current = CurrentEditDrawing(None); + current.target = None; + + // This camera change would not be needed if we have an edit mode stack + change_camera_mode.send(ChangeProjectionMode::to_perspective()); - dbg!(¤t_workspace); if let Some(w) = current_workspace.root { if let Ok(mut v) = workspace_visibility.get_mut(w) { v.is_visible = current_workspace.display; } - dbg!(); if is_site.contains(w) { - dbg!(); if let Some(err) = app_state.set(AppState::SiteEditor).err() { error!("Failed to switch back to site editing mode: {err:?}"); } } else if is_workcell.contains(w) { - dbg!(); if let Some(err) = app_state.set(AppState::WorkcellEditor).err() { error!("Failed to switch back to workcell editing mode: {err:?}"); } } else { - dbg!(); // This logic can probably be improved with an editor mode stack error!( "Unable to identify the type for the current workspace \ diff --git a/rmf_site_editor/src/site/save.rs b/rmf_site_editor/src/site/save.rs index 53863b15..1bb4763c 100644 --- a/rmf_site_editor/src/site/save.rs +++ b/rmf_site_editor/src/site/save.rs @@ -64,7 +64,7 @@ pub enum SiteGenerationError { // editing them. fn assemble_edited_drawing(world: &mut World) { let Some(c) = world.get_resource::().copied() else { return }; - let Some(c) = c.get() else { return }; + let Some(c) = c.target() else { return }; let Some(mut level) = world.get_entity_mut(c.level) else { return }; level.push_children(&[c.drawing]); } @@ -72,7 +72,7 @@ fn assemble_edited_drawing(world: &mut World) { /// Revert the drawing back to the root so it can continue to be edited. fn disassemble_edited_drawing(world: &mut World) { let Some(c) = world.get_resource::().copied() else { return }; - let Some(c) = c.get() else { return }; + let Some(c) = c.target() else { return }; let Some(mut level) = world.get_entity_mut(c.level) else { return }; level.remove_children(&[c.drawing]); } From 593650882f997dcb759e920b88c1a1541476b80e Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Thu, 27 Jul 2023 22:42:17 +0800 Subject: [PATCH 06/34] Tweak edit drawing buttons Signed-off-by: Michael X. Grey --- .../src/widgets/inspector/inspect_layer.rs | 11 +++- rmf_site_editor/src/widgets/inspector/mod.rs | 60 +++++++++---------- rmf_site_editor/src/widgets/mod.rs | 3 +- 3 files changed, 41 insertions(+), 33 deletions(-) diff --git a/rmf_site_editor/src/widgets/inspector/inspect_layer.rs b/rmf_site_editor/src/widgets/inspector/inspect_layer.rs index cba4d3ea..44a4d687 100644 --- a/rmf_site_editor/src/widgets/inspector/inspect_layer.rs +++ b/rmf_site_editor/src/widgets/inspector/inspect_layer.rs @@ -18,7 +18,7 @@ use crate::{ interaction::Hover, recency::ChangeRank, - site::{Change, LayerVisibility, SiteID, VisibilityCycle}, + site::{Change, LayerVisibility, SiteID, VisibilityCycle, BeginEditDrawing}, widgets::{inspector::SelectionWidget, AppEvents, Icons, MoveLayer}, }; use bevy::prelude::*; @@ -111,6 +111,15 @@ impl<'a, 'w, 's> InspectLayer<'a, 'w, 's> { if let Some(site_id) = self.site_id { SelectionWidget::new(self.entity, site_id, self.icons, self.events).show(ui); + if !self.is_floor { + if ui.add( + ImageButton::new(self.events.layers.icons.edit.egui(), [18., 18.]) + ).on_hover_text("Edit Drawing").clicked() { + self.events.layers.begin_edit_drawing.send( + BeginEditDrawing(self.entity) + ) + } + } } } diff --git a/rmf_site_editor/src/widgets/inspector/mod.rs b/rmf_site_editor/src/widgets/inspector/mod.rs index 0d5f1ff1..1d02f67a 100644 --- a/rmf_site_editor/src/widgets/inspector/mod.rs +++ b/rmf_site_editor/src/widgets/inspector/mod.rs @@ -98,7 +98,7 @@ use crate::{ AppState, }; use bevy::{ecs::system::SystemParam, prelude::*}; -use bevy_egui::egui::{Button, RichText, Ui}; +use bevy_egui::egui::{Button, ImageButton, RichText, Ui}; use rmf_site_format::*; // Bevy seems to have a limit of 16 fields in a SystemParam struct, so we split @@ -258,6 +258,34 @@ impl<'a, 'w1, 'w2, 's1, 's2> InspectorWidget<'a, 'w1, 'w2, 's1, 's2> { }); } + if let Ok(ppm) = self.params.component.pixels_per_meter.get(selection) { + if *self.events.app_state.current() == AppState::SiteEditor { + ui.add_space(10.0); + if ui.add( + Button::image_and_text( + self.events.layers.icons.edit.egui(), [18., 18.], + "Edit Drawing", + ) + ).clicked() { + self.events.layers.begin_edit_drawing.send( + BeginEditDrawing(selection) + ); + } + } + ui.add_space(10.0); + if let Some(new_ppm) = + InspectValue::::new(String::from("Pixels per meter"), ppm.0) + .clamp_range(0.0001..=std::f32::INFINITY) + .tooltip("How many image pixels per meter".to_string()) + .show(ui) + { + self.events + .change + .pixels_per_meter + .send(Change::new(PixelsPerMeter(new_ppm), selection)); + } + } + if let Ok((edge, original, labels, category)) = self.params.component.edges.get(selection) { @@ -427,36 +455,6 @@ impl<'a, 'w1, 'w2, 's1, 's2> InspectorWidget<'a, 'w1, 'w2, 's1, 's2> { ui.add_space(10.0); } - if let Ok(ppm) = self.params.component.pixels_per_meter.get(selection) { - if let Some(new_ppm) = - InspectValue::::new(String::from("Pixels per meter"), ppm.0) - .clamp_range(0.0001..=std::f32::INFINITY) - .tooltip("How many image pixels per meter".to_string()) - .show(ui) - { - self.events - .change - .pixels_per_meter - .send(Change::new(PixelsPerMeter(new_ppm), selection)); - } - ui.add_space(10.0); - match self.events.app_state.current() { - AppState::SiteEditor => { - if ui.add(Button::new("Drawing editor")).clicked() { - self.events.layers.begin_edit_drawing.send( - BeginEditDrawing(selection) - ); - } - } - AppState::SiteDrawingEditor => { - if ui.add(Button::new("Scale drawing")).clicked() { - self.events.scale_drawing.send(ScaleDrawing(selection)); - } - } - _ => {} - } - } - if let Ok(camera_properties) = self .params .component diff --git a/rmf_site_editor/src/widgets/mod.rs b/rmf_site_editor/src/widgets/mod.rs index 19733c9a..10aeb6fe 100644 --- a/rmf_site_editor/src/widgets/mod.rs +++ b/rmf_site_editor/src/widgets/mod.rs @@ -205,6 +205,7 @@ pub struct LayerEvents<'w, 's> { pub global_drawing_vis: ResMut<'w, GlobalDrawingVisibility>, pub begin_edit_drawing: EventWriter<'w, 's, BeginEditDrawing>, pub finish_edit_drawing: EventWriter<'w, 's, FinishEditDrawing>, + pub icons: Res<'w, Icons>, } #[derive(SystemParam)] @@ -461,7 +462,7 @@ fn site_visualizer_ui_layout( )); } if ui.add(Button::new("Return to site editor")).clicked() { - events.app_state.set(AppState::SiteEditor); + events.app_state.set(AppState::SiteEditor).ok(); } }); }); From ab03637659dfe0ed3c6eb3fe72e9900d66b457fb Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Thu, 27 Jul 2023 22:58:29 +0800 Subject: [PATCH 07/34] Add an exit icon Signed-off-by: Michael X. Grey --- assets/textures/attribution.md | 2 +- assets/textures/exit.png | Bin 0 -> 6952 bytes rmf_site_editor/src/site_asset_io.rs | 4 ++++ rmf_site_editor/src/widgets/icons.rs | 3 +++ rmf_site_editor/src/widgets/mod.rs | 12 ++++++++++-- 5 files changed, 18 insertions(+), 3 deletions(-) create mode 100644 assets/textures/exit.png diff --git a/assets/textures/attribution.md b/assets/textures/attribution.md index 11eef4fd..d8624011 100644 --- a/assets/textures/attribution.md +++ b/assets/textures/attribution.md @@ -1,4 +1,4 @@ * [`select.png`](https://thenounproject.com/icon/select-3324735/) * [`edit.png`](https://thenounproject.com/icon/edit-2162449/) +* [`exit.png`](https://thenounproject.com/icon/exit-1826632/) * `trash.png`: @mxgrey - diff --git a/assets/textures/exit.png b/assets/textures/exit.png new file mode 100644 index 0000000000000000000000000000000000000000..bc6c6be1df3b32441fc3561ddc2bb0412277ecee GIT binary patch literal 6952 zcmZvARZtvE6YZiQKyY_=mmtA{JHg#u1B)*1?z-qA!6Ag;4#C|CusC6H2o@YJU)}${ z-Kpy7o>TMC)zf{Zt7E>X%6&j3K?MK+9~9)JHQsdae}aPiw)cyfj{^YMg}z#P9vbG} zRIb3UHug@|R30E#Ybt9Wdm8}2XSFNG(Th~*XZWinegh&PW*_)h#Ma9-OWYK`SX!ZR zb^Xj;21=jCgvY|mLxUsJ@N(V*eTsq*X>wD;QXLdCAz!3!5=>*C@ASV8JDe_UA_T2N z{muf?c_CsxPcWY@-%WSCMBt`>Pr-rorH7=ic)RX-$K754s3-olvG@`^a^>r58qQo0 zG&a21WxKN0FgsfmA?-g0RS|XBdm8FhHT#p7>0|vO8#ukM4Z??>aB(c#N1b*?R!@DZ zhaw3WyF+W;$y|O6Y-LT8by1p3`N{mO3yj8R?2}L4YM$1xR>bD)=fvK)Id^p1Z@)2e zY5f&ZZu!ky878>fIkB519?+F%cV0vdTzjU~sTucE37cn%eHmxM+4+YccY%0!@$evJ zkxj>?*l*O@XY-g}EO#5i&doUct9OKZE$zxbHyF$9bi^Vr87?uQ)o+{uMN(Xh!OI?1MFiuTHZ(QxZL`l=co_=IBV?PrF z6W1?IdgbKU&EV>tfmgPgYs3@Nnj<)=C-nd1v1?O!^`}8>h?ciAv59q)w+=N7T_?yD zK&Lz|i?3~{H|bV2sn1~JCnAozaBkOqX34U=tpWp@v}X%)vi6acU1#fA|#WS z0)q44&){n?bK(M{7#h%X>M1h?#Y;Cm=#S{JetIty0=N7A;Bj_YJ*<^SaXDaWDJvh> zbncUXz2jxT;7Y@}HOGY)BU%8v{X<`(bDSCfr7QX6xzs2IgH?zN7 z&tlV$QG%B^5rt|JuC?xtUK4rNVNMsZiy9m{9msGS`Hb*_1-O@}GLTM=nKY#tkfJG% zcTBE8o&fEG-ZrZ%$#8`>Lc?!)^~;|h43sjp>2)$#z2`>8DuIcg21SoAxg$>FCuHRR z*>xzv){gpWq-(o7BTYhh=|gPT#zrlE@ZV_f&!<0GQuN#{WkX2m1^)`5f3;QXcKVGr zUq`^Elz>iw`{is7NEGa+y|*fso=qc5Q2@H6 z0TT4bN6}E;fo_U?niMOBn?ik@af^a_8%g=(5=nD)s8L>A244v1l-6OYaPo)Fg1i4J zVTx-XVw#S56T)~C4$h4g%}nEf`4X7~FH`UnjLu%YJ&kzV6`f4shS;zp5562g*~qo! z`sn215?!lFp#?XVjS*m@7yV1hCa9ET9M`sb``m|wC>1@zq2h-aOE`%c)@%+IWa+!8 zcE$_`!clLSD@PYRDz0!pyZ|cT*o0juHMcc%;r&=RC5=`pg@7zw{hrV$#;~)nm>hsjc9e#HICWvMs&G za|XjzrY#vKmC30W7i#H7jW{d|;uvXccK;$~4tH<&H~!xoP| z(C4#bOHZgRhiE?oVCwXY%h(x*3zxiT|8!kjx>DkS4M$Q~1dI9-iyo&fRL)-4IWOwr zRua2v!d`8OA#ubh-Y|1dUr>O|LEMgJ%@OV+3zvpO`M*kU?RM}d4_<<~6WOo4O$Db| zVaJ6OetK=&Tn?_j_-D{6gCANCEqMe~w5~BV2i7EwG0-&hmh%4oWbqR@^FGsLPs#D` zh|EaWwC(CQ_z!aas>$yFTa`h=g*KXS^7Cq19WO#aTEK1g0K{CZ;%7s)9fW>-Sp7;w+3J*M_(V(Oik0p+8wq?1-$#=4?c``8!1)eAX+}FpRY4RfFq?AE zXQ)vZPBZUf1=Yc0YrzK@vV8VR%$A2Iw{UY5JkdTWjbQ`hVVu)alN$YY>WOpdftOg> zSWw>?%MWzLJ)*rM?m{IHI?xUKq=KDr12`c=DU_7NtvQ|_!%06QW7R~IAJW&+>`}gl zS5;SwiT=yV7;N12*;suk&TOVS#Cx%G*mUH$E-5=gC>%pn*OU8Brkzl_d|Hj_l|eCZ zbEhzSac8Ti$|4!JwAAIBRcW^V-1t%O=+e?<`(nMS=R(qvE2?KF5BCnGj6*KkPA*H> zHPeW4qxRzW3W$~Yhb!4*a#dRK3}|{BDaNSf6Or@5q=Zg!zBaY+O`pX-jf`SO+J_RE zNF62wfpM8q%P*B2z%4WIdzV5+-iv`8Q(@xR(8OIs>%Hvb_QW8|W;jY9nt+;p!BOb- zH?t(iBBm$0RJb64E$5hrQ|2>zgQ_#y)3HjW7)t$OnN%)}GJg7EZ#Cjsfe||0_-lXsETtbK4!*GH=#=zF;hscv$3x$R$#wsxe7@zgX+xKf9 zxg#aLuk-v_gbLvRv*UUM_S)G+-}A4kbXI>&nQE5ZhbTeRh3D%9bT%6MOUM-xsL?kI zBdrfI+FeLm1GFU#mtwm5T@yhI1E&pYR|<$YG&7Vm!6rA(-;p~NB)~x`_xGMs=3?G> zo200Km=7GQ{4{6m>8ro$neGT~)N@$JHc4~E?2-P~yrLAq1Vk1HeY_Ukk1775W05af z`FGrDHH4=7Gx}?-JtGTG9#g>1OXmGU_bChKpNt2GPeL_3cOxPV)meta!3eYe;MD2= zYCWuLw7tGYYO0Dei8ATtg=$g@I>3It~Q{r^( zn6&NS#|X{wafhUj%msp~P-o{-hOMf3Qv^iW1#y=uKH;|?M^7@8{Cf7`Xt}=jT(f}h zrl0#U?;0xkS5Rl9VMlhz%a*bB5JS_sP45P!S1MXz|9ZZ9M#ZfBpUB6oU->tzHp=Sn zR2r0a?ERYaf1~db_hZ@!&UczQDQyVz?o%bVm!=~N4({P%;L((-*_vYqmg*w1VG%)o z3ec=_)++b8eL8K7_nGSd9DuYq^^KwLDh@#y*AU>?it^24e0si))@=Pcr~T;Be#h># zA#5>Vr#sRM?m{rpOVr8ey75jWZ!6x1jRd0UU{<*+I|IYXz`8!qc?gbw98YJ62RJ6< zEhI0AnfqwS!@JC{$b=gfhHo6q4%QHm>c~SFg*A8m7KIu%p zv!KnID3{2hsm6w$k7AS?76-2_7IxowAA_c>UeudbpY>bR-XGtZ-; zod#w1v$6gilzNKw!rOj@x^c1B0n;K~m5;M80Z`oGk9j)HU+b$#@(Uv7s80R`TAdC@ z!B98upUTUbj1Ih%4JJsMpSD*T@#7dET~AcygmGDl1=m`JWf$0d>jWD>fq#_d^P*em zRJYbF+6z?#$JK3*lYpEcycNO_ehBR&S$Fw?Xz?S>-z13~Q`vt5Hvo-WgaQD_!VkJu zI6WPACgL1c>gOP{&&cHfGHIQ9hFdCz+}1%z$$Rk*zTOWePMnh`EJofE$h&;u$7gs* zz8UN=`1`T*7#X8HT8tyQ$j{{iEAWisvu(`bd^sx8^WAAbBz8EjE5LvSHBWoZxpGG= z$KOMdgcgO8Eyqyhx*fe&huXLVqt{r`1twAu4Q>fjUbY)c*e*voUOz0mV9C;Fl&A7k zrCgOvWkxr0&cOQ_xF>nLYJNy(P4;CTCi}IE^})4m5Q5+mIE6yZSP?BPTN{kAap+`Q zZe(U6pVM*CM!13ujYKSA4h0qJ+Uo=;yCHCb{)+ctjnB9bzmxt-QCvUohL%PYo6yxR zxx2b3F)KOQ8f4(Y=o5h?=%35WrlH4SoH;|k4b$-uI4v!dGoi#Wt3I&gNW8u<(`yG+ zbr>c`ZG@2c9TDT|Ba3w zi9pOObowIfFkA~$Ae5tNQv1Vk%vLl9!6btxY&!U{>eyShUU>!%bHdXUh@ASvLL6aN ziKc0Y?)InfrH0we80|KDRTOer=^gc@oNLg}M(Ri*nR-Q4?5T#oj_%O^>)h0VW2&3jKC1+d{Hu)fbCXW=y)zc~is z&#c9Vjdy=~?&%YdN_NIS@Ngr}4o8d`?SEp!-acq=;<*g3E<##&`GZ$=@5BfBo=Y-l zrDJ%wYj-ly+dW1yc+}OWThC8~cCN5V{Y?S#2(9?=JXfyZE#R_Nhc+WF!8z0U!QyQG z$*Z1M?d?rZNHJ0HvCR$!?6&)!mihKVN=|<6t_O@J{1z@Vj_<7~tS!w2K&xc$@( z9aK&ol@fekLv~cK>J8f_@BF{2dVl*|*!H}KO=OJiB^eJp6{%1PN3p00%a z^ga|pI41?Bb3+}c=KO3U@Yjp4XI<>c5cg2PNmbxkJO=wWmnpMU8~^|pZZ9SEML|mH z|IKRNCNy~gDWdZI5@ds>nx!<_?^vUSttwOrq~in~@MFJFFQC>6gN?+C6r@sjc9>cT z$e#3Sgj)rVkG5D)LMf@fbEw90XzaYEO2!dkCO%%AZS02j+7#r$7+F zfmmSXU7pWcAsUW2(Ae!h!M)Es#5OWs3s@j1%|@`QXK$&)r?tc6CRpu|&iT!F3b?UT zlUZE@QhWJjrfR4U6Q0B#sE?+X$0{m}#Tom7RisTjD4qJxlH!GWm@`F*TK9cC8Cr!z z#K~RX>swc46X-Cff;tpDMF@Q%LW1v*D6xTV4mYn0!aYs*W-MLm9`#Nz9yVnXh`~QJ zhr}IcmYu+5ed^sx;~@P>dvA|=FY-4~b~7FB;cLhle@hEYOqDVi&oiSH4g({k9^Sgn zud}1Nt0icf@9`0?Pzu;K#&D+kHbO(TP?D2=({Jlusw3!4y?2$@cLxB_aQ_oHKu#Xf z8~DycK}F`>{yS2PkC@xZY!7b;NJ09ume1;GzKR{LAyH(H!+=h{qG2vd8PjK0ym+Qb zSwlj}&sgE8E-W0Cw252&o6zpKdypyw`c2G+S=L+W+Cx^MW(+S zwf%~g&wzOd>r-JRi$Y&GzK!aMBe^|GKWcLMS@ZWOSH18Do@?- zalu5*E-sCVd_lKR`ZNV&{KU5yxC@fWyh7VMI&Re8KRw;^UipZ$V?W=*ygHOr{nv@M zw)>;neRt5Bva_>Oae9alMt-7=>;V@xH`UnL+4;o9>mL8G5yaWA25}L6LwJYrMUadm z!Fg*kSK#pOVmEShij{?h@7T}ZKkwful+nPydQq{(WnIHbMCKgcUyPDm)OUevr^AS2 z5|#hWVFN=$dm9^BEs(WNc;xaYvLI&`0&tP{d>2^A&wha6r*X9S|GP)upJ)@(e8y0`b}Fa z@nDuyu#X4_(VOEG(RJ<@^rU9y=AXIB%F2*;j*a|Bk>3It%Iy$%_MKm2tV69p1e-lj zUq73T`zJBr$?)m<@iva*+@MycJ?K^Jbh%#2gVJ%S20K2*fFsiikVm7b=3m^SM$pvK z^2$B52Q)`!lDPFP&_)F6==5Qwug&h%mdgTa|kPIlFIr|08pbj zo2V?A5Yl~d>-+T5cgi?9X+s^Q+Mk}43+l}U?n zhm(!%Edk4v8KgeuCVX^SE>xtjjwRdL>I-WpcztUM7uMF4q0P=ELqoDv)z!2uP?gQ@ z0L^Z9X4}!nhX=&z{wPW6^}M|#X&R)STB#WKN2Tq>YF(uB?a?$wYoW)wQKgdW#t)6q zQ$9gKdB5AU=ik$Y1_lQgyTdu6_u@e>balTC|K94>nb7xaCXq>CkdTnr+1W*J^aQDm zTBTN1RoNXc)oPiTd|v_YTnK)^z0zl+TB9ySuv& zDZ?vm>$OsRc@W!CE*$Mk;rfr%^x*#^Gc&^f5t=-_`P-4|efa;SIl7Sl7%vkgRe}u; zpakee2XG+(=tBN8asD$W{v*Z6kHO$u_$!g54%T3>H;T2+XXkq`8J{8kj$!FmJM8qaaFm@w@x_=7hX562x&=FS7Vx zZgzr7dcLBpbb@#nfB!}sGH!JZf$i^KRJ_Ux=QGs(R%&Qy2(6DWA*ww@?hXrKDgVot)r_vL+@b&Q0Zix)DP7a|K$Oouz(YU$s+m98M&+Y%@~5 zAP$bb-*pw75KIg+Lv4J^^va)f>h**^*9X{$X>IEr-fB&G;eT33njC*quG_d#CI51uG`RvrHLJWA#BRcDIwQ*rnHV(Nn*8ef~CEnj&H_O&-NQ`ZRNrDralDf|Ifen dKPcGz4y`$7Bh3|;;t=q*6l7GTze}2h{vXi().unwrap(); let select = IconBuilder::new("textures/select.png", &asset_server); let edit = IconBuilder::new("textures/edit.png", &asset_server); + let exit = IconBuilder::new("textures/exit.png", &asset_server); let trash = IconBuilder::new("textures/trash.png", &asset_server); let layer_up = IconBuilder::new("textures/up.png", &asset_server); let layer_down = IconBuilder::new("textures/down.png", &asset_server); @@ -85,6 +87,7 @@ impl FromWorld for Icons { Self { select: select.build(&mut egui_context), edit: edit.build(&mut egui_context), + exit: exit.build(&mut egui_context), trash: trash.build(&mut egui_context), layer_up: layer_up.build(&mut egui_context), layer_down: layer_down.build(&mut egui_context), diff --git a/rmf_site_editor/src/widgets/mod.rs b/rmf_site_editor/src/widgets/mod.rs index 10aeb6fe..13ec0649 100644 --- a/rmf_site_editor/src/widgets/mod.rs +++ b/rmf_site_editor/src/widgets/mod.rs @@ -395,7 +395,11 @@ fn site_drawing_ui_layout( CreateWidget::new(&mut events).show(ui); }); ui.separator(); - if ui.add(Button::new("Return to site editor")).clicked() { + if ui.add(Button::image_and_text( + events.layers.icons.exit.egui(), + [18., 18.], + "Return to site editor", + )).clicked() { events.layers.finish_edit_drawing.send(FinishEditDrawing(None)); } }); @@ -461,7 +465,11 @@ fn site_visualizer_ui_layout( events.request.current_workspace.root.unwrap(), )); } - if ui.add(Button::new("Return to site editor")).clicked() { + if ui.add(Button::image_and_text( + events.layers.icons.exit.egui(), + [18., 18.], + "Return to site editor" + )).clicked() { events.app_state.set(AppState::SiteEditor).ok(); } }); From e75b1f0bd0ca2d1ef68842e4cb2fb6385b760f17 Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Fri, 28 Jul 2023 14:58:15 +0800 Subject: [PATCH 08/34] Pick, outline, and highlight drawings Signed-off-by: Michael X. Grey --- rmf_site_editor/src/interaction/highlight.rs | 79 +++++++++++++++++++ rmf_site_editor/src/interaction/mod.rs | 5 ++ rmf_site_editor/src/interaction/outline.rs | 22 ++++-- rmf_site_editor/src/keyboard.rs | 4 +- rmf_site_editor/src/site/drawing.rs | 31 +++++--- .../src/site/drawing_editor/mod.rs | 26 ++++-- .../src/widgets/inspector/inspect_layer.rs | 14 +++- 7 files changed, 150 insertions(+), 31 deletions(-) create mode 100644 rmf_site_editor/src/interaction/highlight.rs diff --git a/rmf_site_editor/src/interaction/highlight.rs b/rmf_site_editor/src/interaction/highlight.rs new file mode 100644 index 00000000..b8542134 --- /dev/null +++ b/rmf_site_editor/src/interaction/highlight.rs @@ -0,0 +1,79 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +use crate::{ + interaction::*, + site::DrawingMarker, +}; +use bevy::prelude::*; + +#[derive(Component)] +pub struct Highlight { + pub select: Color, + pub hover: Color, + pub hover_select: Color, +} + +#[derive(Component)] +pub struct SuppressHighlight; + +impl Highlight { + pub fn for_drawing() -> Self { + Self { + select: Color::rgb(1., 0.7, 1.), + hover: Color::rgb(0.7, 1., 1.), + hover_select: Color::rgb(1.0, 0.5, 0.7), + } + } +} + +pub fn add_highlight_visualization( + mut commands: Commands, + new_drawings: Query>, +) { + for e in &new_drawings { + commands + .entity(e) + .insert(Highlight::for_drawing()); + } +} + +pub fn update_highlight_visualization( + highlightable: Query< + (&Hovered, &Selected, &Handle, &Highlight, Option<&SuppressHighlight>), + Or<(Changed, Changed, Changed)>, + >, + mut materials: ResMut>, +) { + for (hovered, selected, m, highlight, suppress) in &highlightable { + let color = if suppress.is_some() { + Color::WHITE + } else if hovered.cue() && selected.cue() { + highlight.hover_select + } else if hovered.cue() { + highlight.hover + } else if selected.cue() { + highlight.select + } else { + Color::WHITE + }; + + if let Some(material) = materials.get_mut(m) { + material.base_color = color; + } + } +} diff --git a/rmf_site_editor/src/interaction/mod.rs b/rmf_site_editor/src/interaction/mod.rs index 95d88e68..4df2b33d 100644 --- a/rmf_site_editor/src/interaction/mod.rs +++ b/rmf_site_editor/src/interaction/mod.rs @@ -42,6 +42,9 @@ pub use edge::*; pub mod gizmo; pub use gizmo::*; +pub mod highlight; +pub use highlight::*; + pub mod lane; pub use lane::*; @@ -181,6 +184,7 @@ impl Plugin for InteractionPlugin { .with_system(update_point_visual_cues.after(maintain_selected_entities)) .with_system(update_path_visual_cues.after(maintain_selected_entities)) .with_system(update_outline_visualization.after(maintain_selected_entities)) + .with_system(update_highlight_visualization.after(maintain_selected_entities)) .with_system( update_cursor_hover_visualization.after(maintain_selected_entities), ) @@ -207,6 +211,7 @@ impl Plugin for InteractionPlugin { .with_system(add_point_visual_cues) .with_system(add_path_visual_cues) .with_system(add_outline_visualization) + .with_system(add_highlight_visualization) .with_system(add_cursor_hover_visualization) .with_system(add_physical_light_visual_cues), ) diff --git a/rmf_site_editor/src/interaction/outline.rs b/rmf_site_editor/src/interaction/outline.rs index 4a3338f6..727776c1 100644 --- a/rmf_site_editor/src/interaction/outline.rs +++ b/rmf_site_editor/src/interaction/outline.rs @@ -15,7 +15,10 @@ * */ -use crate::interaction::*; +use crate::{ + site::DrawingMarker, + interaction::*, +}; use bevy::render::view::RenderLayers; use bevy_mod_outline::{OutlineBundle, OutlineRenderLayers, OutlineVolume, SetOutlineDepth}; use rmf_site_format::{ @@ -105,6 +108,10 @@ impl OutlineVisualization { } } +/// Use this to temporarily prevent objects from being highlighted. +#[derive(Component)] +pub struct SuppressOutline; + pub fn add_outline_visualization( mut commands: Commands, new_entities: Query< @@ -117,6 +124,7 @@ pub fn add_outline_visualization( Added, Added, Added, + Added, Added, Added, Added, @@ -135,13 +143,17 @@ pub fn add_outline_visualization( pub fn update_outline_visualization( mut commands: Commands, outlinable: Query< - (Entity, &Hovered, &Selected, &OutlineVisualization), - Or<(Changed, Changed)>, + (Entity, &Hovered, &Selected, &OutlineVisualization, Option<&SuppressOutline>), + Or<(Changed, Changed, Changed)>, >, descendants: Query<(Option<&Children>, Option<&ComputedVisualCue>)>, ) { - for (e, hovered, selected, vis) in &outlinable { - let color = vis.color(hovered, selected); + for (e, hovered, selected, vis, suppress) in &outlinable { + let color = if suppress.is_some() { + None + } else { + vis.color(hovered, selected) + }; let layers = vis.layers(hovered, selected); let depth = vis.depth(); let root = vis.root().unwrap_or(e); diff --git a/rmf_site_editor/src/keyboard.rs b/rmf_site_editor/src/keyboard.rs index d7e5a331..ea0ba57f 100644 --- a/rmf_site_editor/src/keyboard.rs +++ b/rmf_site_editor/src/keyboard.rs @@ -77,11 +77,11 @@ fn handle_keyboard_input( } if keyboard_input.just_pressed(KeyCode::F2) { - change_camera_mode.send(ChangeProjectionMode::to_perspective()); + change_camera_mode.send(ChangeProjectionMode::to_orthographic()); } if keyboard_input.just_pressed(KeyCode::F3) { - change_camera_mode.send(ChangeProjectionMode::to_orthographic()); + change_camera_mode.send(ChangeProjectionMode::to_perspective()); } if keyboard_input.just_pressed(KeyCode::Escape) { diff --git a/rmf_site_editor/src/site/drawing.rs b/rmf_site_editor/src/site/drawing.rs index 44053297..92681aef 100644 --- a/rmf_site_editor/src/site/drawing.rs +++ b/rmf_site_editor/src/site/drawing.rs @@ -175,6 +175,13 @@ pub fn handle_loaded_drawing( Affine3A::from_translation(Vec3::new(width / 2.0, -height / 2.0, 0.0)), ); let mesh = mesh_assets.add(mesh.into()); + let (alpha, alpha_mode) = drawing_alpha(vis, &default_drawing_vis); + let material = materials.add(StandardMaterial { + base_color_texture: Some(handle.0.clone()), + base_color: *Color::default().set_a(alpha), + alpha_mode, + ..default() + }); let leaf = if let Ok(segment) = segments.get(entity) { segment.leaf @@ -188,22 +195,22 @@ pub fn handle_loaded_drawing( .insert(SpatialBundle::from_transform(pose.transform().with_scale( Vec3::new(1.0 / pixels_per_meter.0, 1.0 / pixels_per_meter.0, 1.), ))) - .insert(Selectable::new(entity)); + .insert(Selectable::new(entity)) + // Put a handle for the material into the main entity + // so that we can modify it during interactions. + .insert(material.clone()); leaf }; let z = drawing_layer_height(rank.get(entity).ok()); - let (alpha, alpha_mode) = drawing_alpha(vis, &default_drawing_vis); - commands.entity(leaf).insert(PbrBundle { - mesh, - material: materials.add(StandardMaterial { - base_color_texture: Some(handle.0.clone()), - base_color: *Color::default().set_a(alpha), - alpha_mode, + commands + .entity(leaf) + .insert(PbrBundle { + mesh, + material, + transform: Transform::from_xyz(0.0, 0.0, z), ..default() - }), - transform: Transform::from_xyz(0.0, 0.0, z), - ..default() - }); + }) + .insert(Selectable::new(entity)); commands.entity(entity).remove::(); } LoadState::Failed => { diff --git a/rmf_site_editor/src/site/drawing_editor/mod.rs b/rmf_site_editor/src/site/drawing_editor/mod.rs index 6dc0e98e..e63b0f92 100644 --- a/rmf_site_editor/src/site/drawing_editor/mod.rs +++ b/rmf_site_editor/src/site/drawing_editor/mod.rs @@ -21,7 +21,7 @@ pub mod optimizer; pub use optimizer::*; use crate::{ - interaction::{CameraControls, HeadlightToggle, Selection, ChangeProjectionMode}, + interaction::{Selection, ChangeProjectionMode, SuppressHighlight, SuppressOutline}, site::{ Anchor, DrawingMarker, Edge, FiducialMarker, MeasurementMarker, Pending, PixelsPerMeter, Point, PreventDeletion, SiteProperties, WorkcellProperties, @@ -112,9 +112,7 @@ fn switch_edit_drawing_mode( if let Some(c) = current.target() { // A drawing was being edited and now we're switching to a // different drawing, so we need to reset the previous drawing. - commands.entity(c.drawing) - .set_parent(c.level) - .remove::(); + restore_edited_drawing(c, &mut commands); } let level = if let Ok(p) = parent.get(*e) { @@ -133,7 +131,10 @@ fn switch_edit_drawing_mode( .insert(PreventDeletion::because( "Cannot delete a drawing that is currently being edited" .to_owned() - )); + )) + // Highlighting the drawing looks bad when the user will be + // constantly hovering over it anyway. + .insert(SuppressHighlight); change_camera_mode.send(ChangeProjectionMode::to_orthographic()); @@ -167,9 +168,7 @@ fn switch_edit_drawing_mode( continue; }; - commands.entity(c.drawing) - .set_parent(c.level) - .remove::(); + restore_edited_drawing(c, &mut commands); current.target = None; // This camera change would not be needed if we have an edit mode stack @@ -202,6 +201,17 @@ fn switch_edit_drawing_mode( } } +/// Restore a drawing that was being edited back to its normal place and behavior +fn restore_edited_drawing( + edit: &EditDrawing, + commands: &mut Commands, +) { + commands.entity(edit.drawing) + .set_parent(edit.level) + .remove::() + .remove::(); +} + fn assign_drawing_parent_to_new_measurements_and_fiducials( mut commands: Commands, mut new_elements: Query< diff --git a/rmf_site_editor/src/widgets/inspector/inspect_layer.rs b/rmf_site_editor/src/widgets/inspector/inspect_layer.rs index 44a4d687..be7bb87e 100644 --- a/rmf_site_editor/src/widgets/inspector/inspect_layer.rs +++ b/rmf_site_editor/src/widgets/inspector/inspect_layer.rs @@ -112,12 +112,18 @@ impl<'a, 'w, 's> InspectLayer<'a, 'w, 's> { if let Some(site_id) = self.site_id { SelectionWidget::new(self.entity, site_id, self.icons, self.events).show(ui); if !self.is_floor { - if ui.add( - ImageButton::new(self.events.layers.icons.edit.egui(), [18., 18.]) - ).on_hover_text("Edit Drawing").clicked() { + let response = ui.add(ImageButton::new( + self.events.layers.icons.edit.egui(), [18., 18.] + )).on_hover_text("Edit Drawing"); + + if response.hovered() { + self.events.request.hover.send(Hover(Some(self.entity))); + } + + if response.clicked() { self.events.layers.begin_edit_drawing.send( BeginEditDrawing(self.entity) - ) + ); } } } From b45b009e28445d7dcb5551dfbb80021cf1fbe527 Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Tue, 1 Aug 2023 21:31:59 +0800 Subject: [PATCH 09/34] Restructure site format to remember semi-transparency preferences Signed-off-by: Michael X. Grey --- .../src/interaction/select_anchor.rs | 4 +- rmf_site_editor/src/occupancy.rs | 12 +- rmf_site_editor/src/site/anchor.rs | 5 +- rmf_site_editor/src/site/constraint.rs | 6 +- rmf_site_editor/src/site/deletion.rs | 12 +- rmf_site_editor/src/site/drawing.rs | 156 ++++++----- .../src/site/drawing_editor/mod.rs | 3 +- .../src/site/drawing_editor/optimizer.rs | 241 +++++++++-------- rmf_site_editor/src/site/floor.rs | 105 ++++---- rmf_site_editor/src/site/lane.rs | 10 +- rmf_site_editor/src/site/layer.rs | 101 -------- rmf_site_editor/src/site/level.rs | 6 +- rmf_site_editor/src/site/lift.rs | 10 +- rmf_site_editor/src/site/light.rs | 10 +- rmf_site_editor/src/site/load.rs | 19 +- rmf_site_editor/src/site/location.rs | 8 +- rmf_site_editor/src/site/mod.rs | 14 +- rmf_site_editor/src/site/save.rs | 60 +++-- rmf_site_editor/src/site/site.rs | 12 +- .../src/site/site_visualizer/mod.rs | 20 +- rmf_site_editor/src/widgets/create.rs | 15 +- .../widgets/inspector/inspect_is_primary.rs | 43 ---- .../src/widgets/inspector/inspect_layer.rs | 6 +- .../src/widgets/inspector/inspect_lift.rs | 10 +- rmf_site_editor/src/widgets/inspector/mod.rs | 24 +- rmf_site_editor/src/widgets/mod.rs | 8 +- rmf_site_editor/src/widgets/view_layers.rs | 125 ++++++--- rmf_site_editor/src/widgets/view_levels.rs | 35 ++- .../src/widgets/view_nav_graphs.rs | 6 +- rmf_site_editor/src/workspace.rs | 4 +- rmf_site_format/src/drawing.rs | 32 ++- rmf_site_format/src/floor.rs | 5 + rmf_site_format/src/layer.rs | 243 ++++++++++++++++++ rmf_site_format/src/legacy/building_map.rs | 51 ++-- rmf_site_format/src/legacy/floor.rs | 3 +- rmf_site_format/src/legacy/nav_graph.rs | 4 +- rmf_site_format/src/level.rs | 25 +- rmf_site_format/src/lib.rs | 3 + rmf_site_format/src/site.rs | 13 +- 39 files changed, 846 insertions(+), 623 deletions(-) delete mode 100644 rmf_site_editor/src/site/layer.rs delete mode 100644 rmf_site_editor/src/widgets/inspector/inspect_is_primary.rs create mode 100644 rmf_site_format/src/layer.rs diff --git a/rmf_site_editor/src/interaction/select_anchor.rs b/rmf_site_editor/src/interaction/select_anchor.rs index 4f75c9be..caab5096 100644 --- a/rmf_site_editor/src/interaction/select_anchor.rs +++ b/rmf_site_editor/src/interaction/select_anchor.rs @@ -26,7 +26,7 @@ use bevy::{ecs::system::SystemParam, prelude::*}; use rmf_site_format::{ Constraint, ConstraintDependents, Door, Edge, Fiducial, Floor, Lane, LiftProperties, Location, Measurement, MeshConstraint, MeshElement, Model, ModelMarker, NameInWorkcell, Path, - PixelsPerMeter, Point, Pose, Side, SiteProperties, Wall, WorkcellCollisionMarker, + PixelsPerMeter, Point, Pose, Side, NameOfSite, Wall, WorkcellCollisionMarker, WorkcellModel, WorkcellVisualMarker, }; use std::collections::HashSet; @@ -1904,7 +1904,7 @@ pub fn handle_select_anchor_mode( mut hover: EventWriter, blockers: Option>, workspace: Res, - open_sites: Query>, + open_sites: Query>, ) { let mut request = match &*mode { InteractionMode::SelectAnchor(request) => request.clone(), diff --git a/rmf_site_editor/src/occupancy.rs b/rmf_site_editor/src/occupancy.rs index 1af75c53..b54840f3 100644 --- a/rmf_site_editor/src/occupancy.rs +++ b/rmf_site_editor/src/occupancy.rs @@ -18,7 +18,7 @@ use crate::{ interaction::ComputedVisualCue, shapes::*, - site::{Category, LevelProperties, SiteAssets, SiteProperties, LANE_LAYER_START}, + site::{Category, LevelElevation, SiteAssets, NameOfSite, LANE_LAYER_START}, }; use bevy::{ math::{swizzles::*, Affine3A, Mat3A, Vec2, Vec3A}, @@ -156,8 +156,8 @@ fn calculate_grid( Option<&ComputedVisualCue>, )>, parents: Query<&Parent>, - levels: Query>, - sites: Query<(), With>, + levels: Query>, + sites: Query<(), With>, mut meshes: ResMut>, assets: Res, grids: Query>, @@ -296,7 +296,7 @@ fn calculate_grid( } fn get_levels_of_sites( - levels: &Query>, + levels: &Query>, parents: &Query<&Parent>, ) -> HashMap> { let mut levels_of_sites: HashMap> = HashMap::new(); @@ -312,8 +312,8 @@ fn get_levels_of_sites( fn get_group( e: Entity, parents: &Query<&Parent>, - levels: &Query>, - sites: &Query<(), With>, + levels: &Query>, + sites: &Query<(), With>, ) -> Group { let mut e_meta = e; loop { diff --git a/rmf_site_editor/src/site/anchor.rs b/rmf_site_editor/src/site/anchor.rs index 3ec59880..10d4ddd3 100644 --- a/rmf_site_editor/src/site/anchor.rs +++ b/rmf_site_editor/src/site/anchor.rs @@ -162,8 +162,9 @@ pub fn assign_orphan_anchors_to_parent( // No level is currently assigned, so we should create one. let new_level_id = commands .spawn(LevelProperties { - name: "".to_string(), - elevation: 0., + name: NameInSite("".to_owned()), + elevation: LevelElevation(0.), + ..default() }) .insert(Category::Level) .id(); diff --git a/rmf_site_editor/src/site/constraint.rs b/rmf_site_editor/src/site/constraint.rs index 666bde80..0a2e0dbd 100644 --- a/rmf_site_editor/src/site/constraint.rs +++ b/rmf_site_editor/src/site/constraint.rs @@ -37,8 +37,8 @@ pub fn assign_orphan_constraints_to_parent( constraints: Query<(Entity, &Edge), (Without, With)>, current_workspace: Res, parents: Query<&Parent>, - levels: Query>, - open_sites: Query>, + levels: Query>, + open_sites: Query>, ) { if let Some(current_site) = current_workspace.to_site(&open_sites) { for (e, edge) in &constraints { @@ -164,7 +164,7 @@ pub fn update_constraint_for_changed_labels( dependents: Query<&Dependents>, fiducials: Query>, constraints: Query<(Entity, &Edge, &Parent), With>, - open_sites: Query>, + open_sites: Query>, ) { let get_fiducial_label = |e: Entity| -> Option<&Label> { let fiducial = dependents diff --git a/rmf_site_editor/src/site/deletion.rs b/rmf_site_editor/src/site/deletion.rs index a0305e33..52c5a223 100644 --- a/rmf_site_editor/src/site/deletion.rs +++ b/rmf_site_editor/src/site/deletion.rs @@ -18,7 +18,10 @@ use crate::{ interaction::{Select, Selection}, log::Log, - site::{Category, CurrentLevel, Dependents, LevelProperties, SiteUpdateStage}, + site::{ + Category, CurrentLevel, Dependents, LevelProperties, NameInSite, + LevelElevation, SiteUpdateStage, + }, }; use bevy::{ecs::system::SystemParam, prelude::*}; use rmf_site_format::{ConstraintDependents, Edge, MeshConstraint, Path, Point}; @@ -85,7 +88,7 @@ struct DeletionParams<'w, 's> { children: Query<'w, 's, &'static Children>, selection: Res<'w, Selection>, current_level: ResMut<'w, CurrentLevel>, - levels: Query<'w, 's, Entity, With>, + levels: Query<'w, 's, Entity, With>, select: EventWriter<'w, 's, Select>, log: EventWriter<'w, 's, Log>, } @@ -345,8 +348,9 @@ fn perform_deletions(all_to_delete: HashSet, params: &mut DeletionParams .commands .spawn(SpatialBundle::default()) .insert(LevelProperties { - elevation: 0.0, - name: "".to_string(), + name: NameInSite("".to_owned()), + elevation: LevelElevation(0.0), + ..default() }) .insert(Category::Level) .id(); diff --git a/rmf_site_editor/src/site/drawing.rs b/rmf_site_editor/src/site/drawing.rs index 92681aef..93e70e89 100644 --- a/rmf_site_editor/src/site/drawing.rs +++ b/rmf_site_editor/src/site/drawing.rs @@ -19,25 +19,22 @@ use crate::{ interaction::Selectable, shapes::make_flat_rect_mesh, site::{ - get_current_workspace_path, Anchor, DefaultFile, FiducialMarker, GlobalFloorVisibility, - LayerVisibility, MeasurementMarker, MeasurementSegment, RecencyRank, + get_current_workspace_path, Anchor, DefaultFile, FiducialMarker, + GlobalDrawingVisibility, LayerVisibility, MeasurementMarker, + MeasurementSegment, RecencyRank, DEFAULT_MEASUREMENT_OFFSET, FLOOR_LAYER_START, }, CurrentWorkspace, }; use bevy::{asset::LoadState, math::Affine3A, prelude::*}; use rmf_site_format::{ - AssetSource, Category, Drawing, IsPrimary, NameInSite, PixelsPerMeter, Pose, + AssetSource, Category, DrawingProperties, NameInSite, PixelsPerMeter, Pose, }; #[derive(Bundle, Debug, Clone)] pub struct DrawingBundle { + pub properties: DrawingProperties, pub category: Category, - pub name: NameInSite, - pub source: AssetSource, - pub pose: Pose, - pub pixels_per_meter: PixelsPerMeter, - pub is_primary: IsPrimary, pub transform: Transform, pub global_transform: GlobalTransform, pub visibility: Visibility, @@ -46,19 +43,15 @@ pub struct DrawingBundle { } impl DrawingBundle { - pub fn new(drawing: &Drawing) -> Self { + pub fn new(properties: DrawingProperties) -> Self { DrawingBundle { + properties, category: Category::Drawing, - name: drawing.name.clone(), - source: drawing.source.clone(), - pose: drawing.pose.clone(), - pixels_per_meter: drawing.pixels_per_meter.clone(), - is_primary: drawing.is_primary.clone(), - transform: Transform::IDENTITY, - global_transform: GlobalTransform::IDENTITY, - visibility: Visibility::VISIBLE, - computed: ComputedVisibility::default(), - marker: DrawingMarker::default(), + transform: default(), + global_transform: default(), + visibility: default(), + computed: default(), + marker: default(), } } } @@ -66,23 +59,8 @@ impl DrawingBundle { #[derive(Component, Clone, Copy, Debug, Default)] pub struct DrawingMarker; -#[derive(Debug, Clone, Copy, Default, Deref, DerefMut, Resource)] -pub struct GlobalDrawingVisibility(pub LayerVisibility); - pub const DRAWING_LAYER_START: f32 = 0.0; -// Semi transparency for drawings, more opaque than floors to make them visible -const DEFAULT_DRAWING_SEMI_TRANSPARENCY: f32 = 0.5; - -/// Resource used to set what the alpha value for partially transparent drawings should be -#[derive(Clone, Resource, Deref, DerefMut)] -pub struct DrawingSemiTransparency(f32); - -impl Default for DrawingSemiTransparency { - fn default() -> Self { - DrawingSemiTransparency(DEFAULT_DRAWING_SEMI_TRANSPARENCY) - } -} #[derive(Debug, Clone, Copy, Component)] pub struct DrawingSegments { @@ -102,14 +80,13 @@ fn drawing_layer_height(rank: Option<&RecencyRank>) -> f32 { pub fn add_drawing_visuals( mut commands: Commands, changed_drawings: Query< - (Entity, &AssetSource, &IsPrimary), + (Entity, &AssetSource), (With, Changed), >, asset_server: Res, current_workspace: Res, site_files: Query<&DefaultFile>, - mut default_floor_vis: ResMut, - drawing_transparency: Res, + default_drawing_vis: Query<&GlobalDrawingVisibility>, ) { // TODO(luca) depending on when this system is executed, this function might be called between // the creation of the drawing and the change of the workspace, making this silently fail @@ -118,7 +95,7 @@ pub fn add_drawing_visuals( Some(file_path) => file_path, None => return, }; - for (e, source, is_primary) in &changed_drawings { + for (e, source) in &changed_drawings { // Append file name to path if it's a local file // TODO(luca) cleanup let asset_source = match source { @@ -128,19 +105,9 @@ pub fn add_drawing_visuals( _ => source.clone(), }; let texture_handle: Handle = asset_server.load(&String::from(&asset_source)); - let visibility = if is_primary.0 == true { - LayerVisibility::Opaque - } else { - LayerVisibility::Alpha(**drawing_transparency) - }; commands .entity(e) - .insert(LoadingDrawing(texture_handle)) - .insert(visibility); - } - - if !changed_drawings.is_empty() { - **default_floor_vis = LayerVisibility::new_semi_transparent(); + .insert(LoadingDrawing(texture_handle)); } } @@ -155,15 +122,16 @@ pub fn handle_loaded_drawing( &PixelsPerMeter, &LoadingDrawing, Option<&LayerVisibility>, + Option<&Parent>, + Option<&RecencyRank>, )>, mut mesh_assets: ResMut>, asset_server: Res, mut materials: ResMut>, - rank: Query<&RecencyRank>, segments: Query<&DrawingSegments>, - default_drawing_vis: Res, + default_drawing_vis: Query<&GlobalDrawingVisibility>, ) { - for (entity, source, pose, pixels_per_meter, handle, vis) in loading_drawings.iter() { + for (entity, source, pose, pixels_per_meter, handle, vis, parent, rank) in loading_drawings.iter() { match asset_server.get_load_state(&handle.0) { LoadState::Loaded => { let img = assets.get(&handle.0).unwrap(); @@ -175,12 +143,13 @@ pub fn handle_loaded_drawing( Affine3A::from_translation(Vec3::new(width / 2.0, -height / 2.0, 0.0)), ); let mesh = mesh_assets.add(mesh.into()); - let (alpha, alpha_mode) = drawing_alpha(vis, &default_drawing_vis); + let default = parent.map(|p| default_drawing_vis.get(p.get()).ok()).flatten(); + let (alpha, alpha_mode) = drawing_alpha(vis, rank, default); let material = materials.add(StandardMaterial { base_color_texture: Some(handle.0.clone()), base_color: *Color::default().set_a(alpha), alpha_mode, - ..default() + ..Default::default() }); let leaf = if let Ok(segment) = segments.get(entity) { @@ -201,14 +170,14 @@ pub fn handle_loaded_drawing( .insert(material.clone()); leaf }; - let z = drawing_layer_height(rank.get(entity).ok()); + let z = drawing_layer_height(rank); commands .entity(leaf) .insert(PbrBundle { mesh, material, transform: Transform::from_xyz(0.0, 0.0, z), - ..default() + ..Default::default() }) .insert(Selectable::new(entity)); commands.entity(entity).remove::(); @@ -285,11 +254,25 @@ pub fn update_drawing_children_to_pixel_coordinates( } } +#[inline] fn drawing_alpha( specific: Option<&LayerVisibility>, - general: &LayerVisibility, + rank: Option<&RecencyRank>, + general: Option<&GlobalDrawingVisibility>, ) -> (f32, AlphaMode) { - let alpha = specific.map(|s| s.alpha()).unwrap_or(general.alpha()); + let alpha = specific.copied() + .unwrap_or_else( + || general.map(|v| { + if let Some(r) = rank { + if r.rank() < v.bottom_count { + return v.bottom; + } + } + v.general + }) + .unwrap_or(LayerVisibility::Opaque) + ).alpha(); + let alpha_mode = if alpha < 1.0 { AlphaMode::Blend } else { @@ -298,16 +281,23 @@ fn drawing_alpha( (alpha, alpha_mode) } +#[inline] fn iter_update_drawing_visibility<'a>( - iter: impl Iterator, &'a DrawingSegments)>, + iter: impl Iterator, + Option<&'a Parent>, + Option<&'a RecencyRank>, + &'a DrawingSegments, + )>, material_handles: &Query<&Handle>, material_assets: &mut ResMut>, - default_drawing_vis: &LayerVisibility, + default_drawing_vis: &Query<&GlobalDrawingVisibility>, ) { - for (vis, segments) in iter { + for (vis, parent, rank, segments) in iter { if let Ok(handle) = material_handles.get(segments.leaf) { if let Some(mat) = material_assets.get_mut(handle) { - let (alpha, alpha_mode) = drawing_alpha(vis, &default_drawing_vis); + let default = parent.map(|p| default_drawing_vis.get(p.get()).ok()).flatten(); + let (alpha, alpha_mode) = drawing_alpha(vis, rank, default); mat.base_color = *mat.base_color.set_a(alpha); mat.alpha_mode = alpha_mode; } @@ -316,35 +306,35 @@ fn iter_update_drawing_visibility<'a>( } // TODO(luca) RemovedComponents is brittle, maybe wrap component in an option? -// TODO(luca) This is copy-pasted from floor.rs, consider having a generic plugin pub fn update_drawing_visibility( - changed_floors: Query<(Option<&LayerVisibility>, &DrawingSegments), Changed>, + changed_drawings: Query, Changed, Changed>)>>, removed_vis: RemovedComponents, - all_floors: Query<(Option<&LayerVisibility>, &DrawingSegments)>, + all_drawings: Query<(Option<&LayerVisibility>, Option<&Parent>, Option<&RecencyRank>, &DrawingSegments)>, material_handles: Query<&Handle>, mut material_assets: ResMut>, - default_drawing_vis: Res, + default_drawing_vis: Query<&GlobalDrawingVisibility>, + changed_default_drawing_vis: Query<&Children, Changed> ) { - if default_drawing_vis.is_changed() { - iter_update_drawing_visibility( - all_floors.iter(), - &material_handles, - &mut material_assets, - &default_drawing_vis, - ); - } else { - iter_update_drawing_visibility( - changed_floors.iter(), - &material_handles, - &mut material_assets, - &default_drawing_vis, - ); + iter_update_drawing_visibility( + changed_drawings.iter().filter_map(|e| all_drawings.get(e).ok()), + &material_handles, + &mut material_assets, + &default_drawing_vis + ); + + iter_update_drawing_visibility( + removed_vis.iter().filter_map(|e| all_drawings.get(e).ok()), + &material_handles, + &mut material_assets, + &default_drawing_vis + ); + for children in &changed_default_drawing_vis { iter_update_drawing_visibility( - removed_vis.iter().filter_map(|e| all_floors.get(e).ok()), + children.iter().filter_map(|e| all_drawings.get(*e).ok()), &material_handles, &mut material_assets, - &default_drawing_vis, + &default_drawing_vis ); - }; + } } diff --git a/rmf_site_editor/src/site/drawing_editor/mod.rs b/rmf_site_editor/src/site/drawing_editor/mod.rs index e63b0f92..55b7f11f 100644 --- a/rmf_site_editor/src/site/drawing_editor/mod.rs +++ b/rmf_site_editor/src/site/drawing_editor/mod.rs @@ -25,6 +25,7 @@ use crate::{ site::{ Anchor, DrawingMarker, Edge, FiducialMarker, MeasurementMarker, Pending, PixelsPerMeter, Point, PreventDeletion, SiteProperties, WorkcellProperties, + NameOfSite, }, WorkspaceMarker, CurrentWorkspace, }; @@ -94,7 +95,7 @@ fn switch_edit_drawing_mode( global_tf: Query<&GlobalTransform>, current_workspace: Res, parent: Query<&Parent, With>, - is_site: Query<(), With>, + is_site: Query<(), With>, is_workcell: Query<(), With>, ) { // TODO(@mxgrey): We can make this implementation much cleaner after we diff --git a/rmf_site_editor/src/site/drawing_editor/optimizer.rs b/rmf_site_editor/src/site/drawing_editor/optimizer.rs index 362ab791..8dcf53e8 100644 --- a/rmf_site_editor/src/site/drawing_editor/optimizer.rs +++ b/rmf_site_editor/src/site/drawing_editor/optimizer.rs @@ -20,8 +20,8 @@ use bevy::prelude::*; use crate::site::{ AlignLevelDrawings, AlignSiteDrawings, Anchor, Angle, Category, Change, ConstraintMarker, - Distance, DrawingMarker, Edge, IsPrimary, LevelProperties, MeasurementMarker, PixelsPerMeter, - Pose, Rotation, ScaleDrawing, SiteProperties, + Distance, DrawingMarker, Edge, LevelElevation, MeasurementMarker, PixelsPerMeter, + Pose, Rotation, ScaleDrawing, SiteProperties, NameOfSite, }; use itertools::{Either, Itertools}; use optimization_engine::{panoc::*, *}; @@ -144,7 +144,7 @@ fn align_drawing_pair( (reference_point, target_point) }; // Guaranteed safe since caller passes a drawing entity - let (_, _, target_pose, target_ppm, _) = params.drawings.get(target_drawing).unwrap(); + let (_, _, target_pose, target_ppm) = params.drawings.get(target_drawing).unwrap(); let mut matching_points = Vec::new(); for edge in constraints.iter() { let start_parent = params @@ -233,7 +233,6 @@ pub struct OptimizationParams<'w, 's> { &'static Children, &'static Pose, &'static PixelsPerMeter, - &'static IsPrimary, ), With, >, @@ -244,132 +243,132 @@ pub struct OptimizationParams<'w, 's> { } pub fn align_level_drawings( - levels: Query<&Children, With>, + levels: Query<&Children, With>, mut events: EventReader, params: OptimizationParams, mut change: OptimizationChangeParams, ) { - for e in events.iter() { - // Get the matching points for this entity - let level_children = levels - .get(**e) - .expect("Align level event sent to non level entity"); - let constraints = level_children - .iter() - .filter_map(|child| params.constraints.get(*child).ok()) - .collect::>(); - if constraints.is_empty() { - warn!("No constraints found for level, skipping optimization"); - continue; - } - let (references, layers): (HashSet<_>, Vec<_>) = level_children - .iter() - .filter_map(|child| params.drawings.get(*child).ok()) - .partition_map(|(e, _, _, _, primary)| { - if primary.0 == true { - Either::Left(e) - } else { - Either::Right(e) - } - }); - if layers.is_empty() { - warn!( - "No non-primary drawings found for level, at least one drawing must be set to \ - non-primary to be optimized against primary drawings.Skipping optimization" - ); - continue; - } - if references.is_empty() { - warn!( - "No primary drawings found for level. At least one drawing must be set to \ - primary to use as a reference for other drawings. Skipping optimization" - ); - continue; - } - for layer_entity in layers { - align_drawing_pair( - &references, - layer_entity, - &constraints, - ¶ms, - &mut change, - ); - } - } + // for e in events.iter() { + // // Get the matching points for this entity + // let level_children = levels + // .get(**e) + // .expect("Align level event sent to non level entity"); + // let constraints = level_children + // .iter() + // .filter_map(|child| params.constraints.get(*child).ok()) + // .collect::>(); + // if constraints.is_empty() { + // warn!("No constraints found for level, skipping optimization"); + // continue; + // } + // let (references, layers): (HashSet<_>, Vec<_>) = level_children + // .iter() + // .filter_map(|child| params.drawings.get(*child).ok()) + // .partition_map(|(e, _, _, _)| { + // if primary.0 == true { + // Either::Left(e) + // } else { + // Either::Right(e) + // } + // }); + // if layers.is_empty() { + // warn!( + // "No non-primary drawings found for level, at least one drawing must be set to \ + // non-primary to be optimized against primary drawings.Skipping optimization" + // ); + // continue; + // } + // if references.is_empty() { + // warn!( + // "No primary drawings found for level. At least one drawing must be set to \ + // primary to use as a reference for other drawings. Skipping optimization" + // ); + // continue; + // } + // for layer_entity in layers { + // align_drawing_pair( + // &references, + // layer_entity, + // &constraints, + // ¶ms, + // &mut change, + // ); + // } + // } } pub fn align_site_drawings( - levels: Query<(Entity, &Children, &Parent, &LevelProperties)>, - sites: Query<&Children, With>, + levels: Query<(Entity, &Children, &Parent), With>, + sites: Query<&Children, With>, mut events: EventReader, params: OptimizationParams, mut change: OptimizationChangeParams, ) { - for e in events.iter() { - // Get the levels that are children of the requested site - let levels = levels - .iter() - .filter(|(_, _, p, _)| ***p == **e) - .collect::>(); - let reference_level = levels - .iter() - .min_by(|l_a, l_b| l_a.3.elevation.partial_cmp(&l_b.3.elevation).unwrap()) - .expect("Site has no levels"); - // Reference level will be the one with minimum elevation - let references = reference_level - .1 - .iter() - .filter_map(|c| { - params - .drawings - .get(*c) - .ok() - .filter(|(_, _, _, _, primary)| primary.0 == true) - }) - .map(|(e, _, _, _, _)| e) - .collect::>(); - // Layers to be optimized are primary drawings in the non reference level - let layers = levels - .iter() - .filter_map(|(e, c, _, _)| (*e != reference_level.0).then(|| c.iter())) - .flatten() - .filter_map(|child| params.drawings.get(*child).ok()) - .filter_map(|(e, _, _, _, primary)| (primary.0 == true).then(|| e)) - .collect::>(); - // Inter level constraints are children of the site - let constraints = sites - .get(**e) - .expect("Align site sent to non site entity") - .iter() - .filter_map(|child| params.constraints.get(*child).ok()) - .collect::>(); - if constraints.is_empty() { - warn!("No constraints found for site, skipping optimization"); - continue; - } - if layers.is_empty() { - warn!( - "No other levels drawings found for site, at least one other level must have a \ - primary drawing to be optimized against reference level. Skipping optimization" - ); - continue; - } - if references.is_empty() { - warn!( - "No reference level drawing found for site. At least one primary drawing must be \ - present in the lowest level to use as a reference for other levels. \ - Skipping optimization" - ); - continue; - } - for layer_entity in layers { - align_drawing_pair( - &references, - layer_entity, - &constraints, - ¶ms, - &mut change, - ); - } - } + // for e in events.iter() { + // // Get the levels that are children of the requested site + // let levels = levels + // .iter() + // .filter(|(_, _, p)| ***p == **e) + // .collect::>(); + // let reference_level = levels + // .iter() + // .min_by(|l_a, l_b| l_a.3.elevation.partial_cmp(&l_b.3.elevation).unwrap()) + // .expect("Site has no levels"); + // // Reference level will be the one with minimum elevation + // let references = reference_level + // .1 + // .iter() + // .filter_map(|c| { + // params + // .drawings + // .get(*c) + // .ok() + // .filter(|(_, _, _, _, primary)| primary.0 == true) + // }) + // .map(|(e, _, _, _, _)| e) + // .collect::>(); + // // Layers to be optimized are primary drawings in the non reference level + // let layers = levels + // .iter() + // .filter_map(|(e, c, _)| (*e != reference_level.0).then(|| c.iter())) + // .flatten() + // .filter_map(|child| params.drawings.get(*child).ok()) + // .filter_map(|(e, _, _, _, primary)| (primary.0 == true).then(|| e)) + // .collect::>(); + // // Inter level constraints are children of the site + // let constraints = sites + // .get(**e) + // .expect("Align site sent to non site entity") + // .iter() + // .filter_map(|child| params.constraints.get(*child).ok()) + // .collect::>(); + // if constraints.is_empty() { + // warn!("No constraints found for site, skipping optimization"); + // continue; + // } + // if layers.is_empty() { + // warn!( + // "No other levels drawings found for site, at least one other level must have a \ + // primary drawing to be optimized against reference level. Skipping optimization" + // ); + // continue; + // } + // if references.is_empty() { + // warn!( + // "No reference level drawing found for site. At least one primary drawing must be \ + // present in the lowest level to use as a reference for other levels. \ + // Skipping optimization" + // ); + // continue; + // } + // for layer_entity in layers { + // align_drawing_pair( + // &references, + // layer_entity, + // &constraints, + // ¶ms, + // &mut change, + // ); + // } + // } } diff --git a/rmf_site_editor/src/site/floor.rs b/rmf_site_editor/src/site/floor.rs index 972a6e58..a4179314 100644 --- a/rmf_site_editor/src/site/floor.rs +++ b/rmf_site_editor/src/site/floor.rs @@ -15,7 +15,12 @@ * */ -use crate::{interaction::Selectable, shapes::*, site::*}; +use crate::{ + interaction::Selectable, + shapes::*, + site::*, + RecencyRanking, +}; use bevy::{ math::Affine3A, prelude::*, @@ -28,22 +33,6 @@ use lyon::{ }; use rmf_site_format::{FloorMarker, Path}; -#[derive(Debug, Clone, Copy, Default, Deref, DerefMut, Resource)] -pub struct GlobalFloorVisibility(pub LayerVisibility); - -// Semi transparency for floors, more transparent than drawings to make them hidden -const DEFAULT_FLOOR_SEMI_TRANSPARENCY: f32 = 0.2; - -/// Resource used to set what the alpha value for partially transparent floors should be -#[derive(Clone, Resource, Deref, DerefMut)] -pub struct FloorSemiTransparency(f32); - -impl Default for FloorSemiTransparency { - fn default() -> Self { - FloorSemiTransparency(DEFAULT_FLOOR_SEMI_TRANSPARENCY) - } -} - pub const FALLBACK_FLOOR_SIZE: f32 = 0.1; pub const FLOOR_LAYER_START: f32 = DRAWING_LAYER_START + 0.001; @@ -181,11 +170,23 @@ fn floor_height(rank: Option<&RecencyRank>) -> f32 { .unwrap_or(FLOOR_LAYER_START) } +#[inline] fn floor_material( specific: Option<&LayerVisibility>, - general: &LayerVisibility, + general: Option<(&GlobalFloorVisibility, &RecencyRanking)>, ) -> StandardMaterial { - let alpha = specific.map(|s| s.alpha()).unwrap_or(general.alpha()); + let alpha = specific.copied() + .unwrap_or_else( + || general.map(|(v, r)| { + if r.is_empty() { + &v.without_drawings + } else { + &v.general + } + }).copied() + .unwrap_or(LayerVisibility::Opaque) + ).alpha(); + Color::rgba(0.3, 0.3, 0.3, alpha).into() } @@ -197,6 +198,7 @@ pub fn add_floor_visuals( &Path, Option<&RecencyRank>, Option<&LayerVisibility>, + Option<&Parent>, ), Added, >, @@ -204,25 +206,26 @@ pub fn add_floor_visuals( mut dependents: Query<&mut Dependents, With>, mut meshes: ResMut>, mut materials: ResMut>, - default_floor_visibility: Res, + default_floor_vis: Query<(&GlobalFloorVisibility, &RecencyRanking)>, ) { - for (e, new_floor, rank, vis) in &floors { + for (e, new_floor, rank, vis, parent) in &floors { let mesh = make_floor_mesh(e, new_floor, &anchors); let mut cmd = commands.entity(e); let height = floor_height(rank); - let material = materials.add(floor_material(vis, default_floor_visibility.as_ref())); + let default = parent.map(|p| default_floor_vis.get(p.get()).ok()).flatten(); + let material = materials.add(floor_material(vis, default)); let mesh_entity_id = cmd .insert(SpatialBundle { transform: Transform::from_xyz(0.0, 0.0, height), - ..default() + ..Default::default() }) .add_children(|p| { p.spawn(PbrBundle { mesh: meshes.add(mesh), // TODO(MXG): load the user-specified texture when one is given material, - ..default() + ..Default::default() }) .insert(Selectable::new(e)) .id() @@ -290,16 +293,18 @@ pub fn update_floor_for_moved_anchors( } } +#[inline] fn iter_update_floor_visibility<'a>( - iter: impl Iterator, &'a FloorSegments)>, + iter: impl Iterator, Option<&'a Parent>, &'a FloorSegments)>, material_handles: &Query<&Handle>, material_assets: &mut ResMut>, - default_floor_vis: &LayerVisibility, + default_floor_vis: &Query<(&GlobalFloorVisibility, &RecencyRanking)>, ) { - for (vis, segments) in iter { + for (vis, parent, segments) in iter { if let Ok(handle) = material_handles.get(segments.mesh) { if let Some(mat) = material_assets.get_mut(handle) { - *mat = floor_material(vis, &default_floor_vis); + let default = parent.map(|p| default_floor_vis.get(p.get()).ok()).flatten(); + *mat = floor_material(vis, default); } } } @@ -307,33 +312,37 @@ fn iter_update_floor_visibility<'a>( // TODO(luca) RemovedComponents is brittle, maybe wrap component in an option? pub fn update_floor_visibility( - changed_floors: Query<(Option<&LayerVisibility>, &FloorSegments), Changed>, + changed_floors: Query, Changed)>>, removed_vis: RemovedComponents, - all_floors: Query<(Option<&LayerVisibility>, &FloorSegments)>, + all_floors: Query<(Option<&LayerVisibility>, Option<&Parent>, &FloorSegments)>, material_handles: Query<&Handle>, mut material_assets: ResMut>, - default_floor_vis: Res, + default_floor_vis: Query<(&GlobalFloorVisibility, &RecencyRanking)>, + changed_default_floor_vis: Query< + &Children, + Or<(Changed, Changed>)>, + >, ) { - if default_floor_vis.is_changed() { - iter_update_floor_visibility( - all_floors.iter(), - &material_handles, - &mut material_assets, - &default_floor_vis, - ); - } else { + iter_update_floor_visibility( + changed_floors.iter().filter_map(|e| all_floors.get(e).ok()), + &material_handles, + &mut material_assets, + &default_floor_vis, + ); + + iter_update_floor_visibility( + removed_vis.iter().filter_map(|e| all_floors.get(e).ok()), + &material_handles, + &mut material_assets, + &default_floor_vis, + ); + + for children in &changed_default_floor_vis { iter_update_floor_visibility( - changed_floors.iter(), + children.iter().filter_map(|e| all_floors.get(*e).ok()), &material_handles, &mut material_assets, &default_floor_vis, ); - - iter_update_floor_visibility( - removed_vis.iter().filter_map(|e| all_floors.get(e).ok()), - &material_handles, - &mut material_assets, - &default_floor_vis, - ); - }; + } } diff --git a/rmf_site_editor/src/site/lane.rs b/rmf_site_editor/src/site/lane.rs index da9854ea..5f0fb1f7 100644 --- a/rmf_site_editor/src/site/lane.rs +++ b/rmf_site_editor/src/site/lane.rs @@ -49,7 +49,7 @@ fn should_display_lane( edge: &Edge, associated: &AssociatedGraphs, parents: &Query<&Parent>, - levels: &Query<(), With>, + levels: &Query<(), With>, current_level: &Res, graphs: &GraphSelect, ) -> bool { @@ -74,7 +74,7 @@ pub fn assign_orphan_nav_elements_to_site( ), >, current_workspace: Res, - open_sites: Query>, + open_sites: Query>, ) { if let Some(current_site) = current_workspace.to_site(&open_sites) { for e in &elements { @@ -89,7 +89,7 @@ pub fn add_lane_visuals( graphs: GraphSelect, anchors: AnchorParams, parents: Query<&Parent>, - levels: Query<(), With>, + levels: Query<(), With>, mut dependents: Query<&mut Dependents, With>, assets: Res, current_level: Res, @@ -241,7 +241,7 @@ pub fn update_changed_lane( >, anchors: AnchorParams, parents: Query<&Parent>, - levels: Query<(), With>, + levels: Query<(), With>, graphs: GraphSelect, mut transforms: Query<&mut Transform>, current_level: Res, @@ -309,7 +309,7 @@ pub fn update_visibility_for_lanes( (With, Without), >, parents: Query<&Parent>, - levels: Query<(), With>, + levels: Query<(), With>, current_level: Res, graphs: GraphSelect, lanes_with_changed_association: Query< diff --git a/rmf_site_editor/src/site/layer.rs b/rmf_site_editor/src/site/layer.rs deleted file mode 100644 index 4d6a1c73..00000000 --- a/rmf_site_editor/src/site/layer.rs +++ /dev/null @@ -1,101 +0,0 @@ -/* - * Copyright (C) 2023 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * -*/ - -use bevy::prelude::*; - -const DEFAULT_LAYER_SEMI_TRANSPARENCY: f32 = 0.2; - -#[derive(Debug, Clone, Copy, Component)] -pub enum LayerVisibility { - /// The layer is fully opaque. This is the default for floors when no drawing is - /// present. - Opaque, - /// Make the layer semi-transparent. This is useful for allowing layers - /// to be visible undearneath them. When a drawing is added to the scene, - /// the floors will automatically change to Alpha(0.1). - Alpha(f32), - /// The layer is fully hidden. - Hidden, -} - -// TODO(MXG): Should this trait be more general? -pub trait VisibilityCycle { - type Value; - fn next(&self, transparency: f32) -> Self::Value; - fn label(&self) -> &'static str; -} - -impl LayerVisibility { - pub fn new_semi_transparent() -> Self { - LayerVisibility::Alpha(DEFAULT_LAYER_SEMI_TRANSPARENCY) - } - - pub fn alpha(&self) -> f32 { - match self { - LayerVisibility::Opaque => 1.0, - LayerVisibility::Alpha(a) => *a, - LayerVisibility::Hidden => 0.0, - } - } -} - -impl VisibilityCycle for LayerVisibility { - type Value = Self; - - /// Cycle to the next visibility option - fn next(&self, transparency: f32) -> LayerVisibility { - match self { - LayerVisibility::Opaque => LayerVisibility::Alpha(transparency), - LayerVisibility::Alpha(_) => LayerVisibility::Hidden, - LayerVisibility::Hidden => LayerVisibility::Opaque, - } - } - - fn label(&self) -> &'static str { - match self { - LayerVisibility::Opaque => "opaque", - LayerVisibility::Alpha(_) => "semi-transparent", - LayerVisibility::Hidden => "hidden", - } - } -} - -impl VisibilityCycle for Option { - type Value = Self; - fn next(&self, transparency: f32) -> Self { - match self { - Some(v) => match v { - LayerVisibility::Hidden => None, - _ => Some(v.next(transparency)), - }, - None => Some(LayerVisibility::Opaque), - } - } - - fn label(&self) -> &'static str { - match self { - Some(v) => v.label(), - None => "global default", - } - } -} - -impl Default for LayerVisibility { - fn default() -> Self { - LayerVisibility::Opaque - } -} diff --git a/rmf_site_editor/src/site/level.rs b/rmf_site_editor/src/site/level.rs index f7368d3b..b5a7cf83 100644 --- a/rmf_site_editor/src/site/level.rs +++ b/rmf_site_editor/src/site/level.rs @@ -20,7 +20,7 @@ use crate::CurrentWorkspace; use bevy::prelude::*; pub fn update_level_visibility( - mut levels: Query<(Entity, &mut Visibility), With>, + mut levels: Query<(Entity, &mut Visibility), With>, current_level: Res, ) { if current_level.is_changed() { @@ -32,8 +32,8 @@ pub fn update_level_visibility( pub fn assign_orphan_levels_to_site( mut commands: Commands, - new_levels: Query, Added)>, - open_sites: Query>, + new_levels: Query, Added)>, + open_sites: Query>, current_workspace: Res, ) { if let Some(site) = current_workspace.to_site(&open_sites) { diff --git a/rmf_site_editor/src/site/lift.rs b/rmf_site_editor/src/site/lift.rs index 6fd2d822..e28c084d 100644 --- a/rmf_site_editor/src/site/lift.rs +++ b/rmf_site_editor/src/site/lift.rs @@ -110,7 +110,7 @@ pub fn add_tags_to_lift( mut commands: Commands, new_lifts: Query<(Entity, &Edge), Added>>, orphan_lifts: Query>, Without)>, - open_sites: Query>, + open_sites: Query>, mut dependents: Query<&mut Dependents, With>, current_workspace: Res, ) { @@ -159,7 +159,7 @@ pub fn update_lift_cabin( mut anchors: Query<&mut Anchor>, assets: Res, mut meshes: ResMut>, - levels: Query<(Entity, &Parent), With>, + levels: Query<(Entity, &Parent), With>, ) { for (e, cabin, recall, child_anchor_group, child_cabin_group, site) in &lifts { // Despawn the previous cabin @@ -348,9 +348,9 @@ pub fn update_lift_door_availability( mut doors: Query<(Entity, &Edge, &mut LevelVisits), With>, dependents: Query<&Dependents, With>, current_level: Res, - new_levels: Query<(), Added>, - all_levels: Query<(), With>, - removed_levels: RemovedComponents, + new_levels: Query<(), Added>, + all_levels: Query<(), With>, + removed_levels: RemovedComponents, parents: Query<&Parent>, ) { for toggle in toggles.iter() { diff --git a/rmf_site_editor/src/site/light.rs b/rmf_site_editor/src/site/light.rs index 0641d338..91c10166 100644 --- a/rmf_site_editor/src/site/light.rs +++ b/rmf_site_editor/src/site/light.rs @@ -27,7 +27,7 @@ use bevy::{ view::VisibleEntities, }, }; -use rmf_site_format::{Category, LevelProperties, Light, LightKind, Pose}; +use rmf_site_format::{Category, NameInSite, LevelElevation, Light, LightKind, Pose}; use std::collections::{BTreeMap, HashMap}; /// True/false for whether the physical lights of an environment should be @@ -143,14 +143,14 @@ pub struct ExportLights(pub std::path::PathBuf); pub fn export_lights( mut exports: EventReader, lights: Query<(&Pose, &LightKind, &Parent)>, - levels: Query<&LevelProperties>, + levels: Query<&NameInSite>, ) { for export in exports.iter() { let mut lights_per_level: BTreeMap> = BTreeMap::new(); for (pose, kind, parent) in &lights { - if let Ok(level) = levels.get(parent.get()) { + if let Ok(name) = levels.get(parent.get()) { lights_per_level - .entry(level.name.clone()) + .entry(name.0.clone()) .or_default() .push(Light { pose: pose.clone(), @@ -173,7 +173,7 @@ pub fn export_lights( let mut root: BTreeMap>> = BTreeMap::new(); for (level, lights) in lights_per_level { let mut lights_map: HashMap> = HashMap::new(); - lights_map.insert("lights".to_string(), lights); + lights_map.insert("lights".to_owned(), lights); root.insert(level, lights_map); } diff --git a/rmf_site_editor/src/site/load.rs b/rmf_site_editor/src/site/load.rs index a1984963..c11cb2d0 100644 --- a/rmf_site_editor/src/site/load.rs +++ b/rmf_site_editor/src/site/load.rs @@ -93,7 +93,7 @@ fn generate_site_entities(commands: &mut Commands, site_data: &rmf_site_format:: for (drawing_id, drawing) in &level_data.drawings { level - .spawn(DrawingBundle::new(drawing)) + .spawn(DrawingBundle::new(drawing.properties.clone())) .insert(SiteID(*drawing_id)) .with_children(|drawing_parent| { for (anchor_id, anchor) in &drawing.anchors { @@ -320,16 +320,17 @@ pub struct ImportNavGraphs { #[derive(SystemParam)] pub struct ImportNavGraphParams<'w, 's> { commands: Commands<'w, 's>, - sites: Query<'w, 's, &'static Children, With>, + sites: Query<'w, 's, &'static Children, With>, levels: Query< 'w, 's, ( Entity, - &'static LevelProperties, + &'static NameInSite, &'static Parent, &'static Children, ), + With, >, lifts: Query< 'w, @@ -357,12 +358,12 @@ fn generate_imported_nav_graphs( }; let mut level_name_to_entity = HashMap::new(); - for (e, level, parent, _) in ¶ms.levels { + for (e, name, parent, _) in ¶ms.levels { if parent.get() != into_site { continue; } - level_name_to_entity.insert(level.name.clone(), e); + level_name_to_entity.insert(name.clone().0, e); } let mut lift_name_to_entity = HashMap::new(); @@ -371,16 +372,16 @@ fn generate_imported_nav_graphs( continue; } - lift_name_to_entity.insert(name.0.clone(), e); + lift_name_to_entity.insert(name.clone().0, e); } let mut id_to_entity = HashMap::new(); for (level_id, level_data) in &from_site_data.levels { - if let Some(e) = level_name_to_entity.get(&level_data.properties.name) { + if let Some(e) = level_name_to_entity.get(&level_data.properties.name.0) { id_to_entity.insert(*level_id, *e); } else { return Err(ImportNavGraphError::MissingLevelName( - level_data.properties.name.clone(), + level_data.properties.name.0.clone(), )); } } @@ -523,7 +524,7 @@ pub fn import_nav_graph( mut import_requests: EventReader, mut autoload: Option>, current_workspace: Res, - open_sites: Query>, + open_sites: Query>, ) { for r in import_requests.iter() { if let Err(err) = generate_imported_nav_graphs(&mut params, r.into_site, &r.from_site) { diff --git a/rmf_site_editor/src/site/location.rs b/rmf_site_editor/src/site/location.rs index 535bf5a4..01d39b27 100644 --- a/rmf_site_editor/src/site/location.rs +++ b/rmf_site_editor/src/site/location.rs @@ -27,7 +27,7 @@ fn should_display_point( point: &Point, associated: &AssociatedGraphs, parents: &Query<&Parent>, - levels: &Query<(), With>, + levels: &Query<(), With>, current_level: &Res, graphs: &GraphSelect, ) -> bool { @@ -46,7 +46,7 @@ pub fn add_location_visuals( graphs: GraphSelect, anchors: AnchorParams, parents: Query<&Parent>, - levels: Query<(), With>, + levels: Query<(), With>, mut dependents: Query<&mut Dependents, With>, assets: Res, current_level: Res, @@ -99,7 +99,7 @@ pub fn update_changed_location( >, anchors: AnchorParams, parents: Query<&Parent>, - levels: Query<(), With>, + levels: Query<(), With>, graphs: GraphSelect, current_level: Res, ) { @@ -160,7 +160,7 @@ pub fn update_visibility_for_locations( (With, Without), >, parents: Query<&Parent>, - levels: Query<(), With>, + levels: Query<(), With>, current_level: Res, graphs: GraphSelect, locations_with_changed_association: Query< diff --git a/rmf_site_editor/src/site/mod.rs b/rmf_site_editor/src/site/mod.rs index 99103a6f..36930b77 100644 --- a/rmf_site_editor/src/site/mod.rs +++ b/rmf_site_editor/src/site/mod.rs @@ -51,9 +51,6 @@ pub use floor::*; pub mod lane; pub use lane::*; -pub mod layer; -pub use layer::*; - pub mod level; pub use level::*; @@ -151,13 +148,9 @@ impl Plugin for SitePlugin { .add_state_to_stage(SiteUpdateStage::AssignOrphans, SiteState::Off) .add_state_to_stage(CoreStage::PostUpdate, SiteState::Off) .insert_resource(ClearColor(Color::rgb(0., 0., 0.))) - .insert_resource(GlobalFloorVisibility::default()) - .insert_resource(GlobalDrawingVisibility::default()) .init_resource::() .init_resource::() .init_resource::() - .init_resource::() - .init_resource::() .add_event::() .add_event::() .add_event::() @@ -175,18 +168,18 @@ impl Plugin for SitePlugin { .add_plugin(RecallPlugin::::default()) .add_plugin(ChangePlugin::::default()) .add_plugin(RecallPlugin::::default()) + .add_plugin(ChangePlugin::::default()) .add_plugin(ChangePlugin::::default()) .add_plugin(ChangePlugin::::default()) .add_plugin(ChangePlugin::::default()) .add_plugin(ChangePlugin::::default()) - .add_plugin(ChangePlugin::::default()) .add_plugin(ChangePlugin::>::default()) .add_plugin(ChangePlugin::::default()) .add_plugin(ChangePlugin::