diff --git a/Cargo.lock b/Cargo.lock index 403d1dfbb9..a739b57406 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -1812,6 +1812,7 @@ dependencies = [ name = "bevyhavior_simulator" version = "0.1.0" dependencies = [ + "approx", "ball_filter", "bevy", "bincode", diff --git a/crates/bevyhavior_simulator/Cargo.toml b/crates/bevyhavior_simulator/Cargo.toml index b87000a76c..213c083ee6 100644 --- a/crates/bevyhavior_simulator/Cargo.toml +++ b/crates/bevyhavior_simulator/Cargo.toml @@ -6,6 +6,7 @@ license.workspace = true homepage.workspace = true [dependencies] +approx = { workspace = true } ball_filter = { workspace = true } bevy = { workspace = true } bincode = { workspace = true } diff --git a/crates/bevyhavior_simulator/src/bin/visual_referee_free_kick_behavior.rs b/crates/bevyhavior_simulator/src/bin/visual_referee_free_kick_behavior.rs new file mode 100644 index 0000000000..230cd5b9fa --- /dev/null +++ b/crates/bevyhavior_simulator/src/bin/visual_referee_free_kick_behavior.rs @@ -0,0 +1,133 @@ +use bevy::{ecs::system::SystemParam, prelude::*}; + +use linear_algebra::point; +use scenario::scenario; +use spl_network_messages::{GameState, PlayerNumber, SubState, Team}; + +use bevyhavior_simulator::{ + ball::BallResource, + game_controller::{GameController, GameControllerCommand}, + robot::Robot, + time::{Ticks, TicksTime}, +}; +use types::{field_dimensions::GlobalFieldSide, motion_command::HeadMotion, roles::Role}; + +/// Is used to generate the test functions for cargo test +#[scenario] +fn visual_referee_free_kick_behavior(app: &mut App) { + app.add_systems(Startup, startup); + app.add_systems(Update, update); +} + +#[derive(SystemParam)] +struct State<'s> { + number_of_detecting_robots_when_home: Local<'s, usize>, + number_of_detecting_robots_when_away: Local<'s, usize>, +} + +/// Runs at the start of the behavior simulator and is used to spawn in robots and set GameStates +fn startup( + mut commands: Commands, + mut game_controller_commands: EventWriter, +) { + for number in [ + PlayerNumber::One, + PlayerNumber::Two, + PlayerNumber::Three, + PlayerNumber::Four, + PlayerNumber::Five, + PlayerNumber::Six, + PlayerNumber::Seven, + ] { + commands.spawn(Robot::new(number)); + } + game_controller_commands.send(GameControllerCommand::SetGameState(GameState::Ready)); +} + +fn update( + mut game_controller: ResMut, + mut game_controller_commands: EventWriter, + time: Res>, + mut exit: EventWriter, + robots: Query<&mut Robot>, + mut ball: ResMut, + mut state: State, +) { + if time.ticks() >= 10_000 { + println!("Scenario failed: Time ran out. Behavior for detecting free kick kicking team was not executed correctly."); + exit.send(AppExit::from_code(1)); + } + + if time.ticks() == 3000 { + // Set substate + game_controller_commands.send(GameControllerCommand::SetSubState( + Some(SubState::PushingFreeKick), + Team::Opponent, + )); + } + + if time.ticks() == 3005 { + for relevant_robot in robots.iter().filter(|robot| { + matches!( + robot.database.main_outputs.role, + Role::DefenderRight | Role::MidfielderRight | Role::Searcher + ) + }) { + if matches!( + relevant_robot + .database + .main_outputs + .motion_command + .head_motion(), + Some(HeadMotion::LookAtReferee { .. }) + ) { + *state.number_of_detecting_robots_when_home += 1; + } + } + } + + if time.ticks() == 3500 { + // Set substate + game_controller_commands.send(GameControllerCommand::SetSubState(None, Team::Opponent)); + } + + if time.ticks() == 4000 { + // Set substate + game_controller_commands.send(GameControllerCommand::SetSubState( + Some(SubState::KickIn), + Team::Opponent, + )); + + game_controller.state.global_field_side = GlobalFieldSide::Away; + + if let Some(ball) = ball.state.as_mut() { + ball.position = point!(2.0, 4.5); + } + } + if time.ticks() == 4002 { + for relevant_robot in robots.iter().filter(|robot| { + matches!( + robot.database.main_outputs.role, + Role::DefenderLeft | Role::MidfielderLeft + ) + }) { + if matches!( + relevant_robot + .database + .main_outputs + .motion_command + .head_motion(), + Some(HeadMotion::LookAtReferee { .. }) + ) { + *state.number_of_detecting_robots_when_away += 1; + } + } + } + + if (*state.number_of_detecting_robots_when_home >= 2) + && (*state.number_of_detecting_robots_when_away >= 2) + { + println!("Done! Successfully performed behavior for free kick kicking team detection."); + exit.send(AppExit::Success); + } +} diff --git a/crates/bevyhavior_simulator/src/fake_data.rs b/crates/bevyhavior_simulator/src/fake_data.rs index eefaac2129..d904fea607 100644 --- a/crates/bevyhavior_simulator/src/fake_data.rs +++ b/crates/bevyhavior_simulator/src/fake_data.rs @@ -56,7 +56,7 @@ pub struct MainOutputs { pub ground_to_field: MainOutput>>, pub has_ground_contact: MainOutput, pub hulk_messages: MainOutput>, - pub majority_vote_is_referee_ready_pose_detected: MainOutput, + pub is_majority_vote_referee_ready_pose_detected: MainOutput, pub visual_referee_proceed_to_ready: MainOutput, pub hypothetical_ball_positions: MainOutput>>, pub is_localization_converged: MainOutput, @@ -88,8 +88,8 @@ impl FakeData { game_controller_address: last_database.game_controller_address.into(), has_ground_contact: last_database.has_ground_contact.into(), hulk_messages: last_database.hulk_messages.clone().into(), - majority_vote_is_referee_ready_pose_detected: last_database - .majority_vote_is_referee_ready_pose_detected + is_majority_vote_referee_ready_pose_detected: last_database + .is_majority_vote_referee_ready_pose_detected .into(), visual_referee_proceed_to_ready: last_database.visual_referee_proceed_to_ready.into(), hypothetical_ball_positions: last_database.hypothetical_ball_positions.clone().into(), diff --git a/crates/bevyhavior_simulator/src/game_controller.rs b/crates/bevyhavior_simulator/src/game_controller.rs index bc05ddb34d..735236fae1 100644 --- a/crates/bevyhavior_simulator/src/game_controller.rs +++ b/crates/bevyhavior_simulator/src/game_controller.rs @@ -5,7 +5,9 @@ use bevy::prelude::*; use spl_network_messages::{ GamePhase, GameState, Penalty, PlayerNumber, SubState, Team, TeamColor, TeamState, }; -use types::{game_controller_state::GameControllerState, players::Players}; +use types::{ + field_dimensions::GlobalFieldSide, game_controller_state::GameControllerState, players::Players, +}; use crate::{autoref::autoref, whistle::WhistleResource}; @@ -135,7 +137,7 @@ impl Default for GameController { penalties: Players::new(None), opponent_penalties: Players::new(None), sub_state: None, - hulks_team_is_home_after_coin_toss: true, + global_field_side: GlobalFieldSide::Home, hulks_team: TeamState { team_number: 24, field_player_color: TeamColor::Green, diff --git a/crates/bevyhavior_simulator/src/robot.rs b/crates/bevyhavior_simulator/src/robot.rs index 549a62d4e1..8d9f39b784 100644 --- a/crates/bevyhavior_simulator/src/robot.rs +++ b/crates/bevyhavior_simulator/src/robot.rs @@ -302,7 +302,7 @@ pub fn move_robots(mut robots: Query<&mut Robot>, mut ball: ResMut head } MotionCommand::SitDown { head } => head, - MotionCommand::Stand { head } => head, + MotionCommand::Stand { head, .. } => head, _ => HeadMotion::Center, }; @@ -313,6 +313,19 @@ pub fn move_robots(mut robots: Query<&mut Robot>, mut ball: ResMut robot.database.main_outputs.look_around.yaw } HeadMotion::LookAt { target, .. } => Orientation2::from_vector(target.coords()).angle(), + HeadMotion::LookAtReferee { .. } => { + if let Some(ground_to_field) = robot.database.main_outputs.ground_to_field { + let expected_referee_position = ground_to_field.inverse() + * robot + .database + .main_outputs + .expected_referee_position + .unwrap_or_default(); + Orientation2::from_vector(expected_referee_position.coords()).angle() + } else { + 0.0 + } + } HeadMotion::LookLeftAndRightOf { target } => { let glance_factor = 0.0; //self.time_elapsed.as_secs_f32().sin(); target.coords().angle(&Vector2::x_axis()) diff --git a/crates/control/src/behavior/initial.rs b/crates/control/src/behavior/initial.rs index 47374e5b31..913f602c81 100644 --- a/crates/control/src/behavior/initial.rs +++ b/crates/control/src/behavior/initial.rs @@ -1,76 +1,53 @@ -use coordinate_systems::Field; -use linear_algebra::Point2; use spl_network_messages::PlayerNumber; use types::{ camera_position::CameraPosition, + field_dimensions::GlobalFieldSide, filtered_game_state::FilteredGameState, motion_command::{HeadMotion, ImageRegion, MotionCommand}, primary_state::PrimaryState, world_state::WorldState, }; -pub fn execute( - world_state: &WorldState, - expected_referee_position: Option>, - enable_pose_detection: bool, -) -> Option { +pub fn execute(world_state: &WorldState, enable_pose_detection: bool) -> Option { + if world_state.robot.primary_state != PrimaryState::Initial + && world_state.robot.primary_state != PrimaryState::Standby + { + return None; + } + if world_state.robot.primary_state == PrimaryState::Initial { return Some(MotionCommand::Initial { head: HeadMotion::Center, - should_look_for_referee: false, }); } - if world_state.robot.primary_state == PrimaryState::Standby { - return Some( - look_at_referee( - expected_referee_position, - world_state.clone(), - enable_pose_detection, - ) - .unwrap_or(MotionCommand::Initial { - head: HeadMotion::Center, - should_look_for_referee: false, - }), - ); - } - None -} - -fn look_at_referee( - expected_referee_position: Option>, - world_state: WorldState, - enable_pose_detection: bool, -) -> Option { - let ground_to_field = world_state.robot.ground_to_field?; - let expected_referee_position = expected_referee_position?; - let filtered_game_controller_state = world_state.filtered_game_controller_state.as_ref()?; - if !enable_pose_detection - || filtered_game_controller_state.game_state != FilteredGameState::Standby - { - return None; - } - let position = ground_to_field.as_pose().position(); + let filtered_game_controller_state = world_state.filtered_game_controller_state.clone()?; - if position.y().signum() == expected_referee_position.y().signum() { - return None; - }; + let should_pose_detection_be_active = world_state.robot.primary_state == PrimaryState::Standby + && filtered_game_controller_state.game_state == FilteredGameState::Standby + && enable_pose_detection; - match ( - world_state.robot.player_number, - filtered_game_controller_state.own_team_is_home_after_coin_toss, - ) { - (PlayerNumber::Four | PlayerNumber::Seven, true) => {} - (PlayerNumber::Two | PlayerNumber::Six, false) => {} - _ => return None, - } + let player_number_should_look_for_referee = matches!( + ( + world_state.robot.player_number, + filtered_game_controller_state.global_field_side, + ), + ( + PlayerNumber::Four | PlayerNumber::Seven, + GlobalFieldSide::Home + ) | (PlayerNumber::Two | PlayerNumber::Six, GlobalFieldSide::Away) + ); Some(MotionCommand::Initial { - head: HeadMotion::LookAt { - target: ground_to_field.inverse() * expected_referee_position, - image_region_target: ImageRegion::Bottom, - camera: Some(CameraPosition::Top), + head: match ( + should_pose_detection_be_active, + player_number_should_look_for_referee, + ) { + (true, true) => HeadMotion::LookAtReferee { + image_region_target: ImageRegion::Bottom, + camera: Some(CameraPosition::Top), + }, + _ => HeadMotion::Center, }, - should_look_for_referee: true, }) } diff --git a/crates/control/src/behavior/look_at_referee.rs b/crates/control/src/behavior/look_at_referee.rs new file mode 100644 index 0000000000..846889e062 --- /dev/null +++ b/crates/control/src/behavior/look_at_referee.rs @@ -0,0 +1,17 @@ +use types::{ + camera_position::CameraPosition, + motion_command::{HeadMotion, ImageRegion, MotionCommand}, +}; + +pub fn execute(enable_pose_detection: bool) -> Option { + Some(MotionCommand::Stand { + head: if enable_pose_detection { + HeadMotion::LookAtReferee { + image_region_target: ImageRegion::Bottom, + camera: Some(CameraPosition::Top), + } + } else { + HeadMotion::Center + }, + }) +} diff --git a/crates/control/src/behavior/mod.rs b/crates/control/src/behavior/mod.rs index c29029c489..2caec2e478 100644 --- a/crates/control/src/behavior/mod.rs +++ b/crates/control/src/behavior/mod.rs @@ -8,6 +8,7 @@ mod initial; mod intercept_ball; mod jump; mod look_around; +mod look_at_referee; mod lost_ball; mod no_ground_contact; pub mod node; diff --git a/crates/control/src/behavior/node.rs b/crates/control/src/behavior/node.rs index 2f2b6590d9..cbc25574f6 100644 --- a/crates/control/src/behavior/node.rs +++ b/crates/control/src/behavior/node.rs @@ -11,7 +11,7 @@ use spl_network_messages::{GamePhase, PlayerNumber, SubState, Team}; use types::{ action::Action, cycle_time::CycleTime, - field_dimensions::{FieldDimensions, Side}, + field_dimensions::{FieldDimensions, GlobalFieldSide, Side}, filtered_game_controller_state::FilteredGameControllerState, filtered_game_state::FilteredGameState, motion_command::{MotionCommand, OrientationMode, WalkSpeed}, @@ -32,8 +32,8 @@ use super::{ defend::Defend, dribble, fall_safely, head::LookAction, - initial, intercept_ball, jump, look_around, lost_ball, no_ground_contact, penalize, - prepare_jump, search, sit_down, stand, stand_up, support, unstiff, walk_to_kick_off, + initial, intercept_ball, jump, look_around, look_at_referee, lost_ball, no_ground_contact, + penalize, prepare_jump, search, sit_down, stand, stand_up, support, unstiff, walk_to_kick_off, walk_to_penalty_kick, walk_to_pose::{WalkAndStand, WalkPathPlanner}, }; @@ -50,7 +50,6 @@ pub struct CreationContext {} #[context] pub struct CycleContext { - expected_referee_position: Input>, "expected_referee_position?">, has_ground_contact: Input, world_state: Input, dribble_path_plan: Input)>, "dribble_path_plan?">, @@ -156,6 +155,17 @@ impl Behavior { actions.push(Action::InterceptBall); match world_state.robot.role { + Role::DefenderLeft + if world_state + .filtered_game_controller_state + .clone() + .is_some_and(|filtered_game_controller_state| { + is_free_kick(filtered_game_controller_state, world_state) + }) => + { + actions.push(Action::LookAtReferee); + actions.push(Action::DefendLeft); + } Role::DefenderLeft => match world_state.filtered_game_controller_state { Some(FilteredGameControllerState { sub_state: Some(SubState::CornerKick), @@ -164,6 +174,17 @@ impl Behavior { }) => actions.push(Action::DefendOpponentCornerKick { side: Side::Left }), _ => actions.push(Action::DefendLeft), }, + Role::DefenderRight + if world_state + .filtered_game_controller_state + .clone() + .is_some_and(|filtered_game_controller_state| { + is_free_kick(filtered_game_controller_state, world_state) + }) => + { + actions.push(Action::LookAtReferee); + actions.push(Action::DefendRight); + } Role::DefenderRight => match world_state.filtered_game_controller_state { Some(FilteredGameControllerState { sub_state: Some(SubState::CornerKick), @@ -189,9 +210,42 @@ impl Behavior { _ => actions.push(Action::DefendGoal), }, Role::Loser => actions.push(Action::SearchForLostBall), + Role::MidfielderLeft + if world_state + .filtered_game_controller_state + .clone() + .is_some_and(|filtered_game_controller_state| { + is_free_kick(filtered_game_controller_state, world_state) + }) => + { + actions.push(Action::LookAtReferee); + actions.push(Action::SupportLeft); + } Role::MidfielderLeft => actions.push(Action::SupportLeft), + Role::MidfielderRight + if world_state + .filtered_game_controller_state + .clone() + .is_some_and(|filtered_game_controller_state| { + is_free_kick(filtered_game_controller_state, world_state) + }) => + { + actions.push(Action::LookAtReferee); + actions.push(Action::SupportRight); + } Role::MidfielderRight => actions.push(Action::SupportRight), Role::ReplacementKeeper => actions.push(Action::DefendGoal), + Role::Searcher + if world_state + .filtered_game_controller_state + .clone() + .is_some_and(|filtered_game_controller_state| { + is_free_kick(filtered_game_controller_state, world_state) + }) => + { + actions.push(Action::LookAtReferee); + actions.push(Action::Search); + } Role::Searcher => actions.push(Action::Search), Role::Striker => match world_state.filtered_game_controller_state { None @@ -256,11 +310,12 @@ impl Behavior { Action::Unstiff => unstiff::execute(world_state), Action::SitDown => sit_down::execute(world_state), Action::Penalize => penalize::execute(world_state), - Action::Initial => initial::execute( - world_state, - context.expected_referee_position.cloned(), - *context.enable_pose_detection, - ), + Action::Initial => { + initial::execute(world_state, *context.enable_pose_detection) + } + Action::LookAtReferee => { + look_at_referee::execute(*context.enable_pose_detection) + } Action::FallSafely => { fall_safely::execute(world_state, *context.has_ground_contact) } @@ -484,3 +539,47 @@ impl Behavior { }) } } + +pub fn is_free_kick( + filtered_game_controller_state: FilteredGameControllerState, + world_state: &WorldState, +) -> bool { + let is_free_kick_filtered_game_controller_state = matches!( + filtered_game_controller_state, + FilteredGameControllerState { + sub_state: Some(SubState::KickIn) | Some(SubState::PushingFreeKick), + game_state: FilteredGameState::Playing { + ball_is_free: false, + .. + }, + .. + } + ); + + let first_two_nonpenalized_nonkeeper_player_numbers: Vec = + filtered_game_controller_state + .penalties + .iter() + .filter_map(|(player_number, penalty)| penalty.is_none().then_some(player_number)) + // Skip the lowest non-penalized player number since this is always the Keeper or ReplacementKeeper + .skip(1) + .take(2) + .collect(); + + let is_correct_free_kick_role = match ( + world_state.robot.role, + filtered_game_controller_state.global_field_side, + ) { + (Role::DefenderRight | Role::MidfielderRight, GlobalFieldSide::Home) => true, + (Role::DefenderLeft | Role::MidfielderLeft, GlobalFieldSide::Away) => true, + (Role::Searcher, _) + if first_two_nonpenalized_nonkeeper_player_numbers + .contains(&world_state.robot.player_number) => + { + true + } + _ => false, + }; + + is_free_kick_filtered_game_controller_state && is_correct_free_kick_role +} diff --git a/crates/control/src/behavior/stand.rs b/crates/control/src/behavior/stand.rs index 04c848fb63..0692116834 100644 --- a/crates/control/src/behavior/stand.rs +++ b/crates/control/src/behavior/stand.rs @@ -19,34 +19,41 @@ pub fn execute( }), PrimaryState::Set => { let ground_to_field = world_state.robot.ground_to_field?; - let (fallback_target, is_opponent_penalty_kick) = - match world_state.filtered_game_controller_state { - Some(FilteredGameControllerState { - sub_state: Some(SubState::PenaltyKick), - kicking_team, - .. - }) - | Some(FilteredGameControllerState { - game_phase: GamePhase::PenaltyShootout { .. }, - kicking_team, - .. - }) => { - let (half, is_opponent_penalty_kick) = match kicking_team { - Team::Hulks => (Half::Opponent, false), - Team::Opponent => (Half::Own, true), - }; - ( - world_state - .rule_ball - .map(|rule_ball| rule_ball.ball_in_ground) - .unwrap_or({ - ground_to_field.inverse() * field_dimensions.penalty_spot(half) - }), - is_opponent_penalty_kick, - ) - } - _ => (ground_to_field.inverse().as_pose().position(), false), - }; + let (fallback_target, is_opponent_penalty_kick) = match world_state + .filtered_game_controller_state + { + Some(FilteredGameControllerState { + sub_state: Some(SubState::PenaltyKick), + kicking_team, + .. + }) + | Some(FilteredGameControllerState { + game_phase: GamePhase::PenaltyShootout { .. }, + kicking_team, + .. + }) => match kicking_team { + Team::Hulks => ( + world_state + .rule_ball + .map(|rule_ball| rule_ball.ball_in_ground) + .unwrap_or({ + ground_to_field.inverse() + * field_dimensions.penalty_spot(Half::Opponent) + }), + false, + ), + Team::Opponent => ( + world_state + .rule_ball + .map(|rule_ball| rule_ball.ball_in_ground) + .unwrap_or({ + ground_to_field.inverse() * field_dimensions.penalty_spot(Half::Own) + }), + true, + ), + }, + _ => (ground_to_field.inverse().as_pose().position(), false), + }; let target = world_state .ball .map(|state| state.ball_in_ground) @@ -92,17 +99,23 @@ pub fn execute( None, ) => { let ground_to_field = world_state.robot.ground_to_field?; - let half = match kicking_team { - Team::Hulks => Half::Opponent, - Team::Opponent => Half::Own, + let target = match kicking_team { + Team::Hulks => world_state + .ball + .or(world_state.rule_ball) + .map(|ball| ball.ball_in_ground) + .unwrap_or({ + ground_to_field.inverse() + * field_dimensions.penalty_spot(Half::Opponent) + }), + Team::Opponent => world_state + .ball + .or(world_state.rule_ball) + .map(|ball| ball.ball_in_ground) + .unwrap_or({ + ground_to_field.inverse() * field_dimensions.penalty_spot(Half::Own) + }), }; - let target = world_state - .ball - .or(world_state.rule_ball) - .map(|ball| ball.ball_in_ground) - .unwrap_or({ - ground_to_field.inverse() * field_dimensions.penalty_spot(half) - }); Some(MotionCommand::Stand { head: HeadMotion::LookAt { diff --git a/crates/control/src/free_kick_signal_filter.rs b/crates/control/src/free_kick_signal_filter.rs new file mode 100644 index 0000000000..1aa295f60f --- /dev/null +++ b/crates/control/src/free_kick_signal_filter.rs @@ -0,0 +1,258 @@ +use std::{ + collections::{BTreeMap, VecDeque}, + time::{Duration, SystemTime}, +}; + +use color_eyre::Result; +use serde::{Deserialize, Serialize}; + +use context_attribute::context; +use framework::{AdditionalOutput, MainOutput, PerceptionInput}; +use hardware::NetworkInterface; +use spl_network_messages::{PlayerNumber, Team}; +use types::{ + cycle_time::CycleTime, + field_dimensions::GlobalFieldSide, + filtered_game_controller_state::FilteredGameControllerState, + messages::IncomingMessage, + players::Players, + pose_detection::{FreeKickSignalDetectionResult, TimeTaggedKickingTeamDetections}, + pose_kinds::PoseKind, +}; + +#[derive(Deserialize, Serialize)] +pub struct FreeKickSignalFilter { + free_kick_signal_detection_times: Players>, + detected_free_kick_detections_queue: VecDeque, + has_sent_free_kick_signal_message: bool, +} + +#[context] +pub struct CreationContext { + referee_pose_queue_length: Parameter, +} + +#[context] +pub struct CycleContext { + hardware_interface: HardwareInterface, + + referee_pose_kind: + PerceptionInput, "ObjectDetectionTop", "referee_pose_kind?">, + network_message: PerceptionInput, "SplNetwork", "filtered_message?">, + filtered_game_controller_state: + RequiredInput, "filtered_game_controller_state?">, + + cycle_time: Input, + + initial_message_grace_period: + Parameter, + minimum_free_kick_signal_detections: + Parameter, + player_number: Parameter, + referee_pose_queue_length: Parameter, + minimum_number_poses_before_message: + Parameter, + + free_kick_detection_times: AdditionalOutput< + Players>, + "free_kick_detection_times", + >, + free_kick_detections_queue: AdditionalOutput, "free_kick_detections_queue">, +} + +#[context] +#[derive(Default)] +pub struct MainOutputs { + pub did_detect_any_free_kick_signal_this_cycle: MainOutput, + pub detected_free_kick_kicking_team: MainOutput>, +} + +impl FreeKickSignalFilter { + pub fn new(context: CreationContext) -> Result { + Ok(Self { + detected_free_kick_detections_queue: VecDeque::with_capacity( + *context.referee_pose_queue_length, + ), + free_kick_signal_detection_times: Default::default(), + has_sent_free_kick_signal_message: false, + }) + } + + pub fn cycle( + &mut self, + mut context: CycleContext, + ) -> Result { + let free_kick_signal_detection_result = self.update(&context)?; + + context + .free_kick_detection_times + .fill_if_subscribed(|| self.free_kick_signal_detection_times); + + context + .free_kick_detections_queue + .fill_if_subscribed(|| self.detected_free_kick_detections_queue.clone()); + + Ok(MainOutputs { + detected_free_kick_kicking_team: free_kick_signal_detection_result + .detected_free_kick_kicking_team + .into(), + did_detect_any_free_kick_signal_this_cycle: free_kick_signal_detection_result + .did_detect_any_free_kick_signal_this_cycle + .into(), + }) + } + + fn update( + &mut self, + context: &CycleContext, + ) -> Result { + let own_detected_pose_times: BTreeMap> = + unpack_own_detections(&context.referee_pose_kind.persistent); + + let mut did_detect_any_free_kick_signal_this_cycle = false; + + for (_, detection) in own_detected_pose_times { + let detected_kicking_team = kicking_team_from_free_kick_signal_detection( + detection, + context.filtered_game_controller_state.global_field_side, + ); + if let Some(detected_kicking_team) = detected_kicking_team { + self.detected_free_kick_detections_queue + .push_front(detected_kicking_team); + did_detect_any_free_kick_signal_this_cycle = true + } else { + continue; + } + } + + self.detected_free_kick_detections_queue + .truncate(*context.referee_pose_queue_length); + + let (own_detected_kicking_team, number_of_detections) = + most_detections(self.detected_free_kick_detections_queue.clone().into()); + + if number_of_detections >= *context.minimum_number_poses_before_message { + self.free_kick_signal_detection_times[*context.player_number] = + Some(TimeTaggedKickingTeamDetections { + time: context.cycle_time.start_time, + detected_kicking_team: own_detected_kicking_team, + }); + } + + let majority_voted_kicking_team_detection = majority_vote_free_kick_signal( + self.free_kick_signal_detection_times, + context.cycle_time.start_time, + *context.initial_message_grace_period, + *context.minimum_free_kick_signal_detections, + ); + + Ok(FreeKickSignalDetectionResult { + did_detect_any_free_kick_signal_this_cycle, + detected_free_kick_kicking_team: majority_voted_kicking_team_detection, + }) + } +} + +fn most_detections(detections: Vec) -> (Team, usize) { + let own_detections_hulks: Vec = detections + .iter() + .cloned() + .filter(|kicking_team| *kicking_team == Team::Hulks) + .collect(); + let own_detections_opponent: Vec = detections + .iter() + .cloned() + .filter(|kicking_team| *kicking_team == Team::Opponent) + .collect(); + + if own_detections_hulks.len() > own_detections_opponent.len() { + (Team::Hulks, own_detections_hulks.len()) + } else { + (Team::Opponent, own_detections_opponent.len()) + } +} + +fn kicking_team_from_free_kick_signal_detection( + free_kick_signal_pose: Option, + global_field_side: GlobalFieldSide, +) -> Option { + match (global_field_side, free_kick_signal_pose) { + ( + GlobalFieldSide::Home, + Some(PoseKind::FreeKick { + global_field_side: GlobalFieldSide::Away, + }), + ) => Some(Team::Hulks), + ( + GlobalFieldSide::Home, + Some(PoseKind::FreeKick { + global_field_side: GlobalFieldSide::Home, + }), + ) => Some(Team::Opponent), + ( + GlobalFieldSide::Away, + Some(PoseKind::FreeKick { + global_field_side: GlobalFieldSide::Away, + }), + ) => Some(Team::Opponent), + ( + GlobalFieldSide::Away, + Some(PoseKind::FreeKick { + global_field_side: GlobalFieldSide::Home, + }), + ) => Some(Team::Hulks), + _ => None, + } +} + +fn majority_vote_free_kick_signal( + free_kick_signal_detection_times: Players>, + cycle_start_time: SystemTime, + initial_message_grace_period: Duration, + minimum_free_kick_signal_detections: usize, +) -> Option { + let still_valid_detections = free_kick_signal_detection_times + .iter() + .filter_map(|(_, time_tagged_detection)| match time_tagged_detection { + Some(TimeTaggedKickingTeamDetections { + time, + detected_kicking_team, + }) if is_in_grace_period(cycle_start_time, *time, initial_message_grace_period) => { + Some(*detected_kicking_team) + } + _ => None, + }) + .collect(); + + let (majority_voted_kicking_team, number_of_detections) = + most_detections(still_valid_detections); + if number_of_detections >= minimum_free_kick_signal_detections { + Some(majority_voted_kicking_team) + } else { + None + } +} + +fn is_in_grace_period( + cycle_start_time: SystemTime, + earlier_time: SystemTime, + grace_period: Duration, +) -> bool { + cycle_start_time + .duration_since(earlier_time) + .expect("Time ran backwards") + < grace_period +} + +fn unpack_own_detections( + detections: &BTreeMap>>, +) -> BTreeMap> { + detections + .iter() + .flat_map(|(time, pose_kinds)| { + pose_kinds + .iter() + .map(|&pose_kind| (*time, pose_kind.cloned())) + }) + .collect() +} diff --git a/crates/control/src/game_controller_filter.rs b/crates/control/src/game_controller_filter.rs index c025599971..dc37eefd63 100644 --- a/crates/control/src/game_controller_filter.rs +++ b/crates/control/src/game_controller_filter.rs @@ -13,6 +13,7 @@ use spl_network_messages::GameControllerStateMessage; use types::{ audio::{Sound, SpeakerRequest}, cycle_time::CycleTime, + field_dimensions::GlobalFieldSide, game_controller_state::GameControllerState, messages::IncomingMessage, }; @@ -118,7 +119,11 @@ impl GameControllerFilter { penalties: message.hulks_team.clone().into(), opponent_penalties: message.opponent_team.clone().into(), sub_state: message.sub_state, - hulks_team_is_home_after_coin_toss: message.hulks_team_is_home_after_coin_toss, + global_field_side: if message.hulks_team_is_home_after_coin_toss { + GlobalFieldSide::Home + } else { + GlobalFieldSide::Away + }, hulks_team: message.hulks_team.clone(), opponent_team: message.opponent_team.clone(), }); diff --git a/crates/control/src/game_controller_state_filter.rs b/crates/control/src/game_controller_state_filter.rs index 883f610f70..9d594c5622 100644 --- a/crates/control/src/game_controller_state_filter.rs +++ b/crates/control/src/game_controller_state_filter.rs @@ -105,9 +105,7 @@ impl GameControllerStateFilter { .hulks_team .remaining_amount_of_messages, sub_state: context.game_controller_state.sub_state, - own_team_is_home_after_coin_toss: context - .game_controller_state - .hulks_team_is_home_after_coin_toss, + global_field_side: context.game_controller_state.global_field_side, new_own_penalties_last_cycle, new_opponent_penalties_last_cycle, }; diff --git a/crates/control/src/led_status.rs b/crates/control/src/led_status.rs index 54593d0ae8..86a6dda8b5 100644 --- a/crates/control/src/led_status.rs +++ b/crates/control/src/led_status.rs @@ -4,6 +4,7 @@ use color_eyre::Result; use context_attribute::context; use framework::{MainOutput, PerceptionInput}; use serde::{Deserialize, Serialize}; +use spl_network_messages::Team; use types::{ ball_detection::BallPercept, color::Rgb, @@ -34,8 +35,11 @@ pub struct CycleContext { cycle_time: Input, filtered_whistle: Input, role: Input, - is_own_referee_ready_pose_detected: Input, - did_detect_any_referee_this_cycle: Input, + is_own_referee_ready_pose_detected: Input, + did_detect_any_ready_signal_this_cycle: Input, + detected_free_kick_kicking_team: Input, "detected_free_kick_kicking_team?">, + did_detect_any_free_kick_signal_this_cycle: + Input, balls_bottom: PerceptionInput>, "VisionBottom", "balls?">, balls_top: PerceptionInput>, "VisionTop", "balls?">, @@ -185,7 +189,9 @@ impl LedStatus { context.role, ball_percepts, *context.is_own_referee_ready_pose_detected, - *context.did_detect_any_referee_this_cycle, + *context.did_detect_any_ready_signal_this_cycle, + context.detected_free_kick_kicking_team.copied(), + *context.did_detect_any_free_kick_signal_this_cycle, ); if let Some(latest_game_controller_message_time) = context @@ -272,6 +278,7 @@ impl LedStatus { ear } + #[allow(clippy::too_many_arguments)] fn get_eyes( cycle_start_time: SystemTime, primary_state: &PrimaryState, @@ -279,6 +286,8 @@ impl LedStatus { ball_percepts: BallPercepts, is_own_referee_ready_pose_detected: bool, did_detect_any_referee_this_cycle: bool, + detected_free_kick_kicking_team: Option, + did_detect_any_free_kick_signal_this_cycle: bool, ) -> (Eye, Eye) { match primary_state { PrimaryState::Unstiff | PrimaryState::Animation { .. } => { @@ -314,12 +323,16 @@ impl LedStatus { Role::Striker => Rgb::RED, Role::StrikerSupporter => Rgb::TURQUOISE, }; - let filtered_referee_ready_color = if is_own_referee_ready_pose_detected { + let filtered_referee_ready_color = if is_own_referee_ready_pose_detected + | detected_free_kick_kicking_team.is_some() + { Some(Rgb::YELLOW) } else { None }; - let referee_ready_percept_color = if did_detect_any_referee_this_cycle { + let referee_ready_percept_color = if did_detect_any_referee_this_cycle + | did_detect_any_free_kick_signal_this_cycle + { Some(Rgb::PURPLE) } else { None diff --git a/crates/control/src/lib.rs b/crates/control/src/lib.rs index 4a676c2fe4..24bcf18f08 100644 --- a/crates/control/src/lib.rs +++ b/crates/control/src/lib.rs @@ -11,6 +11,7 @@ pub mod dribble_path_planner; pub mod fall_state_estimation; pub mod filtered_game_controller_state_timer; pub mod foot_bumper_filter; +pub mod free_kick_signal_filter; pub mod game_controller_filter; pub mod game_controller_state_filter; pub mod ground_contact_detector; @@ -27,7 +28,7 @@ pub mod orientation_filter; pub mod path_planner; pub mod penalty_shot_direction_estimation; pub mod primary_state_filter; -pub mod referee_pose_detection_filter; +pub mod ready_signal_detection_filter; pub mod referee_position_provider; pub mod role_assignment; pub mod rule_obstacle_composer; diff --git a/crates/control/src/localization.rs b/crates/control/src/localization.rs index 9f6e0f3744..9d47f72d25 100644 --- a/crates/control/src/localization.rs +++ b/crates/control/src/localization.rs @@ -18,7 +18,7 @@ use framework::{AdditionalOutput, HistoricInput, MainOutput, PerceptionInput}; use spl_network_messages::{GamePhase, Penalty, PlayerNumber, SubState, Team}; use types::{ cycle_time::CycleTime, - field_dimensions::FieldDimensions, + field_dimensions::{FieldDimensions, GlobalFieldSide}, field_marks::{field_marks_from_field_dimensions, CorrespondencePoints, Direction, FieldMark}, filtered_game_controller_state::FilteredGameControllerState, initial_pose::InitialPose, @@ -577,7 +577,7 @@ impl Localization { Some((ground_to_field, context.filtered_game_controller_state?)) }) .map(|(ground_to_field, game_controller_state)| { - if !game_controller_state.own_team_is_home_after_coin_toss { + if game_controller_state.global_field_side == GlobalFieldSide::Away { (nalgebra::Isometry2::from_parts( Translation2::default(), Rotation2::new(PI).into(), diff --git a/crates/control/src/motion/head_motion.rs b/crates/control/src/motion/head_motion.rs index 81912d7388..a2e1fbaa35 100644 --- a/crates/control/src/motion/head_motion.rs +++ b/crates/control/src/motion/head_motion.rs @@ -140,6 +140,7 @@ impl HeadMotion { } } Some(HeadMotionCommand::LookAt { .. }) + | Some(HeadMotionCommand::LookAtReferee { .. }) | Some(HeadMotionCommand::LookLeftAndRightOf { .. }) => MotorCommands { positions: *context.look_at, stiffnesses, diff --git a/crates/control/src/motion/look_around.rs b/crates/control/src/motion/look_around.rs index 3f8c9105ee..189520c9c9 100644 --- a/crates/control/src/motion/look_around.rs +++ b/crates/control/src/motion/look_around.rs @@ -6,6 +6,7 @@ use framework::{AdditionalOutput, MainOutput}; use serde::{Deserialize, Serialize}; use types::{ cycle_time::CycleTime, + field_dimensions::GlobalFieldSide, filtered_game_controller_state::FilteredGameControllerState, initial_look_around::{ BallSearchLookAround, InitialLookAround, LookAroundMode, QuickLookAround, @@ -63,7 +64,8 @@ impl LookAround { Some(HeadMotion::LookAround) => context.filtered_game_controller_state.map_or( LookAroundMode::Initial(Default::default()), |filtered_game_controller_state| { - if filtered_game_controller_state.own_team_is_home_after_coin_toss { + if filtered_game_controller_state.global_field_side == GlobalFieldSide::Home + { LookAroundMode::Initial(InitialLookAround::Left) } else { LookAroundMode::Initial(InitialLookAround::Right) diff --git a/crates/control/src/motion/look_at.rs b/crates/control/src/motion/look_at.rs index e5932a54ab..f7b8660fdb 100644 --- a/crates/control/src/motion/look_at.rs +++ b/crates/control/src/motion/look_at.rs @@ -6,7 +6,7 @@ use projection::{camera_matrices::CameraMatrices, camera_matrix::CameraMatrix}; use serde::{Deserialize, Serialize}; use context_attribute::context; -use coordinate_systems::{Camera, Ground, Head, Robot}; +use coordinate_systems::{Camera, Field, Ground, Head, Robot}; use framework::MainOutput; use linear_algebra::{distance, point, vector, Isometry3, Point2}; use types::{ @@ -16,6 +16,7 @@ use types::{ motion_command::{GlanceDirection, HeadMotion, ImageRegion, MotionCommand}, parameters::ImageRegionParameters, sensor_data::SensorData, + world_state::WorldState, }; #[derive(Deserialize, Serialize)] @@ -34,6 +35,8 @@ pub struct CycleContext { ground_to_robot: Input>, "ground_to_robot?">, motion_command: Input, sensor_data: Input, + expected_referee_position: Input>, "expected_referee_position?">, + world_state: Input, glance_angle: Parameter, image_region_parameters: Parameter, @@ -73,6 +76,11 @@ impl LookAt { None => return default_output, }; + let ground_to_field = match context.world_state.robot.ground_to_field { + Some(ground_to_robot) => ground_to_robot, + None => return default_output, + }; + let head_motion = match context.motion_command { MotionCommand::Initial { head, .. } => head, MotionCommand::SitDown { head } => head, @@ -92,12 +100,21 @@ impl LookAt { self.last_glance_direction_toggle = Some(cycle_start_time); } + let expected_referee_position = ground_to_field.inverse() + * context + .expected_referee_position + .unwrap_or(&point!(0.0, 0.0)); + let (target, image_region_target, camera) = match *head_motion { HeadMotion::LookAt { target, image_region_target, camera, } => (target, image_region_target, camera), + HeadMotion::LookAtReferee { + image_region_target, + camera, + } => (expected_referee_position, image_region_target, camera), HeadMotion::LookLeftAndRightOf { target } => { let left_right_shift = vector![ 0.0, diff --git a/crates/control/src/referee_pose_detection_filter.rs b/crates/control/src/ready_signal_detection_filter.rs similarity index 51% rename from crates/control/src/referee_pose_detection_filter.rs rename to crates/control/src/ready_signal_detection_filter.rs index 8062ca9cc1..6fa4720722 100644 --- a/crates/control/src/referee_pose_detection_filter.rs +++ b/crates/control/src/ready_signal_detection_filter.rs @@ -10,21 +10,22 @@ use serde::{Deserialize, Serialize}; use context_attribute::context; use framework::{AdditionalOutput, MainOutput, PerceptionInput}; use hardware::NetworkInterface; -use spl_network_messages::{HulkMessage, PlayerNumber, VisualRefereeMessage}; +use spl_network_messages::{GameState, HulkMessage, PlayerNumber, VisualRefereeMessage}; use types::{ cycle_time::CycleTime, + game_controller_state::GameControllerState, messages::{IncomingMessage, OutgoingMessage}, players::Players, - pose_detection::VisualRefereeState, + pose_detection::{ReadySignalDetectionFeedback, ReadySignalState}, pose_kinds::PoseKind, }; #[derive(Deserialize, Serialize)] -pub struct RefereePoseDetectionFilter { - detection_times: Players>, - detected_above_arm_poses_queue: VecDeque, +pub struct ReadySignalDetectionFilter { + ready_signal_detection_times: Players>, + detected_ready_signal_queue: VecDeque, motion_in_standby_count: usize, - visual_referee_state: VisualRefereeState, + ready_signal_state: ReadySignalState, } #[context] @@ -41,11 +42,12 @@ pub struct CycleContext { network_message: PerceptionInput, "SplNetwork", "filtered_message?">, cycle_time: Input, + game_controller_state: RequiredInput, "game_controller_state?">, initial_message_grace_period: - Parameter, - minimum_above_head_arms_detections: - Parameter, + Parameter, + minimum_ready_signal_detections: + Parameter, player_number: Parameter, referee_pose_queue_length: Parameter, minimum_number_poses_before_message: @@ -59,20 +61,20 @@ pub struct CycleContext { #[context] #[derive(Default)] pub struct MainOutputs { - pub majority_vote_is_referee_ready_pose_detected: MainOutput, - pub is_referee_ready_pose_detected: MainOutput, - pub did_detect_any_referee_this_cycle: MainOutput, + pub is_majority_vote_referee_ready_pose_detected: MainOutput, + pub is_own_referee_ready_pose_detected: MainOutput, + pub did_detect_any_ready_signal_this_cycle: MainOutput, } -impl RefereePoseDetectionFilter { +impl ReadySignalDetectionFilter { pub fn new(context: CreationContext) -> Result { Ok(Self { - visual_referee_state: VisualRefereeState::WaitingForDetections, - detection_times: Default::default(), - motion_in_standby_count: 0, - detected_above_arm_poses_queue: VecDeque::with_capacity( + ready_signal_detection_times: Default::default(), + detected_ready_signal_queue: VecDeque::with_capacity( *context.referee_pose_queue_length, ), + motion_in_standby_count: 0, + ready_signal_state: ReadySignalState::WaitingForDetections, }) } @@ -80,81 +82,117 @@ impl RefereePoseDetectionFilter { &mut self, mut context: CycleContext, ) -> Result { + if !matches!( + context.game_controller_state.game_state, + GameState::Standby { .. } + ) { + self.detected_ready_signal_queue = Default::default(); + self.motion_in_standby_count = Default::default(); + self.ready_signal_detection_times = Default::default(); + self.ready_signal_state = Default::default(); + + return Ok(MainOutputs { + is_majority_vote_referee_ready_pose_detected: false.into(), + is_own_referee_ready_pose_detected: false.into(), + did_detect_any_ready_signal_this_cycle: false.into(), + }); + } + let cycle_start_time = context.cycle_time.start_time; - let (is_referee_ready_pose_detected, did_detect_any_referee_this_cycle) = - self.update(&context)?; + let ready_signal_detection_feedback = self.update_own_detections(&context)?; - let majority_vote_is_referee_ready_pose_detected = decide( - self.detection_times, + let is_majority_vote_referee_ready_pose_detected = majority_vote_ready_signal( + self.ready_signal_detection_times, cycle_start_time, *context.initial_message_grace_period, - *context.minimum_above_head_arms_detections, + *context.minimum_ready_signal_detections, ); context .player_referee_detection_times - .fill_if_subscribed(|| self.detection_times); + .fill_if_subscribed(|| self.ready_signal_detection_times); context .referee_pose_queue - .fill_if_subscribed(|| self.detected_above_arm_poses_queue.clone()); + .fill_if_subscribed(|| self.detected_ready_signal_queue.clone()); Ok(MainOutputs { - majority_vote_is_referee_ready_pose_detected: - majority_vote_is_referee_ready_pose_detected.into(), - is_referee_ready_pose_detected: is_referee_ready_pose_detected.into(), - did_detect_any_referee_this_cycle: did_detect_any_referee_this_cycle.into(), + is_majority_vote_referee_ready_pose_detected: + is_majority_vote_referee_ready_pose_detected.into(), + is_own_referee_ready_pose_detected: ready_signal_detection_feedback + .is_referee_ready_pose_detected + .into(), + did_detect_any_ready_signal_this_cycle: ready_signal_detection_feedback + .did_detect_any_ready_signal_this_cycle + .into(), }) } - fn update(&mut self, context: &CycleContext) -> Result<(bool, bool)> { + fn update_own_detections( + &mut self, + context: &CycleContext, + ) -> Result { let time_tagged_persistent_messages = unpack_message_tree(&context.network_message.persistent); for (time, message) in time_tagged_persistent_messages { - self.detection_times[message.player_number] = Some(time); + self.ready_signal_detection_times[message.player_number] = Some(time); } - let own_detected_pose_times = - unpack_own_detection_tree(&context.referee_pose_kind.persistent); - let mut did_detect_any_referee_this_cycle = false; + let own_detected_pose_times: BTreeMap> = + unpack_own_detections(&context.referee_pose_kind.persistent); + + let ready_signal_detection_feedback = + Self::own_ready_signal_detection_evaluation(self, context, own_detected_pose_times)?; + + Ok(ready_signal_detection_feedback) + } + + fn own_ready_signal_detection_evaluation( + &mut self, + context: &CycleContext, + own_detected_pose_times: BTreeMap>, + ) -> Result { + let mut did_detect_any_ready_signal_this_cycle = false; for (_, detection) in own_detected_pose_times { - let detected_visual_referee = detection == Some(PoseKind::AboveHeadArms); - self.detected_above_arm_poses_queue + let detected_visual_referee = detection == Some(PoseKind::Ready); + self.detected_ready_signal_queue .push_front(detected_visual_referee); - did_detect_any_referee_this_cycle |= detected_visual_referee + did_detect_any_ready_signal_this_cycle |= detected_visual_referee } - self.detected_above_arm_poses_queue + self.detected_ready_signal_queue .truncate(*context.referee_pose_queue_length); let detected_referee_pose_count = self - .detected_above_arm_poses_queue + .detected_ready_signal_queue .iter() .filter(|x| **x) .count(); if detected_referee_pose_count >= *context.minimum_number_poses_before_message { - self.detection_times[*context.player_number] = Some(context.cycle_time.start_time); + self.ready_signal_detection_times[*context.player_number] = + Some(context.cycle_time.start_time); send_own_detection_message(context.hardware_interface.clone(), *context.player_number)?; } - Ok(( - detected_referee_pose_count >= *context.minimum_number_poses_before_message, - did_detect_any_referee_this_cycle, - )) + Ok(ReadySignalDetectionFeedback { + is_referee_ready_pose_detected: detected_referee_pose_count + >= *context.minimum_number_poses_before_message, + did_detect_any_ready_signal_this_cycle, + }) } } -fn decide( - pose_detection_times: Players>, +fn majority_vote_ready_signal( + ready_signal_detection_times: Players>, cycle_start_time: SystemTime, initial_message_grace_period: Duration, - minimum_above_head_arms_detections: usize, + minimum_ready_signal_detections: usize, ) -> bool { - let detected_above_head_arms_poses = pose_detection_times + let detected_ready_signal_detections = ready_signal_detection_times .iter() .filter(|(_, detection_time)| match detection_time { Some(detection_time) => is_in_grace_period( @@ -165,7 +203,7 @@ fn decide( None => false, }) .count(); - detected_above_head_arms_poses >= minimum_above_head_arms_detections + detected_ready_signal_detections >= minimum_ready_signal_detections } fn is_in_grace_period( @@ -194,10 +232,10 @@ fn unpack_message_tree( .collect() } -fn unpack_own_detection_tree( - pose_kind_tree: &BTreeMap>>, +fn unpack_own_detections( + detections: &BTreeMap>>, ) -> BTreeMap> { - pose_kind_tree + detections .iter() .flat_map(|(time, pose_kinds)| { pose_kinds diff --git a/crates/control/src/referee_position_provider.rs b/crates/control/src/referee_position_provider.rs index 3d6a102f40..927df2097a 100644 --- a/crates/control/src/referee_position_provider.rs +++ b/crates/control/src/referee_position_provider.rs @@ -5,7 +5,8 @@ use framework::MainOutput; use linear_algebra::{point, Point2}; use serde::{Deserialize, Serialize}; use types::{ - field_dimensions::FieldDimensions, filtered_game_controller_state::FilteredGameControllerState, + field_dimensions::{FieldDimensions, GlobalFieldSide}, + filtered_game_controller_state::FilteredGameControllerState, }; #[derive(Deserialize, Serialize)] @@ -34,14 +35,12 @@ impl RefereePositionProvider { } pub fn cycle(&mut self, context: CycleContext) -> Result { - let expected_referee_position = if context - .filtered_game_controller_state - .own_team_is_home_after_coin_toss - { - point![0.0, context.field_dimensions.width / 2.0,] - } else { - point![0.0, -context.field_dimensions.width / 2.0,] - }; + let expected_referee_position = + if context.filtered_game_controller_state.global_field_side == GlobalFieldSide::Home { + point![0.0, context.field_dimensions.width / 2.0,] + } else { + point![0.0, -context.field_dimensions.width / 2.0,] + }; Ok(MainOutputs { expected_referee_position: Some(expected_referee_position).into(), diff --git a/crates/control/src/role_assignment.rs b/crates/control/src/role_assignment.rs index 418c287592..1bb9f4cb11 100644 --- a/crates/control/src/role_assignment.rs +++ b/crates/control/src/role_assignment.rs @@ -139,6 +139,7 @@ impl RoleAssignment { role_for_penalty_shootout(context.filtered_game_controller_state), keep_current_role_in_penalty_kick(context.filtered_game_controller_state, self.role), keep_current_role_if_not_in_playing(primary_state, self.role), + keep_current_role_during_free_kicks(context.filtered_game_controller_state, self.role), Some(role_from_state_machine), ] .iter() @@ -622,6 +623,29 @@ fn keep_current_role_in_penalty_kick( None } +fn keep_current_role_during_free_kicks( + filtered_game_controller_state: Option<&FilteredGameControllerState>, + current_role: Role, +) -> Option { + if let Some(FilteredGameControllerState { + sub_state: Some(SubState::KickIn | SubState::PushingFreeKick), + .. + }) = filtered_game_controller_state + { + if [ + Role::DefenderLeft, + Role::DefenderRight, + Role::MidfielderLeft, + Role::DefenderRight, + ] + .contains(¤t_role) + { + return Some(current_role); + } + } + None +} + fn claim_striker_or_other_role( striker_event: StrikerEvent, time_to_reach_kick_position: Option, @@ -774,6 +798,7 @@ mod test { striker_trusts_team_ball_duration in Just(Duration::from_secs(5)), optional_roles in Just(&[Role::DefenderLeft, Role::StrikerSupporter]) ) { + let filtered_game_controller_state: Option = filtered_game_controller_state; let new_role = update_role_state_machine( initial_role, detected_own_ball, diff --git a/crates/control/src/sacrificial_lamb.rs b/crates/control/src/sacrificial_lamb.rs index 0bea2411dd..c8ae45f63b 100644 --- a/crates/control/src/sacrificial_lamb.rs +++ b/crates/control/src/sacrificial_lamb.rs @@ -8,12 +8,12 @@ use context_attribute::context; use framework::{AdditionalOutput, MainOutput, PerceptionInput}; use serde::{Deserialize, Serialize}; use spl_network_messages::{GameControllerStateMessage, Penalty, PlayerNumber}; -use types::{cycle_time::CycleTime, messages::IncomingMessage, pose_detection::VisualRefereeState}; +use types::{cycle_time::CycleTime, messages::IncomingMessage, pose_detection::ReadySignalState}; #[derive(Deserialize, Serialize)] pub struct SacrificialLamb { last_majority_vote_verdict: bool, - visual_referee_state: VisualRefereeState, + visual_referee_state: ReadySignalState, motion_in_standby_count: usize, } @@ -25,8 +25,8 @@ pub struct CycleContext { network_message: PerceptionInput, "SplNetwork", "filtered_message?">, cycle_time: Input, - majority_vote_is_referee_ready_pose_detected: - Input, + is_majority_vote_referee_ready_pose_detected: + Input, player_number: Parameter, wait_for_opponent_penalties_period: @@ -35,7 +35,7 @@ pub struct CycleContext { Parameter, sacrificial_lamb: Parameter, - visual_referee_state: AdditionalOutput, + visual_referee_state: AdditionalOutput, } #[context] @@ -48,7 +48,7 @@ impl SacrificialLamb { pub fn new(_context: CreationContext) -> Result { Ok(Self { last_majority_vote_verdict: false, - visual_referee_state: VisualRefereeState::WaitingForDetections, + visual_referee_state: ReadySignalState::WaitingForDetections, motion_in_standby_count: 0, }) } @@ -82,8 +82,8 @@ impl SacrificialLamb { .max(); let current_majority_vote_verdict = !self.last_majority_vote_verdict - && *context.majority_vote_is_referee_ready_pose_detected; - self.last_majority_vote_verdict = *context.majority_vote_is_referee_ready_pose_detected; + && *context.is_majority_vote_referee_ready_pose_detected; + self.last_majority_vote_verdict = *context.is_majority_vote_referee_ready_pose_detected; let motion_in_standby = new_motion_in_standby_count.is_some_and(|new_motion_in_standby_count| { @@ -97,47 +97,47 @@ impl SacrificialLamb { current_majority_vote_verdict, motion_in_standby, ) { - (VisualRefereeState::WaitingForDetections, true, motion_in_standby) => { + (ReadySignalState::WaitingForDetections, true, motion_in_standby) => { if motion_in_standby { - VisualRefereeState::WaitingForDetections + ReadySignalState::WaitingForDetections } else { - VisualRefereeState::WaitingForOpponentPenalties { + ReadySignalState::WaitingForOpponentPenalties { active_since: cycle_start_time, } } } - (VisualRefereeState::WaitingForOpponentPenalties { .. }, _, true) => { - VisualRefereeState::WaitingForDetections + (ReadySignalState::WaitingForOpponentPenalties { .. }, _, true) => { + ReadySignalState::WaitingForDetections } - (VisualRefereeState::WaitingForOpponentPenalties { active_since }, _, false) => { + (ReadySignalState::WaitingForOpponentPenalties { active_since }, _, false) => { if cycle_start_time .duration_since(active_since) .expect("time ran backwards") >= *context.wait_for_opponent_penalties_period { if context.player_number == context.sacrificial_lamb { - VisualRefereeState::GoToReady + ReadySignalState::GoToReady } else { - VisualRefereeState::WaitingForOwnPenalties { + ReadySignalState::WaitingForOwnPenalties { active_since: cycle_start_time, } } } else { - VisualRefereeState::WaitingForOpponentPenalties { active_since } + ReadySignalState::WaitingForOpponentPenalties { active_since } } } - (VisualRefereeState::WaitingForOwnPenalties { .. }, _, true) => { - VisualRefereeState::WaitingForDetections + (ReadySignalState::WaitingForOwnPenalties { .. }, _, true) => { + ReadySignalState::WaitingForDetections } - (VisualRefereeState::WaitingForOwnPenalties { active_since }, _, false) => { + (ReadySignalState::WaitingForOwnPenalties { active_since }, _, false) => { if cycle_start_time .duration_since(active_since) .expect("time ran backwards") >= *context.wait_for_own_penalties_period { - VisualRefereeState::GoToReady + ReadySignalState::GoToReady } else { - VisualRefereeState::WaitingForOwnPenalties { active_since } + ReadySignalState::WaitingForOwnPenalties { active_since } } } (current_state, _, _) => current_state, @@ -149,7 +149,7 @@ impl SacrificialLamb { Ok(MainOutputs { visual_referee_proceed_to_ready: (self.visual_referee_state - == VisualRefereeState::GoToReady) + == ReadySignalState::GoToReady) .into(), }) } diff --git a/crates/hulk_manifest/src/lib.rs b/crates/hulk_manifest/src/lib.rs index 692ed3dc4d..b2ae7e754a 100644 --- a/crates/hulk_manifest/src/lib.rs +++ b/crates/hulk_manifest/src/lib.rs @@ -54,6 +54,7 @@ pub fn collect_hulk_cyclers() -> Result { "control::fall_state_estimation", "control::filtered_game_controller_state_timer", "control::foot_bumper_filter", + "control::free_kick_signal_filter", "control::game_controller_filter", "control::game_controller_state_filter", "control::ground_contact_detector", @@ -95,7 +96,7 @@ pub fn collect_hulk_cyclers() -> Result { "control::orientation_filter", "control::penalty_shot_direction_estimation", "control::primary_state_filter", - "control::referee_pose_detection_filter", + "control::ready_signal_detection_filter", "control::referee_position_provider", "control::role_assignment", "control::rule_obstacle_composer", diff --git a/crates/object_detection/src/pose_detection.rs b/crates/object_detection/src/pose_detection.rs index 129aa01360..c312884444 100644 --- a/crates/object_detection/src/pose_detection.rs +++ b/crates/object_detection/src/pose_detection.rs @@ -20,25 +20,30 @@ use linear_algebra::{point, vector}; use types::{ bounding_box::BoundingBox, color::Rgb, - motion_command::MotionCommand, - pose_detection::{HumanPose, Keypoints}, + motion_command::{HeadMotion, MotionCommand}, + pose_detection::{DetectionRegion, HumanPose, Keypoints}, ycbcr422_image::YCbCr422Image, }; const DETECTION_IMAGE_HEIGHT: usize = 480; -const DETECTION_IMAGE_WIDTH: usize = 192; -const DETECTION_IMAGE_START_X: usize = (640 - DETECTION_IMAGE_WIDTH) / 2; +const DETECTION_IMAGE_WIDTH_NARROW: usize = 192; +const DETECTION_IMAGE_WIDTH_FULL: usize = 640; +const DETECTION_IMAGE_START_X: usize = (640 - DETECTION_IMAGE_WIDTH_NARROW) / 2; const EXPECTED_OUTPUT_NAME: &str = "detections"; -const MAX_DETECTIONS: usize = 1890; +const MAX_DETECTIONS_NARROW: usize = 1890; +const MAX_DETECTIONS_FULL: usize = 6300; -const STRIDE: usize = DETECTION_IMAGE_HEIGHT * DETECTION_IMAGE_WIDTH; +const STRIDE_NARROW: usize = DETECTION_IMAGE_HEIGHT * DETECTION_IMAGE_WIDTH_NARROW; +const STRIDE_FULL: usize = DETECTION_IMAGE_HEIGHT * DETECTION_IMAGE_WIDTH_FULL; #[derive(Deserialize, Serialize)] pub struct PoseDetection { #[serde(skip, default = "deserialize_not_implemented")] - network: CompiledModel, + network_narrow: CompiledModel, + #[serde(skip, default = "deserialize_not_implemented")] + network_full: CompiledModel, } #[context] @@ -73,20 +78,47 @@ impl PoseDetection { let paths = context.hardware_interface.get_paths(); let neural_network_folder = paths.neural_networks; - let model_xml_name = "yolo11n-pose-ov.xml"; - - let model_path = neural_network_folder.join(model_xml_name); - let weights_path = neural_network_folder - .join(model_xml_name) - .with_extension("bin"); + let model_xml_name_narrow = "yolo11n-pose-ov-narrow.xml"; + let model_xml_name_full = "yolo11n-pose-ov-full.xml"; let mut core = Core::new()?; - let network = core + let network_narrow = core + .read_model_from_file( + neural_network_folder + .join(model_xml_name_narrow) + .to_str() + .wrap_err("failed to get detection model path")?, + neural_network_folder + .join(model_xml_name_narrow) + .with_extension("bin") + .to_str() + .wrap_err("failed to get detection weights path")?, + ) + .map_err(|error| match error { + GeneralError => eyre!("{error}: possible incomplete OpenVino installation"), + _ => eyre!("{error}: failed to create detection network"), + })?; + + let number_of_inputs = network_narrow + .get_inputs_len() + .wrap_err("failed to get number of inputs")?; + let output_name = network_narrow.get_output_by_index(0)?.get_name()?; + if number_of_inputs != 1 || output_name != EXPECTED_OUTPUT_NAME { + bail!( + "expected exactly one input and output name to be '{}'", + EXPECTED_OUTPUT_NAME + ); + } + + let network_full = core .read_model_from_file( - model_path + neural_network_folder + .join(model_xml_name_full) .to_str() .wrap_err("failed to get detection model path")?, - weights_path + neural_network_folder + .join(model_xml_name_full) + .with_extension("bin") .to_str() .wrap_err("failed to get detection weights path")?, ) @@ -95,10 +127,10 @@ impl PoseDetection { _ => eyre!("{error}: failed to create detection network"), })?; - let number_of_inputs = network + let number_of_inputs = network_full .get_inputs_len() .wrap_err("failed to get number of inputs")?; - let output_name = network.get_output_by_index(0)?.get_name()?; + let output_name = network_full.get_output_by_index(0)?.get_name()?; if number_of_inputs != 1 || output_name != EXPECTED_OUTPUT_NAME { bail!( "expected exactly one input and output name to be '{}'", @@ -107,40 +139,82 @@ impl PoseDetection { } Ok(Self { - network: core.compile_model(&network, DeviceType::CPU)?, + network_narrow: core.compile_model(&network_narrow, DeviceType::CPU)?, + network_full: core.compile_model(&network_full, DeviceType::CPU)?, }) } pub fn cycle(&mut self, mut context: CycleContext) -> Result { - let behavior_requests_pose_detection = matches!( - context.motion_command, - MotionCommand::Initial { - should_look_for_referee: true, - .. - } - ); + let (behavior_requests_pose_detection, image_size_used_for_detection) = + match context.motion_command { + MotionCommand::Initial { + head: HeadMotion::LookAtReferee { .. }, + .. + } => (true, DetectionRegion::Narrow), + MotionCommand::Stand { + head: HeadMotion::LookAtReferee { .. }, + .. + } => (true, DetectionRegion::Full), + _ => (false, DetectionRegion::Narrow), + }; if !behavior_requests_pose_detection && !context.override_pose_detection { return Ok(MainOutputs::default()); }; let image = context.image; - let mut tensor = Tensor::new(ElementType::F32, &self.network.get_input()?.get_shape()?)?; - { - let earlier = SystemTime::now(); - - load_into_scratchpad(tensor.get_data_mut()?, image); - - context.preprocess_duration.fill_if_subscribed(|| { - SystemTime::now() - .duration_since(earlier) - .expect("time ran backwards") - }); - } + let mut infer_request = match image_size_used_for_detection { + DetectionRegion::Narrow => { + let mut tensor = Tensor::new( + ElementType::F32, + &self.network_narrow.get_input()?.get_shape()?, + )?; + { + let earlier = SystemTime::now(); + + load_into_scratchpad( + tensor.get_data_mut()?, + image, + image_size_used_for_detection, + ); + + context.preprocess_duration.fill_if_subscribed(|| { + SystemTime::now() + .duration_since(earlier) + .expect("time ran backwards") + }); + } - let mut infer_request = self.network.create_infer_request()?; + let mut infer_request = self.network_narrow.create_infer_request()?; + infer_request.set_input_tensor(&tensor)?; + infer_request + } + DetectionRegion::Full => { + let mut tensor = Tensor::new( + ElementType::F32, + &self.network_full.get_input()?.get_shape()?, + )?; + { + let earlier = SystemTime::now(); + + load_into_scratchpad( + tensor.get_data_mut()?, + image, + image_size_used_for_detection, + ); + + context.preprocess_duration.fill_if_subscribed(|| { + SystemTime::now() + .duration_since(earlier) + .expect("time ran backwards") + }); + } - infer_request.set_input_tensor(&tensor)?; + let mut infer_request = self.network_full.create_infer_request()?; + infer_request.set_input_tensor(&tensor)?; + infer_request + } + }; { let earlier = SystemTime::now(); @@ -152,10 +226,21 @@ impl PoseDetection { .expect("time ran backwards") }); } - let prediction = infer_request.get_output_tensor_by_index(0)?; - let prediction = - ArrayView::from_shape((56, MAX_DETECTIONS), prediction.get_data::()?)?; + let detection_image_start = match image_size_used_for_detection { + DetectionRegion::Narrow => DETECTION_IMAGE_START_X, + DetectionRegion::Full => 0, + }; + + let prediction = infer_request.get_output_tensor_by_index(0)?; + let prediction = match image_size_used_for_detection { + DetectionRegion::Narrow => { + ArrayView::from_shape((56, MAX_DETECTIONS_NARROW), prediction.get_data::()?)? + } + DetectionRegion::Full => { + ArrayView::from_shape((56, MAX_DETECTIONS_FULL), prediction.get_data::()?)? + } + }; let earlier = SystemTime::now(); let poses = prediction .columns() @@ -168,7 +253,7 @@ impl PoseDetection { let bounding_box_slice = row.slice(s![0..4]); // bbox re-scale - let center_x = bounding_box_slice[0] + DETECTION_IMAGE_START_X as f32; + let center_x = bounding_box_slice[0] + detection_image_start as f32; let center_y = bounding_box_slice[1]; let center = point![center_x, center_y]; @@ -184,7 +269,7 @@ impl PoseDetection { let keypoints_slice = row.slice(s![5..]); let keypoints = Keypoints::try_new( keypoints_slice.as_standard_layout().as_slice()?, - DETECTION_IMAGE_START_X as f32, + detection_image_start as f32, 0.0, )?; Some(HumanPose::new(bounding_box, keypoints)) @@ -205,17 +290,30 @@ impl PoseDetection { } } -fn load_into_scratchpad(scratchpad: &mut [f32], image: &YCbCr422Image) { +fn load_into_scratchpad( + scratchpad: &mut [f32], + image: &YCbCr422Image, + image_size: DetectionRegion, +) { + let (detection_image_width, detection_image_start, stride) = match image_size { + DetectionRegion::Narrow => ( + DETECTION_IMAGE_WIDTH_NARROW, + DETECTION_IMAGE_START_X, + STRIDE_NARROW, + ), + DetectionRegion::Full => (DETECTION_IMAGE_WIDTH_FULL, 0, STRIDE_FULL), + }; + let mut scratchpad_index = 0; for y in 0..DETECTION_IMAGE_HEIGHT as u32 { for x in - DETECTION_IMAGE_START_X as u32..(DETECTION_IMAGE_START_X + DETECTION_IMAGE_WIDTH) as u32 + detection_image_start as u32..(detection_image_start + detection_image_width) as u32 { let pixel: Rgb = image.at(x, y).into(); scratchpad[scratchpad_index] = pixel.red as f32 / 255.; - scratchpad[scratchpad_index + STRIDE] = pixel.green as f32 / 255.; - scratchpad[scratchpad_index + 2 * STRIDE] = pixel.blue as f32 / 255.; + scratchpad[scratchpad_index + stride] = pixel.green as f32 / 255.; + scratchpad[scratchpad_index + 2 * stride] = pixel.blue as f32 / 255.; scratchpad_index += 1; } diff --git a/crates/object_detection/src/pose_interpretation.rs b/crates/object_detection/src/pose_interpretation.rs index 86cb9b3536..aa88ca8ac2 100644 --- a/crates/object_detection/src/pose_interpretation.rs +++ b/crates/object_detection/src/pose_interpretation.rs @@ -1,4 +1,4 @@ -use std::time::Duration; +use std::{ops::Range, time::Duration}; use color_eyre::Result; use ordered_float::NotNan; @@ -13,6 +13,7 @@ use projection::{camera_matrices::CameraMatrices, camera_matrix::CameraMatrix, P use spl_network_messages::PlayerNumber; use types::{ fall_state::FallState, + field_dimensions::GlobalFieldSide, pose_detection::{HumanPose, Keypoints, RefereePoseCandidate}, pose_kinds::{PoseKind, PoseKindPosition}, }; @@ -43,6 +44,8 @@ pub struct CycleContext { Parameter, foot_z_offset: Parameter, minimum_shoulder_angle: Parameter, + free_kick_signal_angle_range: + Parameter, "pose_detection.free_kick_signal_angle_range">, rejected_pose_kind_positions: AdditionalOutput>, "rejected_pose_kind_positions">, @@ -92,8 +95,13 @@ impl PoseInterpretation { *context.foot_z_offset, ); - let referee_pose_kind = - referee_pose.map(|pose| interpret_pose(pose, *context.minimum_shoulder_angle)); + let referee_pose_kind = referee_pose.map(|pose| { + interpret_pose( + pose, + *context.minimum_shoulder_angle, + context.free_kick_signal_angle_range, + ) + }); context.rejected_pose_kind_positions.fill_if_subscribed(|| { get_all_pose_kind_positions( @@ -102,6 +110,7 @@ impl PoseInterpretation { context.ground_to_field, *context.foot_z_offset, *context.minimum_shoulder_angle, + context.free_kick_signal_angle_range, ) }); @@ -112,6 +121,7 @@ impl PoseInterpretation { context.ground_to_field, *context.foot_z_offset, *context.minimum_shoulder_angle, + context.free_kick_signal_angle_range, ) }); @@ -122,6 +132,7 @@ impl PoseInterpretation { context.ground_to_field, *context.foot_z_offset, *context.minimum_shoulder_angle, + context.free_kick_signal_angle_range, ) }); @@ -181,15 +192,58 @@ fn get_closest_referee_pose( }) } -fn interpret_pose(human_pose: HumanPose, minimum_shoulder_angle: f32) -> PoseKind { - if is_above_head_arms_pose(human_pose.keypoints, minimum_shoulder_angle) { - PoseKind::AboveHeadArms +fn interpret_pose( + human_pose: HumanPose, + minimum_shoulder_angle: f32, + free_kick_signal_angle_range: &Range, +) -> PoseKind { + if is_ready_signal_pose(human_pose.keypoints, minimum_shoulder_angle) { + PoseKind::Ready + } else if let Some(side) = is_free_kick_pose(human_pose.keypoints, free_kick_signal_angle_range) + { + PoseKind::FreeKick { + global_field_side: side, + } } else { PoseKind::UndefinedPose } } -fn is_above_head_arms_pose(keypoints: Keypoints, minimum_shoulder_angle: f32) -> bool { +fn is_free_kick_pose( + keypoints: Keypoints, + free_kick_signal_angle_range: &Range, +) -> Option { + let left_shoulder_to_hand = + keypoints.left_shoulder.point.coords() - keypoints.left_hand.point.coords(); + let left_shoulder_to_feet = + keypoints.left_shoulder.point.coords() - keypoints.left_foot.point.coords(); + let left_arm_rotation = + Rotation2::rotation_between(left_shoulder_to_hand, left_shoulder_to_feet); + + let right_shoulder_to_hand = + keypoints.right_shoulder.point.coords() - keypoints.right_hand.point.coords(); + let right_shoulder_to_feet = + keypoints.right_shoulder.point.coords() - keypoints.right_foot.point.coords(); + let right_arm_rotation = + Rotation2::rotation_between(right_shoulder_to_hand, right_shoulder_to_feet); + + let arm_rotation_difference = + Rotation2::rotation_between(left_shoulder_to_hand, right_shoulder_to_hand); + let is_free_kick_pose = + free_kick_signal_angle_range.contains(&arm_rotation_difference.angle().abs()); + if is_free_kick_pose && free_kick_signal_angle_range.contains(&left_arm_rotation.angle().abs()) + { + Some(GlobalFieldSide::Away) + } else if is_free_kick_pose + && free_kick_signal_angle_range.contains(&right_arm_rotation.angle().abs()) + { + Some(GlobalFieldSide::Home) + } else { + None + } +} + +fn is_ready_signal_pose(keypoints: Keypoints, minimum_shoulder_angle: f32) -> bool { are_hands_above_shoulder(&keypoints) && is_right_shoulder_angled_up( &keypoints, @@ -242,6 +296,7 @@ fn get_all_pose_kind_positions( ground_to_field: Option<&Isometry2>, foot_z_offset: f32, minimum_shoulder_angle: f32, + free_kick_signal_angle_range: &Range, ) -> Vec> { poses .iter() @@ -252,6 +307,7 @@ fn get_all_pose_kind_positions( ground_to_field, foot_z_offset, minimum_shoulder_angle, + free_kick_signal_angle_range, ) }) .collect() @@ -263,6 +319,7 @@ fn get_pose_kind_position( ground_to_field: Option<&Isometry2>, foot_z_offset: f32, minimum_shoulder_angle: f32, + free_kick_signal_angle_range: &Range, ) -> Option> { let left_foot_ground_position = camera_matrix_top .pixel_to_ground_with_z(pose?.keypoints.left_foot.point, foot_z_offset) @@ -270,7 +327,8 @@ fn get_pose_kind_position( let right_foot_ground_position = camera_matrix_top .pixel_to_ground_with_z(pose?.keypoints.right_foot.point, foot_z_offset) .ok()?; - let interpreted_pose_kind = interpret_pose(pose?, minimum_shoulder_angle); + let interpreted_pose_kind = + interpret_pose(pose?, minimum_shoulder_angle, free_kick_signal_angle_range); Some(PoseKindPosition { pose_kind: interpreted_pose_kind, position: center( diff --git a/crates/path_serde/src/implementation.rs b/crates/path_serde/src/implementation.rs index bfb372c73a..b15e72c2dd 100644 --- a/crates/path_serde/src/implementation.rs +++ b/crates/path_serde/src/implementation.rs @@ -103,7 +103,7 @@ where impl PathDeserialize for Option where - T: PathDeserialize + Default, + T: PathDeserialize, { fn deserialize_path<'de, D>( &mut self, @@ -115,12 +115,9 @@ where { match self { Some(some) => some.deserialize_path(path, deserializer), - None => { - let mut value = T::default(); - value.deserialize_path(path, deserializer)?; - *self = Some(value); - Ok(()) - } + None => Err(deserialize::Error::PathDoesNotExist { + path: path.to_string(), + }), } } } diff --git a/crates/types/src/action.rs b/crates/types/src/action.rs index e38b25a31e..3f8a1debc2 100644 --- a/crates/types/src/action.rs +++ b/crates/types/src/action.rs @@ -30,6 +30,7 @@ pub enum Action { InterceptBall, Jump, LookAround, + LookAtReferee, NoGroundContact, Penalize, PrepareJump, diff --git a/crates/types/src/field_dimensions.rs b/crates/types/src/field_dimensions.rs index b570fb4f8c..648f631b2d 100644 --- a/crates/types/src/field_dimensions.rs +++ b/crates/types/src/field_dimensions.rs @@ -34,6 +34,39 @@ pub struct FieldDimensions { pub goal_depth: f32, } +#[derive( + Clone, + Copy, + Debug, + Serialize, + Deserialize, + PathSerialize, + PathDeserialize, + PathIntrospect, + PartialEq, + Eq, +)] +pub enum GlobalFieldSide { + Home, + Away, +} + +impl GlobalFieldSide { + pub fn sign(self) -> f32 { + match self { + GlobalFieldSide::Home => -1.0, + GlobalFieldSide::Away => 1.0, + } + } + + pub fn mirror(self) -> Self { + match self { + GlobalFieldSide::Home => GlobalFieldSide::Away, + GlobalFieldSide::Away => GlobalFieldSide::Home, + } + } +} + #[derive(Clone, Copy, PartialEq, Eq)] pub enum Half { Own, diff --git a/crates/types/src/filtered_game_controller_state.rs b/crates/types/src/filtered_game_controller_state.rs index 3be23ffd47..9175ae18eb 100644 --- a/crates/types/src/filtered_game_controller_state.rs +++ b/crates/types/src/filtered_game_controller_state.rs @@ -4,7 +4,9 @@ use path_serde::{PathIntrospect, PathSerialize}; use serde::{Deserialize, Serialize}; use spl_network_messages::{GamePhase, Penalty, PlayerNumber, SubState, Team}; -use crate::{filtered_game_state::FilteredGameState, players::Players}; +use crate::{ + field_dimensions::GlobalFieldSide, filtered_game_state::FilteredGameState, players::Players, +}; #[derive(Clone, Debug, Serialize, Deserialize, PathSerialize, PathIntrospect, PartialEq)] pub struct FilteredGameControllerState { @@ -16,7 +18,7 @@ pub struct FilteredGameControllerState { pub penalties: Players>, pub remaining_number_of_messages: u16, pub sub_state: Option, - pub own_team_is_home_after_coin_toss: bool, + pub global_field_side: GlobalFieldSide, pub new_own_penalties_last_cycle: HashMap, pub new_opponent_penalties_last_cycle: HashMap, @@ -33,7 +35,7 @@ impl Default for FilteredGameControllerState { penalties: Default::default(), remaining_number_of_messages: Default::default(), sub_state: Default::default(), - own_team_is_home_after_coin_toss: Default::default(), + global_field_side: GlobalFieldSide::Away, new_own_penalties_last_cycle: Default::default(), new_opponent_penalties_last_cycle: Default::default(), } diff --git a/crates/types/src/game_controller_state.rs b/crates/types/src/game_controller_state.rs index 7be7b9a165..f76372062b 100644 --- a/crates/types/src/game_controller_state.rs +++ b/crates/types/src/game_controller_state.rs @@ -4,7 +4,7 @@ use path_serde::{PathDeserialize, PathIntrospect, PathSerialize}; use serde::{Deserialize, Serialize}; use spl_network_messages::{GamePhase, GameState, Penalty, SubState, Team, TeamState}; -use crate::players::Players; +use crate::{field_dimensions::GlobalFieldSide, players::Players}; #[derive(Clone, Debug, Serialize, Deserialize, PathSerialize, PathDeserialize, PathIntrospect)] pub struct GameControllerState { @@ -16,7 +16,7 @@ pub struct GameControllerState { pub penalties: Players>, pub opponent_penalties: Players>, pub sub_state: Option, - pub hulks_team_is_home_after_coin_toss: bool, + pub global_field_side: GlobalFieldSide, pub hulks_team: TeamState, pub opponent_team: TeamState, } diff --git a/crates/types/src/motion_command.rs b/crates/types/src/motion_command.rs index 78d513e168..a616a45d36 100644 --- a/crates/types/src/motion_command.rs +++ b/crates/types/src/motion_command.rs @@ -50,7 +50,6 @@ pub enum MotionCommand { }, Initial { head: HeadMotion, - should_look_for_referee: bool, }, Jump { direction: JumpDirection, @@ -156,6 +155,10 @@ pub enum HeadMotion { image_region_target: ImageRegion, camera: Option, }, + LookAtReferee { + image_region_target: ImageRegion, + camera: Option, + }, LookLeftAndRightOf { target: Point2, }, diff --git a/crates/types/src/pose_detection.rs b/crates/types/src/pose_detection.rs index f0d76980ac..7b3fc8e431 100644 --- a/crates/types/src/pose_detection.rs +++ b/crates/types/src/pose_detection.rs @@ -6,9 +6,18 @@ use serde::{Deserialize, Serialize}; use coordinate_systems::Pixel; use linear_algebra::{point, Point2}; +use spl_network_messages::Team; use crate::bounding_box::BoundingBox; +#[derive( + Debug, Clone, Copy, Serialize, Deserialize, PathSerialize, PathDeserialize, PathIntrospect, +)] +pub enum DetectionRegion { + Narrow, + Full, +} + pub const OVERALL_KEYPOINT_INDEX_MASK: [usize; 15] = [0, 1, 2, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16]; pub const VISUAL_REFEREE_KEYPOINT_INDEX_MASK: [usize; 8] = [5, 6, 7, 8, 9, 10, 15, 16]; @@ -154,8 +163,33 @@ pub struct RefereePoseCandidate { pub distance_to_referee_position: f32, } +#[derive( + Debug, Clone, Copy, Serialize, Deserialize, PathSerialize, PathDeserialize, PathIntrospect, +)] +pub struct ReadySignalDetectionFeedback { + pub is_referee_ready_pose_detected: bool, + pub did_detect_any_ready_signal_this_cycle: bool, +} + +#[derive( + Debug, Clone, Copy, Serialize, Deserialize, PathSerialize, PathDeserialize, PathIntrospect, +)] +pub struct FreeKickSignalDetectionResult { + pub did_detect_any_free_kick_signal_this_cycle: bool, + pub detected_free_kick_kicking_team: Option, +} + +#[derive( + Debug, Clone, Copy, Serialize, Deserialize, PathSerialize, PathDeserialize, PathIntrospect, +)] +pub struct TimeTaggedKickingTeamDetections { + pub time: SystemTime, + pub detected_kicking_team: Team, +} + #[derive( Debug, + Default, Clone, Copy, Serialize, @@ -165,9 +199,14 @@ pub struct RefereePoseCandidate { PathDeserialize, PathIntrospect, )] -pub enum VisualRefereeState { +pub enum ReadySignalState { + #[default] WaitingForDetections, - WaitingForOpponentPenalties { active_since: SystemTime }, - WaitingForOwnPenalties { active_since: SystemTime }, + WaitingForOpponentPenalties { + active_since: SystemTime, + }, + WaitingForOwnPenalties { + active_since: SystemTime, + }, GoToReady, } diff --git a/crates/types/src/pose_kinds.rs b/crates/types/src/pose_kinds.rs index 1b1c6f9b57..3f729c5089 100644 --- a/crates/types/src/pose_kinds.rs +++ b/crates/types/src/pose_kinds.rs @@ -2,6 +2,8 @@ use linear_algebra::Point2; use path_serde::{PathDeserialize, PathIntrospect, PathSerialize}; use serde::{Deserialize, Serialize}; +use crate::field_dimensions::GlobalFieldSide; + #[derive( Debug, Default, @@ -15,7 +17,10 @@ use serde::{Deserialize, Serialize}; Eq, )] pub enum PoseKind { - AboveHeadArms, + Ready, + FreeKick { + global_field_side: GlobalFieldSide, + }, #[default] UndefinedPose, } diff --git a/etc/neural_networks/yolo11n-pose-ov-full.bin b/etc/neural_networks/yolo11n-pose-ov-full.bin new file mode 100644 index 0000000000..e7f52f5c83 Binary files /dev/null and b/etc/neural_networks/yolo11n-pose-ov-full.bin differ diff --git a/etc/neural_networks/yolo11n-pose-ov-full.xml b/etc/neural_networks/yolo11n-pose-ov-full.xml new file mode 100644 index 0000000000..48373739d4 --- /dev/null +++ b/etc/neural_networks/yolo11n-pose-ov-full.xml @@ -0,0 +1,12028 @@ + + + + + + + + 1 + 3 + 480 + 640 + + + + + + + + 1 + 2 + 6300 + + + + + + + + 16 + 3 + 3 + 3 + + + + + + + + 1 + 3 + 480 + 640 + + + 16 + 3 + 3 + 3 + + + + + 1 + 16 + 240 + 320 + + + + + + + + 1 + 16 + 1 + 1 + + + + + + + + 1 + 16 + 240 + 320 + + + 1 + 16 + 1 + 1 + + + + + 1 + 16 + 240 + 320 + + + + + + + 1 + 16 + 240 + 320 + + + + + 1 + 16 + 240 + 320 + + + + + + + + 32 + 16 + 3 + 3 + + + + + + + + 1 + 16 + 240 + 320 + + + 32 + 16 + 3 + 3 + + + + + 1 + 32 + 120 + 160 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 120 + 160 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 120 + 160 + + + + + + + 1 + 32 + 120 + 160 + + + + + 1 + 32 + 120 + 160 + + + + + + + + 32 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 120 + 160 + + + 32 + 32 + 1 + 1 + + + + + 1 + 32 + 120 + 160 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 120 + 160 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 120 + 160 + + + + + + + 1 + 32 + 120 + 160 + + + + + 1 + 32 + 120 + 160 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 32 + 120 + 160 + + + + 2 + + + + + 1 + 16 + 120 + 160 + + + 1 + 16 + 120 + 160 + + + + + + + + 8 + 16 + 3 + 3 + + + + + + + + 1 + 16 + 120 + 160 + + + 8 + 16 + 3 + 3 + + + + + 1 + 8 + 120 + 160 + + + + + + + + 1 + 8 + 1 + 1 + + + + + + + + 1 + 8 + 120 + 160 + + + 1 + 8 + 1 + 1 + + + + + 1 + 8 + 120 + 160 + + + + + + + 1 + 8 + 120 + 160 + + + + + 1 + 8 + 120 + 160 + + + + + + + + 16 + 8 + 3 + 3 + + + + + + + + 1 + 8 + 120 + 160 + + + 16 + 8 + 3 + 3 + + + + + 1 + 16 + 120 + 160 + + + + + + + + 1 + 16 + 1 + 1 + + + + + + + + 1 + 16 + 120 + 160 + + + 1 + 16 + 1 + 1 + + + + + 1 + 16 + 120 + 160 + + + + + + + 1 + 16 + 120 + 160 + + + + + 1 + 16 + 120 + 160 + + + + + + + + 1 + 16 + 120 + 160 + + + 1 + 16 + 120 + 160 + + + + + 1 + 16 + 120 + 160 + + + + + + + + 1 + 16 + 120 + 160 + + + 1 + 16 + 120 + 160 + + + 1 + 16 + 120 + 160 + + + + + 1 + 48 + 120 + 160 + + + + + + + + 64 + 48 + 1 + 1 + + + + + + + + 1 + 48 + 120 + 160 + + + 64 + 48 + 1 + 1 + + + + + 1 + 64 + 120 + 160 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 120 + 160 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 120 + 160 + + + + + + + 1 + 64 + 120 + 160 + + + + + 1 + 64 + 120 + 160 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 120 + 160 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 80 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 80 + + + + + + + 1 + 64 + 60 + 80 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 64 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 80 + + + 64 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 80 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 80 + + + + + + + 1 + 64 + 60 + 80 + + + + + 1 + 64 + 60 + 80 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 64 + 60 + 80 + + + + 2 + + + + + 1 + 32 + 60 + 80 + + + 1 + 32 + 60 + 80 + + + + + + + + 16 + 32 + 3 + 3 + + + + + + + + 1 + 32 + 60 + 80 + + + 16 + 32 + 3 + 3 + + + + + 1 + 16 + 60 + 80 + + + + + + + + 1 + 16 + 1 + 1 + + + + + + + + 1 + 16 + 60 + 80 + + + 1 + 16 + 1 + 1 + + + + + 1 + 16 + 60 + 80 + + + + + + + 1 + 16 + 60 + 80 + + + + + 1 + 16 + 60 + 80 + + + + + + + + 32 + 16 + 3 + 3 + + + + + + + + 1 + 16 + 60 + 80 + + + 32 + 16 + 3 + 3 + + + + + 1 + 32 + 60 + 80 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 60 + 80 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 60 + 80 + + + + + + + 1 + 32 + 60 + 80 + + + + + 1 + 32 + 60 + 80 + + + + + + + + 1 + 32 + 60 + 80 + + + 1 + 32 + 60 + 80 + + + + + 1 + 32 + 60 + 80 + + + + + + + + 1 + 32 + 60 + 80 + + + 1 + 32 + 60 + 80 + + + 1 + 32 + 60 + 80 + + + + + 1 + 96 + 60 + 80 + + + + + + + + 128 + 96 + 1 + 1 + + + + + + + + 1 + 96 + 60 + 80 + + + 128 + 96 + 1 + 1 + + + + + 1 + 128 + 60 + 80 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 60 + 80 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 60 + 80 + + + + + + + 1 + 128 + 60 + 80 + + + + + 1 + 128 + 60 + 80 + + + + + + + + 128 + 128 + 3 + 3 + + + + + + + + 1 + 128 + 60 + 80 + + + 128 + 128 + 3 + 3 + + + + + 1 + 128 + 30 + 40 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 40 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 30 + 40 + + + + + + + 1 + 128 + 30 + 40 + + + + + 1 + 128 + 30 + 40 + + + + + + + + 128 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 40 + + + 128 + 128 + 1 + 1 + + + + + 1 + 128 + 30 + 40 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 40 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 30 + 40 + + + + + + + 1 + 128 + 30 + 40 + + + + + 1 + 128 + 30 + 40 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 128 + 30 + 40 + + + + 2 + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 30 + 40 + + + + + + + + 32 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 40 + + + 32 + 64 + 1 + 1 + + + + + 1 + 32 + 30 + 40 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 30 + 40 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 30 + 40 + + + + + + + 1 + 32 + 30 + 40 + + + + + 1 + 32 + 30 + 40 + + + + + + + + 32 + 32 + 3 + 3 + + + + + + + + 1 + 32 + 30 + 40 + + + 32 + 32 + 3 + 3 + + + + + 1 + 32 + 30 + 40 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 30 + 40 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 30 + 40 + + + + + + + 1 + 32 + 30 + 40 + + + + + 1 + 32 + 30 + 40 + + + + + + + + 32 + 32 + 3 + 3 + + + + + + + + 1 + 32 + 30 + 40 + + + 32 + 32 + 3 + 3 + + + + + 1 + 32 + 30 + 40 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 30 + 40 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 30 + 40 + + + + + + + 1 + 32 + 30 + 40 + + + + + 1 + 32 + 30 + 40 + + + + + + + + 1 + 32 + 30 + 40 + + + 1 + 32 + 30 + 40 + + + + + 1 + 32 + 30 + 40 + + + + + + + + 32 + 32 + 3 + 3 + + + + + + + + 1 + 32 + 30 + 40 + + + 32 + 32 + 3 + 3 + + + + + 1 + 32 + 30 + 40 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 30 + 40 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 30 + 40 + + + + + + + 1 + 32 + 30 + 40 + + + + + 1 + 32 + 30 + 40 + + + + + + + + 32 + 32 + 3 + 3 + + + + + + + + 1 + 32 + 30 + 40 + + + 32 + 32 + 3 + 3 + + + + + 1 + 32 + 30 + 40 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 30 + 40 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 30 + 40 + + + + + + + 1 + 32 + 30 + 40 + + + + + 1 + 32 + 30 + 40 + + + + + + + + 1 + 32 + 30 + 40 + + + 1 + 32 + 30 + 40 + + + + + 1 + 32 + 30 + 40 + + + + + + + + 32 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 40 + + + 32 + 64 + 1 + 1 + + + + + 1 + 32 + 30 + 40 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 30 + 40 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 30 + 40 + + + + + + + 1 + 32 + 30 + 40 + + + + + 1 + 32 + 30 + 40 + + + + + + + + 1 + 32 + 30 + 40 + + + 1 + 32 + 30 + 40 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 64 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 40 + + + 64 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 40 + + + + + + + 1 + 64 + 30 + 40 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 30 + 40 + + + + + 1 + 192 + 30 + 40 + + + + + + + + 128 + 192 + 1 + 1 + + + + + + + + 1 + 192 + 30 + 40 + + + 128 + 192 + 1 + 1 + + + + + 1 + 128 + 30 + 40 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 40 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 30 + 40 + + + + + + + 1 + 128 + 30 + 40 + + + + + 1 + 128 + 30 + 40 + + + + + + + + 256 + 128 + 3 + 3 + + + + + + + + 1 + 128 + 30 + 40 + + + 256 + 128 + 3 + 3 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 20 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + 1 + 256 + 15 + 20 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 256 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 20 + + + 256 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 20 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + 1 + 256 + 15 + 20 + + + + + 1 + 256 + 15 + 20 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 256 + 15 + 20 + + + + 2 + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 15 + 20 + + + + + + + + 64 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 20 + + + 64 + 128 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 20 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 20 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 20 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 20 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 64 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 20 + + + 64 + 128 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 15 + 20 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 128 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 20 + + + 128 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 20 + + + + + + + 1 + 128 + 15 + 20 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 15 + 20 + + + + + 1 + 384 + 15 + 20 + + + + + + + + 256 + 384 + 1 + 1 + + + + + + + + 1 + 384 + 15 + 20 + + + 256 + 384 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 20 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + 1 + 256 + 15 + 20 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 128 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 20 + + + 128 + 256 + 1 + 1 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 20 + + + + + + + 1 + 128 + 15 + 20 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 128 + 15 + 20 + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 128 + 15 + 20 + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 128 + 15 + 20 + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 15 + 20 + + + + + 1 + 512 + 15 + 20 + + + + + + + + 256 + 512 + 1 + 1 + + + + + + + + 1 + 512 + 15 + 20 + + + 256 + 512 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 20 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + 1 + 256 + 15 + 20 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 256 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 20 + + + 256 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 20 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + 1 + 256 + 15 + 20 + + + + + 1 + 256 + 15 + 20 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 256 + 15 + 20 + + + + 2 + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 15 + 20 + + + + + + + + 256 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 20 + + + 256 + 128 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 20 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 4 + + + + + + + + 1 + 256 + 15 + 20 + + + 4 + + + + + 1 + 2 + 128 + 300 + + + + + + + + + + + + + + 3 + + + + + + + 1 + 2 + 128 + 300 + + + + 3 + + + + + 1 + 2 + 32 + 300 + + + 1 + 2 + 32 + 300 + + + 1 + 2 + 64 + 300 + + + + + + + + 1 + 1 + 1 + 1 + + + + + + + + 1 + 2 + 32 + 300 + + + 1 + 1 + 1 + 1 + + + + + 1 + 2 + 32 + 300 + + + + + + + + 1 + 2 + 32 + 300 + + + 1 + 2 + 32 + 300 + + + + + 1 + 2 + 300 + 300 + + + + + + + + 1 + 2 + 300 + 300 + + + + + 1 + 2 + 300 + 300 + + + + + + + + 1 + 2 + 64 + 300 + + + 1 + 2 + 300 + 300 + + + + + 1 + 2 + 64 + 300 + + + + + + + + 1 + 128 + 15 + 20 + + + + + 4 + + + + + + + + 1 + 2 + 64 + 300 + + + 4 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 2 + 64 + 300 + + + 4 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 128 + 1 + 1 + 3 + 3 + + + + + + + + 1 + 128 + 15 + 20 + + + 128 + 1 + 1 + 3 + 3 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 15 + 20 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 128 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 20 + + + 128 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 15 + 20 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 256 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 20 + + + 256 + 128 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 20 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + 1 + 256 + 15 + 20 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 128 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 20 + + + 128 + 256 + 1 + 1 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 15 + 20 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 15 + 20 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 256 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 20 + + + 256 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 20 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + 1 + 256 + 15 + 20 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 2 + + + + + + + + 2 + + + + + + + + 1 + 256 + 15 + 20 + + + 2 + + + 2 + + + + + 1 + 256 + 30 + 40 + + + + + + + + 1 + 256 + 30 + 40 + + + 1 + 128 + 30 + 40 + + + + + 1 + 384 + 30 + 40 + + + + + + + + 128 + 384 + 1 + 1 + + + + + + + + 1 + 384 + 30 + 40 + + + 128 + 384 + 1 + 1 + + + + + 1 + 128 + 30 + 40 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 40 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 30 + 40 + + + + + + + 1 + 128 + 30 + 40 + + + + + 1 + 128 + 30 + 40 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 128 + 30 + 40 + + + + 2 + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 30 + 40 + + + + + + + + 32 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 30 + 40 + + + 32 + 64 + 3 + 3 + + + + + 1 + 32 + 30 + 40 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 30 + 40 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 30 + 40 + + + + + + + 1 + 32 + 30 + 40 + + + + + 1 + 32 + 30 + 40 + + + + + + + + 64 + 32 + 3 + 3 + + + + + + + + 1 + 32 + 30 + 40 + + + 64 + 32 + 3 + 3 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 40 + + + + + + + 1 + 64 + 30 + 40 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 30 + 40 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 30 + 40 + + + + + 1 + 192 + 30 + 40 + + + + + + + + 128 + 192 + 1 + 1 + + + + + + + + 1 + 192 + 30 + 40 + + + 128 + 192 + 1 + 1 + + + + + 1 + 128 + 30 + 40 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 40 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 30 + 40 + + + + + + + 1 + 128 + 30 + 40 + + + + + 1 + 128 + 30 + 40 + + + + + + + + 2 + + + + + + + + 2 + + + + + + + + 1 + 128 + 30 + 40 + + + 2 + + + 2 + + + + + 1 + 128 + 60 + 80 + + + + + + + + 1 + 128 + 60 + 80 + + + 1 + 128 + 60 + 80 + + + + + 1 + 256 + 60 + 80 + + + + + + + + 64 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 60 + 80 + + + 64 + 256 + 1 + 1 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 80 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 80 + + + + + + + 1 + 64 + 60 + 80 + + + + + 1 + 64 + 60 + 80 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 64 + 60 + 80 + + + + 2 + + + + + 1 + 32 + 60 + 80 + + + 1 + 32 + 60 + 80 + + + + + + + + 16 + 32 + 3 + 3 + + + + + + + + 1 + 32 + 60 + 80 + + + 16 + 32 + 3 + 3 + + + + + 1 + 16 + 60 + 80 + + + + + + + + 1 + 16 + 1 + 1 + + + + + + + + 1 + 16 + 60 + 80 + + + 1 + 16 + 1 + 1 + + + + + 1 + 16 + 60 + 80 + + + + + + + 1 + 16 + 60 + 80 + + + + + 1 + 16 + 60 + 80 + + + + + + + + 32 + 16 + 3 + 3 + + + + + + + + 1 + 16 + 60 + 80 + + + 32 + 16 + 3 + 3 + + + + + 1 + 32 + 60 + 80 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 60 + 80 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 60 + 80 + + + + + + + 1 + 32 + 60 + 80 + + + + + 1 + 32 + 60 + 80 + + + + + + + + 1 + 32 + 60 + 80 + + + 1 + 32 + 60 + 80 + + + + + 1 + 32 + 60 + 80 + + + + + + + + 1 + 32 + 60 + 80 + + + 1 + 32 + 60 + 80 + + + 1 + 32 + 60 + 80 + + + + + 1 + 96 + 60 + 80 + + + + + + + + 64 + 96 + 1 + 1 + + + + + + + + 1 + 96 + 60 + 80 + + + 64 + 96 + 1 + 1 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 80 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 80 + + + + + + + 1 + 64 + 60 + 80 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 60 + 80 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 80 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 80 + + + + + + + 1 + 64 + 60 + 80 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 60 + 80 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 80 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 80 + + + + + + + 1 + 64 + 60 + 80 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 64 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 80 + + + 64 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 80 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 64 + 1 + 1 + 3 + 3 + + + + + + + + 1 + 64 + 60 + 80 + + + 64 + 1 + 1 + 3 + 3 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 80 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 80 + + + + + + + 1 + 64 + 60 + 80 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 64 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 80 + + + 64 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 80 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 80 + + + + + + + 1 + 64 + 60 + 80 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 64 + 1 + 1 + 3 + 3 + + + + + + + + 1 + 64 + 60 + 80 + + + 64 + 1 + 1 + 3 + 3 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 80 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 80 + + + + + + + 1 + 64 + 60 + 80 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 64 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 80 + + + 64 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 80 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 80 + + + + + + + 1 + 64 + 60 + 80 + + + + + 1 + 64 + 60 + 80 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 80 + + + 1 + 64 + 1 + 1 + + + + + 1 + 1 + 60 + 80 + + + + + + + + 1 + 1 + 1 + 1 + + + + + + + + 1 + 1 + 60 + 80 + + + 1 + 1 + 1 + 1 + + + + + 1 + 1 + 60 + 80 + + + + + + + + 1 + 64 + 60 + 80 + + + 1 + 1 + 60 + 80 + + + + + 1 + 65 + 60 + 80 + + + + + + + + 3 + + + + + + + + 1 + 65 + 60 + 80 + + + 3 + + + + + 1 + 65 + 4800 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 60 + 80 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 40 + + + + + + + 1 + 64 + 30 + 40 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 1 + 64 + 30 + 40 + + + 1 + 128 + 30 + 40 + + + + + 1 + 192 + 30 + 40 + + + + + + + + 128 + 192 + 1 + 1 + + + + + + + + 1 + 192 + 30 + 40 + + + 128 + 192 + 1 + 1 + + + + + 1 + 128 + 30 + 40 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 40 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 30 + 40 + + + + + + + 1 + 128 + 30 + 40 + + + + + 1 + 128 + 30 + 40 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 128 + 30 + 40 + + + + 2 + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 30 + 40 + + + + + + + + 32 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 30 + 40 + + + 32 + 64 + 3 + 3 + + + + + 1 + 32 + 30 + 40 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 30 + 40 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 30 + 40 + + + + + + + 1 + 32 + 30 + 40 + + + + + 1 + 32 + 30 + 40 + + + + + + + + 64 + 32 + 3 + 3 + + + + + + + + 1 + 32 + 30 + 40 + + + 64 + 32 + 3 + 3 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 40 + + + + + + + 1 + 64 + 30 + 40 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 30 + 40 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 30 + 40 + + + + + 1 + 192 + 30 + 40 + + + + + + + + 128 + 192 + 1 + 1 + + + + + + + + 1 + 192 + 30 + 40 + + + 128 + 192 + 1 + 1 + + + + + 1 + 128 + 30 + 40 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 40 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 30 + 40 + + + + + + + 1 + 128 + 30 + 40 + + + + + 1 + 128 + 30 + 40 + + + + + + + + 64 + 128 + 3 + 3 + + + + + + + + 1 + 128 + 30 + 40 + + + 64 + 128 + 3 + 3 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 40 + + + + + + + 1 + 64 + 30 + 40 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 30 + 40 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 40 + + + + + + + 1 + 64 + 30 + 40 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 64 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 40 + + + 64 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 128 + 1 + 1 + 3 + 3 + + + + + + + + 1 + 128 + 30 + 40 + + + 128 + 1 + 1 + 3 + 3 + + + + + 1 + 128 + 30 + 40 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 40 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 30 + 40 + + + + + + + 1 + 128 + 30 + 40 + + + + + 1 + 128 + 30 + 40 + + + + + + + + 64 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 40 + + + 64 + 128 + 1 + 1 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 40 + + + + + + + 1 + 64 + 30 + 40 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 64 + 1 + 1 + 3 + 3 + + + + + + + + 1 + 64 + 30 + 40 + + + 64 + 1 + 1 + 3 + 3 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 40 + + + + + + + 1 + 64 + 30 + 40 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 64 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 40 + + + 64 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 40 + + + + + + + 1 + 64 + 30 + 40 + + + + + 1 + 64 + 30 + 40 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 40 + + + 1 + 64 + 1 + 1 + + + + + 1 + 1 + 30 + 40 + + + + + + + + 1 + 1 + 1 + 1 + + + + + + + + 1 + 1 + 30 + 40 + + + 1 + 1 + 1 + 1 + + + + + 1 + 1 + 30 + 40 + + + + + + + + 1 + 64 + 30 + 40 + + + 1 + 1 + 30 + 40 + + + + + 1 + 65 + 30 + 40 + + + + + + + + 3 + + + + + + + + 1 + 65 + 30 + 40 + + + 3 + + + + + 1 + 65 + 1200 + + + + + + + + 128 + 128 + 3 + 3 + + + + + + + + 1 + 128 + 30 + 40 + + + 128 + 128 + 3 + 3 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 20 + + + + + + + 1 + 128 + 15 + 20 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 128 + 15 + 20 + + + 1 + 256 + 15 + 20 + + + + + 1 + 384 + 15 + 20 + + + + + + + + 256 + 384 + 1 + 1 + + + + + + + + 1 + 384 + 15 + 20 + + + 256 + 384 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 20 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + 1 + 256 + 15 + 20 + + + + + 1 + 256 + 15 + 20 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 256 + 15 + 20 + + + + 2 + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 15 + 20 + + + + + + + + 64 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 20 + + + 64 + 128 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 20 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 20 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 20 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 20 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 64 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 20 + + + 64 + 128 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 15 + 20 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 128 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 20 + + + 128 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 20 + + + + + + + 1 + 128 + 15 + 20 + + + + + 1 + 128 + 15 + 20 + + + + + + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 15 + 20 + + + 1 + 128 + 15 + 20 + + + + + 1 + 384 + 15 + 20 + + + + + + + + 256 + 384 + 1 + 1 + + + + + + + + 1 + 384 + 15 + 20 + + + 256 + 384 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 20 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + 1 + 256 + 15 + 20 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 64 + 256 + 3 + 3 + + + + + + + + 1 + 256 + 15 + 20 + + + 64 + 256 + 3 + 3 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 20 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 64 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 64 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 256 + 1 + 1 + 3 + 3 + + + + + + + + 1 + 256 + 15 + 20 + + + 256 + 1 + 1 + 3 + 3 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 20 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 20 + + + + + + + 1 + 256 + 15 + 20 + + + + + 1 + 256 + 15 + 20 + + + + + + + + 64 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 20 + + + 64 + 256 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 64 + 1 + 1 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 20 + + + 64 + 1 + 1 + 3 + 3 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 64 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 64 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 20 + + + + + + + 1 + 64 + 15 + 20 + + + + + 1 + 64 + 15 + 20 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 64 + 1 + 1 + + + + + 1 + 1 + 15 + 20 + + + + + + + + 1 + 1 + 1 + 1 + + + + + + + + 1 + 1 + 15 + 20 + + + 1 + 1 + 1 + 1 + + + + + 1 + 1 + 15 + 20 + + + + + + + + 1 + 64 + 15 + 20 + + + 1 + 1 + 15 + 20 + + + + + 1 + 65 + 15 + 20 + + + + + + + + 3 + + + + + + + + 1 + 65 + 15 + 20 + + + 3 + + + + + 1 + 65 + 300 + + + + + + + + 1 + 65 + 4800 + + + 1 + 65 + 1200 + + + 1 + 65 + 300 + + + + + 1 + 65 + 6300 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 65 + 6300 + + + + 2 + + + + + 1 + 64 + 6300 + + + 1 + 1 + 6300 + + + + + + + + 4 + + + + + + + + 1 + 64 + 6300 + + + 4 + + + + + 1 + 4 + 16 + 6300 + + + + + + + + 4 + + + + + + + 1 + 4 + 16 + 6300 + + + 4 + + + + + 1 + 16 + 4 + 6300 + + + + + + + + 1 + 16 + 4 + 6300 + + + + + 1 + 16 + 4 + 6300 + + + + + + + + 1 + 16 + 1 + 1 + + + + + + + + 1 + 16 + 4 + 6300 + + + 1 + 16 + 1 + 1 + + + + + 1 + 1 + 4 + 6300 + + + + + + + + 3 + + + + + + + + 1 + 1 + 4 + 6300 + + + 3 + + + + + 1 + 4 + 6300 + + + + + + + + 1 + + + + + + + + + + + + + + 4 + + + 1 + + + + + + 1 + + + + + + + + 1 + + + + + + + + 1 + 64 + 6300 + + + + + 3 + + + + + + + + 1 + + + + + + + + + + + + + + 3 + + + 1 + + + + + + 1 + + + + + + + + 1 + + + 1 + + + 1 + + + + + 3 + + + + + + + + 3 + + + + + 3 + + + + + + + + 1 + + + + + + + + 3 + + + + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + 1 + + + + + + + + 1 + + + + + 1 + + + + + + + + + 1 + + + + + 1 + + + + + + + + 1 + + + + + + + + 1 + + + 1 + + + + + 2 + + + + + + + 1 + 4 + 6300 + + + + 2 + + + + + 1 + 2 + 6300 + + + 1 + 2 + 6300 + + + + + + + + 1 + 2 + 6300 + + + 1 + 2 + 6300 + + + + + 1 + 2 + 6300 + + + + + + + + 1 + 2 + 6300 + + + 1 + 2 + 6300 + + + + + 1 + 2 + 6300 + + + + + + + + 1 + 2 + 6300 + + + 1 + 2 + 6300 + + + + + 1 + 2 + 6300 + + + + + + + + 1 + 1 + 1 + + + + + + + + 1 + 2 + 6300 + + + 1 + 1 + 1 + + + + + 1 + 2 + 6300 + + + + + + + + 1 + 2 + 6300 + + + 1 + 2 + 6300 + + + + + 1 + 2 + 6300 + + + + + + + + 1 + 2 + 6300 + + + 1 + 2 + 6300 + + + + + 1 + 4 + 6300 + + + + + + + + 1 + 1 + 6300 + + + + + + + + 1 + 4 + 6300 + + + 1 + 1 + 6300 + + + + + 1 + 4 + 6300 + + + + + + + 1 + 1 + 6300 + + + + + 1 + 1 + 6300 + + + + + + + + 51 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 60 + 80 + + + 51 + 64 + 3 + 3 + + + + + 1 + 51 + 60 + 80 + + + + + + + + 1 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 60 + 80 + + + 1 + 51 + 1 + 1 + + + + + 1 + 51 + 60 + 80 + + + + + + + 1 + 51 + 60 + 80 + + + + + 1 + 51 + 60 + 80 + + + + + + + + 51 + 51 + 3 + 3 + + + + + + + + 1 + 51 + 60 + 80 + + + 51 + 51 + 3 + 3 + + + + + 1 + 51 + 60 + 80 + + + + + + + + 1 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 60 + 80 + + + 1 + 51 + 1 + 1 + + + + + 1 + 51 + 60 + 80 + + + + + + + 1 + 51 + 60 + 80 + + + + + 1 + 51 + 60 + 80 + + + + + + + + 51 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 60 + 80 + + + 51 + 51 + 1 + 1 + + + + + 1 + 51 + 60 + 80 + + + + + + + + 1 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 60 + 80 + + + 1 + 51 + 1 + 1 + + + + + 1 + 51 + 60 + 80 + + + + + + + + 3 + + + + + + + + 1 + 51 + 60 + 80 + + + 3 + + + + + 1 + 51 + 4800 + + + + + + + + 51 + 128 + 3 + 3 + + + + + + + + 1 + 128 + 30 + 40 + + + 51 + 128 + 3 + 3 + + + + + 1 + 51 + 30 + 40 + + + + + + + + 1 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 30 + 40 + + + 1 + 51 + 1 + 1 + + + + + 1 + 51 + 30 + 40 + + + + + + + 1 + 51 + 30 + 40 + + + + + 1 + 51 + 30 + 40 + + + + + + + + 51 + 51 + 3 + 3 + + + + + + + + 1 + 51 + 30 + 40 + + + 51 + 51 + 3 + 3 + + + + + 1 + 51 + 30 + 40 + + + + + + + + 1 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 30 + 40 + + + 1 + 51 + 1 + 1 + + + + + 1 + 51 + 30 + 40 + + + + + + + 1 + 51 + 30 + 40 + + + + + 1 + 51 + 30 + 40 + + + + + + + + 51 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 30 + 40 + + + 51 + 51 + 1 + 1 + + + + + 1 + 51 + 30 + 40 + + + + + + + + 1 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 30 + 40 + + + 1 + 51 + 1 + 1 + + + + + 1 + 51 + 30 + 40 + + + + + + + + 3 + + + + + + + + 1 + 51 + 30 + 40 + + + 3 + + + + + 1 + 51 + 1200 + + + + + + + + 51 + 256 + 3 + 3 + + + + + + + + 1 + 256 + 15 + 20 + + + 51 + 256 + 3 + 3 + + + + + 1 + 51 + 15 + 20 + + + + + + + + 1 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 15 + 20 + + + 1 + 51 + 1 + 1 + + + + + 1 + 51 + 15 + 20 + + + + + + + 1 + 51 + 15 + 20 + + + + + 1 + 51 + 15 + 20 + + + + + + + + 51 + 51 + 3 + 3 + + + + + + + + 1 + 51 + 15 + 20 + + + 51 + 51 + 3 + 3 + + + + + 1 + 51 + 15 + 20 + + + + + + + + 1 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 15 + 20 + + + 1 + 51 + 1 + 1 + + + + + 1 + 51 + 15 + 20 + + + + + + + 1 + 51 + 15 + 20 + + + + + 1 + 51 + 15 + 20 + + + + + + + + 51 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 15 + 20 + + + 51 + 51 + 1 + 1 + + + + + 1 + 51 + 15 + 20 + + + + + + + + 1 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 15 + 20 + + + 1 + 51 + 1 + 1 + + + + + 1 + 51 + 15 + 20 + + + + + + + + 3 + + + + + + + + 1 + 51 + 15 + 20 + + + 3 + + + + + 1 + 51 + 300 + + + + + + + + 1 + 51 + 4800 + + + 1 + 51 + 1200 + + + 1 + 51 + 300 + + + + + 1 + 51 + 6300 + + + + + + + + 4 + + + + + + + + 1 + 51 + 6300 + + + 4 + + + + + 1 + 17 + 3 + 6300 + + + + + + + + 1 + + + + + + + + 1 + + + + + + + + 1 + + + + + + + + 1 + + + + + + + 1 + 17 + 3 + 6300 + + + 1 + + + 1 + + + 1 + + + 1 + + + + + 1 + 17 + 2 + 6300 + + + + + + + + 1 + 1 + 1 + 6300 + + + + + + + + 1 + 17 + 2 + 6300 + + + 1 + 1 + 1 + 6300 + + + + + 1 + 17 + 2 + 6300 + + + + + + + + 1 + 1 + 2 + 6300 + + + + + + + + 1 + 17 + 2 + 6300 + + + 1 + 1 + 2 + 6300 + + + + + 1 + 17 + 2 + 6300 + + + + + + + + 1 + + + + + + + + 1 + + + + + + + + 1 + + + + + + + 1 + 17 + 3 + 6300 + + + 1 + + + 1 + + + 1 + + + 1 + + + + + 1 + 17 + 1 + 6300 + + + + + + + 1 + 17 + 1 + 6300 + + + + + 1 + 17 + 1 + 6300 + + + + + + + + 1 + 17 + 2 + 6300 + + + 1 + 17 + 1 + 6300 + + + + + 1 + 17 + 3 + 6300 + + + + + + + + 3 + + + + + + + + 1 + 17 + 3 + 6300 + + + 3 + + + + + 1 + 51 + 6300 + + + + + + + + 1 + 4 + 6300 + + + 1 + 1 + 6300 + + + 1 + 51 + 6300 + + + + + 1 + 56 + 6300 + + + + + + + 1 + 56 + 6300 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/etc/neural_networks/yolo11n-pose-ov-narrow.bin b/etc/neural_networks/yolo11n-pose-ov-narrow.bin new file mode 100644 index 0000000000..0f4f1e5860 Binary files /dev/null and b/etc/neural_networks/yolo11n-pose-ov-narrow.bin differ diff --git a/etc/neural_networks/yolo11n-pose-ov-narrow.xml b/etc/neural_networks/yolo11n-pose-ov-narrow.xml new file mode 100644 index 0000000000..1c9d765346 --- /dev/null +++ b/etc/neural_networks/yolo11n-pose-ov-narrow.xml @@ -0,0 +1,12028 @@ + + + + + + + + 1 + 3 + 480 + 192 + + + + + + + + 1 + 2 + 1890 + + + + + + + + 16 + 3 + 3 + 3 + + + + + + + + 1 + 3 + 480 + 192 + + + 16 + 3 + 3 + 3 + + + + + 1 + 16 + 240 + 96 + + + + + + + + 1 + 16 + 1 + 1 + + + + + + + + 1 + 16 + 240 + 96 + + + 1 + 16 + 1 + 1 + + + + + 1 + 16 + 240 + 96 + + + + + + + 1 + 16 + 240 + 96 + + + + + 1 + 16 + 240 + 96 + + + + + + + + 32 + 16 + 3 + 3 + + + + + + + + 1 + 16 + 240 + 96 + + + 32 + 16 + 3 + 3 + + + + + 1 + 32 + 120 + 48 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 120 + 48 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 120 + 48 + + + + + + + 1 + 32 + 120 + 48 + + + + + 1 + 32 + 120 + 48 + + + + + + + + 32 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 120 + 48 + + + 32 + 32 + 1 + 1 + + + + + 1 + 32 + 120 + 48 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 120 + 48 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 120 + 48 + + + + + + + 1 + 32 + 120 + 48 + + + + + 1 + 32 + 120 + 48 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 32 + 120 + 48 + + + + 2 + + + + + 1 + 16 + 120 + 48 + + + 1 + 16 + 120 + 48 + + + + + + + + 8 + 16 + 3 + 3 + + + + + + + + 1 + 16 + 120 + 48 + + + 8 + 16 + 3 + 3 + + + + + 1 + 8 + 120 + 48 + + + + + + + + 1 + 8 + 1 + 1 + + + + + + + + 1 + 8 + 120 + 48 + + + 1 + 8 + 1 + 1 + + + + + 1 + 8 + 120 + 48 + + + + + + + 1 + 8 + 120 + 48 + + + + + 1 + 8 + 120 + 48 + + + + + + + + 16 + 8 + 3 + 3 + + + + + + + + 1 + 8 + 120 + 48 + + + 16 + 8 + 3 + 3 + + + + + 1 + 16 + 120 + 48 + + + + + + + + 1 + 16 + 1 + 1 + + + + + + + + 1 + 16 + 120 + 48 + + + 1 + 16 + 1 + 1 + + + + + 1 + 16 + 120 + 48 + + + + + + + 1 + 16 + 120 + 48 + + + + + 1 + 16 + 120 + 48 + + + + + + + + 1 + 16 + 120 + 48 + + + 1 + 16 + 120 + 48 + + + + + 1 + 16 + 120 + 48 + + + + + + + + 1 + 16 + 120 + 48 + + + 1 + 16 + 120 + 48 + + + 1 + 16 + 120 + 48 + + + + + 1 + 48 + 120 + 48 + + + + + + + + 64 + 48 + 1 + 1 + + + + + + + + 1 + 48 + 120 + 48 + + + 64 + 48 + 1 + 1 + + + + + 1 + 64 + 120 + 48 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 120 + 48 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 120 + 48 + + + + + + + 1 + 64 + 120 + 48 + + + + + 1 + 64 + 120 + 48 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 120 + 48 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 24 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 24 + + + + + + + 1 + 64 + 60 + 24 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 64 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 24 + + + 64 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 24 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 24 + + + + + + + 1 + 64 + 60 + 24 + + + + + 1 + 64 + 60 + 24 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 64 + 60 + 24 + + + + 2 + + + + + 1 + 32 + 60 + 24 + + + 1 + 32 + 60 + 24 + + + + + + + + 16 + 32 + 3 + 3 + + + + + + + + 1 + 32 + 60 + 24 + + + 16 + 32 + 3 + 3 + + + + + 1 + 16 + 60 + 24 + + + + + + + + 1 + 16 + 1 + 1 + + + + + + + + 1 + 16 + 60 + 24 + + + 1 + 16 + 1 + 1 + + + + + 1 + 16 + 60 + 24 + + + + + + + 1 + 16 + 60 + 24 + + + + + 1 + 16 + 60 + 24 + + + + + + + + 32 + 16 + 3 + 3 + + + + + + + + 1 + 16 + 60 + 24 + + + 32 + 16 + 3 + 3 + + + + + 1 + 32 + 60 + 24 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 60 + 24 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 60 + 24 + + + + + + + 1 + 32 + 60 + 24 + + + + + 1 + 32 + 60 + 24 + + + + + + + + 1 + 32 + 60 + 24 + + + 1 + 32 + 60 + 24 + + + + + 1 + 32 + 60 + 24 + + + + + + + + 1 + 32 + 60 + 24 + + + 1 + 32 + 60 + 24 + + + 1 + 32 + 60 + 24 + + + + + 1 + 96 + 60 + 24 + + + + + + + + 128 + 96 + 1 + 1 + + + + + + + + 1 + 96 + 60 + 24 + + + 128 + 96 + 1 + 1 + + + + + 1 + 128 + 60 + 24 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 60 + 24 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 60 + 24 + + + + + + + 1 + 128 + 60 + 24 + + + + + 1 + 128 + 60 + 24 + + + + + + + + 128 + 128 + 3 + 3 + + + + + + + + 1 + 128 + 60 + 24 + + + 128 + 128 + 3 + 3 + + + + + 1 + 128 + 30 + 12 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 12 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 30 + 12 + + + + + + + 1 + 128 + 30 + 12 + + + + + 1 + 128 + 30 + 12 + + + + + + + + 128 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 12 + + + 128 + 128 + 1 + 1 + + + + + 1 + 128 + 30 + 12 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 12 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 30 + 12 + + + + + + + 1 + 128 + 30 + 12 + + + + + 1 + 128 + 30 + 12 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 128 + 30 + 12 + + + + 2 + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 30 + 12 + + + + + + + + 32 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 12 + + + 32 + 64 + 1 + 1 + + + + + 1 + 32 + 30 + 12 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 30 + 12 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 30 + 12 + + + + + + + 1 + 32 + 30 + 12 + + + + + 1 + 32 + 30 + 12 + + + + + + + + 32 + 32 + 3 + 3 + + + + + + + + 1 + 32 + 30 + 12 + + + 32 + 32 + 3 + 3 + + + + + 1 + 32 + 30 + 12 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 30 + 12 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 30 + 12 + + + + + + + 1 + 32 + 30 + 12 + + + + + 1 + 32 + 30 + 12 + + + + + + + + 32 + 32 + 3 + 3 + + + + + + + + 1 + 32 + 30 + 12 + + + 32 + 32 + 3 + 3 + + + + + 1 + 32 + 30 + 12 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 30 + 12 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 30 + 12 + + + + + + + 1 + 32 + 30 + 12 + + + + + 1 + 32 + 30 + 12 + + + + + + + + 1 + 32 + 30 + 12 + + + 1 + 32 + 30 + 12 + + + + + 1 + 32 + 30 + 12 + + + + + + + + 32 + 32 + 3 + 3 + + + + + + + + 1 + 32 + 30 + 12 + + + 32 + 32 + 3 + 3 + + + + + 1 + 32 + 30 + 12 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 30 + 12 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 30 + 12 + + + + + + + 1 + 32 + 30 + 12 + + + + + 1 + 32 + 30 + 12 + + + + + + + + 32 + 32 + 3 + 3 + + + + + + + + 1 + 32 + 30 + 12 + + + 32 + 32 + 3 + 3 + + + + + 1 + 32 + 30 + 12 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 30 + 12 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 30 + 12 + + + + + + + 1 + 32 + 30 + 12 + + + + + 1 + 32 + 30 + 12 + + + + + + + + 1 + 32 + 30 + 12 + + + 1 + 32 + 30 + 12 + + + + + 1 + 32 + 30 + 12 + + + + + + + + 32 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 12 + + + 32 + 64 + 1 + 1 + + + + + 1 + 32 + 30 + 12 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 30 + 12 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 30 + 12 + + + + + + + 1 + 32 + 30 + 12 + + + + + 1 + 32 + 30 + 12 + + + + + + + + 1 + 32 + 30 + 12 + + + 1 + 32 + 30 + 12 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 64 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 12 + + + 64 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 12 + + + + + + + 1 + 64 + 30 + 12 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 30 + 12 + + + + + 1 + 192 + 30 + 12 + + + + + + + + 128 + 192 + 1 + 1 + + + + + + + + 1 + 192 + 30 + 12 + + + 128 + 192 + 1 + 1 + + + + + 1 + 128 + 30 + 12 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 12 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 30 + 12 + + + + + + + 1 + 128 + 30 + 12 + + + + + 1 + 128 + 30 + 12 + + + + + + + + 256 + 128 + 3 + 3 + + + + + + + + 1 + 128 + 30 + 12 + + + 256 + 128 + 3 + 3 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 6 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + 1 + 256 + 15 + 6 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 256 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 6 + + + 256 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 6 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + 1 + 256 + 15 + 6 + + + + + 1 + 256 + 15 + 6 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 256 + 15 + 6 + + + + 2 + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 15 + 6 + + + + + + + + 64 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 6 + + + 64 + 128 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 6 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 6 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 6 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 6 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 64 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 6 + + + 64 + 128 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 15 + 6 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 128 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 6 + + + 128 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 6 + + + + + + + 1 + 128 + 15 + 6 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 15 + 6 + + + + + 1 + 384 + 15 + 6 + + + + + + + + 256 + 384 + 1 + 1 + + + + + + + + 1 + 384 + 15 + 6 + + + 256 + 384 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 6 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + 1 + 256 + 15 + 6 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 128 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 6 + + + 128 + 256 + 1 + 1 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 6 + + + + + + + 1 + 128 + 15 + 6 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 128 + 15 + 6 + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 128 + 15 + 6 + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 128 + 15 + 6 + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 15 + 6 + + + + + 1 + 512 + 15 + 6 + + + + + + + + 256 + 512 + 1 + 1 + + + + + + + + 1 + 512 + 15 + 6 + + + 256 + 512 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 6 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + 1 + 256 + 15 + 6 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 256 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 6 + + + 256 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 6 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + 1 + 256 + 15 + 6 + + + + + 1 + 256 + 15 + 6 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 256 + 15 + 6 + + + + 2 + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 15 + 6 + + + + + + + + 256 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 6 + + + 256 + 128 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 6 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 4 + + + + + + + + 1 + 256 + 15 + 6 + + + 4 + + + + + 1 + 2 + 128 + 90 + + + + + + + + + + + + + + 3 + + + + + + + 1 + 2 + 128 + 90 + + + + 3 + + + + + 1 + 2 + 32 + 90 + + + 1 + 2 + 32 + 90 + + + 1 + 2 + 64 + 90 + + + + + + + + 1 + 1 + 1 + 1 + + + + + + + + 1 + 2 + 32 + 90 + + + 1 + 1 + 1 + 1 + + + + + 1 + 2 + 32 + 90 + + + + + + + + 1 + 2 + 32 + 90 + + + 1 + 2 + 32 + 90 + + + + + 1 + 2 + 90 + 90 + + + + + + + + 1 + 2 + 90 + 90 + + + + + 1 + 2 + 90 + 90 + + + + + + + + 1 + 2 + 64 + 90 + + + 1 + 2 + 90 + 90 + + + + + 1 + 2 + 64 + 90 + + + + + + + + 1 + 128 + 15 + 6 + + + + + 4 + + + + + + + + 1 + 2 + 64 + 90 + + + 4 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 2 + 64 + 90 + + + 4 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 128 + 1 + 1 + 3 + 3 + + + + + + + + 1 + 128 + 15 + 6 + + + 128 + 1 + 1 + 3 + 3 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 15 + 6 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 128 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 6 + + + 128 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 15 + 6 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 256 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 6 + + + 256 + 128 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 6 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + 1 + 256 + 15 + 6 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 128 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 6 + + + 128 + 256 + 1 + 1 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 15 + 6 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 15 + 6 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 256 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 6 + + + 256 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 6 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + 1 + 256 + 15 + 6 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 2 + + + + + + + + 2 + + + + + + + + 1 + 256 + 15 + 6 + + + 2 + + + 2 + + + + + 1 + 256 + 30 + 12 + + + + + + + + 1 + 256 + 30 + 12 + + + 1 + 128 + 30 + 12 + + + + + 1 + 384 + 30 + 12 + + + + + + + + 128 + 384 + 1 + 1 + + + + + + + + 1 + 384 + 30 + 12 + + + 128 + 384 + 1 + 1 + + + + + 1 + 128 + 30 + 12 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 12 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 30 + 12 + + + + + + + 1 + 128 + 30 + 12 + + + + + 1 + 128 + 30 + 12 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 128 + 30 + 12 + + + + 2 + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 30 + 12 + + + + + + + + 32 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 30 + 12 + + + 32 + 64 + 3 + 3 + + + + + 1 + 32 + 30 + 12 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 30 + 12 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 30 + 12 + + + + + + + 1 + 32 + 30 + 12 + + + + + 1 + 32 + 30 + 12 + + + + + + + + 64 + 32 + 3 + 3 + + + + + + + + 1 + 32 + 30 + 12 + + + 64 + 32 + 3 + 3 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 12 + + + + + + + 1 + 64 + 30 + 12 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 30 + 12 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 30 + 12 + + + + + 1 + 192 + 30 + 12 + + + + + + + + 128 + 192 + 1 + 1 + + + + + + + + 1 + 192 + 30 + 12 + + + 128 + 192 + 1 + 1 + + + + + 1 + 128 + 30 + 12 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 12 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 30 + 12 + + + + + + + 1 + 128 + 30 + 12 + + + + + 1 + 128 + 30 + 12 + + + + + + + + 2 + + + + + + + + 2 + + + + + + + + 1 + 128 + 30 + 12 + + + 2 + + + 2 + + + + + 1 + 128 + 60 + 24 + + + + + + + + 1 + 128 + 60 + 24 + + + 1 + 128 + 60 + 24 + + + + + 1 + 256 + 60 + 24 + + + + + + + + 64 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 60 + 24 + + + 64 + 256 + 1 + 1 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 24 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 24 + + + + + + + 1 + 64 + 60 + 24 + + + + + 1 + 64 + 60 + 24 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 64 + 60 + 24 + + + + 2 + + + + + 1 + 32 + 60 + 24 + + + 1 + 32 + 60 + 24 + + + + + + + + 16 + 32 + 3 + 3 + + + + + + + + 1 + 32 + 60 + 24 + + + 16 + 32 + 3 + 3 + + + + + 1 + 16 + 60 + 24 + + + + + + + + 1 + 16 + 1 + 1 + + + + + + + + 1 + 16 + 60 + 24 + + + 1 + 16 + 1 + 1 + + + + + 1 + 16 + 60 + 24 + + + + + + + 1 + 16 + 60 + 24 + + + + + 1 + 16 + 60 + 24 + + + + + + + + 32 + 16 + 3 + 3 + + + + + + + + 1 + 16 + 60 + 24 + + + 32 + 16 + 3 + 3 + + + + + 1 + 32 + 60 + 24 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 60 + 24 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 60 + 24 + + + + + + + 1 + 32 + 60 + 24 + + + + + 1 + 32 + 60 + 24 + + + + + + + + 1 + 32 + 60 + 24 + + + 1 + 32 + 60 + 24 + + + + + 1 + 32 + 60 + 24 + + + + + + + + 1 + 32 + 60 + 24 + + + 1 + 32 + 60 + 24 + + + 1 + 32 + 60 + 24 + + + + + 1 + 96 + 60 + 24 + + + + + + + + 64 + 96 + 1 + 1 + + + + + + + + 1 + 96 + 60 + 24 + + + 64 + 96 + 1 + 1 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 24 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 24 + + + + + + + 1 + 64 + 60 + 24 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 60 + 24 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 24 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 24 + + + + + + + 1 + 64 + 60 + 24 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 60 + 24 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 24 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 24 + + + + + + + 1 + 64 + 60 + 24 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 64 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 24 + + + 64 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 24 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 64 + 1 + 1 + 3 + 3 + + + + + + + + 1 + 64 + 60 + 24 + + + 64 + 1 + 1 + 3 + 3 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 24 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 24 + + + + + + + 1 + 64 + 60 + 24 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 64 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 24 + + + 64 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 24 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 24 + + + + + + + 1 + 64 + 60 + 24 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 64 + 1 + 1 + 3 + 3 + + + + + + + + 1 + 64 + 60 + 24 + + + 64 + 1 + 1 + 3 + 3 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 24 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 24 + + + + + + + 1 + 64 + 60 + 24 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 64 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 24 + + + 64 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 24 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 60 + 24 + + + + + + + 1 + 64 + 60 + 24 + + + + + 1 + 64 + 60 + 24 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 60 + 24 + + + 1 + 64 + 1 + 1 + + + + + 1 + 1 + 60 + 24 + + + + + + + + 1 + 1 + 1 + 1 + + + + + + + + 1 + 1 + 60 + 24 + + + 1 + 1 + 1 + 1 + + + + + 1 + 1 + 60 + 24 + + + + + + + + 1 + 64 + 60 + 24 + + + 1 + 1 + 60 + 24 + + + + + 1 + 65 + 60 + 24 + + + + + + + + 3 + + + + + + + + 1 + 65 + 60 + 24 + + + 3 + + + + + 1 + 65 + 1440 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 60 + 24 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 12 + + + + + + + 1 + 64 + 30 + 12 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 1 + 64 + 30 + 12 + + + 1 + 128 + 30 + 12 + + + + + 1 + 192 + 30 + 12 + + + + + + + + 128 + 192 + 1 + 1 + + + + + + + + 1 + 192 + 30 + 12 + + + 128 + 192 + 1 + 1 + + + + + 1 + 128 + 30 + 12 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 12 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 30 + 12 + + + + + + + 1 + 128 + 30 + 12 + + + + + 1 + 128 + 30 + 12 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 128 + 30 + 12 + + + + 2 + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 30 + 12 + + + + + + + + 32 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 30 + 12 + + + 32 + 64 + 3 + 3 + + + + + 1 + 32 + 30 + 12 + + + + + + + + 1 + 32 + 1 + 1 + + + + + + + + 1 + 32 + 30 + 12 + + + 1 + 32 + 1 + 1 + + + + + 1 + 32 + 30 + 12 + + + + + + + 1 + 32 + 30 + 12 + + + + + 1 + 32 + 30 + 12 + + + + + + + + 64 + 32 + 3 + 3 + + + + + + + + 1 + 32 + 30 + 12 + + + 64 + 32 + 3 + 3 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 12 + + + + + + + 1 + 64 + 30 + 12 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 30 + 12 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 30 + 12 + + + + + 1 + 192 + 30 + 12 + + + + + + + + 128 + 192 + 1 + 1 + + + + + + + + 1 + 192 + 30 + 12 + + + 128 + 192 + 1 + 1 + + + + + 1 + 128 + 30 + 12 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 12 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 30 + 12 + + + + + + + 1 + 128 + 30 + 12 + + + + + 1 + 128 + 30 + 12 + + + + + + + + 64 + 128 + 3 + 3 + + + + + + + + 1 + 128 + 30 + 12 + + + 64 + 128 + 3 + 3 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 12 + + + + + + + 1 + 64 + 30 + 12 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 30 + 12 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 12 + + + + + + + 1 + 64 + 30 + 12 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 64 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 12 + + + 64 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 128 + 1 + 1 + 3 + 3 + + + + + + + + 1 + 128 + 30 + 12 + + + 128 + 1 + 1 + 3 + 3 + + + + + 1 + 128 + 30 + 12 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 12 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 30 + 12 + + + + + + + 1 + 128 + 30 + 12 + + + + + 1 + 128 + 30 + 12 + + + + + + + + 64 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 30 + 12 + + + 64 + 128 + 1 + 1 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 12 + + + + + + + 1 + 64 + 30 + 12 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 64 + 1 + 1 + 3 + 3 + + + + + + + + 1 + 64 + 30 + 12 + + + 64 + 1 + 1 + 3 + 3 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 12 + + + + + + + 1 + 64 + 30 + 12 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 64 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 12 + + + 64 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 30 + 12 + + + + + + + 1 + 64 + 30 + 12 + + + + + 1 + 64 + 30 + 12 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 30 + 12 + + + 1 + 64 + 1 + 1 + + + + + 1 + 1 + 30 + 12 + + + + + + + + 1 + 1 + 1 + 1 + + + + + + + + 1 + 1 + 30 + 12 + + + 1 + 1 + 1 + 1 + + + + + 1 + 1 + 30 + 12 + + + + + + + + 1 + 64 + 30 + 12 + + + 1 + 1 + 30 + 12 + + + + + 1 + 65 + 30 + 12 + + + + + + + + 3 + + + + + + + + 1 + 65 + 30 + 12 + + + 3 + + + + + 1 + 65 + 360 + + + + + + + + 128 + 128 + 3 + 3 + + + + + + + + 1 + 128 + 30 + 12 + + + 128 + 128 + 3 + 3 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 6 + + + + + + + 1 + 128 + 15 + 6 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 128 + 15 + 6 + + + 1 + 256 + 15 + 6 + + + + + 1 + 384 + 15 + 6 + + + + + + + + 256 + 384 + 1 + 1 + + + + + + + + 1 + 384 + 15 + 6 + + + 256 + 384 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 6 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + 1 + 256 + 15 + 6 + + + + + 1 + 256 + 15 + 6 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 256 + 15 + 6 + + + + 2 + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 15 + 6 + + + + + + + + 64 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 6 + + + 64 + 128 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 6 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 6 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 6 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 6 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 64 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 6 + + + 64 + 128 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 15 + 6 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 128 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 6 + + + 128 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 128 + 1 + 1 + + + + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 1 + 1 + + + + + 1 + 128 + 15 + 6 + + + + + + + 1 + 128 + 15 + 6 + + + + + 1 + 128 + 15 + 6 + + + + + + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 15 + 6 + + + 1 + 128 + 15 + 6 + + + + + 1 + 384 + 15 + 6 + + + + + + + + 256 + 384 + 1 + 1 + + + + + + + + 1 + 384 + 15 + 6 + + + 256 + 384 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 6 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + 1 + 256 + 15 + 6 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 64 + 256 + 3 + 3 + + + + + + + + 1 + 256 + 15 + 6 + + + 64 + 256 + 3 + 3 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 64 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 6 + + + 64 + 64 + 3 + 3 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 64 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 64 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 256 + 1 + 1 + 3 + 3 + + + + + + + + 1 + 256 + 15 + 6 + + + 256 + 1 + 1 + 3 + 3 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 1 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 6 + + + 1 + 256 + 1 + 1 + + + + + 1 + 256 + 15 + 6 + + + + + + + 1 + 256 + 15 + 6 + + + + + 1 + 256 + 15 + 6 + + + + + + + + 64 + 256 + 1 + 1 + + + + + + + + 1 + 256 + 15 + 6 + + + 64 + 256 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 64 + 1 + 1 + 3 + 3 + + + + + + + + 1 + 64 + 15 + 6 + + + 64 + 1 + 1 + 3 + 3 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 64 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 64 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 64 + 15 + 6 + + + + + + + 1 + 64 + 15 + 6 + + + + + 1 + 64 + 15 + 6 + + + + + + + + 1 + 64 + 1 + 1 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 64 + 1 + 1 + + + + + 1 + 1 + 15 + 6 + + + + + + + + 1 + 1 + 1 + 1 + + + + + + + + 1 + 1 + 15 + 6 + + + 1 + 1 + 1 + 1 + + + + + 1 + 1 + 15 + 6 + + + + + + + + 1 + 64 + 15 + 6 + + + 1 + 1 + 15 + 6 + + + + + 1 + 65 + 15 + 6 + + + + + + + + 3 + + + + + + + + 1 + 65 + 15 + 6 + + + 3 + + + + + 1 + 65 + 90 + + + + + + + + 1 + 65 + 1440 + + + 1 + 65 + 360 + + + 1 + 65 + 90 + + + + + 1 + 65 + 1890 + + + + + + + + + + + + + + 2 + + + + + + + 1 + 65 + 1890 + + + + 2 + + + + + 1 + 64 + 1890 + + + 1 + 1 + 1890 + + + + + + + + 4 + + + + + + + + 1 + 64 + 1890 + + + 4 + + + + + 1 + 4 + 16 + 1890 + + + + + + + + 4 + + + + + + + 1 + 4 + 16 + 1890 + + + 4 + + + + + 1 + 16 + 4 + 1890 + + + + + + + + 1 + 16 + 4 + 1890 + + + + + 1 + 16 + 4 + 1890 + + + + + + + + 1 + 16 + 1 + 1 + + + + + + + + 1 + 16 + 4 + 1890 + + + 1 + 16 + 1 + 1 + + + + + 1 + 1 + 4 + 1890 + + + + + + + + 3 + + + + + + + + 1 + 1 + 4 + 1890 + + + 3 + + + + + 1 + 4 + 1890 + + + + + + + + 1 + + + + + + + + + + + + + + 4 + + + 1 + + + + + + 1 + + + + + + + + 1 + + + + + + + + 1 + 64 + 1890 + + + + + 3 + + + + + + + + 1 + + + + + + + + + + + + + + 3 + + + 1 + + + + + + 1 + + + + + + + + 1 + + + 1 + + + 1 + + + + + 3 + + + + + + + + 3 + + + + + 3 + + + + + + + + 1 + + + + + + + + 3 + + + + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + 1 + + + + + + + + 1 + + + + + 1 + + + + + + + + + 1 + + + + + 1 + + + + + + + + 1 + + + + + + + + 1 + + + 1 + + + + + 2 + + + + + + + 1 + 4 + 1890 + + + + 2 + + + + + 1 + 2 + 1890 + + + 1 + 2 + 1890 + + + + + + + + 1 + 2 + 1890 + + + 1 + 2 + 1890 + + + + + 1 + 2 + 1890 + + + + + + + + 1 + 2 + 1890 + + + 1 + 2 + 1890 + + + + + 1 + 2 + 1890 + + + + + + + + 1 + 2 + 1890 + + + 1 + 2 + 1890 + + + + + 1 + 2 + 1890 + + + + + + + + 1 + 1 + 1 + + + + + + + + 1 + 2 + 1890 + + + 1 + 1 + 1 + + + + + 1 + 2 + 1890 + + + + + + + + 1 + 2 + 1890 + + + 1 + 2 + 1890 + + + + + 1 + 2 + 1890 + + + + + + + + 1 + 2 + 1890 + + + 1 + 2 + 1890 + + + + + 1 + 4 + 1890 + + + + + + + + 1 + 1 + 1890 + + + + + + + + 1 + 4 + 1890 + + + 1 + 1 + 1890 + + + + + 1 + 4 + 1890 + + + + + + + 1 + 1 + 1890 + + + + + 1 + 1 + 1890 + + + + + + + + 51 + 64 + 3 + 3 + + + + + + + + 1 + 64 + 60 + 24 + + + 51 + 64 + 3 + 3 + + + + + 1 + 51 + 60 + 24 + + + + + + + + 1 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 60 + 24 + + + 1 + 51 + 1 + 1 + + + + + 1 + 51 + 60 + 24 + + + + + + + 1 + 51 + 60 + 24 + + + + + 1 + 51 + 60 + 24 + + + + + + + + 51 + 51 + 3 + 3 + + + + + + + + 1 + 51 + 60 + 24 + + + 51 + 51 + 3 + 3 + + + + + 1 + 51 + 60 + 24 + + + + + + + + 1 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 60 + 24 + + + 1 + 51 + 1 + 1 + + + + + 1 + 51 + 60 + 24 + + + + + + + 1 + 51 + 60 + 24 + + + + + 1 + 51 + 60 + 24 + + + + + + + + 51 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 60 + 24 + + + 51 + 51 + 1 + 1 + + + + + 1 + 51 + 60 + 24 + + + + + + + + 1 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 60 + 24 + + + 1 + 51 + 1 + 1 + + + + + 1 + 51 + 60 + 24 + + + + + + + + 3 + + + + + + + + 1 + 51 + 60 + 24 + + + 3 + + + + + 1 + 51 + 1440 + + + + + + + + 51 + 128 + 3 + 3 + + + + + + + + 1 + 128 + 30 + 12 + + + 51 + 128 + 3 + 3 + + + + + 1 + 51 + 30 + 12 + + + + + + + + 1 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 30 + 12 + + + 1 + 51 + 1 + 1 + + + + + 1 + 51 + 30 + 12 + + + + + + + 1 + 51 + 30 + 12 + + + + + 1 + 51 + 30 + 12 + + + + + + + + 51 + 51 + 3 + 3 + + + + + + + + 1 + 51 + 30 + 12 + + + 51 + 51 + 3 + 3 + + + + + 1 + 51 + 30 + 12 + + + + + + + + 1 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 30 + 12 + + + 1 + 51 + 1 + 1 + + + + + 1 + 51 + 30 + 12 + + + + + + + 1 + 51 + 30 + 12 + + + + + 1 + 51 + 30 + 12 + + + + + + + + 51 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 30 + 12 + + + 51 + 51 + 1 + 1 + + + + + 1 + 51 + 30 + 12 + + + + + + + + 1 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 30 + 12 + + + 1 + 51 + 1 + 1 + + + + + 1 + 51 + 30 + 12 + + + + + + + + 3 + + + + + + + + 1 + 51 + 30 + 12 + + + 3 + + + + + 1 + 51 + 360 + + + + + + + + 51 + 256 + 3 + 3 + + + + + + + + 1 + 256 + 15 + 6 + + + 51 + 256 + 3 + 3 + + + + + 1 + 51 + 15 + 6 + + + + + + + + 1 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 15 + 6 + + + 1 + 51 + 1 + 1 + + + + + 1 + 51 + 15 + 6 + + + + + + + 1 + 51 + 15 + 6 + + + + + 1 + 51 + 15 + 6 + + + + + + + + 51 + 51 + 3 + 3 + + + + + + + + 1 + 51 + 15 + 6 + + + 51 + 51 + 3 + 3 + + + + + 1 + 51 + 15 + 6 + + + + + + + + 1 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 15 + 6 + + + 1 + 51 + 1 + 1 + + + + + 1 + 51 + 15 + 6 + + + + + + + 1 + 51 + 15 + 6 + + + + + 1 + 51 + 15 + 6 + + + + + + + + 51 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 15 + 6 + + + 51 + 51 + 1 + 1 + + + + + 1 + 51 + 15 + 6 + + + + + + + + 1 + 51 + 1 + 1 + + + + + + + + 1 + 51 + 15 + 6 + + + 1 + 51 + 1 + 1 + + + + + 1 + 51 + 15 + 6 + + + + + + + + 3 + + + + + + + + 1 + 51 + 15 + 6 + + + 3 + + + + + 1 + 51 + 90 + + + + + + + + 1 + 51 + 1440 + + + 1 + 51 + 360 + + + 1 + 51 + 90 + + + + + 1 + 51 + 1890 + + + + + + + + 4 + + + + + + + + 1 + 51 + 1890 + + + 4 + + + + + 1 + 17 + 3 + 1890 + + + + + + + + 1 + + + + + + + + 1 + + + + + + + + 1 + + + + + + + + 1 + + + + + + + 1 + 17 + 3 + 1890 + + + 1 + + + 1 + + + 1 + + + 1 + + + + + 1 + 17 + 2 + 1890 + + + + + + + + 1 + 1 + 1 + 1890 + + + + + + + + 1 + 17 + 2 + 1890 + + + 1 + 1 + 1 + 1890 + + + + + 1 + 17 + 2 + 1890 + + + + + + + + 1 + 1 + 2 + 1890 + + + + + + + + 1 + 17 + 2 + 1890 + + + 1 + 1 + 2 + 1890 + + + + + 1 + 17 + 2 + 1890 + + + + + + + + 1 + + + + + + + + 1 + + + + + + + + 1 + + + + + + + 1 + 17 + 3 + 1890 + + + 1 + + + 1 + + + 1 + + + 1 + + + + + 1 + 17 + 1 + 1890 + + + + + + + 1 + 17 + 1 + 1890 + + + + + 1 + 17 + 1 + 1890 + + + + + + + + 1 + 17 + 2 + 1890 + + + 1 + 17 + 1 + 1890 + + + + + 1 + 17 + 3 + 1890 + + + + + + + + 3 + + + + + + + + 1 + 17 + 3 + 1890 + + + 3 + + + + + 1 + 51 + 1890 + + + + + + + + 1 + 4 + 1890 + + + 1 + 1 + 1890 + + + 1 + 51 + 1890 + + + + + 1 + 56 + 1890 + + + + + + + 1 + 56 + 1890 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/etc/neural_networks/yolo11n-pose-ov.bin b/etc/neural_networks/yolo11n-pose-ov.bin deleted file mode 100644 index f3beff5099..0000000000 Binary files a/etc/neural_networks/yolo11n-pose-ov.bin and /dev/null differ diff --git a/etc/neural_networks/yolo11n-pose-ov.xml b/etc/neural_networks/yolo11n-pose-ov.xml deleted file mode 100644 index 91db8a59d3..0000000000 --- a/etc/neural_networks/yolo11n-pose-ov.xml +++ /dev/null @@ -1,20468 +0,0 @@ - - - - - - - - 1 - 3 - 480 - 192 - - - - - - - - 16 - 3 - 3 - 3 - - - - - - - - - - - 16 - 3 - 3 - 3 - - - - - 16 - 3 - 3 - 3 - - - - - - - - 1 - 3 - 480 - 192 - - - 16 - 3 - 3 - 3 - - - - - 1 - 16 - 240 - 96 - - - - - - - - 1 - 16 - 1 - 1 - - - - - - - - - - - 1 - 16 - 1 - 1 - - - - - 1 - 16 - 1 - 1 - - - - - - - - 1 - 16 - 240 - 96 - - - 1 - 16 - 1 - 1 - - - - - 1 - 16 - 240 - 96 - - - - - - - 1 - 16 - 240 - 96 - - - - - 1 - 16 - 240 - 96 - - - - - - - - 32 - 16 - 3 - 3 - - - - - - - - - - - 32 - 16 - 3 - 3 - - - - - 32 - 16 - 3 - 3 - - - - - - - - 1 - 16 - 240 - 96 - - - 32 - 16 - 3 - 3 - - - - - 1 - 32 - 120 - 48 - - - - - - - - 1 - 32 - 1 - 1 - - - - - - - - - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 1 - 1 - - - - - - - - 1 - 32 - 120 - 48 - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 120 - 48 - - - - - - - 1 - 32 - 120 - 48 - - - - - 1 - 32 - 120 - 48 - - - - - - - - 32 - 32 - 1 - 1 - - - - - - - - - - - 32 - 32 - 1 - 1 - - - - - 32 - 32 - 1 - 1 - - - - - - - - 1 - 32 - 120 - 48 - - - 32 - 32 - 1 - 1 - - - - - 1 - 32 - 120 - 48 - - - - - - - - 1 - 32 - 1 - 1 - - - - - - - - - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 1 - 1 - - - - - - - - 1 - 32 - 120 - 48 - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 120 - 48 - - - - - - - 1 - 32 - 120 - 48 - - - - - 1 - 32 - 120 - 48 - - - - - - - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - - - - 1 - - - - - - - - 1 - 32 - 120 - 48 - - - - - 4 - - - - - - - - - - - 1 - - - - - - - - - - - - - - - - - 4 - - - 1 - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - 2 - - - 1 - - - 1 - - - 1 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 32 - 120 - 48 - - - 2 - - - 2 - - - 2 - - - - - 1 - 16 - 120 - 48 - - - - - - - - - - - 2 - - - - - - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - 2 - - - 1 - - - 1 - - - 1 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 32 - 120 - 48 - - - 2 - - - 2 - - - 2 - - - - - 1 - 16 - 120 - 48 - - - - - - - - 8 - 16 - 3 - 3 - - - - - - - - - - - 8 - 16 - 3 - 3 - - - - - 8 - 16 - 3 - 3 - - - - - - - - 1 - 16 - 120 - 48 - - - 8 - 16 - 3 - 3 - - - - - 1 - 8 - 120 - 48 - - - - - - - - 1 - 8 - 1 - 1 - - - - - - - - - - - 1 - 8 - 1 - 1 - - - - - 1 - 8 - 1 - 1 - - - - - - - - 1 - 8 - 120 - 48 - - - 1 - 8 - 1 - 1 - - - - - 1 - 8 - 120 - 48 - - - - - - - 1 - 8 - 120 - 48 - - - - - 1 - 8 - 120 - 48 - - - - - - - - 16 - 8 - 3 - 3 - - - - - - - - - - - 16 - 8 - 3 - 3 - - - - - 16 - 8 - 3 - 3 - - - - - - - - 1 - 8 - 120 - 48 - - - 16 - 8 - 3 - 3 - - - - - 1 - 16 - 120 - 48 - - - - - - - - 1 - 16 - 1 - 1 - - - - - - - - - - - 1 - 16 - 1 - 1 - - - - - 1 - 16 - 1 - 1 - - - - - - - - 1 - 16 - 120 - 48 - - - 1 - 16 - 1 - 1 - - - - - 1 - 16 - 120 - 48 - - - - - - - 1 - 16 - 120 - 48 - - - - - 1 - 16 - 120 - 48 - - - - - - - - 1 - 16 - 120 - 48 - - - 1 - 16 - 120 - 48 - - - - - 1 - 16 - 120 - 48 - - - - - - - - 1 - 16 - 120 - 48 - - - 1 - 16 - 120 - 48 - - - 1 - 16 - 120 - 48 - - - - - 1 - 48 - 120 - 48 - - - - - - - - 64 - 48 - 1 - 1 - - - - - - - - - - - 64 - 48 - 1 - 1 - - - - - 64 - 48 - 1 - 1 - - - - - - - - 1 - 48 - 120 - 48 - - - 64 - 48 - 1 - 1 - - - - - 1 - 64 - 120 - 48 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 120 - 48 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 120 - 48 - - - - - - - 1 - 64 - 120 - 48 - - - - - 1 - 64 - 120 - 48 - - - - - - - - 64 - 64 - 3 - 3 - - - - - - - - - - - 64 - 64 - 3 - 3 - - - - - 64 - 64 - 3 - 3 - - - - - - - - 1 - 64 - 120 - 48 - - - 64 - 64 - 3 - 3 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 60 - 24 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 60 - 24 - - - - - - - 1 - 64 - 60 - 24 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 64 - 64 - 1 - 1 - - - - - - - - - - - 64 - 64 - 1 - 1 - - - - - 64 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 60 - 24 - - - 64 - 64 - 1 - 1 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 60 - 24 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 60 - 24 - - - - - - - 1 - 64 - 60 - 24 - - - - - 1 - 64 - 60 - 24 - - - - - - - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - - - - 1 - - - - - - - - 1 - 64 - 60 - 24 - - - - - 4 - - - - - - - - - - - 1 - - - - - - - - - - - - - - - - - 4 - - - 1 - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - 2 - - - 1 - - - 1 - - - 1 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 64 - 60 - 24 - - - 2 - - - 2 - - - 2 - - - - - 1 - 32 - 60 - 24 - - - - - - - - - - - 2 - - - - - - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - 2 - - - 1 - - - 1 - - - 1 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 64 - 60 - 24 - - - 2 - - - 2 - - - 2 - - - - - 1 - 32 - 60 - 24 - - - - - - - - 16 - 32 - 3 - 3 - - - - - - - - - - - 16 - 32 - 3 - 3 - - - - - 16 - 32 - 3 - 3 - - - - - - - - 1 - 32 - 60 - 24 - - - 16 - 32 - 3 - 3 - - - - - 1 - 16 - 60 - 24 - - - - - - - - 1 - 16 - 1 - 1 - - - - - - - - - - - 1 - 16 - 1 - 1 - - - - - 1 - 16 - 1 - 1 - - - - - - - - 1 - 16 - 60 - 24 - - - 1 - 16 - 1 - 1 - - - - - 1 - 16 - 60 - 24 - - - - - - - 1 - 16 - 60 - 24 - - - - - 1 - 16 - 60 - 24 - - - - - - - - 32 - 16 - 3 - 3 - - - - - - - - - - - 32 - 16 - 3 - 3 - - - - - 32 - 16 - 3 - 3 - - - - - - - - 1 - 16 - 60 - 24 - - - 32 - 16 - 3 - 3 - - - - - 1 - 32 - 60 - 24 - - - - - - - - 1 - 32 - 1 - 1 - - - - - - - - - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 1 - 1 - - - - - - - - 1 - 32 - 60 - 24 - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 60 - 24 - - - - - - - 1 - 32 - 60 - 24 - - - - - 1 - 32 - 60 - 24 - - - - - - - - 1 - 32 - 60 - 24 - - - 1 - 32 - 60 - 24 - - - - - 1 - 32 - 60 - 24 - - - - - - - - 1 - 32 - 60 - 24 - - - 1 - 32 - 60 - 24 - - - 1 - 32 - 60 - 24 - - - - - 1 - 96 - 60 - 24 - - - - - - - - 128 - 96 - 1 - 1 - - - - - - - - - - - 128 - 96 - 1 - 1 - - - - - 128 - 96 - 1 - 1 - - - - - - - - 1 - 96 - 60 - 24 - - - 128 - 96 - 1 - 1 - - - - - 1 - 128 - 60 - 24 - - - - - - - - 1 - 128 - 1 - 1 - - - - - - - - - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 60 - 24 - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 60 - 24 - - - - - - - 1 - 128 - 60 - 24 - - - - - 1 - 128 - 60 - 24 - - - - - - - - 128 - 128 - 3 - 3 - - - - - - - - - - - 128 - 128 - 3 - 3 - - - - - 128 - 128 - 3 - 3 - - - - - - - - 1 - 128 - 60 - 24 - - - 128 - 128 - 3 - 3 - - - - - 1 - 128 - 30 - 12 - - - - - - - - 1 - 128 - 1 - 1 - - - - - - - - - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 30 - 12 - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 30 - 12 - - - - - - - 1 - 128 - 30 - 12 - - - - - 1 - 128 - 30 - 12 - - - - - - - - 128 - 128 - 1 - 1 - - - - - - - - - - - 128 - 128 - 1 - 1 - - - - - 128 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 30 - 12 - - - 128 - 128 - 1 - 1 - - - - - 1 - 128 - 30 - 12 - - - - - - - - 1 - 128 - 1 - 1 - - - - - - - - - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 30 - 12 - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 30 - 12 - - - - - - - 1 - 128 - 30 - 12 - - - - - 1 - 128 - 30 - 12 - - - - - - - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - - - - 1 - - - - - - - - 1 - 128 - 30 - 12 - - - - - 4 - - - - - - - - - - - 1 - - - - - - - - - - - - - - - - - 4 - - - 1 - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - 2 - - - 1 - - - 1 - - - 1 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 128 - 30 - 12 - - - 2 - - - 2 - - - 2 - - - - - 1 - 64 - 30 - 12 - - - - - - - - - - - 2 - - - - - - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - 2 - - - 1 - - - 1 - - - 1 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 128 - 30 - 12 - - - 2 - - - 2 - - - 2 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 32 - 64 - 1 - 1 - - - - - - - - - - - 32 - 64 - 1 - 1 - - - - - 32 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 30 - 12 - - - 32 - 64 - 1 - 1 - - - - - 1 - 32 - 30 - 12 - - - - - - - - 1 - 32 - 1 - 1 - - - - - - - - - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 1 - 1 - - - - - - - - 1 - 32 - 30 - 12 - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 30 - 12 - - - - - - - 1 - 32 - 30 - 12 - - - - - 1 - 32 - 30 - 12 - - - - - - - - 32 - 32 - 3 - 3 - - - - - - - - - - - 32 - 32 - 3 - 3 - - - - - 32 - 32 - 3 - 3 - - - - - - - - 1 - 32 - 30 - 12 - - - 32 - 32 - 3 - 3 - - - - - 1 - 32 - 30 - 12 - - - - - - - - 1 - 32 - 1 - 1 - - - - - - - - - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 1 - 1 - - - - - - - - 1 - 32 - 30 - 12 - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 30 - 12 - - - - - - - 1 - 32 - 30 - 12 - - - - - 1 - 32 - 30 - 12 - - - - - - - - 32 - 32 - 3 - 3 - - - - - - - - - - - 32 - 32 - 3 - 3 - - - - - 32 - 32 - 3 - 3 - - - - - - - - 1 - 32 - 30 - 12 - - - 32 - 32 - 3 - 3 - - - - - 1 - 32 - 30 - 12 - - - - - - - - 1 - 32 - 1 - 1 - - - - - - - - - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 1 - 1 - - - - - - - - 1 - 32 - 30 - 12 - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 30 - 12 - - - - - - - 1 - 32 - 30 - 12 - - - - - 1 - 32 - 30 - 12 - - - - - - - - 1 - 32 - 30 - 12 - - - 1 - 32 - 30 - 12 - - - - - 1 - 32 - 30 - 12 - - - - - - - - 32 - 32 - 3 - 3 - - - - - - - - - - - 32 - 32 - 3 - 3 - - - - - 32 - 32 - 3 - 3 - - - - - - - - 1 - 32 - 30 - 12 - - - 32 - 32 - 3 - 3 - - - - - 1 - 32 - 30 - 12 - - - - - - - - 1 - 32 - 1 - 1 - - - - - - - - - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 1 - 1 - - - - - - - - 1 - 32 - 30 - 12 - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 30 - 12 - - - - - - - 1 - 32 - 30 - 12 - - - - - 1 - 32 - 30 - 12 - - - - - - - - 32 - 32 - 3 - 3 - - - - - - - - - - - 32 - 32 - 3 - 3 - - - - - 32 - 32 - 3 - 3 - - - - - - - - 1 - 32 - 30 - 12 - - - 32 - 32 - 3 - 3 - - - - - 1 - 32 - 30 - 12 - - - - - - - - 1 - 32 - 1 - 1 - - - - - - - - - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 1 - 1 - - - - - - - - 1 - 32 - 30 - 12 - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 30 - 12 - - - - - - - 1 - 32 - 30 - 12 - - - - - 1 - 32 - 30 - 12 - - - - - - - - 1 - 32 - 30 - 12 - - - 1 - 32 - 30 - 12 - - - - - 1 - 32 - 30 - 12 - - - - - - - - 32 - 64 - 1 - 1 - - - - - - - - - - - 32 - 64 - 1 - 1 - - - - - 32 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 30 - 12 - - - 32 - 64 - 1 - 1 - - - - - 1 - 32 - 30 - 12 - - - - - - - - 1 - 32 - 1 - 1 - - - - - - - - - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 1 - 1 - - - - - - - - 1 - 32 - 30 - 12 - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 30 - 12 - - - - - - - 1 - 32 - 30 - 12 - - - - - 1 - 32 - 30 - 12 - - - - - - - - 1 - 32 - 30 - 12 - - - 1 - 32 - 30 - 12 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 64 - 64 - 1 - 1 - - - - - - - - - - - 64 - 64 - 1 - 1 - - - - - 64 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 30 - 12 - - - 64 - 64 - 1 - 1 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 30 - 12 - - - - - - - 1 - 64 - 30 - 12 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 30 - 12 - - - - - 1 - 192 - 30 - 12 - - - - - - - - 128 - 192 - 1 - 1 - - - - - - - - - - - 128 - 192 - 1 - 1 - - - - - 128 - 192 - 1 - 1 - - - - - - - - 1 - 192 - 30 - 12 - - - 128 - 192 - 1 - 1 - - - - - 1 - 128 - 30 - 12 - - - - - - - - 1 - 128 - 1 - 1 - - - - - - - - - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 30 - 12 - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 30 - 12 - - - - - - - 1 - 128 - 30 - 12 - - - - - 1 - 128 - 30 - 12 - - - - - - - - 256 - 128 - 3 - 3 - - - - - - - - - - - 256 - 128 - 3 - 3 - - - - - 256 - 128 - 3 - 3 - - - - - - - - 1 - 128 - 30 - 12 - - - 256 - 128 - 3 - 3 - - - - - 1 - 256 - 15 - 6 - - - - - - - - 1 - 256 - 1 - 1 - - - - - - - - - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 1 - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - 1 - 256 - 15 - 6 - - - - - 1 - 256 - 15 - 6 - - - - - - - - 256 - 256 - 1 - 1 - - - - - - - - - - - 256 - 256 - 1 - 1 - - - - - 256 - 256 - 1 - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - 256 - 256 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - - 1 - 256 - 1 - 1 - - - - - - - - - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 1 - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - 1 - 256 - 15 - 6 - - - - - 1 - 256 - 15 - 6 - - - - - - - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - - - - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - - - 4 - - - - - - - - - - - 1 - - - - - - - - - - - - - - - - - 4 - - - 1 - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - 2 - - - 1 - - - 1 - - - 1 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 256 - 15 - 6 - - - 2 - - - 2 - - - 2 - - - - - 1 - 128 - 15 - 6 - - - - - - - - - - - 2 - - - - - - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - 2 - - - 1 - - - 1 - - - 1 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 256 - 15 - 6 - - - 2 - - - 2 - - - 2 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 64 - 128 - 1 - 1 - - - - - - - - - - - 64 - 128 - 1 - 1 - - - - - 64 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 15 - 6 - - - 64 - 128 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 64 - 64 - 3 - 3 - - - - - - - - - - - 64 - 64 - 3 - 3 - - - - - 64 - 64 - 3 - 3 - - - - - - - - 1 - 64 - 15 - 6 - - - 64 - 64 - 3 - 3 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 64 - 64 - 3 - 3 - - - - - - - - - - - 64 - 64 - 3 - 3 - - - - - 64 - 64 - 3 - 3 - - - - - - - - 1 - 64 - 15 - 6 - - - 64 - 64 - 3 - 3 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 64 - 64 - 3 - 3 - - - - - - - - - - - 64 - 64 - 3 - 3 - - - - - 64 - 64 - 3 - 3 - - - - - - - - 1 - 64 - 15 - 6 - - - 64 - 64 - 3 - 3 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 64 - 64 - 3 - 3 - - - - - - - - - - - 64 - 64 - 3 - 3 - - - - - 64 - 64 - 3 - 3 - - - - - - - - 1 - 64 - 15 - 6 - - - 64 - 64 - 3 - 3 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 64 - 128 - 1 - 1 - - - - - - - - - - - 64 - 128 - 1 - 1 - - - - - 64 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 15 - 6 - - - 64 - 128 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 15 - 6 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 128 - 128 - 1 - 1 - - - - - - - - - - - 128 - 128 - 1 - 1 - - - - - 128 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 15 - 6 - - - 128 - 128 - 1 - 1 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 1 - 128 - 1 - 1 - - - - - - - - - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 15 - 6 - - - - - - - 1 - 128 - 15 - 6 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 15 - 6 - - - - - 1 - 384 - 15 - 6 - - - - - - - - 256 - 384 - 1 - 1 - - - - - - - - - - - 256 - 384 - 1 - 1 - - - - - 256 - 384 - 1 - 1 - - - - - - - - 1 - 384 - 15 - 6 - - - 256 - 384 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - - 1 - 256 - 1 - 1 - - - - - - - - - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 1 - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - 1 - 256 - 15 - 6 - - - - - 1 - 256 - 15 - 6 - - - - - - - - 128 - 256 - 1 - 1 - - - - - - - - - - - 128 - 256 - 1 - 1 - - - - - 128 - 256 - 1 - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - 128 - 256 - 1 - 1 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 1 - 128 - 1 - 1 - - - - - - - - - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 15 - 6 - - - - - - - 1 - 128 - 15 - 6 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 1 - 128 - 15 - 6 - - - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 15 - 6 - - - - - - - - 1 - 128 - 15 - 6 - - - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 15 - 6 - - - - - - - - 1 - 128 - 15 - 6 - - - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 15 - 6 - - - - - - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 15 - 6 - - - - - 1 - 512 - 15 - 6 - - - - - - - - 256 - 512 - 1 - 1 - - - - - - - - - - - 256 - 512 - 1 - 1 - - - - - 256 - 512 - 1 - 1 - - - - - - - - 1 - 512 - 15 - 6 - - - 256 - 512 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - - 1 - 256 - 1 - 1 - - - - - - - - - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 1 - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - 1 - 256 - 15 - 6 - - - - - 1 - 256 - 15 - 6 - - - - - - - - 256 - 256 - 1 - 1 - - - - - - - - - - - 256 - 256 - 1 - 1 - - - - - 256 - 256 - 1 - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - 256 - 256 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - - 1 - 256 - 1 - 1 - - - - - - - - - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 1 - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - 1 - 256 - 15 - 6 - - - - - 1 - 256 - 15 - 6 - - - - - - - - - - - - - - 2 - - - - - - - 1 - 256 - 15 - 6 - - - - 2 - - - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 15 - 6 - - - - - - - - 256 - 128 - 1 - 1 - - - - - - - - - - - 256 - 128 - 1 - 1 - - - - - 256 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 15 - 6 - - - 256 - 128 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - - 1 - 256 - 1 - 1 - - - - - - - - - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 1 - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - - - - - 4 - - - - - - - - 1 - 256 - 15 - 6 - - - 4 - - - - - 1 - 2 - 128 - 90 - - - - - - - - - - - - - - 3 - - - - - - - 1 - 2 - 128 - 90 - - - - 3 - - - - - 1 - 2 - 32 - 90 - - - 1 - 2 - 32 - 90 - - - 1 - 2 - 64 - 90 - - - - - - - - 1 - 1 - 1 - 1 - - - - - - - - - - - 1 - 1 - 1 - 1 - - - - - 1 - 1 - 1 - 1 - - - - - - - - 1 - 2 - 32 - 90 - - - 1 - 1 - 1 - 1 - - - - - 1 - 2 - 32 - 90 - - - - - - - - 1 - 2 - 32 - 90 - - - 1 - 2 - 32 - 90 - - - - - 1 - 2 - 90 - 90 - - - - - - - - 1 - 2 - 90 - 90 - - - - - 1 - 2 - 90 - 90 - - - - - - - - 1 - 2 - 64 - 90 - - - 1 - 2 - 90 - 90 - - - - - 1 - 2 - 64 - 90 - - - - - - - - - - - 4 - - - - - - - - 1 - 2 - 64 - 90 - - - 4 - - - - - 1 - 128 - 15 - 6 - - - - - - - - - - - 4 - - - - - - - - 1 - 2 - 64 - 90 - - - 4 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 128 - 1 - 1 - 3 - 3 - - - - - - - - - - - 128 - 1 - 1 - 3 - 3 - - - - - 128 - 1 - 1 - 3 - 3 - - - - - - - - 1 - 128 - 15 - 6 - - - 128 - 1 - 1 - 3 - 3 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 1 - 128 - 1 - 1 - - - - - - - - - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 15 - 6 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 128 - 128 - 1 - 1 - - - - - - - - - - - 128 - 128 - 1 - 1 - - - - - 128 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 15 - 6 - - - 128 - 128 - 1 - 1 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 1 - 128 - 1 - 1 - - - - - - - - - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 15 - 6 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 256 - 128 - 1 - 1 - - - - - - - - - - - 256 - 128 - 1 - 1 - - - - - 256 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 15 - 6 - - - 256 - 128 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - - 1 - 256 - 1 - 1 - - - - - - - - - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 1 - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - 1 - 256 - 15 - 6 - - - - - 1 - 256 - 15 - 6 - - - - - - - - 128 - 256 - 1 - 1 - - - - - - - - - - - 128 - 256 - 1 - 1 - - - - - 128 - 256 - 1 - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - 128 - 256 - 1 - 1 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 1 - 128 - 1 - 1 - - - - - - - - - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 15 - 6 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 15 - 6 - - - - - 1 - 256 - 15 - 6 - - - - - - - - 256 - 256 - 1 - 1 - - - - - - - - - - - 256 - 256 - 1 - 1 - - - - - 256 - 256 - 1 - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - 256 - 256 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - - 1 - 256 - 1 - 1 - - - - - - - - - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 1 - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - 1 - 256 - 15 - 6 - - - - - 1 - 256 - 15 - 6 - - - - - - - - - - - 4 - - - - - - - - 1 - 256 - 15 - 6 - - - 4 - - - - - 1 - 256 - 30 - 12 - - - - - - - - 1 - 256 - 30 - 12 - - - 1 - 128 - 30 - 12 - - - - - 1 - 384 - 30 - 12 - - - - - - - - 128 - 384 - 1 - 1 - - - - - - - - - - - 128 - 384 - 1 - 1 - - - - - 128 - 384 - 1 - 1 - - - - - - - - 1 - 384 - 30 - 12 - - - 128 - 384 - 1 - 1 - - - - - 1 - 128 - 30 - 12 - - - - - - - - 1 - 128 - 1 - 1 - - - - - - - - - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 30 - 12 - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 30 - 12 - - - - - - - 1 - 128 - 30 - 12 - - - - - 1 - 128 - 30 - 12 - - - - - - - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - - - - 1 - - - - - - - - 1 - 128 - 30 - 12 - - - - - 4 - - - - - - - - - - - 1 - - - - - - - - - - - - - - - - - 4 - - - 1 - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - 2 - - - 1 - - - 1 - - - 1 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 128 - 30 - 12 - - - 2 - - - 2 - - - 2 - - - - - 1 - 64 - 30 - 12 - - - - - - - - - - - 2 - - - - - - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - 2 - - - 1 - - - 1 - - - 1 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 128 - 30 - 12 - - - 2 - - - 2 - - - 2 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 32 - 64 - 3 - 3 - - - - - - - - - - - 32 - 64 - 3 - 3 - - - - - 32 - 64 - 3 - 3 - - - - - - - - 1 - 64 - 30 - 12 - - - 32 - 64 - 3 - 3 - - - - - 1 - 32 - 30 - 12 - - - - - - - - 1 - 32 - 1 - 1 - - - - - - - - - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 1 - 1 - - - - - - - - 1 - 32 - 30 - 12 - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 30 - 12 - - - - - - - 1 - 32 - 30 - 12 - - - - - 1 - 32 - 30 - 12 - - - - - - - - 64 - 32 - 3 - 3 - - - - - - - - - - - 64 - 32 - 3 - 3 - - - - - 64 - 32 - 3 - 3 - - - - - - - - 1 - 32 - 30 - 12 - - - 64 - 32 - 3 - 3 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 30 - 12 - - - - - - - 1 - 64 - 30 - 12 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 30 - 12 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 30 - 12 - - - - - 1 - 192 - 30 - 12 - - - - - - - - 128 - 192 - 1 - 1 - - - - - - - - - - - 128 - 192 - 1 - 1 - - - - - 128 - 192 - 1 - 1 - - - - - - - - 1 - 192 - 30 - 12 - - - 128 - 192 - 1 - 1 - - - - - 1 - 128 - 30 - 12 - - - - - - - - 1 - 128 - 1 - 1 - - - - - - - - - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 30 - 12 - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 30 - 12 - - - - - - - 1 - 128 - 30 - 12 - - - - - 1 - 128 - 30 - 12 - - - - - - - - - - - 4 - - - - - - - - 1 - 128 - 30 - 12 - - - 4 - - - - - 1 - 128 - 60 - 24 - - - - - - - - 1 - 128 - 60 - 24 - - - 1 - 128 - 60 - 24 - - - - - 1 - 256 - 60 - 24 - - - - - - - - 64 - 256 - 1 - 1 - - - - - - - - - - - 64 - 256 - 1 - 1 - - - - - 64 - 256 - 1 - 1 - - - - - - - - 1 - 256 - 60 - 24 - - - 64 - 256 - 1 - 1 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 60 - 24 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 60 - 24 - - - - - - - 1 - 64 - 60 - 24 - - - - - 1 - 64 - 60 - 24 - - - - - - - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - - - - 1 - - - - - - - - 1 - 64 - 60 - 24 - - - - - 4 - - - - - - - - - - - 1 - - - - - - - - - - - - - - - - - 4 - - - 1 - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - 2 - - - 1 - - - 1 - - - 1 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 64 - 60 - 24 - - - 2 - - - 2 - - - 2 - - - - - 1 - 32 - 60 - 24 - - - - - - - - - - - 2 - - - - - - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - 2 - - - 1 - - - 1 - - - 1 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 64 - 60 - 24 - - - 2 - - - 2 - - - 2 - - - - - 1 - 32 - 60 - 24 - - - - - - - - 16 - 32 - 3 - 3 - - - - - - - - - - - 16 - 32 - 3 - 3 - - - - - 16 - 32 - 3 - 3 - - - - - - - - 1 - 32 - 60 - 24 - - - 16 - 32 - 3 - 3 - - - - - 1 - 16 - 60 - 24 - - - - - - - - 1 - 16 - 1 - 1 - - - - - - - - - - - 1 - 16 - 1 - 1 - - - - - 1 - 16 - 1 - 1 - - - - - - - - 1 - 16 - 60 - 24 - - - 1 - 16 - 1 - 1 - - - - - 1 - 16 - 60 - 24 - - - - - - - 1 - 16 - 60 - 24 - - - - - 1 - 16 - 60 - 24 - - - - - - - - 32 - 16 - 3 - 3 - - - - - - - - - - - 32 - 16 - 3 - 3 - - - - - 32 - 16 - 3 - 3 - - - - - - - - 1 - 16 - 60 - 24 - - - 32 - 16 - 3 - 3 - - - - - 1 - 32 - 60 - 24 - - - - - - - - 1 - 32 - 1 - 1 - - - - - - - - - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 1 - 1 - - - - - - - - 1 - 32 - 60 - 24 - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 60 - 24 - - - - - - - 1 - 32 - 60 - 24 - - - - - 1 - 32 - 60 - 24 - - - - - - - - 1 - 32 - 60 - 24 - - - 1 - 32 - 60 - 24 - - - - - 1 - 32 - 60 - 24 - - - - - - - - 1 - 32 - 60 - 24 - - - 1 - 32 - 60 - 24 - - - 1 - 32 - 60 - 24 - - - - - 1 - 96 - 60 - 24 - - - - - - - - 64 - 96 - 1 - 1 - - - - - - - - - - - 64 - 96 - 1 - 1 - - - - - 64 - 96 - 1 - 1 - - - - - - - - 1 - 96 - 60 - 24 - - - 64 - 96 - 1 - 1 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 60 - 24 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 60 - 24 - - - - - - - 1 - 64 - 60 - 24 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 51 - 64 - 3 - 3 - - - - - - - - - - - 51 - 64 - 3 - 3 - - - - - 51 - 64 - 3 - 3 - - - - - - - - 1 - 64 - 60 - 24 - - - 51 - 64 - 3 - 3 - - - - - 1 - 51 - 60 - 24 - - - - - - - - 1 - 51 - 1 - 1 - - - - - - - - - - - 1 - 51 - 1 - 1 - - - - - 1 - 51 - 1 - 1 - - - - - - - - 1 - 51 - 60 - 24 - - - 1 - 51 - 1 - 1 - - - - - 1 - 51 - 60 - 24 - - - - - - - 1 - 51 - 60 - 24 - - - - - 1 - 51 - 60 - 24 - - - - - - - - 51 - 51 - 3 - 3 - - - - - - - - - - - 51 - 51 - 3 - 3 - - - - - 51 - 51 - 3 - 3 - - - - - - - - 1 - 51 - 60 - 24 - - - 51 - 51 - 3 - 3 - - - - - 1 - 51 - 60 - 24 - - - - - - - - 1 - 51 - 1 - 1 - - - - - - - - - - - 1 - 51 - 1 - 1 - - - - - 1 - 51 - 1 - 1 - - - - - - - - 1 - 51 - 60 - 24 - - - 1 - 51 - 1 - 1 - - - - - 1 - 51 - 60 - 24 - - - - - - - 1 - 51 - 60 - 24 - - - - - 1 - 51 - 60 - 24 - - - - - - - - 51 - 51 - 1 - 1 - - - - - - - - - - - 51 - 51 - 1 - 1 - - - - - 51 - 51 - 1 - 1 - - - - - - - - 1 - 51 - 60 - 24 - - - 51 - 51 - 1 - 1 - - - - - 1 - 51 - 60 - 24 - - - - - - - - 1 - 51 - 1 - 1 - - - - - - - - - - - 1 - 51 - 1 - 1 - - - - - 1 - 51 - 1 - 1 - - - - - - - - 1 - 51 - 60 - 24 - - - 1 - 51 - 1 - 1 - - - - - 1 - 51 - 60 - 24 - - - - - - - - - - - 3 - - - - - - - - 1 - 51 - 60 - 24 - - - 3 - - - - - 1 - 51 - 1440 - - - - - - - - 64 - 64 - 3 - 3 - - - - - - - - - - - 64 - 64 - 3 - 3 - - - - - 64 - 64 - 3 - 3 - - - - - - - - 1 - 64 - 60 - 24 - - - 64 - 64 - 3 - 3 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 30 - 12 - - - - - - - 1 - 64 - 30 - 12 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 1 - 64 - 30 - 12 - - - 1 - 128 - 30 - 12 - - - - - 1 - 192 - 30 - 12 - - - - - - - - 128 - 192 - 1 - 1 - - - - - - - - - - - 128 - 192 - 1 - 1 - - - - - 128 - 192 - 1 - 1 - - - - - - - - 1 - 192 - 30 - 12 - - - 128 - 192 - 1 - 1 - - - - - 1 - 128 - 30 - 12 - - - - - - - - 1 - 128 - 1 - 1 - - - - - - - - - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 30 - 12 - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 30 - 12 - - - - - - - 1 - 128 - 30 - 12 - - - - - 1 - 128 - 30 - 12 - - - - - - - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - - - - 1 - - - - - - - - 1 - 128 - 30 - 12 - - - - - 4 - - - - - - - - - - - 1 - - - - - - - - - - - - - - - - - 4 - - - 1 - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - 2 - - - 1 - - - 1 - - - 1 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 128 - 30 - 12 - - - 2 - - - 2 - - - 2 - - - - - 1 - 64 - 30 - 12 - - - - - - - - - - - 2 - - - - - - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - 2 - - - 1 - - - 1 - - - 1 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 128 - 30 - 12 - - - 2 - - - 2 - - - 2 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 32 - 64 - 3 - 3 - - - - - - - - - - - 32 - 64 - 3 - 3 - - - - - 32 - 64 - 3 - 3 - - - - - - - - 1 - 64 - 30 - 12 - - - 32 - 64 - 3 - 3 - - - - - 1 - 32 - 30 - 12 - - - - - - - - 1 - 32 - 1 - 1 - - - - - - - - - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 1 - 1 - - - - - - - - 1 - 32 - 30 - 12 - - - 1 - 32 - 1 - 1 - - - - - 1 - 32 - 30 - 12 - - - - - - - 1 - 32 - 30 - 12 - - - - - 1 - 32 - 30 - 12 - - - - - - - - 64 - 32 - 3 - 3 - - - - - - - - - - - 64 - 32 - 3 - 3 - - - - - 64 - 32 - 3 - 3 - - - - - - - - 1 - 32 - 30 - 12 - - - 64 - 32 - 3 - 3 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 30 - 12 - - - - - - - 1 - 64 - 30 - 12 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 30 - 12 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 30 - 12 - - - - - 1 - 192 - 30 - 12 - - - - - - - - 128 - 192 - 1 - 1 - - - - - - - - - - - 128 - 192 - 1 - 1 - - - - - 128 - 192 - 1 - 1 - - - - - - - - 1 - 192 - 30 - 12 - - - 128 - 192 - 1 - 1 - - - - - 1 - 128 - 30 - 12 - - - - - - - - 1 - 128 - 1 - 1 - - - - - - - - - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 30 - 12 - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 30 - 12 - - - - - - - 1 - 128 - 30 - 12 - - - - - 1 - 128 - 30 - 12 - - - - - - - - 51 - 128 - 3 - 3 - - - - - - - - - - - 51 - 128 - 3 - 3 - - - - - 51 - 128 - 3 - 3 - - - - - - - - 1 - 128 - 30 - 12 - - - 51 - 128 - 3 - 3 - - - - - 1 - 51 - 30 - 12 - - - - - - - - 1 - 51 - 1 - 1 - - - - - - - - - - - 1 - 51 - 1 - 1 - - - - - 1 - 51 - 1 - 1 - - - - - - - - 1 - 51 - 30 - 12 - - - 1 - 51 - 1 - 1 - - - - - 1 - 51 - 30 - 12 - - - - - - - 1 - 51 - 30 - 12 - - - - - 1 - 51 - 30 - 12 - - - - - - - - 51 - 51 - 3 - 3 - - - - - - - - - - - 51 - 51 - 3 - 3 - - - - - 51 - 51 - 3 - 3 - - - - - - - - 1 - 51 - 30 - 12 - - - 51 - 51 - 3 - 3 - - - - - 1 - 51 - 30 - 12 - - - - - - - - 1 - 51 - 1 - 1 - - - - - - - - - - - 1 - 51 - 1 - 1 - - - - - 1 - 51 - 1 - 1 - - - - - - - - 1 - 51 - 30 - 12 - - - 1 - 51 - 1 - 1 - - - - - 1 - 51 - 30 - 12 - - - - - - - 1 - 51 - 30 - 12 - - - - - 1 - 51 - 30 - 12 - - - - - - - - 51 - 51 - 1 - 1 - - - - - - - - - - - 51 - 51 - 1 - 1 - - - - - 51 - 51 - 1 - 1 - - - - - - - - 1 - 51 - 30 - 12 - - - 51 - 51 - 1 - 1 - - - - - 1 - 51 - 30 - 12 - - - - - - - - 1 - 51 - 1 - 1 - - - - - - - - - - - 1 - 51 - 1 - 1 - - - - - 1 - 51 - 1 - 1 - - - - - - - - 1 - 51 - 30 - 12 - - - 1 - 51 - 1 - 1 - - - - - 1 - 51 - 30 - 12 - - - - - - - - - - - 3 - - - - - - - - 1 - 51 - 30 - 12 - - - 3 - - - - - 1 - 51 - 360 - - - - - - - - 128 - 128 - 3 - 3 - - - - - - - - - - - 128 - 128 - 3 - 3 - - - - - 128 - 128 - 3 - 3 - - - - - - - - 1 - 128 - 30 - 12 - - - 128 - 128 - 3 - 3 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 1 - 128 - 1 - 1 - - - - - - - - - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 15 - 6 - - - - - - - 1 - 128 - 15 - 6 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 1 - 128 - 15 - 6 - - - 1 - 256 - 15 - 6 - - - - - 1 - 384 - 15 - 6 - - - - - - - - 256 - 384 - 1 - 1 - - - - - - - - - - - 256 - 384 - 1 - 1 - - - - - 256 - 384 - 1 - 1 - - - - - - - - 1 - 384 - 15 - 6 - - - 256 - 384 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - - 1 - 256 - 1 - 1 - - - - - - - - - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 1 - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - 1 - 256 - 15 - 6 - - - - - 1 - 256 - 15 - 6 - - - - - - - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - - - - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - - - 4 - - - - - - - - - - - 1 - - - - - - - - - - - - - - - - - 4 - - - 1 - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - 2 - - - 1 - - - 1 - - - 1 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 256 - 15 - 6 - - - 2 - - - 2 - - - 2 - - - - - 1 - 128 - 15 - 6 - - - - - - - - - - - 2 - - - - - - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - 2 - - - 1 - - - 1 - - - 1 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 256 - 15 - 6 - - - 2 - - - 2 - - - 2 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 64 - 128 - 1 - 1 - - - - - - - - - - - 64 - 128 - 1 - 1 - - - - - 64 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 15 - 6 - - - 64 - 128 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 64 - 64 - 3 - 3 - - - - - - - - - - - 64 - 64 - 3 - 3 - - - - - 64 - 64 - 3 - 3 - - - - - - - - 1 - 64 - 15 - 6 - - - 64 - 64 - 3 - 3 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 64 - 64 - 3 - 3 - - - - - - - - - - - 64 - 64 - 3 - 3 - - - - - 64 - 64 - 3 - 3 - - - - - - - - 1 - 64 - 15 - 6 - - - 64 - 64 - 3 - 3 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 64 - 64 - 3 - 3 - - - - - - - - - - - 64 - 64 - 3 - 3 - - - - - 64 - 64 - 3 - 3 - - - - - - - - 1 - 64 - 15 - 6 - - - 64 - 64 - 3 - 3 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 64 - 64 - 3 - 3 - - - - - - - - - - - 64 - 64 - 3 - 3 - - - - - 64 - 64 - 3 - 3 - - - - - - - - 1 - 64 - 15 - 6 - - - 64 - 64 - 3 - 3 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 64 - 128 - 1 - 1 - - - - - - - - - - - 64 - 128 - 1 - 1 - - - - - 64 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 15 - 6 - - - 64 - 128 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 15 - 6 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 128 - 128 - 1 - 1 - - - - - - - - - - - 128 - 128 - 1 - 1 - - - - - 128 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 15 - 6 - - - 128 - 128 - 1 - 1 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 1 - 128 - 1 - 1 - - - - - - - - - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 15 - 6 - - - - - - - 1 - 128 - 15 - 6 - - - - - 1 - 128 - 15 - 6 - - - - - - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 15 - 6 - - - 1 - 128 - 15 - 6 - - - - - 1 - 384 - 15 - 6 - - - - - - - - 256 - 384 - 1 - 1 - - - - - - - - - - - 256 - 384 - 1 - 1 - - - - - 256 - 384 - 1 - 1 - - - - - - - - 1 - 384 - 15 - 6 - - - 256 - 384 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - - 1 - 256 - 1 - 1 - - - - - - - - - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 1 - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - 1 - 256 - 15 - 6 - - - - - 1 - 256 - 15 - 6 - - - - - - - - 51 - 256 - 3 - 3 - - - - - - - - - - - 51 - 256 - 3 - 3 - - - - - 51 - 256 - 3 - 3 - - - - - - - - 1 - 256 - 15 - 6 - - - 51 - 256 - 3 - 3 - - - - - 1 - 51 - 15 - 6 - - - - - - - - 1 - 51 - 1 - 1 - - - - - - - - - - - 1 - 51 - 1 - 1 - - - - - 1 - 51 - 1 - 1 - - - - - - - - 1 - 51 - 15 - 6 - - - 1 - 51 - 1 - 1 - - - - - 1 - 51 - 15 - 6 - - - - - - - 1 - 51 - 15 - 6 - - - - - 1 - 51 - 15 - 6 - - - - - - - - 51 - 51 - 3 - 3 - - - - - - - - - - - 51 - 51 - 3 - 3 - - - - - 51 - 51 - 3 - 3 - - - - - - - - 1 - 51 - 15 - 6 - - - 51 - 51 - 3 - 3 - - - - - 1 - 51 - 15 - 6 - - - - - - - - 1 - 51 - 1 - 1 - - - - - - - - - - - 1 - 51 - 1 - 1 - - - - - 1 - 51 - 1 - 1 - - - - - - - - 1 - 51 - 15 - 6 - - - 1 - 51 - 1 - 1 - - - - - 1 - 51 - 15 - 6 - - - - - - - 1 - 51 - 15 - 6 - - - - - 1 - 51 - 15 - 6 - - - - - - - - 51 - 51 - 1 - 1 - - - - - - - - - - - 51 - 51 - 1 - 1 - - - - - 51 - 51 - 1 - 1 - - - - - - - - 1 - 51 - 15 - 6 - - - 51 - 51 - 1 - 1 - - - - - 1 - 51 - 15 - 6 - - - - - - - - 1 - 51 - 1 - 1 - - - - - - - - - - - 1 - 51 - 1 - 1 - - - - - 1 - 51 - 1 - 1 - - - - - - - - 1 - 51 - 15 - 6 - - - 1 - 51 - 1 - 1 - - - - - 1 - 51 - 15 - 6 - - - - - - - - - - - 3 - - - - - - - - 1 - 51 - 15 - 6 - - - 3 - - - - - 1 - 51 - 90 - - - - - - - - 1 - 51 - 1440 - - - 1 - 51 - 360 - - - 1 - 51 - 90 - - - - - 1 - 51 - 1890 - - - - - - - - 64 - 256 - 3 - 3 - - - - - - - - - - - 64 - 256 - 3 - 3 - - - - - 64 - 256 - 3 - 3 - - - - - - - - 1 - 256 - 15 - 6 - - - 64 - 256 - 3 - 3 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 64 - 64 - 3 - 3 - - - - - - - - - - - 64 - 64 - 3 - 3 - - - - - 64 - 64 - 3 - 3 - - - - - - - - 1 - 64 - 15 - 6 - - - 64 - 64 - 3 - 3 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 64 - 64 - 1 - 1 - - - - - - - - - - - 64 - 64 - 1 - 1 - - - - - 64 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 64 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 256 - 1 - 1 - 3 - 3 - - - - - - - - - - - 256 - 1 - 1 - 3 - 3 - - - - - 256 - 1 - 1 - 3 - 3 - - - - - - - - 1 - 256 - 15 - 6 - - - 256 - 1 - 1 - 3 - 3 - - - - - 1 - 256 - 15 - 6 - - - - - - - - 1 - 256 - 1 - 1 - - - - - - - - - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 1 - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - 1 - 256 - 1 - 1 - - - - - 1 - 256 - 15 - 6 - - - - - - - 1 - 256 - 15 - 6 - - - - - 1 - 256 - 15 - 6 - - - - - - - - 64 - 256 - 1 - 1 - - - - - - - - - - - 64 - 256 - 1 - 1 - - - - - 64 - 256 - 1 - 1 - - - - - - - - 1 - 256 - 15 - 6 - - - 64 - 256 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 64 - 1 - 1 - 3 - 3 - - - - - - - - - - - 64 - 1 - 1 - 3 - 3 - - - - - 64 - 1 - 1 - 3 - 3 - - - - - - - - 1 - 64 - 15 - 6 - - - 64 - 1 - 1 - 3 - 3 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 64 - 64 - 1 - 1 - - - - - - - - - - - 64 - 64 - 1 - 1 - - - - - 64 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 64 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 15 - 6 - - - - - - - 1 - 64 - 15 - 6 - - - - - 1 - 64 - 15 - 6 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 64 - 1 - 1 - - - - - 1 - 1 - 15 - 6 - - - - - - - - 1 - 1 - 1 - 1 - - - - - - - - - - - 1 - 1 - 1 - 1 - - - - - 1 - 1 - 1 - 1 - - - - - - - - 1 - 1 - 15 - 6 - - - 1 - 1 - 1 - 1 - - - - - 1 - 1 - 15 - 6 - - - - - - - - 1 - 64 - 15 - 6 - - - 1 - 1 - 15 - 6 - - - - - 1 - 65 - 15 - 6 - - - - - - - - 64 - 128 - 3 - 3 - - - - - - - - - - - 64 - 128 - 3 - 3 - - - - - 64 - 128 - 3 - 3 - - - - - - - - 1 - 128 - 30 - 12 - - - 64 - 128 - 3 - 3 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 30 - 12 - - - - - - - 1 - 64 - 30 - 12 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 64 - 64 - 3 - 3 - - - - - - - - - - - 64 - 64 - 3 - 3 - - - - - 64 - 64 - 3 - 3 - - - - - - - - 1 - 64 - 30 - 12 - - - 64 - 64 - 3 - 3 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 30 - 12 - - - - - - - 1 - 64 - 30 - 12 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 64 - 64 - 1 - 1 - - - - - - - - - - - 64 - 64 - 1 - 1 - - - - - 64 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 30 - 12 - - - 64 - 64 - 1 - 1 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 128 - 1 - 1 - 3 - 3 - - - - - - - - - - - 128 - 1 - 1 - 3 - 3 - - - - - 128 - 1 - 1 - 3 - 3 - - - - - - - - 1 - 128 - 30 - 12 - - - 128 - 1 - 1 - 3 - 3 - - - - - 1 - 128 - 30 - 12 - - - - - - - - 1 - 128 - 1 - 1 - - - - - - - - - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 30 - 12 - - - 1 - 128 - 1 - 1 - - - - - 1 - 128 - 30 - 12 - - - - - - - 1 - 128 - 30 - 12 - - - - - 1 - 128 - 30 - 12 - - - - - - - - 64 - 128 - 1 - 1 - - - - - - - - - - - 64 - 128 - 1 - 1 - - - - - 64 - 128 - 1 - 1 - - - - - - - - 1 - 128 - 30 - 12 - - - 64 - 128 - 1 - 1 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 30 - 12 - - - - - - - 1 - 64 - 30 - 12 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 64 - 1 - 1 - 3 - 3 - - - - - - - - - - - 64 - 1 - 1 - 3 - 3 - - - - - 64 - 1 - 1 - 3 - 3 - - - - - - - - 1 - 64 - 30 - 12 - - - 64 - 1 - 1 - 3 - 3 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 30 - 12 - - - - - - - 1 - 64 - 30 - 12 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 64 - 64 - 1 - 1 - - - - - - - - - - - 64 - 64 - 1 - 1 - - - - - 64 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 30 - 12 - - - 64 - 64 - 1 - 1 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 30 - 12 - - - - - - - 1 - 64 - 30 - 12 - - - - - 1 - 64 - 30 - 12 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 30 - 12 - - - 1 - 64 - 1 - 1 - - - - - 1 - 1 - 30 - 12 - - - - - - - - 1 - 1 - 1 - 1 - - - - - - - - - - - 1 - 1 - 1 - 1 - - - - - 1 - 1 - 1 - 1 - - - - - - - - 1 - 1 - 30 - 12 - - - 1 - 1 - 1 - 1 - - - - - 1 - 1 - 30 - 12 - - - - - - - - 1 - 64 - 30 - 12 - - - 1 - 1 - 30 - 12 - - - - - 1 - 65 - 30 - 12 - - - - - - - - 64 - 64 - 3 - 3 - - - - - - - - - - - 64 - 64 - 3 - 3 - - - - - 64 - 64 - 3 - 3 - - - - - - - - 1 - 64 - 60 - 24 - - - 64 - 64 - 3 - 3 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 60 - 24 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 60 - 24 - - - - - - - 1 - 64 - 60 - 24 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 64 - 64 - 3 - 3 - - - - - - - - - - - 64 - 64 - 3 - 3 - - - - - 64 - 64 - 3 - 3 - - - - - - - - 1 - 64 - 60 - 24 - - - 64 - 64 - 3 - 3 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 60 - 24 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 60 - 24 - - - - - - - 1 - 64 - 60 - 24 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 64 - 64 - 1 - 1 - - - - - - - - - - - 64 - 64 - 1 - 1 - - - - - 64 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 60 - 24 - - - 64 - 64 - 1 - 1 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 60 - 24 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 64 - 1 - 1 - 3 - 3 - - - - - - - - - - - 64 - 1 - 1 - 3 - 3 - - - - - 64 - 1 - 1 - 3 - 3 - - - - - - - - 1 - 64 - 60 - 24 - - - 64 - 1 - 1 - 3 - 3 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 60 - 24 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 60 - 24 - - - - - - - 1 - 64 - 60 - 24 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 64 - 64 - 1 - 1 - - - - - - - - - - - 64 - 64 - 1 - 1 - - - - - 64 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 60 - 24 - - - 64 - 64 - 1 - 1 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 60 - 24 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 60 - 24 - - - - - - - 1 - 64 - 60 - 24 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 64 - 1 - 1 - 3 - 3 - - - - - - - - - - - 64 - 1 - 1 - 3 - 3 - - - - - 64 - 1 - 1 - 3 - 3 - - - - - - - - 1 - 64 - 60 - 24 - - - 64 - 1 - 1 - 3 - 3 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 60 - 24 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 60 - 24 - - - - - - - 1 - 64 - 60 - 24 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 64 - 64 - 1 - 1 - - - - - - - - - - - 64 - 64 - 1 - 1 - - - - - 64 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 60 - 24 - - - 64 - 64 - 1 - 1 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 60 - 24 - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 60 - 24 - - - - - - - 1 - 64 - 60 - 24 - - - - - 1 - 64 - 60 - 24 - - - - - - - - 1 - 64 - 1 - 1 - - - - - - - - - - - 1 - 64 - 1 - 1 - - - - - 1 - 64 - 1 - 1 - - - - - - - - 1 - 64 - 60 - 24 - - - 1 - 64 - 1 - 1 - - - - - 1 - 1 - 60 - 24 - - - - - - - - 1 - 1 - 1 - 1 - - - - - - - - - - - 1 - 1 - 1 - 1 - - - - - 1 - 1 - 1 - 1 - - - - - - - - 1 - 1 - 60 - 24 - - - 1 - 1 - 1 - 1 - - - - - 1 - 1 - 60 - 24 - - - - - - - - 1 - 64 - 60 - 24 - - - 1 - 1 - 60 - 24 - - - - - 1 - 65 - 60 - 24 - - - - - - - - 1 - 2 - 1890 - - - - - - - - - - - 1 - 2 - 1890 - - - - - 1 - 2 - 1890 - - - - - - - - - - - 3 - - - - - - - - 1 - 65 - 60 - 24 - - - 3 - - - - - 1 - 65 - 1440 - - - - - - - - - - - 3 - - - - - - - - 1 - 65 - 30 - 12 - - - 3 - - - - - 1 - 65 - 360 - - - - - - - - - - - 3 - - - - - - - - 1 - 65 - 15 - 6 - - - 3 - - - - - 1 - 65 - 90 - - - - - - - - 1 - 65 - 1440 - - - 1 - 65 - 360 - - - 1 - 65 - 90 - - - - - 1 - 65 - 1890 - - - - - - - - - - - - - - 2 - - - - - - - 1 - 65 - 1890 - - - - 2 - - - - - 1 - 64 - 1890 - - - 1 - 1 - 1890 - - - - - - - - - - - 4 - - - - - - - - 1 - 64 - 1890 - - - 4 - - - - - 1 - 4 - 16 - 1890 - - - - - - - - 4 - - - - - - - 1 - 4 - 16 - 1890 - - - 4 - - - - - 1 - 16 - 4 - 1890 - - - - - - - - 1 - 16 - 4 - 1890 - - - - - 1 - 16 - 4 - 1890 - - - - - - - - 1 - 16 - 1 - 1 - - - - - - - - - - - 1 - 16 - 1 - 1 - - - - - 1 - 16 - 1 - 1 - - - - - - - - 1 - 16 - 4 - 1890 - - - 1 - 16 - 1 - 1 - - - - - 1 - 1 - 4 - 1890 - - - - - - - - - - - 3 - - - - - - - - 1 - 1 - 4 - 1890 - - - 3 - - - - - 1 - 4 - 1890 - - - - - - - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - - - - 1 - - - - - - - - 1 - 4 - 1890 - - - - - 3 - - - - - - - - - - - 1 - - - - - - - - - - - - - - - - - 3 - - - 1 - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - 2 - - - 1 - - - 1 - - - 1 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 4 - 1890 - - - 2 - - - 2 - - - 2 - - - - - 1 - 2 - 1890 - - - - - - - - 1 - 2 - 1890 - - - 1 - 2 - 1890 - - - - - 1 - 2 - 1890 - - - - - - - - - - - 2 - - - - - - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 1 - - - 1 - - - - - 1 - - - - - - - - - - - 1 - - - - - - - 2 - - - 1 - - - 1 - - - 1 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 4 - 1890 - - - 2 - - - 2 - - - 2 - - - - - 1 - 2 - 1890 - - - - - - - - 1 - 2 - 1890 - - - 1 - 2 - 1890 - - - - - 1 - 2 - 1890 - - - - - - - - 1 - 2 - 1890 - - - 1 - 2 - 1890 - - - - - 1 - 2 - 1890 - - - - - - - - 1 - 1 - 1 - - - - - - - - - - - 1 - 1 - 1 - - - - - 1 - 1 - 1 - - - - - - - - 1 - 2 - 1890 - - - 1 - 1 - 1 - - - - - 1 - 2 - 1890 - - - - - - - - 1 - 2 - 1890 - - - 1 - 2 - 1890 - - - - - 1 - 2 - 1890 - - - - - - - - 1 - 2 - 1890 - - - 1 - 2 - 1890 - - - - - 1 - 4 - 1890 - - - - - - - - 1 - 1 - 1890 - - - - - - - - - - - 1 - 1 - 1890 - - - - - 1 - 1 - 1890 - - - - - - - - 1 - 4 - 1890 - - - 1 - 1 - 1890 - - - - - 1 - 4 - 1890 - - - - - - - 1 - 1 - 1890 - - - - - 1 - 1 - 1890 - - - - - - - - 1 - 1 - - - - - - - - 1 - 17 - - - - - - - - 1 - 17 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 2 - - - 2 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 2 - - - 2 - - - 2 - - - - - 2 - - - - - - - - 1 - 1 - - - 2 - - - - - 1 - 17 - - - - - - - - 1 - - - - - - - 1 - 17 - - - 1 - - - - - 1 - 17 - 1 - - - - - - - - 17 - - - - - - - - 17 - - - 2 - - - - - 1 - 17 - - - - - - - - 1 - - - - - - - 1 - 17 - - - 1 - - - - - 1 - 17 - 1 - - - - - - - - 1 - 17 - 1 - - - 1 - 17 - 1 - - - - - 1 - 17 - 2 - - - - - - - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 51 - 1890 - - - 2 - - - 2 - - - 2 - - - - - 1 - 17 - 1890 - - - - - - - 1 - 17 - 1890 - - - - - 1 - 17 - 1890 - - - - - - - - 1 - 17 - 1890 - - - - - 3 - - - - - - - - 1 - 17 - 1890 - - - 3 - - - - - 1 - 17 - 1890 - - - - - - - - 1 - 51 - 1890 - - - - - 3 - - - - - - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 3 - - - 1 - - - 1 - - - 1 - - - - - 1 - - - - - - - - 2 - - - 1 - - - - - 3 - - - - - - - - 1 - 17 - 1890 - - - 3 - - - - - 1 - 17 - 1890 - - - - - - - 1 - 51 - 1890 - - - 1 - 17 - 2 - - - 1 - 17 - 1890 - - - - - 1 - 51 - 1890 - - - - - - - - 1 - 1 - - - - - - - - 1 - 17 - - - - - - - - 1 - 17 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 2 - - - 2 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 2 - - - 2 - - - 2 - - - - - 2 - - - - - - - - 1 - 1 - - - 2 - - - - - 1 - 17 - - - - - - - - 1 - - - - - - - 1 - 17 - - - 1 - - - - - 1 - 17 - 1 - - - - - - - - 17 - - - - - - - - 17 - - - 2 - - - - - 1 - 17 - - - - - - - - 1 - - - - - - - 1 - 17 - - - 1 - - - - - 1 - 17 - 1 - - - - - - - - 1 - 17 - 1 - - - 1 - 17 - 1 - - - - - 1 - 17 - 2 - - - - - - - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 51 - 1890 - - - 2 - - - 2 - - - 2 - - - - - 1 - 17 - 1890 - - - - - - - - 1 - 1 - 1890 - - - - - - - - - - - 1 - 1 - 1890 - - - - - 1 - 1 - 1890 - - - - - - - - 1 - 17 - 1890 - - - 1 - 1 - 1890 - - - - - 1 - 17 - 1890 - - - - - - - - 1 - 1 - 1890 - - - - - - - - - - - 1 - 1 - 1890 - - - - - 1 - 1 - 1890 - - - - - - - - 1 - 17 - 1890 - - - 1 - 1 - 1890 - - - - - 1 - 17 - 1890 - - - - - - - - 1 - 17 - 1890 - - - - - 3 - - - - - - - - 1 - 17 - 1890 - - - 3 - - - - - 1 - 17 - 1890 - - - - - - - - 1 - 51 - 1890 - - - - - 3 - - - - - - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 3 - - - 1 - - - 1 - - - 1 - - - - - 1 - - - - - - - - 2 - - - 1 - - - - - 3 - - - - - - - - 1 - 17 - 1890 - - - 3 - - - - - 1 - 17 - 1890 - - - - - - - 1 - 51 - 1890 - - - 1 - 17 - 2 - - - 1 - 17 - 1890 - - - - - 1 - 51 - 1890 - - - - - - - - 1 - 1 - - - - - - - - 1 - 17 - - - - - - - - 1 - 17 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 2 - - - 2 - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 2 - - - 2 - - - 2 - - - - - 2 - - - - - - - - 1 - 1 - - - 2 - - - - - 1 - 17 - - - - - - - - 1 - - - - - - - 1 - 17 - - - 1 - - - - - 1 - 17 - 1 - - - - - - - - 17 - - - - - - - - 17 - - - 2 - - - - - 1 - 17 - - - - - - - - 1 - - - - - - - 1 - 17 - - - 1 - - - - - 1 - 17 - 1 - - - - - - - - 1 - 17 - 1 - - - 1 - 17 - 1 - - - - - 1 - 17 - 2 - - - - - - - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - - - - 2 - - - - - - - - 1 - 51 - 1890 - - - 2 - - - 2 - - - 2 - - - - - 1 - 17 - 1890 - - - - - - - - 1 - 1 - 1890 - - - - - - - - - - - 1 - 1 - 1890 - - - - - 1 - 1 - 1890 - - - - - - - - 1 - 17 - 1890 - - - 1 - 1 - 1890 - - - - - 1 - 17 - 1890 - - - - - - - - 1 - 1 - 1890 - - - - - - - - - - - 1 - 1 - 1890 - - - - - 1 - 1 - 1890 - - - - - - - - 1 - 17 - 1890 - - - 1 - 1 - 1890 - - - - - 1 - 17 - 1890 - - - - - - - - 1 - 17 - 1890 - - - - - 3 - - - - - - - - 1 - 17 - 1890 - - - 3 - - - - - 1 - 17 - 1890 - - - - - - - - 1 - 51 - 1890 - - - - - 3 - - - - - - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - - - - 1 - - - - - - - - 3 - - - 1 - - - 1 - - - 1 - - - - - 1 - - - - - - - - 2 - - - 1 - - - - - 3 - - - - - - - - 1 - 17 - 1890 - - - 3 - - - - - 1 - 17 - 1890 - - - - - - - 1 - 51 - 1890 - - - 1 - 17 - 2 - - - 1 - 17 - 1890 - - - - - 1 - 51 - 1890 - - - - - - - - 1 - 4 - 1890 - - - 1 - 1 - 1890 - - - 1 - 51 - 1890 - - - - - 1 - 56 - 1890 - - - - - - - 1 - 56 - 1890 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/etc/parameters/default.json b/etc/parameters/default.json index 9b86984a8c..9cc77c40cb 100644 --- a/etc/parameters/default.json +++ b/etc/parameters/default.json @@ -7,6 +7,7 @@ "minimum_overall_keypoint_confidence": 0.5, "minimum_visual_referee_keypoint_confidence": 0.8, "minimum_shoulder_angle": 0.2, + "free_kick_signal_angle_range": [1.2, 2.3], "foot_z_offset": 0.025, "referee_pose_queue_length": 8, "minimum_number_poses_before_message": 3, @@ -997,7 +998,7 @@ }, "minimum_bottom_focus_pitch": 0.2, "image_regions": { - "bottom": [0.5, 0.7], + "bottom": [0.5, 1.0], "center": [0.5, 0.5] } }, @@ -1251,12 +1252,19 @@ "distance_to_consider_ball_moved_in_kick_off": 0.3, "whistle_acceptance_goal_distance": [0.5, 0.5] }, - "referee_pose_detection_filter": { + "ready_signal_detection_filter": { "initial_message_grace_period": { "nanos": 0, "secs": 3 }, - "minimum_above_head_arms_detections": 1 + "minimum_ready_signal_detections": 1 + }, + "free_kick_signal_detection_filter": { + "initial_message_grace_period": { + "nanos": 0, + "secs": 3 + }, + "minimum_free_kick_signal_detections": 1 }, "sacrificial_lamb": { "wait_for_opponent_penalties_period": { diff --git a/tools/twix/src/panels/image/overlays/pose_detection.rs b/tools/twix/src/panels/image/overlays/pose_detection.rs index 1e375b5d85..76915b59c0 100644 --- a/tools/twix/src/panels/image/overlays/pose_detection.rs +++ b/tools/twix/src/panels/image/overlays/pose_detection.rs @@ -4,8 +4,12 @@ use color_eyre::Result; use coordinate_systems::Pixel; use eframe::egui::{Align2, Color32, FontId, Stroke}; use linear_algebra::point; -use types::pose_detection::{ - HumanPose, Keypoint, OVERALL_KEYPOINT_INDEX_MASK, VISUAL_REFEREE_KEYPOINT_INDEX_MASK, +use types::{ + filtered_game_controller_state::FilteredGameControllerState, + filtered_game_state::FilteredGameState, + pose_detection::{ + HumanPose, Keypoint, OVERALL_KEYPOINT_INDEX_MASK, VISUAL_REFEREE_KEYPOINT_INDEX_MASK, + }, }; use crate::{ @@ -41,6 +45,7 @@ const DETECTION_IMAGE_START_X: f32 = (IMAGE_WIDTH - DETECTION_IMAGE_WIDTH) / 2.0 pub struct PoseDetection { accepted_human_poses: BufferHandle>, rejected_human_poses: BufferHandle>, + filtered_game_controller_state: BufferHandle>, } impl Overlay for PoseDetection { @@ -55,9 +60,12 @@ impl Overlay for PoseDetection { nao.subscribe_value(format!("{cycler}.main_outputs.accepted_human_poses")); let rejected_human_poses = nao.subscribe_value(format!("{cycler}.main_outputs.rejected_human_poses")); + let filtered_game_controller_state = + nao.subscribe_value("Control.main_outputs.filtered_game_controller_state".to_string()); Self { accepted_human_poses, rejected_human_poses, + filtered_game_controller_state, } } @@ -84,7 +92,13 @@ impl Overlay for PoseDetection { Color32::from_rgb(100, 100, 255), )?; - paint_detection_dead_zone(painter); + if let Some(Some(FilteredGameControllerState { + game_state: FilteredGameState::Standby, + .. + })) = self.filtered_game_controller_state.get_last_value()? + { + paint_detection_dead_zone(painter); + }; Ok(()) }