file_path
stringlengths
21
224
content
stringlengths
0
80.8M
erasromani/isaac-sim-python/grasp/grasping_scenarios/franka.py
# Credits: The majority of this code is taken from build code associated with nvidia/isaac-sim:2020.2.2_ea with minor modifications. import time import os import numpy as np import carb.tokens import omni.kit.settings from pxr import Usd, UsdGeom, Gf from collections import deque from omni.isaac.dynamic_control import _dynamic_control from omni.isaac.motion_planning import _motion_planning from omni.isaac.samples.scripts.utils import math_utils # default joint configuration default_config = (0.00, -1.3, 0.00, -2.87, 0.00, 2.00, 0.75) # Alternative default config for motion planning alternate_config = [ (1.5356, -1.3813, -1.5151, -2.0015, -1.3937, 1.5887, 1.4597), (-1.5356, -1.3813, 1.5151, -2.0015, 1.3937, 1.5887, 0.4314), ] class Gripper: """ Gripper for franka. """ def __init__(self, dc, ar): """ Initialize gripper. Args: dc (omni.isaac.motion_planning._motion_planning.MotionPlanning): motion planning interface from RMP extension ar (int): articulation identifier """ self.dc = dc self.ar = ar self.finger_j1 = self.dc.find_articulation_dof(self.ar, "panda_finger_joint1") self.finger_j2 = self.dc.find_articulation_dof(self.ar, "panda_finger_joint2") self.width = 0 self.width_history = deque(maxlen=50) def open(self, wait=False): """ Open gripper. """ if self.width < 0.045: self.move(0.045, wait=True) self.move(0.09, wait=wait) def close(self, wait=False, force=0): """ Close gripper. """ self.move(0, wait=wait) def move(self, width=0.03, speed=0.2, wait=False): """ Modify width. """ self.width = width # if wait: # time.sleep(0.5) def update(self): """ Actuate gripper. """ self.dc.set_dof_position_target(self.finger_j1, self.width * 0.5 * 100) self.dc.set_dof_position_target(self.finger_j2, self.width * 0.5 * 100) self.width_history.append(self.get_width()) def get_width(self): """ Get current width. """ return sum(self.get_position()) def get_position(self): """ Get left and right finger local position. """ return self.dc.get_dof_position(self.finger_j1), self.dc.get_dof_position(self.finger_j2) def get_velocity(self, from_articulation=True): """ Get left and right finger local velocity. """ if from_articulation: return (self.dc.get_dof_velocity(self.finger_j1), self.dc.get_dof_velocity(self.finger_j2)) else: leftfinger_handle = self.dc.get_rigid_body(self.dc.get_articulation_path(self.ar) + '/panda_leftfinger') rightfinger_handle = self.dc.get_rigid_body(self.dc.get_articulation_path(self.ar) + '/panda_rightfinger') leftfinger_velocity = np.linalg.norm(np.array(self.dc.get_rigid_body_local_linear_velocity(leftfinger_handle))) rightfinger_velocity = np.linalg.norm(np.array(self.dc.get_rigid_body_local_linear_velocity(rightfinger_handle))) return (leftfinger_velocity, rightfinger_velocity) def is_moving(self, tol=1e-2): """ Determine if gripper fingers are moving """ if len(self.width_history) < self.width_history.maxlen or np.array(self.width_history).std() > tol: return True else: return False def get_state(self): """ Get gripper state. """ dof_states = self.dc.get_articulation_dof_states(self.ar, _dynamic_control.STATE_ALL) return dof_states[-2], dof_states[-1] def is_closed(self, tol=1e-2): """ Determine if gripper is closed. """ if self.get_width() < tol: return True else: return False class Status: """ Class that contains status for end effector """ def __init__(self, mp, rmp_handle): """ Initialize status object. Args: mp (omni.isaac.dynamic_control._dynamic_control.DynamicControl): dynamic control interface rmp_handle (int): RMP handle identifier """ self.mp = mp self.rmp_handle = rmp_handle self.orig = np.array([0, 0, 0]) self.axis_x = np.array([1, 0, 0]) self.axis_y = np.array([0, 1, 0]) self.axis_z = np.array([0, 0, 1]) self.current_frame = {"orig": self.orig, "axis_x": self.axis_x, "axis_y": self.axis_y, "axis_z": self.axis_z} self.target_frame = {"orig": self.orig, "axis_x": self.axis_x, "axis_y": self.axis_y, "axis_z": self.axis_z} self.frame = self.current_frame def update(self): """ Update end effector state. """ state = self.mp.getRMPState(self.rmp_handle) target = self.mp.getRMPTarget(self.rmp_handle) self.orig = np.array([state[0].x, state[0].y, state[0].z]) self.axis_x = np.array([state[1].x, state[1].y, state[1].z]) self.axis_y = np.array([state[2].x, state[2].y, state[2].z]) self.axis_z = np.array([state[3].x, state[3].y, state[3].z]) self.current_frame = {"orig": self.orig, "axis_x": self.axis_x, "axis_y": self.axis_y, "axis_z": self.axis_z} self.frame = self.current_frame self.current_target = { "orig": np.array([target[0].x, target[0].y, target[0].z]), "axis_x": np.array([target[1].x, target[1].y, target[1].z]), "axis_y": np.array([target[2].x, target[2].y, target[2].z]), "axis_z": np.array([target[3].x, target[3].y, target[3].z]), } class EndEffector: """ End effector object that controls movement. """ def __init__(self, dc, mp, ar, rmp_handle): """ Initialize end effector. Args: dc (omni.isaac.motion_planning._motion_planning.MotionPlanning): motion planning interface from RMP extension mp (omni.isaac.dynamic_control._dynamic_control.DynamicControl): dynamic control interface ar (int): articulation identifier rmp_handle (int): RMP handle identifier """ self.dc = dc self.ar = ar self.mp = mp self.rmp_handle = rmp_handle self.gripper = Gripper(dc, ar) self.status = Status(mp, rmp_handle) self.UpRot = Gf.Rotation(Gf.Vec3d(0, 0, 1), 90) def freeze(self): self.go_local( orig=self.status.orig, axis_x=self.status.axis_x, axis_z=self.status.axis_z, wait_for_target=False ) def go_local( self, target=None, orig=[], axis_x=[], axis_y=[], axis_z=[], required_orig_err=0.01, required_axis_x_err=0.01, required_axis_y_err=0.01, required_axis_z_err=0.01, orig_thresh=None, axis_x_thresh=None, axis_y_thresh=None, axis_z_thresh=None, approach_direction=[], approach_standoff=0.1, approach_standoff_std_dev=0.001, use_level_surface_orientation=False, use_target_weight_override=True, use_default_config=False, wait_for_target=True, wait_time=None, ): self.target_weight_override_value = 10000.0 self.target_weight_override_std_dev = 0.03 if orig_thresh: required_orig_err = orig_thresh if axis_x_thresh: required_axis_x_err = axis_x_thresh if axis_y_thresh: required_axis_y_err = axis_y_thresh if axis_z_thresh: required_axis_z_err = axis_z_thresh if target: orig = target["orig"] if "axis_x" in target and target["axis_x"] is not None: axis_x = target["axis_x"] if "axis_y" in target and target["axis_y"] is not None: axis_y = target["axis_y"] if "axis_z" in target and target["axis_z"] is not None: axis_z = target["axis_z"] orig = np.array(orig) axis_x = np.array(axis_x) axis_y = np.array(axis_y) axis_z = np.array(axis_z) approach = _motion_planning.Approach((0, 0, 1), 0, 0) if len(approach_direction) != 0: approach = _motion_planning.Approach(approach_direction, approach_standoff, approach_standoff_std_dev) pose_command = _motion_planning.PartialPoseCommand() if len(orig) > 0: pose_command.set(_motion_planning.Command(orig, approach), int(_motion_planning.FrameElement.ORIG)) if len(axis_x) > 0: pose_command.set(_motion_planning.Command(axis_x), int(_motion_planning.FrameElement.AXIS_X)) if len(axis_y) > 0: pose_command.set(_motion_planning.Command(axis_y), int(_motion_planning.FrameElement.AXIS_Y)) if len(axis_z) > 0: pose_command.set(_motion_planning.Command(axis_z), int(_motion_planning.FrameElement.AXIS_Z)) self.mp.goLocal(self.rmp_handle, pose_command) if wait_for_target and wait_time: error = 1 future_time = time.time() + wait_time while error > required_orig_err and time.time() < future_time: # time.sleep(0.1) error = self.mp.getError(self.rmp_handle) def look_at(self, gripper_pos, target): # Y up works for look at but sometimes flips, go_local might be a safer bet with a locked y_axis orientation = math_utils.lookAt(gripper_pos, target, (0, 1, 0)) mat = Gf.Matrix3d(orientation).GetTranspose() self.go_local( orig=[gripper_pos[0], gripper_pos[1], gripper_pos[2]], axis_x=[mat.GetColumn(0)[0], mat.GetColumn(0)[1], mat.GetColumn(0)[2]], axis_z=[mat.GetColumn(2)[0], mat.GetColumn(2)[1], mat.GetColumn(2)[2]], ) class Franka: """ Franka objects that contains implementation details for robot control. """ def __init__(self, stage, prim, dc, mp, world=None, group_path="", default_config=None, is_ghost=False): """ Initialize Franka controller. Args: stage (pxr.Usd.Stage): usd stage prim (pxr.Usd.Prim): robot prim dc (omni.isaac.motion_planning._motion_planning.MotionPlanning): motion planning interface from RMP extension mp (omni.isaac.dynamic_control._dynamic_control.DynamicControl): dynamic control interface world (omni.isaac.samples.scripts.utils.world.World): simulation world handler default_config (tuple or list): default configuration for robot revolute joint drivers is_ghost (bool): flag for turning off collision and modifying visuals for robot arm """ self.dc = dc self.mp = mp self.prim = prim self.stage = stage # get handle to the articulation for this franka self.ar = self.dc.get_articulation(prim.GetPath().pathString) self.is_ghost = is_ghost self.base = self.dc.get_articulation_root_body(self.ar) body_count = self.dc.get_articulation_body_count(self.ar) for bodyIdx in range(body_count): body = self.dc.get_articulation_body(self.ar, bodyIdx) self.dc.set_rigid_body_disable_gravity(body, True) exec_folder = os.path.abspath( carb.tokens.get_tokens_interface().resolve( f"{os.environ['ISAAC_PATH']}/exts/omni.isaac.motion_planning/resources/lula/lula_franka" ) ) self.rmp_handle = self.mp.registerRmp( exec_folder + "/urdf/lula_franka_gen.urdf", exec_folder + "/config/robot_descriptor.yaml", exec_folder + "/config/franka_rmpflow_common.yaml", prim.GetPath().pathString, "right_gripper", True, ) print("franka rmp handle", self.rmp_handle) if world is not None: self.world = world self.world.rmp_handle = self.rmp_handle self.world.register_parent(self.base, self.prim, "panda_link0") settings = omni.kit.settings.get_settings_interface() self.mp.setFrequency(self.rmp_handle, settings.get("/physics/timeStepsPerSecond"), True) self.end_effector = EndEffector(self.dc, self.mp, self.ar, self.rmp_handle) if default_config: self.mp.setDefaultConfig(self.rmp_handle, default_config) self.target_visibility = True if self.is_ghost: self.target_visibility = False self.imageable = UsdGeom.Imageable(self.prim) def __del__(self): """ Unregister RMP. """ self.mp.unregisterRmp(self.rmp_handle) print(" Delete Franka") def set_pose(self, pos, rot): """ Set robot pose. """ self._mp.setTargetLocal(self.rmp_handle, pos, rot) def set_speed(self, speed_level): """ Set robot speed. """ pass def update(self): """ Update robot state. """ self.end_effector.gripper.update() self.end_effector.status.update() if self.imageable: if self.target_visibility is not self.imageable.ComputeVisibility(Usd.TimeCode.Default()): if self.target_visibility: self.imageable.MakeVisible() else: self.imageable.MakeInvisible() def send_config(self, config): """ Set robot default configuration. """ if self.is_ghost is False: self.mp.setDefaultConfig(self.rmp_handle, config)
erasromani/isaac-sim-python/grasp/utils/isaac_utils.py
# Credits: All code except class RigidBody and Camera is taken from build code associated with nvidia/isaac-sim:2020.2.2_ea. import numpy as np import omni.kit from pxr import Usd, UsdGeom, Gf, PhysicsSchema, PhysxSchema def create_prim_from_usd(stage, prim_env_path, prim_usd_path, location): """ Create prim from usd. """ envPrim = stage.DefinePrim(prim_env_path, "Xform") # create an empty Xform at the given path envPrim.GetReferences().AddReference(prim_usd_path) # attach the USD to the given path set_translate(envPrim, location) # set pose return stage.GetPrimAtPath(envPrim.GetPath().pathString) def set_up_z_axis(stage): """ Utility function to specify the stage with the z axis as "up". """ rootLayer = stage.GetRootLayer() rootLayer.SetPermissionToEdit(True) with Usd.EditContext(stage, rootLayer): UsdGeom.SetStageUpAxis(stage, UsdGeom.Tokens.z) def set_translate(prim, new_loc): """ Specify position of a given prim, reuse any existing transform ops when possible. """ properties = prim.GetPropertyNames() if "xformOp:translate" in properties: translate_attr = prim.GetAttribute("xformOp:translate") translate_attr.Set(new_loc) elif "xformOp:translation" in properties: translation_attr = prim.GetAttribute("xformOp:translate") translation_attr.Set(new_loc) elif "xformOp:transform" in properties: transform_attr = prim.GetAttribute("xformOp:transform") matrix = prim.GetAttribute("xformOp:transform").Get() matrix.SetTranslateOnly(new_loc) transform_attr.Set(matrix) else: xform = UsdGeom.Xformable(prim) xform_op = xform.AddXformOp(UsdGeom.XformOp.TypeTransform, UsdGeom.XformOp.PrecisionDouble, "") xform_op.Set(Gf.Matrix4d().SetTranslate(new_loc)) def set_rotate(prim, rot_mat): """ Specify orientation of a given prim, reuse any existing transform ops when possible. """ properties = prim.GetPropertyNames() if "xformOp:rotate" in properties: rotate_attr = prim.GetAttribute("xformOp:rotate") rotate_attr.Set(rot_mat) elif "xformOp:transform" in properties: transform_attr = prim.GetAttribute("xformOp:transform") matrix = prim.GetAttribute("xformOp:transform").Get() matrix.SetRotateOnly(rot_mat.ExtractRotation()) transform_attr.Set(matrix) else: xform = UsdGeom.Xformable(prim) xform_op = xform.AddXformOp(UsdGeom.XformOp.TypeTransform, UsdGeom.XformOp.PrecisionDouble, "") xform_op.Set(Gf.Matrix4d().SetRotate(rot_mat)) def create_background(stage, background_stage): """ Create background stage. """ background_path = "/background" if not stage.GetPrimAtPath(background_path): backPrim = stage.DefinePrim(background_path, "Xform") backPrim.GetReferences().AddReference(background_stage) # Move the stage down -104cm so that the floor is below the table wheels, move in y axis to get light closer set_translate(backPrim, Gf.Vec3d(0, -400, -104)) def setup_physics(stage): """ Set default physics parameters. """ # Specify gravity metersPerUnit = UsdGeom.GetStageMetersPerUnit(stage) gravityScale = 9.81 / metersPerUnit gravity = Gf.Vec3f(0.0, 0.0, -gravityScale) scene = PhysicsSchema.PhysicsScene.Define(stage, "/physics/scene") scene.CreateGravityAttr().Set(gravity) PhysxSchema.PhysxSceneAPI.Apply(stage.GetPrimAtPath("/physics/scene")) physxSceneAPI = PhysxSchema.PhysxSceneAPI.Get(stage, "/physics/scene") physxSceneAPI.CreatePhysxSceneEnableCCDAttr(True) physxSceneAPI.CreatePhysxSceneEnableStabilizationAttr(True) physxSceneAPI.CreatePhysxSceneEnableGPUDynamicsAttr(False) physxSceneAPI.CreatePhysxSceneBroadphaseTypeAttr("MBP") physxSceneAPI.CreatePhysxSceneSolverTypeAttr("TGS") class Camera: """ Camera object that contain state information for a camera in the scene. """ def __init__(self, camera_path, translation, rotation): """ Initializes the Camera object. Args: camera_path (str): path of camera in stage hierarchy translation (list or tuple): camera position rotation (list or tuple): camera orientation described by euler angles in degrees """ self.prim = self._kit.create_prim( camera_path, "Camera", translation=translation, rotation=rotatation, ) self.name = self.prim.GetPrimPath().name self.vpi = omni.kit.viewport.get_viewport_interface def set_translate(self, position): """ Set camera position. Args: position (tuple): camera position specified by (X, Y, Z) """ if not isinstance(position, tuple): position = tuple(position) translate_attr = self.prim.GetAttribute("xformOp:translate") translate_attr.Set(position) def set_rotate(self, rotation): """ Set camera position. Args: rotation (tuple): camera orientation specified by three euler angles in degrees """ if not isinstance(rotation, tuple): rotation = tuple(rotation) rotate_attr = self.prim.GetAttribute("xformOp:rotateZYX") rotate_attr.Set(rotation) def activate(self): """ Activate camera to viewport. """ self.vpi.get_viewport_window().set_active_camera(str(self.prim.GetPath())) def __repr__(self): return self.name class Camera: """ Camera object that contain state information for a camera in the scene. """ def __init__(self, camera_path, translation, rotation): """ Initializes the Camera object. Args: camera_path (str): path of camera in stage hierarchy translation (list or tuple): camera position rotation (list or tuple): camera orientation described by euler angles in degrees """ self.prim = self._kit.create_prim( camera_path, "Camera", translation=translation, rotation=rotation, ) self.name = self.prim.GetPrimPath().name self.vpi = omni.kit.viewport.get_viewport_interface def set_translate(self, position): """ Set camera position. Args: position (tuple): camera position specified by (X, Y, Z) """ if not isinstance(position, tuple): position = tuple(position) translate_attr = self.prim.GetAttribute("xformOp:translate") translate_attr.Set(position) def set_rotate(self, rotation): """ Set camera position. Args: rotation (tuple): camera orientation specified by three euler angles in degrees """ if not isinstance(rotation, tuple): rotation = tuple(rotation) rotate_attr = self.prim.GetAttribute("xformOp:rotateZYX") rotate_attr.Set(rotation) def activate(self): """ Activate camera to viewport. """ self.vpi.get_viewport_window().set_active_camera(str(self.prim.GetPath())) def __repr__(self): return self.name class RigidBody: """ RigidBody objects that contains state information of the rigid body. """ def __init__(self, prim, dc): """ Initializes for RigidBody object Args: prim (pxr.Usd.Prim): rigid body prim dc (omni.isaac.motion_planning._motion_planning.MotionPlanning): motion planning interface from RMP extension """ self.prim = prim self._dc = dc self.name = prim.GetPrimPath().name self.handle = self.get_rigid_body_handle() def get_rigid_body_handle(self): """ Get rigid body handle. """ object_children = self.prim.GetChildren() for child in object_children: child_path = child.GetPath().pathString body_handle = self._dc.get_rigid_body(child_path) if body_handle != 0: bin_path = child_path object_handle = self._dc.get_rigid_body(bin_path) if object_handle != 0: return object_handle def get_linear_velocity(self): """ Get linear velocity of rigid body. """ return np.array(self._dc.get_rigid_body_linear_velocity(self.handle)) def get_angular_velocity(self): """ Get angular velocity of rigid body. """ return np.array(self._dc.get_rigid_body_angular_velocity(self.handle)) def get_speed(self): """ Get speed of rigid body given by the l2 norm of the velocity. """ velocity = self.get_linear_velocity() speed = np.linalg.norm(velocity) return speed def get_pose(self): """ Get pose of the rigid body containing the position and orientation information. """ return self._dc.get_rigid_body_pose(self.handle) def get_position(self): """ Get the position of the rigid body object. """ pose = self.get_pose() position = np.array(pose.p) return position def get_orientation(self): """ Get orientation of the rigid body object. """ pose = self.get_pose() orientation = np.array(pose.r) return orientation def get_bound(self): """ Get bounds of the rigid body object in global coordinates. """ bound = UsdGeom.Mesh(self.prim).ComputeWorldBound(0.0, "default").GetBox() return [np.array(bound.GetMin()), np.array(bound.GetMax())] def __repr__(self): return self.name
erasromani/isaac-sim-python/grasp/utils/visualize.py
import os import ffmpeg import matplotlib.pyplot as plt def screenshot(sd_helper, suffix="", prefix="image", directory="images/"): """ Take a screenshot of the current time step of a running NVIDIA Omniverse Isaac-Sim simulation. Args: sd_helper (omni.isaac.synthetic_utils.SyntheticDataHelper): helper class for visualizing OmniKit simulation suffix (str or int): suffix for output filename of image screenshot of current time step of simulation prefix (str): prefix for output filename of image screenshot of current time step of simulation directory (str): output directory of image screenshot of current time step of simulation """ gt = sd_helper.get_groundtruth( [ "rgb", ] ) image = gt["rgb"][..., :3] plt.imshow(image) if suffix == "": suffix = 0 if isinstance(suffix, int): filename = os.path.join(directory, f'{prefix}_{suffix:05}.png') else: filename = os.path.join(directory, f'{prefix}_{suffix}.png') plt.axis('off') plt.savefig(filename) def img2vid(input_pattern, output_fn, pattern_type='glob', framerate=25): """ Create video from a collection of images. Args: input_pattern (str): input pattern for a path of collection of images output_fn (str): video output filename pattern_type (str): pattern type for input pattern framerate (int): video framerate """ ( ffmpeg .input(input_pattern, pattern_type=pattern_type, framerate=framerate) .output(output_fn) .run(overwrite_output=True, quiet=True) )
erasromani/isaac-sim-python/grasp/utils/__init__.py
pantelis-classes/omniverse-ai/README.md
# Learning in Simulated Worlds in Omniverse. Please go to the wiki tab. ![image](https://user-images.githubusercontent.com/589439/143660504-bbcdb786-ea5f-4f74-9496-489032fa2e03.png) https://github.com/pantelis-classes/omniverse-ai/wiki <hr /> # Wiki Navigation * [Home][home] * [Isaac-Sim-SDK-Omniverse-Installation][Omniverse] * [Synthetic-Data-Generation][SDG] * [NVIDIA Transfer Learning Toolkit (TLT) Installation][TLT] * [NVIDIA TAO][TAO] * [detectnet_v2 Installation][detectnet_v2] * [Jupyter Notebook][Jupyter-Notebook] [home]: https://github.com/pantelis-classes/omniverse-ai/wiki [Omniverse]: https://github.com/pantelis-classes/omniverse-ai/wiki/Isaac-Sim-SDK-Omniverse-Installation [SDG]: https://github.com/pantelis-classes/omniverse-ai/wiki/Synthetic-Data-Generation-(Python-API) [TLT]: https://github.com/pantelis-classes/omniverse-ai/wiki/NVIDIA-Transfer-Learning-Toolkit-(TLT)-Installation [NTLTSD]: https://github.com/pantelis-classes/omniverse-ai/wiki/Using-NVIDIA-TLT-with-Synthetic-Data [TAO]: https://github.com/pantelis-classes/omniverse-ai/wiki/TAO-(NVIDIA-Train,-Adapt,-and-Optimize) [detectnet_v2]: https://github.com/pantelis-classes/omniverse-ai/wiki/detectnet_v2-Installation [Jupyter-Notebook]: https://github.com/pantelis-classes/omniverse-ai/wiki/Jupyter-Notebook <hr /> <a href="https://docs.google.com/document/d/1WAzdqlWE0RUns41-0P951mnsqMR7I2XV/edit?usp=sharing&ouid=112712585131518554614&rtpof=true&sd=true"> ![image](https://user-images.githubusercontent.com/589439/161171527-4e748031-ff4d-46ed-b1ac-b521cd8ffd3c.png)</a> ## Reports <a href="https://docs.google.com/document/d/1jVXxrNgtOosZw_vAORzomSnmy45G3qK_mmk2B4oJtPg/edit?usp=sharing">Domain Randomization Paper</a><br> This report provides an indepth understanding on how Domain Randomization helps perception machine learning tasks such as object detection and/or segmentation. <a href="https://docs.google.com/document/d/1WAzdqlWE0RUns41-0P951mnsqMR7I2XV/edit?usp=sharing&ouid=112712585131518554614&rtpof=true&sd=true">Final Report</a><br> This final report contains an indepth explanation on the hardware/software used, the methods used to collect the data, an explanation on the data collected, trained and pruned, and the overall conclusions made from the trained and pruned datasets. <a href="https://docs.google.com/document/d/1WAzdqlWE0RUns41-0P951mnsqMR7I2XV/edit?usp=sharing&ouid=112712585131518554614&rtpof=true&sd=true">![image](https://user-images.githubusercontent.com/589439/161171433-d2359618-b3dc-4839-b509-c938ce401f73.png)</a> ## Authors <a href="https://github.com/dfsanchez999">Diego Sanchez</a> | <a href="https://harp.njit.edu/~jga26/">Jibran Absarulislam</a> | <a href="https://github.com/markkcruz">Mark Cruz</a> | <a href="https://github.com/sppatel2112">Sapan Patel</a> ## Supervisor <a href="https://pantelis.github.io/">Dr. Pantelis Monogioudis</a> ## Credits <a href="https://developer.nvidia.com/nvidia-omniverse-platform">NVIDIA Omniverse</a><br> A platform that enables universal interoperability across different applications and 3D ecosystem vendors providing real-time scene updates.
pantelis-classes/omniverse-ai/Images/images.md
# A markdown file containing all the images in the wiki. (Saved in github's cloud) ![image](https://user-images.githubusercontent.com/589439/143155216-aad83dd6-0bc7-4c85-8c45-4696659a0ff2.png) ![image](https://user-images.githubusercontent.com/589439/143155405-5ab0c92a-10ea-4af2-bcc3-10215808025c.png) ![image](https://user-images.githubusercontent.com/589439/143155607-66dd62b1-9096-4960-af80-05c7d0560616.png) ![image](https://user-images.githubusercontent.com/589439/143155666-96fc6a9d-ca5c-4e10-bb4b-0b75c6afd331.png) ![image](https://user-images.githubusercontent.com/589439/143155774-8a7f0020-70e7-48a4-ad38-9abfda935f1b.png) ![image](https://user-images.githubusercontent.com/589439/143155905-39760d3e-ef68-4a03-8af8-8f1ea0fa7801.png) ![image](https://user-images.githubusercontent.com/589439/143155958-7fe5ce25-d447-4a07-b79b-9785ac456b9a.png) ![image](https://user-images.githubusercontent.com/589439/143155991-41cd11df-3ff9-4ca5-b112-7e63785740db.png) ![image](https://user-images.githubusercontent.com/589439/143156000-5b8dea90-b63b-4c05-90e5-da8f484070e2.png) ![image](https://user-images.githubusercontent.com/589439/143156018-cc426e4a-2785-4050-b643-dc2bee6251aa.png) ![image](https://user-images.githubusercontent.com/589439/143156108-4e4c2f1e-138b-451e-87a7-3cff9da960cb.png) ![image](https://user-images.githubusercontent.com/589439/143156160-4aef319c-3756-4ff6-b429-032d2e45513f.png) ![image](https://user-images.githubusercontent.com/589439/143156180-226269c5-ba2c-4f29-ad2e-378eaf8ee523.png) ![image](https://user-images.githubusercontent.com/589439/143156205-4d4b8afb-c334-4a22-af62-33f7174c716d.png) ![image](https://user-images.githubusercontent.com/589439/143156303-93a31da8-2dc3-49d5-b80a-0246b877dd34.png) ![image](https://user-images.githubusercontent.com/589439/143156381-07c34f94-b2f5-42ac-a61e-10fb5f27a8c9.png) ![image](https://user-images.githubusercontent.com/589439/143157449-7a86072c-0dc4-4e49-a1b3-a62c3f88187c.png) ![image](https://user-images.githubusercontent.com/589439/143157471-7b9bfc36-d505-4b77-8938-d9387e8280b1.png) ![image](https://user-images.githubusercontent.com/589439/143157512-a862401e-38f8-4334-90eb-3f597c583a48.png) ![image](https://user-images.githubusercontent.com/589439/143157553-744bfd7e-5b14-4905-bc84-cf01a245d9ff.png) ![image](https://user-images.githubusercontent.com/589439/143158851-a4f7a00b-4f25-40e0-ae2e-2fba3edef08e.png) ![image](https://user-images.githubusercontent.com/589439/143158880-17506781-abc2-4188-aca3-4546dcb475f9.png) ![image](https://user-images.githubusercontent.com/589439/143158912-97fb24ad-8b49-432e-a3d7-4badb0977714.png) ![image](https://user-images.githubusercontent.com/589439/143158967-afad1831-822f-4440-9a4b-9248c909007d.png) ![image](https://user-images.githubusercontent.com/589439/143160948-90380e23-e8cc-42b3-8933-4d88c5c9bc90.png) ![image](https://user-images.githubusercontent.com/589439/143655465-4efa6088-9bcd-4df4-92f3-d641975ece93.png) ![image](https://user-images.githubusercontent.com/589439/143655576-0ff7992c-0339-48c5-94f1-2be90b2877e5.png ![image](https://user-images.githubusercontent.com/589439/143655623-cc957acf-a6f3-4e23-ad84-2f63762db770.png) ![image](https://user-images.githubusercontent.com/589439/143655734-92f93f94-723b-4a03-aee3-9004ebdfa931.png) ![image](https://user-images.githubusercontent.com/589439/143655803-423dddd8-398e-49e0-839f-d96a5e655441.png) ![image](https://user-images.githubusercontent.com/589439/143656306-85f1aefd-a6a8-4f07-a2e9-b7153ff175ce.png) ![image](https://user-images.githubusercontent.com/589439/143663079-a9503fd4-75f1-4bb0-bfd8-ada3bd9fa2ec.png) ![image](https://user-images.githubusercontent.com/589439/143663183-0bdb6ee0-84be-4788-bdc7-0ab23e9e5d41.png) ![image](https://user-images.githubusercontent.com/589439/143663255-907bff87-ae02-4c4d-8400-ef6a914c3aae.png) ![image](https://user-images.githubusercontent.com/589439/143663347-4ec70e43-da4d-4b97-bd26-b336586bc9d7.png) ![image](https://user-images.githubusercontent.com/589439/143663405-5323b62f-74a8-409f-80a8-c2c6ad961497.png) ![image](https://user-images.githubusercontent.com/589439/143664760-9d9bc86e-9e4a-4bf0-882a-3fa2db1d416b.png) ![image](https://user-images.githubusercontent.com/589439/143664935-4e1d2e45-b4da-4f83-922c-2e7581a65f98.png) ![image](https://user-images.githubusercontent.com/589439/143665245-9dc7ac44-78cd-45ac-992c-f3e23d1a044e.png) ![image](https://user-images.githubusercontent.com/589439/143665289-9f80a74d-f3f4-45b9-a92a-e213a6c37056.png) ![image](https://user-images.githubusercontent.com/589439/143666284-5ff41514-5c89-4cc7-afa0-b17ed9003b61.png) ![image](https://user-images.githubusercontent.com/589439/143666323-eb172e58-d0cb-4228-af31-f9f7daf43d19.png) ![image](https://user-images.githubusercontent.com/589439/143666365-9cbab570-213f-403b-bdc9-d891025fabac.png) ![image](https://user-images.githubusercontent.com/589439/143666538-47885861-2340-4fca-9507-8a1a66d82fe9.png) ![image](https://user-images.githubusercontent.com/589439/143666560-4a7dd70c-abde-4af8-a1c7-16eab5d99bf3.png) ![image](https://user-images.githubusercontent.com/589439/143666727-f7a06dbc-aba6-410f-8bd5-0aa24ecf38d3.png) ![image](https://user-images.githubusercontent.com/589439/143666820-b12aafdd-f1e1-4c46-889c-34af1c9ca929.png) ![image](https://user-images.githubusercontent.com/589439/143666829-813f9715-3a2d-49f1-9124-5a690681accc.png) ![image](https://user-images.githubusercontent.com/589439/143666852-90d659de-01a0-4685-bf36-42868e1c77d9.png) ![image](https://user-images.githubusercontent.com/589439/143666866-5896317b-1255-4e67-abe7-5f3ff03be288.png) ![image](https://user-images.githubusercontent.com/589439/143666874-a453b635-63e6-44e0-94c1-7127e1c7f729.png) ![image](https://user-images.githubusercontent.com/589439/143723668-73111ae8-0ac5-4729-b89b-481d29b25d16.png) ![image](https://user-images.githubusercontent.com/589439/143723824-968874c9-5f8e-44cc-a535-d0d336a72b78.png) ![image](https://user-images.githubusercontent.com/589439/143723906-baf552bc-e9d1-435b-8d43-553f6f0a6707.png) ![image](https://user-images.githubusercontent.com/589439/143723930-c9c8658f-339d-4693-894a-daf70dea28ae.png) ![image](https://user-images.githubusercontent.com/589439/143724110-61196b6e-7d6e-4fc5-86a4-c7234cd4d379.png) ![image](https://user-images.githubusercontent.com/589439/143724128-692a9f83-0365-4f0f-9068-e8e6af9cac15.png) ![image](https://user-images.githubusercontent.com/589439/143724159-ae6c0578-14e4-463b-8287-ef4147ff0f34.png) ![image](https://user-images.githubusercontent.com/589439/143724167-70721d41-12f2-4322-b611-3f07df92d344.png) ![image](https://user-images.githubusercontent.com/589439/143724450-3e95cb75-0dba-45da-9abf-7de026d3b8f3.png) ![image](https://user-images.githubusercontent.com/589439/143724459-afaf363f-dd92-494b-9707-5400f409d05a.png) ![image](https://user-images.githubusercontent.com/589439/143724476-77609fc2-e5a7-4773-94d9-799f2b78be6f.png) ![image](https://user-images.githubusercontent.com/589439/143724492-3036d310-3569-4820-9087-daca2bf9869f.png) ![image](https://user-images.githubusercontent.com/589439/143724167-70721d41-12f2-4322-b611-3f07df92d344.png) ![image](https://user-images.githubusercontent.com/589439/143727424-3d4930ef-647a-42cc-838a-ea7284dbda2a.png) ![image](https://user-images.githubusercontent.com/589439/143727464-598963b9-73c6-4b65-a617-5eecf454f4e9.png) ![image](https://user-images.githubusercontent.com/589439/143727479-6828fc05-4672-4c60-8a21-f1fe6e97d0ea.png) ![image](https://user-images.githubusercontent.com/589439/143727509-2313c55c-bc6d-4451-91f1-f4424fac580a.png) ![image](https://user-images.githubusercontent.com/589439/143727576-96f5f991-0493-4417-94e8-e12ab8bfd769.png) ![image](https://user-images.githubusercontent.com/589439/143727645-23bc99ea-105b-455b-b03f-1737892d3b9a.png) ![image](https://user-images.githubusercontent.com/589439/143729065-f90e8ed0-07ac-4c77-8e4b-8d4c7fcffdef.png) ![image](https://user-images.githubusercontent.com/589439/143729154-00111bfe-534d-4403-bcab-92e3adf032ee.png) ![image](https://user-images.githubusercontent.com/589439/143729162-ad6f82c6-643e-4ec0-a082-75842c237053.png) ![image](https://user-images.githubusercontent.com/589439/143729232-16e479b2-527e-4b0f-94b0-e43bd08cfba8.png) ![image](https://user-images.githubusercontent.com/589439/143729360-d16987b0-25ab-42db-a08d-66bae5576443.png) ![image](https://user-images.githubusercontent.com/589439/143729413-dffdd2dc-d0cb-40aa-8b0f-fd567b2a527c.png) ![image](https://user-images.githubusercontent.com/589439/143729441-e43fde75-76ed-489d-acef-56fea5ddf539.png) ![image](https://user-images.githubusercontent.com/589439/143729376-8e7db409-6651-4a55-90a7-8750d77d5838.png) ![image](https://user-images.githubusercontent.com/589439/143729521-c7b0fc38-baf0-4701-9032-dba324497f5e.png) ![image](https://user-images.githubusercontent.com/589439/143730115-59cf1d93-b27b-4902-a39b-522551733281.png) ![image](https://user-images.githubusercontent.com/589439/143730111-33db8027-2c8e-41e8-98a6-9e5e45984fc5.png) ![image](https://user-images.githubusercontent.com/589439/143797035-060165d6-d462-4160-b9f0-a2b31bdd3d72.png) ![image](https://user-images.githubusercontent.com/589439/143808844-e4244060-5842-41e2-868d-7a75c57a3c21.png) ![image](https://user-images.githubusercontent.com/589439/143809035-2ae69802-7929-47a6-a445-12b571cacd14.png) ![image](https://user-images.githubusercontent.com/589439/143809423-cea91ff5-916f-4c03-b7c3-e4eb625756a4.png) ![image](https://user-images.githubusercontent.com/589439/143809877-6e766d73-ff1c-405f-bd6f-600a58736b25.png) ![image](https://user-images.githubusercontent.com/589439/143809929-1e119a3b-0239-4144-bece-a1d9aa7d51bf.png) ![image](https://user-images.githubusercontent.com/589439/143809965-7997fd22-e172-4360-af13-8c0d65b83f4e.png) ![image](https://user-images.githubusercontent.com/589439/143809992-3a41471a-dd02-4a3e-acea-96b7a7c3a674.png) ![image](https://user-images.githubusercontent.com/589439/143810068-5f175928-4e4d-4820-8b14-067a31b35cd6.png) ![image](https://user-images.githubusercontent.com/589439/143810077-6bfb77d3-4643-4129-a8c4-0b4fbf196b43.png) ![image](https://user-images.githubusercontent.com/589439/143810093-f8508bb1-5728-4010-b87b-21f4aed74e73.png) ![image](https://user-images.githubusercontent.com/589439/143810115-c88787cb-3cae-433a-93c8-712a25db0c78.png) ![image](https://user-images.githubusercontent.com/589439/143810872-231209ca-eb71-4bd2-930d-3527fbaaace0.png) ![image](https://user-images.githubusercontent.com/589439/143810896-a9875ab8-b9ab-4ced-ad49-c47ea321a052.png) ![image](https://user-images.githubusercontent.com/589439/143810915-c9428405-1f00-462d-8a80-2d1467c95e7b.png) ![image](https://user-images.githubusercontent.com/589439/143810942-972f34b4-b7a4-4532-9e8d-6f6bcc01ac9f.png) ![image](https://user-images.githubusercontent.com/589439/143810970-69367200-b71e-481f-b813-3d447e154bb3.png) ![image](https://user-images.githubusercontent.com/589439/143811032-4adc40ef-fa0e-4596-88b5-2a24610cdaf3.png) ![image](https://user-images.githubusercontent.com/589439/143811081-edaa58f5-d3e6-40c6-9dab-f19e547d090e.png) ![image](https://user-images.githubusercontent.com/589439/143811255-0b946589-2679-4747-b514-3b91ac2259cd.png) ![image](https://user-images.githubusercontent.com/589439/143811275-488e15be-15bd-4341-8392-834cd68bbcad.png)
pantelis-classes/omniverse-ai/training_output/dataset1/train_1_summary.txt
Mean average_precision (in %): 4.2231 Mean average_precision (in %): 6.1684 Mean average_precision (in %): 8.5120 Mean average_precision (in %): 10.1440 Mean average_precision (in %): 12.0589 Mean average_precision (in %): 13.8389 Mean average_precision (in %): 13.8909 Mean average_precision (in %): 14.6698 Mean average_precision (in %): 15.8793 Mean average_precision (in %): 16.7417 Validation cost: 0.001164 Validation cost: 0.001069 Validation cost: 0.000885 Validation cost: 0.000975 Validation cost: 0.000967 Validation cost: 0.000840 Validation cost: 0.000776 Validation cost: 0.000779 Validation cost: 0.000783 Validation cost: 0.000682
pantelis-classes/omniverse-ai/training_output/dataset1/train_1.txt
2021-11-27 16:31:00,082 [INFO] root: Registry: ['nvcr.io'] 2021-11-27 16:31:00,127 [INFO] tlt.components.instance_handler.local_instance: Running command in container: nvcr.io/nvidia/tao/tao-toolkit-tf:v3.21.11-tf1.15.4-py3 Matplotlib created a temporary config/cache directory at /tmp/matplotlib-72jja2oo because the default path (/.config/matplotlib) is not a writable directory; it is highly recommended to set the MPLCONFIGDIR environment variable to a writable directory, in particular to speed up the import of Matplotlib and to better support multiprocessing. Using TensorFlow backend. WARNING:tensorflow:Deprecation warnings have been disabled. Set TF_ENABLE_DEPRECATION_WARNINGS=1 to re-enable them. Using TensorFlow backend. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:43: The name tf.train.SessionRunHook is deprecated. Please use tf.estimator.SessionRunHook instead. 2021-11-27 21:31:04,350 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:43: The name tf.train.SessionRunHook is deprecated. Please use tf.estimator.SessionRunHook instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/checkpoint_saver_hook.py:25: The name tf.train.CheckpointSaverHook is deprecated. Please use tf.estimator.CheckpointSaverHook instead. 2021-11-27 21:31:04,451 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/checkpoint_saver_hook.py:25: The name tf.train.CheckpointSaverHook is deprecated. Please use tf.estimator.CheckpointSaverHook instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/scripts/train.py:69: The name tf.logging.set_verbosity is deprecated. Please use tf.compat.v1.logging.set_verbosity instead. 2021-11-27 21:31:04,453 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/scripts/train.py:69: The name tf.logging.set_verbosity is deprecated. Please use tf.compat.v1.logging.set_verbosity instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/scripts/train.py:69: The name tf.logging.INFO is deprecated. Please use tf.compat.v1.logging.INFO instead. 2021-11-27 21:31:04,453 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/scripts/train.py:69: The name tf.logging.INFO is deprecated. Please use tf.compat.v1.logging.INFO instead. WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/horovod/tensorflow/__init__.py:117: The name tf.global_variables is deprecated. Please use tf.compat.v1.global_variables instead. 2021-11-27 21:31:04,458 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/horovod/tensorflow/__init__.py:117: The name tf.global_variables is deprecated. Please use tf.compat.v1.global_variables instead. WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/horovod/tensorflow/__init__.py:143: The name tf.get_default_graph is deprecated. Please use tf.compat.v1.get_default_graph instead. 2021-11-27 21:31:04,458 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/horovod/tensorflow/__init__.py:143: The name tf.get_default_graph is deprecated. Please use tf.compat.v1.get_default_graph instead. 2021-11-27 21:31:04,700 [INFO] __main__: Loading experiment spec at /workspace/tao-experiments/detectnet_v2/specs/detectnet_v2_train_resnet18_kitti.txt. 2021-11-27 21:31:04,701 [INFO] iva.detectnet_v2.spec_handler.spec_loader: Merging specification from /workspace/tao-experiments/detectnet_v2/specs/detectnet_v2_train_resnet18_kitti.txt 2021-11-27 21:31:04,793 [INFO] __main__: Cannot iterate over exactly 86 samples with a batch size of 4; each epoch will therefore take one extra step. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:107: The name tf.variable_scope is deprecated. Please use tf.compat.v1.variable_scope instead. 2021-11-27 21:31:04,796 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:107: The name tf.variable_scope is deprecated. Please use tf.compat.v1.variable_scope instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:110: The name tf.get_variable is deprecated. Please use tf.compat.v1.get_variable instead. 2021-11-27 21:31:04,796 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:110: The name tf.get_variable is deprecated. Please use tf.compat.v1.get_variable instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:113: The name tf.assign is deprecated. Please use tf.compat.v1.assign instead. 2021-11-27 21:31:04,797 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:113: The name tf.assign is deprecated. Please use tf.compat.v1.assign instead. WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:517: The name tf.placeholder is deprecated. Please use tf.compat.v1.placeholder instead. 2021-11-27 21:31:04,932 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:517: The name tf.placeholder is deprecated. Please use tf.compat.v1.placeholder instead. WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:4138: The name tf.random_uniform is deprecated. Please use tf.random.uniform instead. 2021-11-27 21:31:04,932 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:4138: The name tf.random_uniform is deprecated. Please use tf.random.uniform instead. WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:1834: The name tf.nn.fused_batch_norm is deprecated. Please use tf.compat.v1.nn.fused_batch_norm instead. 2021-11-27 21:31:04,945 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:1834: The name tf.nn.fused_batch_norm is deprecated. Please use tf.compat.v1.nn.fused_batch_norm instead. WARNING:tensorflow:From /opt/nvidia/third_party/keras/tensorflow_backend.py:187: The name tf.nn.avg_pool is deprecated. Please use tf.nn.avg_pool2d instead. 2021-11-27 21:31:05,658 [WARNING] tensorflow: From /opt/nvidia/third_party/keras/tensorflow_backend.py:187: The name tf.nn.avg_pool is deprecated. Please use tf.nn.avg_pool2d instead. WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:174: The name tf.get_default_session is deprecated. Please use tf.compat.v1.get_default_session instead. 2021-11-27 21:31:05,788 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:174: The name tf.get_default_session is deprecated. Please use tf.compat.v1.get_default_session instead. WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:199: The name tf.is_variable_initialized is deprecated. Please use tf.compat.v1.is_variable_initialized instead. 2021-11-27 21:31:05,789 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:199: The name tf.is_variable_initialized is deprecated. Please use tf.compat.v1.is_variable_initialized instead. WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:206: The name tf.variables_initializer is deprecated. Please use tf.compat.v1.variables_initializer instead. 2021-11-27 21:31:05,989 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:206: The name tf.variables_initializer is deprecated. Please use tf.compat.v1.variables_initializer instead. 2021-11-27 21:31:09,663 [INFO] iva.detectnet_v2.objectives.bbox_objective: Default L1 loss function will be used. __________________________________________________________________________________________________ Layer (type) Output Shape Param # Connected to ================================================================================================== input_1 (InputLayer) (None, 3, 384, 1248) 0 __________________________________________________________________________________________________ conv1 (Conv2D) (None, 64, 192, 624) 9472 input_1[0][0] __________________________________________________________________________________________________ bn_conv1 (BatchNormalization) (None, 64, 192, 624) 256 conv1[0][0] __________________________________________________________________________________________________ activation_1 (Activation) (None, 64, 192, 624) 0 bn_conv1[0][0] __________________________________________________________________________________________________ block_1a_conv_1 (Conv2D) (None, 64, 96, 312) 36928 activation_1[0][0] __________________________________________________________________________________________________ block_1a_bn_1 (BatchNormalizati (None, 64, 96, 312) 256 block_1a_conv_1[0][0] __________________________________________________________________________________________________ block_1a_relu_1 (Activation) (None, 64, 96, 312) 0 block_1a_bn_1[0][0] __________________________________________________________________________________________________ block_1a_conv_2 (Conv2D) (None, 64, 96, 312) 36928 block_1a_relu_1[0][0] __________________________________________________________________________________________________ block_1a_conv_shortcut (Conv2D) (None, 64, 96, 312) 4160 activation_1[0][0] __________________________________________________________________________________________________ block_1a_bn_2 (BatchNormalizati (None, 64, 96, 312) 256 block_1a_conv_2[0][0] __________________________________________________________________________________________________ block_1a_bn_shortcut (BatchNorm (None, 64, 96, 312) 256 block_1a_conv_shortcut[0][0] __________________________________________________________________________________________________ add_1 (Add) (None, 64, 96, 312) 0 block_1a_bn_2[0][0] block_1a_bn_shortcut[0][0] __________________________________________________________________________________________________ block_1a_relu (Activation) (None, 64, 96, 312) 0 add_1[0][0] __________________________________________________________________________________________________ block_1b_conv_1 (Conv2D) (None, 64, 96, 312) 36928 block_1a_relu[0][0] __________________________________________________________________________________________________ block_1b_bn_1 (BatchNormalizati (None, 64, 96, 312) 256 block_1b_conv_1[0][0] __________________________________________________________________________________________________ block_1b_relu_1 (Activation) (None, 64, 96, 312) 0 block_1b_bn_1[0][0] __________________________________________________________________________________________________ block_1b_conv_2 (Conv2D) (None, 64, 96, 312) 36928 block_1b_relu_1[0][0] __________________________________________________________________________________________________ block_1b_bn_2 (BatchNormalizati (None, 64, 96, 312) 256 block_1b_conv_2[0][0] __________________________________________________________________________________________________ add_2 (Add) (None, 64, 96, 312) 0 block_1b_bn_2[0][0] block_1a_relu[0][0] __________________________________________________________________________________________________ block_1b_relu (Activation) (None, 64, 96, 312) 0 add_2[0][0] __________________________________________________________________________________________________ block_2a_conv_1 (Conv2D) (None, 128, 48, 156) 73856 block_1b_relu[0][0] __________________________________________________________________________________________________ block_2a_bn_1 (BatchNormalizati (None, 128, 48, 156) 512 block_2a_conv_1[0][0] __________________________________________________________________________________________________ block_2a_relu_1 (Activation) (None, 128, 48, 156) 0 block_2a_bn_1[0][0] __________________________________________________________________________________________________ block_2a_conv_2 (Conv2D) (None, 128, 48, 156) 147584 block_2a_relu_1[0][0] __________________________________________________________________________________________________ block_2a_conv_shortcut (Conv2D) (None, 128, 48, 156) 8320 block_1b_relu[0][0] __________________________________________________________________________________________________ block_2a_bn_2 (BatchNormalizati (None, 128, 48, 156) 512 block_2a_conv_2[0][0] __________________________________________________________________________________________________ block_2a_bn_shortcut (BatchNorm (None, 128, 48, 156) 512 block_2a_conv_shortcut[0][0] __________________________________________________________________________________________________ add_3 (Add) (None, 128, 48, 156) 0 block_2a_bn_2[0][0] block_2a_bn_shortcut[0][0] __________________________________________________________________________________________________ block_2a_relu (Activation) (None, 128, 48, 156) 0 add_3[0][0] __________________________________________________________________________________________________ block_2b_conv_1 (Conv2D) (None, 128, 48, 156) 147584 block_2a_relu[0][0] __________________________________________________________________________________________________ block_2b_bn_1 (BatchNormalizati (None, 128, 48, 156) 512 block_2b_conv_1[0][0] __________________________________________________________________________________________________ block_2b_relu_1 (Activation) (None, 128, 48, 156) 0 block_2b_bn_1[0][0] __________________________________________________________________________________________________ block_2b_conv_2 (Conv2D) (None, 128, 48, 156) 147584 block_2b_relu_1[0][0] __________________________________________________________________________________________________ block_2b_bn_2 (BatchNormalizati (None, 128, 48, 156) 512 block_2b_conv_2[0][0] __________________________________________________________________________________________________ add_4 (Add) (None, 128, 48, 156) 0 block_2b_bn_2[0][0] block_2a_relu[0][0] __________________________________________________________________________________________________ block_2b_relu (Activation) (None, 128, 48, 156) 0 add_4[0][0] __________________________________________________________________________________________________ block_3a_conv_1 (Conv2D) (None, 256, 24, 78) 295168 block_2b_relu[0][0] __________________________________________________________________________________________________ block_3a_bn_1 (BatchNormalizati (None, 256, 24, 78) 1024 block_3a_conv_1[0][0] __________________________________________________________________________________________________ block_3a_relu_1 (Activation) (None, 256, 24, 78) 0 block_3a_bn_1[0][0] __________________________________________________________________________________________________ block_3a_conv_2 (Conv2D) (None, 256, 24, 78) 590080 block_3a_relu_1[0][0] __________________________________________________________________________________________________ block_3a_conv_shortcut (Conv2D) (None, 256, 24, 78) 33024 block_2b_relu[0][0] __________________________________________________________________________________________________ block_3a_bn_2 (BatchNormalizati (None, 256, 24, 78) 1024 block_3a_conv_2[0][0] __________________________________________________________________________________________________ block_3a_bn_shortcut (BatchNorm (None, 256, 24, 78) 1024 block_3a_conv_shortcut[0][0] __________________________________________________________________________________________________ add_5 (Add) (None, 256, 24, 78) 0 block_3a_bn_2[0][0] block_3a_bn_shortcut[0][0] __________________________________________________________________________________________________ block_3a_relu (Activation) (None, 256, 24, 78) 0 add_5[0][0] __________________________________________________________________________________________________ block_3b_conv_1 (Conv2D) (None, 256, 24, 78) 590080 block_3a_relu[0][0] __________________________________________________________________________________________________ block_3b_bn_1 (BatchNormalizati (None, 256, 24, 78) 1024 block_3b_conv_1[0][0] __________________________________________________________________________________________________ block_3b_relu_1 (Activation) (None, 256, 24, 78) 0 block_3b_bn_1[0][0] __________________________________________________________________________________________________ block_3b_conv_2 (Conv2D) (None, 256, 24, 78) 590080 block_3b_relu_1[0][0] __________________________________________________________________________________________________ block_3b_bn_2 (BatchNormalizati (None, 256, 24, 78) 1024 block_3b_conv_2[0][0] __________________________________________________________________________________________________ add_6 (Add) (None, 256, 24, 78) 0 block_3b_bn_2[0][0] block_3a_relu[0][0] __________________________________________________________________________________________________ block_3b_relu (Activation) (None, 256, 24, 78) 0 add_6[0][0] __________________________________________________________________________________________________ block_4a_conv_1 (Conv2D) (None, 512, 24, 78) 1180160 block_3b_relu[0][0] __________________________________________________________________________________________________ block_4a_bn_1 (BatchNormalizati (None, 512, 24, 78) 2048 block_4a_conv_1[0][0] __________________________________________________________________________________________________ block_4a_relu_1 (Activation) (None, 512, 24, 78) 0 block_4a_bn_1[0][0] __________________________________________________________________________________________________ block_4a_conv_2 (Conv2D) (None, 512, 24, 78) 2359808 block_4a_relu_1[0][0] __________________________________________________________________________________________________ block_4a_conv_shortcut (Conv2D) (None, 512, 24, 78) 131584 block_3b_relu[0][0] __________________________________________________________________________________________________ block_4a_bn_2 (BatchNormalizati (None, 512, 24, 78) 2048 block_4a_conv_2[0][0] __________________________________________________________________________________________________ block_4a_bn_shortcut (BatchNorm (None, 512, 24, 78) 2048 block_4a_conv_shortcut[0][0] __________________________________________________________________________________________________ add_7 (Add) (None, 512, 24, 78) 0 block_4a_bn_2[0][0] block_4a_bn_shortcut[0][0] __________________________________________________________________________________________________ block_4a_relu (Activation) (None, 512, 24, 78) 0 add_7[0][0] __________________________________________________________________________________________________ block_4b_conv_1 (Conv2D) (None, 512, 24, 78) 2359808 block_4a_relu[0][0] __________________________________________________________________________________________________ block_4b_bn_1 (BatchNormalizati (None, 512, 24, 78) 2048 block_4b_conv_1[0][0] __________________________________________________________________________________________________ block_4b_relu_1 (Activation) (None, 512, 24, 78) 0 block_4b_bn_1[0][0] __________________________________________________________________________________________________ block_4b_conv_2 (Conv2D) (None, 512, 24, 78) 2359808 block_4b_relu_1[0][0] __________________________________________________________________________________________________ block_4b_bn_2 (BatchNormalizati (None, 512, 24, 78) 2048 block_4b_conv_2[0][0] __________________________________________________________________________________________________ add_8 (Add) (None, 512, 24, 78) 0 block_4b_bn_2[0][0] block_4a_relu[0][0] __________________________________________________________________________________________________ block_4b_relu (Activation) (None, 512, 24, 78) 0 add_8[0][0] __________________________________________________________________________________________________ output_bbox (Conv2D) (None, 36, 24, 78) 18468 block_4b_relu[0][0] __________________________________________________________________________________________________ output_cov (Conv2D) (None, 9, 24, 78) 4617 block_4b_relu[0][0] ================================================================================================== Total params: 11,218,413 Trainable params: 11,208,685 Non-trainable params: 9,728 __________________________________________________________________________________________________ 2021-11-27 21:31:09,687 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: Serial augmentation enabled = False 2021-11-27 21:31:09,687 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: Pseudo sharding enabled = False 2021-11-27 21:31:09,687 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: Max Image Dimensions (all sources): (0, 0) 2021-11-27 21:31:09,687 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: number of cpus: 16, io threads: 32, compute threads: 16, buffered batches: 4 2021-11-27 21:31:09,687 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: total dataset size 86, number of sources: 1, batch size per gpu: 4, steps: 22 WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/tensorflow_core/python/autograph/converters/directives.py:119: The name tf.set_random_seed is deprecated. Please use tf.compat.v1.set_random_seed instead. 2021-11-27 21:31:09,715 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/tensorflow_core/python/autograph/converters/directives.py:119: The name tf.set_random_seed is deprecated. Please use tf.compat.v1.set_random_seed instead. WARNING:tensorflow:Entity <bound method DriveNetTFRecordsParser.__call__ of <iva.detectnet_v2.dataloader.drivenet_dataloader.DriveNetTFRecordsParser object at 0x7fb0548cc7b8>> could not be transformed and will be executed as-is. Please report this to the AutoGraph team. When filing the bug, set the verbosity to 10 (on Linux, `export AUTOGRAPH_VERBOSITY=10`) and attach the full output. Cause: Unable to locate the source code of <bound method DriveNetTFRecordsParser.__call__ of <iva.detectnet_v2.dataloader.drivenet_dataloader.DriveNetTFRecordsParser object at 0x7fb0548cc7b8>>. Note that functions defined in certain environments, like the interactive Python shell do not expose their source code. If that is the case, you should to define them in a .py source file. If you are certain the code is graph-compatible, wrap the call using @tf.autograph.do_not_convert. Original error: could not get source code 2021-11-27 21:31:09,747 [WARNING] tensorflow: Entity <bound method DriveNetTFRecordsParser.__call__ of <iva.detectnet_v2.dataloader.drivenet_dataloader.DriveNetTFRecordsParser object at 0x7fb0548cc7b8>> could not be transformed and will be executed as-is. Please report this to the AutoGraph team. When filing the bug, set the verbosity to 10 (on Linux, `export AUTOGRAPH_VERBOSITY=10`) and attach the full output. Cause: Unable to locate the source code of <bound method DriveNetTFRecordsParser.__call__ of <iva.detectnet_v2.dataloader.drivenet_dataloader.DriveNetTFRecordsParser object at 0x7fb0548cc7b8>>. Note that functions defined in certain environments, like the interactive Python shell do not expose their source code. If that is the case, you should to define them in a .py source file. If you are certain the code is graph-compatible, wrap the call using @tf.autograph.do_not_convert. Original error: could not get source code 2021-11-27 21:31:09,759 [INFO] iva.detectnet_v2.dataloader.default_dataloader: Bounding box coordinates were detected in the input specification! Bboxes will be automatically converted to polygon coordinates. 2021-11-27 21:31:09,925 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: shuffle: True - shard 0 of 1 2021-11-27 21:31:09,928 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: sampling 1 datasets with weights: 2021-11-27 21:31:09,928 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: source: 0 weight: 1.000000 WARNING:tensorflow:Entity <bound method Processor.__call__ of <modulus.blocks.data_loaders.multi_source_loader.processors.asset_loader.AssetLoader object at 0x7fb08e894a58>> could not be transformed and will be executed as-is. Please report this to the AutoGraph team. When filing the bug, set the verbosity to 10 (on Linux, `export AUTOGRAPH_VERBOSITY=10`) and attach the full output. Cause: Unable to locate the source code of <bound method Processor.__call__ of <modulus.blocks.data_loaders.multi_source_loader.processors.asset_loader.AssetLoader object at 0x7fb08e894a58>>. Note that functions defined in certain environments, like the interactive Python shell do not expose their source code. If that is the case, you should to define them in a .py source file. If you are certain the code is graph-compatible, wrap the call using @tf.autograph.do_not_convert. Original error: could not get source code 2021-11-27 21:31:09,938 [WARNING] tensorflow: Entity <bound method Processor.__call__ of <modulus.blocks.data_loaders.multi_source_loader.processors.asset_loader.AssetLoader object at 0x7fb08e894a58>> could not be transformed and will be executed as-is. Please report this to the AutoGraph team. When filing the bug, set the verbosity to 10 (on Linux, `export AUTOGRAPH_VERBOSITY=10`) and attach the full output. Cause: Unable to locate the source code of <bound method Processor.__call__ of <modulus.blocks.data_loaders.multi_source_loader.processors.asset_loader.AssetLoader object at 0x7fb08e894a58>>. Note that functions defined in certain environments, like the interactive Python shell do not expose their source code. If that is the case, you should to define them in a .py source file. If you are certain the code is graph-compatible, wrap the call using @tf.autograph.do_not_convert. Original error: could not get source code 2021-11-27 21:31:10,177 [INFO] __main__: Found 86 samples in training set WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/rasterizers/bbox_rasterizer.py:347: The name tf.bincount is deprecated. Please use tf.math.bincount instead. 2021-11-27 21:31:10,244 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/rasterizers/bbox_rasterizer.py:347: The name tf.bincount is deprecated. Please use tf.math.bincount instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/training/training_proto_utilities.py:89: The name tf.train.get_or_create_global_step is deprecated. Please use tf.compat.v1.train.get_or_create_global_step instead. 2021-11-27 21:31:10,357 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/training/training_proto_utilities.py:89: The name tf.train.get_or_create_global_step is deprecated. Please use tf.compat.v1.train.get_or_create_global_step instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/training/training_proto_utilities.py:36: The name tf.train.AdamOptimizer is deprecated. Please use tf.compat.v1.train.AdamOptimizer instead. 2021-11-27 21:31:10,367 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/training/training_proto_utilities.py:36: The name tf.train.AdamOptimizer is deprecated. Please use tf.compat.v1.train.AdamOptimizer instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_functions.py:17: The name tf.log is deprecated. Please use tf.math.log instead. 2021-11-27 21:31:10,482 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_functions.py:17: The name tf.log is deprecated. Please use tf.math.log instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:235: The name tf.assign_add is deprecated. Please use tf.compat.v1.assign_add instead. 2021-11-27 21:31:10,574 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:235: The name tf.assign_add is deprecated. Please use tf.compat.v1.assign_add instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/model/detectnet_model.py:591: The name tf.summary.scalar is deprecated. Please use tf.compat.v1.summary.scalar instead. 2021-11-27 21:31:10,591 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/model/detectnet_model.py:591: The name tf.summary.scalar is deprecated. Please use tf.compat.v1.summary.scalar instead. 2021-11-27 21:31:11,937 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: Serial augmentation enabled = False 2021-11-27 21:31:11,937 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: Pseudo sharding enabled = False 2021-11-27 21:31:11,937 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: Max Image Dimensions (all sources): (0, 0) 2021-11-27 21:31:11,938 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: number of cpus: 16, io threads: 32, compute threads: 16, buffered batches: 4 2021-11-27 21:31:11,938 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: total dataset size 14, number of sources: 1, batch size per gpu: 4, steps: 4 WARNING:tensorflow:Entity <bound method DriveNetTFRecordsParser.__call__ of <iva.detectnet_v2.dataloader.drivenet_dataloader.DriveNetTFRecordsParser object at 0x7fb0548cc780>> could not be transformed and will be executed as-is. Please report this to the AutoGraph team. When filing the bug, set the verbosity to 10 (on Linux, `export AUTOGRAPH_VERBOSITY=10`) and attach the full output. Cause: Unable to locate the source code of <bound method DriveNetTFRecordsParser.__call__ of <iva.detectnet_v2.dataloader.drivenet_dataloader.DriveNetTFRecordsParser object at 0x7fb0548cc780>>. Note that functions defined in certain environments, like the interactive Python shell do not expose their source code. If that is the case, you should to define them in a .py source file. If you are certain the code is graph-compatible, wrap the call using @tf.autograph.do_not_convert. Original error: could not get source code 2021-11-27 21:31:11,944 [WARNING] tensorflow: Entity <bound method DriveNetTFRecordsParser.__call__ of <iva.detectnet_v2.dataloader.drivenet_dataloader.DriveNetTFRecordsParser object at 0x7fb0548cc780>> could not be transformed and will be executed as-is. Please report this to the AutoGraph team. When filing the bug, set the verbosity to 10 (on Linux, `export AUTOGRAPH_VERBOSITY=10`) and attach the full output. Cause: Unable to locate the source code of <bound method DriveNetTFRecordsParser.__call__ of <iva.detectnet_v2.dataloader.drivenet_dataloader.DriveNetTFRecordsParser object at 0x7fb0548cc780>>. Note that functions defined in certain environments, like the interactive Python shell do not expose their source code. If that is the case, you should to define them in a .py source file. If you are certain the code is graph-compatible, wrap the call using @tf.autograph.do_not_convert. Original error: could not get source code 2021-11-27 21:31:11,956 [INFO] iva.detectnet_v2.dataloader.default_dataloader: Bounding box coordinates were detected in the input specification! Bboxes will be automatically converted to polygon coordinates. 2021-11-27 21:31:12,109 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: shuffle: False - shard 0 of 1 2021-11-27 21:31:12,112 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: sampling 1 datasets with weights: 2021-11-27 21:31:12,112 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: source: 0 weight: 1.000000 WARNING:tensorflow:Entity <bound method Processor.__call__ of <modulus.blocks.data_loaders.multi_source_loader.processors.asset_loader.AssetLoader object at 0x7fb0101b1ac8>> could not be transformed and will be executed as-is. Please report this to the AutoGraph team. When filing the bug, set the verbosity to 10 (on Linux, `export AUTOGRAPH_VERBOSITY=10`) and attach the full output. Cause: Unable to locate the source code of <bound method Processor.__call__ of <modulus.blocks.data_loaders.multi_source_loader.processors.asset_loader.AssetLoader object at 0x7fb0101b1ac8>>. Note that functions defined in certain environments, like the interactive Python shell do not expose their source code. If that is the case, you should to define them in a .py source file. If you are certain the code is graph-compatible, wrap the call using @tf.autograph.do_not_convert. Original error: could not get source code 2021-11-27 21:31:12,121 [WARNING] tensorflow: Entity <bound method Processor.__call__ of <modulus.blocks.data_loaders.multi_source_loader.processors.asset_loader.AssetLoader object at 0x7fb0101b1ac8>> could not be transformed and will be executed as-is. Please report this to the AutoGraph team. When filing the bug, set the verbosity to 10 (on Linux, `export AUTOGRAPH_VERBOSITY=10`) and attach the full output. Cause: Unable to locate the source code of <bound method Processor.__call__ of <modulus.blocks.data_loaders.multi_source_loader.processors.asset_loader.AssetLoader object at 0x7fb0101b1ac8>>. Note that functions defined in certain environments, like the interactive Python shell do not expose their source code. If that is the case, you should to define them in a .py source file. If you are certain the code is graph-compatible, wrap the call using @tf.autograph.do_not_convert. Original error: could not get source code 2021-11-27 21:31:12,271 [INFO] __main__: Found 14 samples in validation set WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/validation_hook.py:40: The name tf.summary.FileWriterCache is deprecated. Please use tf.compat.v1.summary.FileWriterCache instead. 2021-11-27 21:31:12,762 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/validation_hook.py:40: The name tf.summary.FileWriterCache is deprecated. Please use tf.compat.v1.summary.FileWriterCache instead. 2021-11-27 21:31:13,616 [INFO] __main__: Checkpoint interval: 10 WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/scripts/train.py:109: The name tf.train.Scaffold is deprecated. Please use tf.compat.v1.train.Scaffold instead. 2021-11-27 21:31:13,616 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/scripts/train.py:109: The name tf.train.Scaffold is deprecated. Please use tf.compat.v1.train.Scaffold instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/common/graph/initializers.py:14: The name tf.local_variables_initializer is deprecated. Please use tf.compat.v1.local_variables_initializer instead. 2021-11-27 21:31:13,616 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/common/graph/initializers.py:14: The name tf.local_variables_initializer is deprecated. Please use tf.compat.v1.local_variables_initializer instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/common/graph/initializers.py:15: The name tf.tables_initializer is deprecated. Please use tf.compat.v1.tables_initializer instead. 2021-11-27 21:31:13,616 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/common/graph/initializers.py:15: The name tf.tables_initializer is deprecated. Please use tf.compat.v1.tables_initializer instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/common/graph/initializers.py:16: The name tf.get_collection is deprecated. Please use tf.compat.v1.get_collection instead. 2021-11-27 21:31:13,617 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/common/graph/initializers.py:16: The name tf.get_collection is deprecated. Please use tf.compat.v1.get_collection instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/utils.py:59: The name tf.train.LoggingTensorHook is deprecated. Please use tf.estimator.LoggingTensorHook instead. 2021-11-27 21:31:13,618 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/utils.py:59: The name tf.train.LoggingTensorHook is deprecated. Please use tf.estimator.LoggingTensorHook instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/utils.py:60: The name tf.train.StopAtStepHook is deprecated. Please use tf.estimator.StopAtStepHook instead. 2021-11-27 21:31:13,618 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/utils.py:60: The name tf.train.StopAtStepHook is deprecated. Please use tf.estimator.StopAtStepHook instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/utils.py:73: The name tf.train.StepCounterHook is deprecated. Please use tf.estimator.StepCounterHook instead. 2021-11-27 21:31:13,618 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/utils.py:73: The name tf.train.StepCounterHook is deprecated. Please use tf.estimator.StepCounterHook instead. INFO:tensorflow:Create CheckpointSaverHook. 2021-11-27 21:31:13,618 [INFO] tensorflow: Create CheckpointSaverHook. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/utils.py:99: The name tf.train.SummarySaverHook is deprecated. Please use tf.estimator.SummarySaverHook instead. 2021-11-27 21:31:13,618 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/utils.py:99: The name tf.train.SummarySaverHook is deprecated. Please use tf.estimator.SummarySaverHook instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/training/utilities.py:140: The name tf.train.SingularMonitoredSession is deprecated. Please use tf.compat.v1.train.SingularMonitoredSession instead. 2021-11-27 21:31:13,619 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/training/utilities.py:140: The name tf.train.SingularMonitoredSession is deprecated. Please use tf.compat.v1.train.SingularMonitoredSession instead. INFO:tensorflow:Graph was finalized. 2021-11-27 21:31:14,169 [INFO] tensorflow: Graph was finalized. INFO:tensorflow:Running local_init_op. 2021-11-27 21:31:15,298 [INFO] tensorflow: Running local_init_op. INFO:tensorflow:Done running local_init_op. 2021-11-27 21:31:15,678 [INFO] tensorflow: Done running local_init_op. INFO:tensorflow:Saving checkpoints for step-0. 2021-11-27 21:31:20,052 [INFO] tensorflow: Saving checkpoints for step-0. INFO:tensorflow:epoch = 0.0, learning_rate = 4.9999994e-06, loss = 0.083847225, step = 0 2021-11-27 21:31:33,730 [INFO] tensorflow: epoch = 0.0, learning_rate = 4.9999994e-06, loss = 0.083847225, step = 0 2021-11-27 21:31:33,731 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 0/120: loss: 0.08385 learning rate: 0.00000 Time taken: 0:00:00 ETA: 0:00:00 2021-11-27 21:31:33,731 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 0.964 INFO:tensorflow:global_step/sec: 1.4339 2021-11-27 21:31:35,125 [INFO] tensorflow: global_step/sec: 1.4339 INFO:tensorflow:global_step/sec: 15.1283 2021-11-27 21:31:35,258 [INFO] tensorflow: global_step/sec: 15.1283 INFO:tensorflow:global_step/sec: 14.7831 2021-11-27 21:31:35,393 [INFO] tensorflow: global_step/sec: 14.7831 INFO:tensorflow:global_step/sec: 14.4561 2021-11-27 21:31:35,531 [INFO] tensorflow: global_step/sec: 14.4561 INFO:tensorflow:global_step/sec: 14.9825 2021-11-27 21:31:35,665 [INFO] tensorflow: global_step/sec: 14.9825 INFO:tensorflow:global_step/sec: 14.6884 2021-11-27 21:31:35,801 [INFO] tensorflow: global_step/sec: 14.6884 INFO:tensorflow:global_step/sec: 14.3131 2021-11-27 21:31:35,941 [INFO] tensorflow: global_step/sec: 14.3131 INFO:tensorflow:global_step/sec: 14.5834 2021-11-27 21:31:36,078 [INFO] tensorflow: global_step/sec: 14.5834 INFO:tensorflow:global_step/sec: 14.6913 2021-11-27 21:31:36,214 [INFO] tensorflow: global_step/sec: 14.6913 INFO:tensorflow:global_step/sec: 14.085 2021-11-27 21:31:36,356 [INFO] tensorflow: global_step/sec: 14.085 5df7bf374f13:58:92 [0] NCCL INFO Bootstrap : Using lo:127.0.0.1<0> 5df7bf374f13:58:92 [0] NCCL INFO NET/Plugin : Plugin load returned 0 : libnccl-net.so: cannot open shared object file: No such file or directory. 5df7bf374f13:58:92 [0] NCCL INFO NET/IB : No device found. 5df7bf374f13:58:92 [0] NCCL INFO NET/Socket : Using [0]lo:127.0.0.1<0> [1]eth0:172.17.0.2<0> 5df7bf374f13:58:92 [0] NCCL INFO Using network Socket NCCL version 2.9.9+cuda11.3 5df7bf374f13:58:92 [0] NCCL INFO Channel 00/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 01/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 02/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 03/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 04/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 05/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 06/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 07/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 08/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 09/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 10/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 11/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 12/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 13/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 14/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 15/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 16/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 17/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 18/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 19/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 20/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 21/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 22/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 23/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 24/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 25/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 26/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 27/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 28/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 29/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 30/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Channel 31/32 : 0 5df7bf374f13:58:92 [0] NCCL INFO Trees [0] -1/-1/-1->0->-1 [1] -1/-1/-1->0->-1 [2] -1/-1/-1->0->-1 [3] -1/-1/-1->0->-1 [4] -1/-1/-1->0->-1 [5] -1/-1/-1->0->-1 [6] -1/-1/-1->0->-1 [7] -1/-1/-1->0->-1 [8] -1/-1/-1->0->-1 [9] -1/-1/-1->0->-1 [10] -1/-1/-1->0->-1 [11] -1/-1/-1->0->-1 [12] -1/-1/-1->0->-1 [13] -1/-1/-1->0->-1 [14] -1/-1/-1->0->-1 [15] -1/-1/-1->0->-1 [16] -1/-1/-1->0->-1 [17] -1/-1/-1->0->-1 [18] -1/-1/-1->0->-1 [19] -1/-1/-1->0->-1 [20] -1/-1/-1->0->-1 [21] -1/-1/-1->0->-1 [22] -1/-1/-1->0->-1 [23] -1/-1/-1->0->-1 [24] -1/-1/-1->0->-1 [25] -1/-1/-1->0->-1 [26] -1/-1/-1->0->-1 [27] -1/-1/-1->0->-1 [28] -1/-1/-1->0->-1 [29] -1/-1/-1->0->-1 [30] -1/-1/-1->0->-1 [31] -1/-1/-1->0->-1 5df7bf374f13:58:92 [0] NCCL INFO Connected all rings 5df7bf374f13:58:92 [0] NCCL INFO Connected all trees 5df7bf374f13:58:92 [0] NCCL INFO 32 coll channels, 32 p2p channels, 32 p2p channels per peer 5df7bf374f13:58:92 [0] NCCL INFO comm 0x7fb05377d730 rank 0 nranks 1 cudaDev 0 busId 9000 - Init COMPLETE INFO:tensorflow:global_step/sec: 5.08956 2021-11-27 21:31:36,749 [INFO] tensorflow: global_step/sec: 5.08956 2021-11-27 21:31:36,750 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 1/120: loss: 0.27070 learning rate: 0.00001 Time taken: 0:00:07.095566 ETA: 0:14:04.372386 INFO:tensorflow:global_step/sec: 15.2007 2021-11-27 21:31:36,880 [INFO] tensorflow: global_step/sec: 15.2007 2021-11-27 21:31:36,881 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 13.697 INFO:tensorflow:global_step/sec: 15.2471 2021-11-27 21:31:37,012 [INFO] tensorflow: global_step/sec: 15.2471 INFO:tensorflow:global_step/sec: 15.1556 2021-11-27 21:31:37,144 [INFO] tensorflow: global_step/sec: 15.1556 INFO:tensorflow:global_step/sec: 14.4213 2021-11-27 21:31:37,282 [INFO] tensorflow: global_step/sec: 14.4213 INFO:tensorflow:global_step/sec: 14.5097 2021-11-27 21:31:37,420 [INFO] tensorflow: global_step/sec: 14.5097 INFO:tensorflow:global_step/sec: 14.3531 2021-11-27 21:31:37,559 [INFO] tensorflow: global_step/sec: 14.3531 INFO:tensorflow:global_step/sec: 14.9384 2021-11-27 21:31:37,693 [INFO] tensorflow: global_step/sec: 14.9384 INFO:tensorflow:global_step/sec: 14.5288 2021-11-27 21:31:37,831 [INFO] tensorflow: global_step/sec: 14.5288 INFO:tensorflow:global_step/sec: 14.3725 2021-11-27 21:31:37,970 [INFO] tensorflow: global_step/sec: 14.3725 INFO:tensorflow:global_step/sec: 14.5218 2021-11-27 21:31:38,108 [INFO] tensorflow: global_step/sec: 14.5218 INFO:tensorflow:global_step/sec: 13.7074 2021-11-27 21:31:38,254 [INFO] tensorflow: global_step/sec: 13.7074 2021-11-27 21:31:38,255 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 2/120: loss: 0.16879 learning rate: 0.00001 Time taken: 0:00:01.506391 ETA: 0:02:57.754172 INFO:tensorflow:global_step/sec: 14.5663 2021-11-27 21:31:38,391 [INFO] tensorflow: global_step/sec: 14.5663 INFO:tensorflow:global_step/sec: 14.6227 2021-11-27 21:31:38,528 [INFO] tensorflow: global_step/sec: 14.6227 2021-11-27 21:31:38,597 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.277 INFO:tensorflow:global_step/sec: 14.7751 2021-11-27 21:31:38,663 [INFO] tensorflow: global_step/sec: 14.7751 INFO:tensorflow:epoch = 2.3636363636363638, learning_rate = 1.2385377e-05, loss = 0.12353368, step = 52 (5.073 sec) 2021-11-27 21:31:38,803 [INFO] tensorflow: epoch = 2.3636363636363638, learning_rate = 1.2385377e-05, loss = 0.12353368, step = 52 (5.073 sec) INFO:tensorflow:global_step/sec: 14.259 2021-11-27 21:31:38,803 [INFO] tensorflow: global_step/sec: 14.259 INFO:tensorflow:global_step/sec: 14.955 2021-11-27 21:31:38,937 [INFO] tensorflow: global_step/sec: 14.955 INFO:tensorflow:global_step/sec: 14.5101 2021-11-27 21:31:39,075 [INFO] tensorflow: global_step/sec: 14.5101 INFO:tensorflow:global_step/sec: 14.7515 2021-11-27 21:31:39,211 [INFO] tensorflow: global_step/sec: 14.7515 INFO:tensorflow:global_step/sec: 14.6212 2021-11-27 21:31:39,347 [INFO] tensorflow: global_step/sec: 14.6212 INFO:tensorflow:global_step/sec: 14.9123 2021-11-27 21:31:39,482 [INFO] tensorflow: global_step/sec: 14.9123 INFO:tensorflow:global_step/sec: 14.6786 2021-11-27 21:31:39,618 [INFO] tensorflow: global_step/sec: 14.6786 INFO:tensorflow:global_step/sec: 14.6051 2021-11-27 21:31:39,755 [INFO] tensorflow: global_step/sec: 14.6051 2021-11-27 21:31:39,756 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 3/120: loss: 0.07809 learning rate: 0.00002 Time taken: 0:00:01.501290 ETA: 0:02:55.650968 INFO:tensorflow:global_step/sec: 14.9706 2021-11-27 21:31:39,888 [INFO] tensorflow: global_step/sec: 14.9706 INFO:tensorflow:global_step/sec: 14.2494 2021-11-27 21:31:40,029 [INFO] tensorflow: global_step/sec: 14.2494 INFO:tensorflow:global_step/sec: 15.1121 2021-11-27 21:31:40,161 [INFO] tensorflow: global_step/sec: 15.1121 INFO:tensorflow:global_step/sec: 14.9982 2021-11-27 21:31:40,294 [INFO] tensorflow: global_step/sec: 14.9982 2021-11-27 21:31:40,295 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.905 INFO:tensorflow:global_step/sec: 14.8274 2021-11-27 21:31:40,429 [INFO] tensorflow: global_step/sec: 14.8274 INFO:tensorflow:global_step/sec: 14.4947 2021-11-27 21:31:40,567 [INFO] tensorflow: global_step/sec: 14.4947 INFO:tensorflow:global_step/sec: 15.265 2021-11-27 21:31:40,698 [INFO] tensorflow: global_step/sec: 15.265 INFO:tensorflow:global_step/sec: 14.539 2021-11-27 21:31:40,836 [INFO] tensorflow: global_step/sec: 14.539 INFO:tensorflow:global_step/sec: 14.9142 2021-11-27 21:31:40,970 [INFO] tensorflow: global_step/sec: 14.9142 INFO:tensorflow:global_step/sec: 15.199 2021-11-27 21:31:41,102 [INFO] tensorflow: global_step/sec: 15.199 INFO:tensorflow:global_step/sec: 13.7134 2021-11-27 21:31:41,247 [INFO] tensorflow: global_step/sec: 13.7134 2021-11-27 21:31:41,248 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 4/120: loss: 0.03462 learning rate: 0.00002 Time taken: 0:00:01.490692 ETA: 0:02:52.920288 INFO:tensorflow:global_step/sec: 14.6668 2021-11-27 21:31:41,384 [INFO] tensorflow: global_step/sec: 14.6668 INFO:tensorflow:global_step/sec: 14.8054 2021-11-27 21:31:41,519 [INFO] tensorflow: global_step/sec: 14.8054 INFO:tensorflow:global_step/sec: 14.7128 2021-11-27 21:31:41,655 [INFO] tensorflow: global_step/sec: 14.7128 INFO:tensorflow:global_step/sec: 14.9107 2021-11-27 21:31:41,789 [INFO] tensorflow: global_step/sec: 14.9107 INFO:tensorflow:global_step/sec: 14.3228 2021-11-27 21:31:41,929 [INFO] tensorflow: global_step/sec: 14.3228 2021-11-27 21:31:41,997 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.762 INFO:tensorflow:global_step/sec: 14.439 2021-11-27 21:31:42,067 [INFO] tensorflow: global_step/sec: 14.439 INFO:tensorflow:global_step/sec: 14.7513 2021-11-27 21:31:42,203 [INFO] tensorflow: global_step/sec: 14.7513 INFO:tensorflow:global_step/sec: 14.1891 2021-11-27 21:31:42,344 [INFO] tensorflow: global_step/sec: 14.1891 INFO:tensorflow:global_step/sec: 14.1307 2021-11-27 21:31:42,485 [INFO] tensorflow: global_step/sec: 14.1307 INFO:tensorflow:global_step/sec: 13.6667 2021-11-27 21:31:42,631 [INFO] tensorflow: global_step/sec: 13.6667 INFO:tensorflow:global_step/sec: 13.3258 2021-11-27 21:31:42,782 [INFO] tensorflow: global_step/sec: 13.3258 2021-11-27 21:31:42,782 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 5/120: loss: 0.02198 learning rate: 0.00003 Time taken: 0:00:01.527407 ETA: 0:02:55.651770 INFO:tensorflow:global_step/sec: 14.2794 2021-11-27 21:31:42,922 [INFO] tensorflow: global_step/sec: 14.2794 INFO:tensorflow:global_step/sec: 15.0424 2021-11-27 21:31:43,055 [INFO] tensorflow: global_step/sec: 15.0424 INFO:tensorflow:global_step/sec: 14.9816 2021-11-27 21:31:43,188 [INFO] tensorflow: global_step/sec: 14.9816 INFO:tensorflow:global_step/sec: 14.9566 2021-11-27 21:31:43,322 [INFO] tensorflow: global_step/sec: 14.9566 INFO:tensorflow:global_step/sec: 15.1547 2021-11-27 21:31:43,454 [INFO] tensorflow: global_step/sec: 15.1547 INFO:tensorflow:global_step/sec: 15.7944 2021-11-27 21:31:43,580 [INFO] tensorflow: global_step/sec: 15.7944 INFO:tensorflow:global_step/sec: 14.9112 2021-11-27 21:31:43,714 [INFO] tensorflow: global_step/sec: 14.9112 2021-11-27 21:31:43,715 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.224 INFO:tensorflow:global_step/sec: 15.0502 2021-11-27 21:31:43,847 [INFO] tensorflow: global_step/sec: 15.0502 INFO:tensorflow:epoch = 5.7727272727272725, learning_rate = 4.582378e-05, loss = 0.013955122, step = 127 (5.110 sec) 2021-11-27 21:31:43,913 [INFO] tensorflow: epoch = 5.7727272727272725, learning_rate = 4.582378e-05, loss = 0.013955122, step = 127 (5.110 sec) INFO:tensorflow:global_step/sec: 15.4896 2021-11-27 21:31:43,976 [INFO] tensorflow: global_step/sec: 15.4896 INFO:tensorflow:global_step/sec: 15.6989 2021-11-27 21:31:44,104 [INFO] tensorflow: global_step/sec: 15.6989 INFO:tensorflow:global_step/sec: 14.5323 2021-11-27 21:31:44,241 [INFO] tensorflow: global_step/sec: 14.5323 2021-11-27 21:31:44,242 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 6/120: loss: 0.01475 learning rate: 0.00005 Time taken: 0:00:01.465466 ETA: 0:02:47.063181 INFO:tensorflow:global_step/sec: 15.3628 2021-11-27 21:31:44,372 [INFO] tensorflow: global_step/sec: 15.3628 INFO:tensorflow:global_step/sec: 14.0582 2021-11-27 21:31:44,514 [INFO] tensorflow: global_step/sec: 14.0582 INFO:tensorflow:global_step/sec: 15.1287 2021-11-27 21:31:44,646 [INFO] tensorflow: global_step/sec: 15.1287 INFO:tensorflow:global_step/sec: 15.6548 2021-11-27 21:31:44,774 [INFO] tensorflow: global_step/sec: 15.6548 INFO:tensorflow:global_step/sec: 14.9995 2021-11-27 21:31:44,907 [INFO] tensorflow: global_step/sec: 14.9995 INFO:tensorflow:global_step/sec: 15.6112 2021-11-27 21:31:45,035 [INFO] tensorflow: global_step/sec: 15.6112 INFO:tensorflow:global_step/sec: 14.9585 2021-11-27 21:31:45,169 [INFO] tensorflow: global_step/sec: 14.9585 INFO:tensorflow:global_step/sec: 12.65 2021-11-27 21:31:45,327 [INFO] tensorflow: global_step/sec: 12.65 2021-11-27 21:31:45,394 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.584 INFO:tensorflow:global_step/sec: 14.7737 2021-11-27 21:31:45,463 [INFO] tensorflow: global_step/sec: 14.7737 INFO:tensorflow:global_step/sec: 15.0168 2021-11-27 21:31:45,596 [INFO] tensorflow: global_step/sec: 15.0168 INFO:tensorflow:global_step/sec: 14.2155 2021-11-27 21:31:45,736 [INFO] tensorflow: global_step/sec: 14.2155 2021-11-27 21:31:45,737 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 7/120: loss: 0.00729 learning rate: 0.00007 Time taken: 0:00:01.495057 ETA: 0:02:48.941399 INFO:tensorflow:global_step/sec: 15.3858 2021-11-27 21:31:45,866 [INFO] tensorflow: global_step/sec: 15.3858 INFO:tensorflow:global_step/sec: 15.1341 2021-11-27 21:31:45,999 [INFO] tensorflow: global_step/sec: 15.1341 INFO:tensorflow:global_step/sec: 14.8159 2021-11-27 21:31:46,134 [INFO] tensorflow: global_step/sec: 14.8159 INFO:tensorflow:global_step/sec: 15.4425 2021-11-27 21:31:46,263 [INFO] tensorflow: global_step/sec: 15.4425 INFO:tensorflow:global_step/sec: 15.3908 2021-11-27 21:31:46,393 [INFO] tensorflow: global_step/sec: 15.3908 INFO:tensorflow:global_step/sec: 14.7018 2021-11-27 21:31:46,529 [INFO] tensorflow: global_step/sec: 14.7018 INFO:tensorflow:global_step/sec: 15.5721 2021-11-27 21:31:46,657 [INFO] tensorflow: global_step/sec: 15.5721 INFO:tensorflow:global_step/sec: 15.362 2021-11-27 21:31:46,788 [INFO] tensorflow: global_step/sec: 15.362 INFO:tensorflow:global_step/sec: 14.6713 2021-11-27 21:31:46,924 [INFO] tensorflow: global_step/sec: 14.6713 INFO:tensorflow:global_step/sec: 15.4033 2021-11-27 21:31:47,054 [INFO] tensorflow: global_step/sec: 15.4033 2021-11-27 21:31:47,055 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.215 INFO:tensorflow:global_step/sec: 13.9334 2021-11-27 21:31:47,197 [INFO] tensorflow: global_step/sec: 13.9334 2021-11-27 21:31:47,198 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 8/120: loss: 0.00513 learning rate: 0.00011 Time taken: 0:00:01.454498 ETA: 0:02:42.903755 INFO:tensorflow:global_step/sec: 14.699 2021-11-27 21:31:47,333 [INFO] tensorflow: global_step/sec: 14.699 INFO:tensorflow:global_step/sec: 14.0021 2021-11-27 21:31:47,476 [INFO] tensorflow: global_step/sec: 14.0021 INFO:tensorflow:global_step/sec: 14.2694 2021-11-27 21:31:47,616 [INFO] tensorflow: global_step/sec: 14.2694 INFO:tensorflow:global_step/sec: 14.2976 2021-11-27 21:31:47,756 [INFO] tensorflow: global_step/sec: 14.2976 INFO:tensorflow:global_step/sec: 14.8727 2021-11-27 21:31:47,891 [INFO] tensorflow: global_step/sec: 14.8727 INFO:tensorflow:global_step/sec: 13.9839 2021-11-27 21:31:48,034 [INFO] tensorflow: global_step/sec: 13.9839 INFO:tensorflow:global_step/sec: 14.4957 2021-11-27 21:31:48,172 [INFO] tensorflow: global_step/sec: 14.4957 INFO:tensorflow:global_step/sec: 14.6333 2021-11-27 21:31:48,308 [INFO] tensorflow: global_step/sec: 14.6333 INFO:tensorflow:global_step/sec: 14.3759 2021-11-27 21:31:48,448 [INFO] tensorflow: global_step/sec: 14.3759 INFO:tensorflow:global_step/sec: 14.4949 2021-11-27 21:31:48,586 [INFO] tensorflow: global_step/sec: 14.4949 INFO:tensorflow:global_step/sec: 14.3527 2021-11-27 21:31:48,725 [INFO] tensorflow: global_step/sec: 14.3527 2021-11-27 21:31:48,726 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 9/120: loss: 0.00476 learning rate: 0.00016 Time taken: 0:00:01.529690 ETA: 0:02:49.795540 2021-11-27 21:31:48,793 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.549 INFO:tensorflow:global_step/sec: 14.7406 2021-11-27 21:31:48,861 [INFO] tensorflow: global_step/sec: 14.7406 INFO:tensorflow:epoch = 9.181818181818182, learning_rate = 0.00016954016, loss = 0.0040661036, step = 202 (5.087 sec) 2021-11-27 21:31:49,000 [INFO] tensorflow: epoch = 9.181818181818182, learning_rate = 0.00016954016, loss = 0.0040661036, step = 202 (5.087 sec) INFO:tensorflow:global_step/sec: 14.3046 2021-11-27 21:31:49,000 [INFO] tensorflow: global_step/sec: 14.3046 INFO:tensorflow:global_step/sec: 14.3506 2021-11-27 21:31:49,140 [INFO] tensorflow: global_step/sec: 14.3506 INFO:tensorflow:global_step/sec: 14.1451 2021-11-27 21:31:49,281 [INFO] tensorflow: global_step/sec: 14.1451 INFO:tensorflow:global_step/sec: 14.2535 2021-11-27 21:31:49,421 [INFO] tensorflow: global_step/sec: 14.2535 INFO:tensorflow:global_step/sec: 14.344 2021-11-27 21:31:49,561 [INFO] tensorflow: global_step/sec: 14.344 INFO:tensorflow:global_step/sec: 14.3969 2021-11-27 21:31:49,700 [INFO] tensorflow: global_step/sec: 14.3969 INFO:tensorflow:global_step/sec: 13.9282 2021-11-27 21:31:49,843 [INFO] tensorflow: global_step/sec: 13.9282 INFO:tensorflow:global_step/sec: 14.2082 2021-11-27 21:31:49,984 [INFO] tensorflow: global_step/sec: 14.2082 INFO:tensorflow:global_step/sec: 13.9338 2021-11-27 21:31:50,128 [INFO] tensorflow: global_step/sec: 13.9338 INFO:tensorflow:Saving checkpoints for step-220. 2021-11-27 21:31:50,199 [INFO] tensorflow: Saving checkpoints for step-220. INFO:tensorflow:global_step/sec: 0.796942 2021-11-27 21:31:52,637 [INFO] tensorflow: global_step/sec: 0.796942 2021-11-27 21:31:52,638 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 10/120: loss: 0.00352 learning rate: 0.00023 Time taken: 0:00:03.906896 ETA: 0:07:09.758573 INFO:tensorflow:global_step/sec: 14.776 2021-11-27 21:31:52,773 [INFO] tensorflow: global_step/sec: 14.776 INFO:tensorflow:global_step/sec: 15.0587 2021-11-27 21:31:52,905 [INFO] tensorflow: global_step/sec: 15.0587 2021-11-27 21:31:52,906 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 24.312 INFO:tensorflow:global_step/sec: 15.0996 2021-11-27 21:31:53,038 [INFO] tensorflow: global_step/sec: 15.0996 INFO:tensorflow:global_step/sec: 15.4241 2021-11-27 21:31:53,168 [INFO] tensorflow: global_step/sec: 15.4241 INFO:tensorflow:global_step/sec: 15.0456 2021-11-27 21:31:53,301 [INFO] tensorflow: global_step/sec: 15.0456 INFO:tensorflow:global_step/sec: 15.0163 2021-11-27 21:31:53,434 [INFO] tensorflow: global_step/sec: 15.0163 INFO:tensorflow:global_step/sec: 15.2481 2021-11-27 21:31:53,565 [INFO] tensorflow: global_step/sec: 15.2481 INFO:tensorflow:global_step/sec: 14.945 2021-11-27 21:31:53,699 [INFO] tensorflow: global_step/sec: 14.945 INFO:tensorflow:global_step/sec: 15.5128 2021-11-27 21:31:53,828 [INFO] tensorflow: global_step/sec: 15.5128 INFO:tensorflow:global_step/sec: 15.1793 2021-11-27 21:31:53,959 [INFO] tensorflow: global_step/sec: 15.1793 INFO:tensorflow:epoch = 11.0, learning_rate = 0.000340646, loss = 0.0036697325, step = 242 (5.108 sec) 2021-11-27 21:31:54,107 [INFO] tensorflow: epoch = 11.0, learning_rate = 0.000340646, loss = 0.0036697325, step = 242 (5.108 sec) INFO:tensorflow:global_step/sec: 13.4528 2021-11-27 21:31:54,108 [INFO] tensorflow: global_step/sec: 13.4528 2021-11-27 21:31:54,109 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 11/120: loss: 0.00367 learning rate: 0.00034 Time taken: 0:00:01.469206 ETA: 0:02:40.143464 INFO:tensorflow:global_step/sec: 15.0168 2021-11-27 21:31:54,241 [INFO] tensorflow: global_step/sec: 15.0168 INFO:tensorflow:global_step/sec: 15.5093 2021-11-27 21:31:54,370 [INFO] tensorflow: global_step/sec: 15.5093 INFO:tensorflow:global_step/sec: 15.0362 2021-11-27 21:31:54,503 [INFO] tensorflow: global_step/sec: 15.0362 2021-11-27 21:31:54,572 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.049 INFO:tensorflow:global_step/sec: 14.6749 2021-11-27 21:31:54,639 [INFO] tensorflow: global_step/sec: 14.6749 INFO:tensorflow:global_step/sec: 15.5167 2021-11-27 21:31:54,768 [INFO] tensorflow: global_step/sec: 15.5167 INFO:tensorflow:global_step/sec: 15.7521 2021-11-27 21:31:54,895 [INFO] tensorflow: global_step/sec: 15.7521 INFO:tensorflow:global_step/sec: 15.2175 2021-11-27 21:31:55,027 [INFO] tensorflow: global_step/sec: 15.2175 INFO:tensorflow:global_step/sec: 14.9397 2021-11-27 21:31:55,161 [INFO] tensorflow: global_step/sec: 14.9397 INFO:tensorflow:global_step/sec: 15.2052 2021-11-27 21:31:55,292 [INFO] tensorflow: global_step/sec: 15.2052 INFO:tensorflow:global_step/sec: 15.5283 2021-11-27 21:31:55,421 [INFO] tensorflow: global_step/sec: 15.5283 INFO:tensorflow:global_step/sec: 13.4821 2021-11-27 21:31:55,569 [INFO] tensorflow: global_step/sec: 13.4821 2021-11-27 21:31:55,570 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 12/120: loss: 0.00225 learning rate: 0.00050 Time taken: 0:00:01.463416 ETA: 0:02:38.048887 INFO:tensorflow:global_step/sec: 14.946 2021-11-27 21:31:55,703 [INFO] tensorflow: global_step/sec: 14.946 INFO:tensorflow:global_step/sec: 15.2221 2021-11-27 21:31:55,834 [INFO] tensorflow: global_step/sec: 15.2221 INFO:tensorflow:global_step/sec: 14.8006 2021-11-27 21:31:55,970 [INFO] tensorflow: global_step/sec: 14.8006 INFO:tensorflow:global_step/sec: 14.7063 2021-11-27 21:31:56,106 [INFO] tensorflow: global_step/sec: 14.7063 INFO:tensorflow:global_step/sec: 15.2172 2021-11-27 21:31:56,237 [INFO] tensorflow: global_step/sec: 15.2172 2021-11-27 21:31:56,238 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.032 INFO:tensorflow:global_step/sec: 14.5762 2021-11-27 21:31:56,374 [INFO] tensorflow: global_step/sec: 14.5762 INFO:tensorflow:global_step/sec: 14.2912 2021-11-27 21:31:56,514 [INFO] tensorflow: global_step/sec: 14.2912 INFO:tensorflow:global_step/sec: 14.2393 2021-11-27 21:31:56,655 [INFO] tensorflow: global_step/sec: 14.2393 INFO:tensorflow:global_step/sec: 14.8867 2021-11-27 21:31:56,789 [INFO] tensorflow: global_step/sec: 14.8867 INFO:tensorflow:global_step/sec: 14.1512 2021-11-27 21:31:56,930 [INFO] tensorflow: global_step/sec: 14.1512 INFO:tensorflow:global_step/sec: 13.8276 2021-11-27 21:31:57,075 [INFO] tensorflow: global_step/sec: 13.8276 2021-11-27 21:31:57,076 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 13/120: loss: 0.00187 learning rate: 0.00050 Time taken: 0:00:01.501979 ETA: 0:02:40.711714 INFO:tensorflow:global_step/sec: 15.014 2021-11-27 21:31:57,208 [INFO] tensorflow: global_step/sec: 15.014 INFO:tensorflow:global_step/sec: 14.5506 2021-11-27 21:31:57,346 [INFO] tensorflow: global_step/sec: 14.5506 INFO:tensorflow:global_step/sec: 14.6047 2021-11-27 21:31:57,483 [INFO] tensorflow: global_step/sec: 14.6047 INFO:tensorflow:global_step/sec: 14.6228 2021-11-27 21:31:57,619 [INFO] tensorflow: global_step/sec: 14.6228 INFO:tensorflow:global_step/sec: 14.5923 2021-11-27 21:31:57,756 [INFO] tensorflow: global_step/sec: 14.5923 INFO:tensorflow:global_step/sec: 14.595 2021-11-27 21:31:57,893 [INFO] tensorflow: global_step/sec: 14.595 2021-11-27 21:31:57,966 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.864 INFO:tensorflow:global_step/sec: 14.0557 2021-11-27 21:31:58,036 [INFO] tensorflow: global_step/sec: 14.0557 INFO:tensorflow:global_step/sec: 15.359 2021-11-27 21:31:58,166 [INFO] tensorflow: global_step/sec: 15.359 INFO:tensorflow:global_step/sec: 14.7587 2021-11-27 21:31:58,302 [INFO] tensorflow: global_step/sec: 14.7587 INFO:tensorflow:global_step/sec: 13.7878 2021-11-27 21:31:58,447 [INFO] tensorflow: global_step/sec: 13.7878 INFO:tensorflow:global_step/sec: 14.0349 2021-11-27 21:31:58,589 [INFO] tensorflow: global_step/sec: 14.0349 2021-11-27 21:31:58,590 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 14/120: loss: 0.00258 learning rate: 0.00050 Time taken: 0:00:01.511611 ETA: 0:02:40.230815 INFO:tensorflow:global_step/sec: 15.0277 2021-11-27 21:31:58,722 [INFO] tensorflow: global_step/sec: 15.0277 INFO:tensorflow:global_step/sec: 14.2623 2021-11-27 21:31:58,862 [INFO] tensorflow: global_step/sec: 14.2623 INFO:tensorflow:global_step/sec: 14.6964 2021-11-27 21:31:58,998 [INFO] tensorflow: global_step/sec: 14.6964 INFO:tensorflow:global_step/sec: 14.8048 2021-11-27 21:31:59,134 [INFO] tensorflow: global_step/sec: 14.8048 INFO:tensorflow:epoch = 14.40909090909091, learning_rate = 0.00049999997, loss = 0.0022279387, step = 317 (5.099 sec) 2021-11-27 21:31:59,206 [INFO] tensorflow: epoch = 14.40909090909091, learning_rate = 0.00049999997, loss = 0.0022279387, step = 317 (5.099 sec) INFO:tensorflow:global_step/sec: 13.9091 2021-11-27 21:31:59,277 [INFO] tensorflow: global_step/sec: 13.9091 INFO:tensorflow:global_step/sec: 14.4141 2021-11-27 21:31:59,416 [INFO] tensorflow: global_step/sec: 14.4141 INFO:tensorflow:global_step/sec: 13.5095 2021-11-27 21:31:59,564 [INFO] tensorflow: global_step/sec: 13.5095 INFO:tensorflow:global_step/sec: 14.5998 2021-11-27 21:31:59,701 [INFO] tensorflow: global_step/sec: 14.5998 2021-11-27 21:31:59,702 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.626 INFO:tensorflow:global_step/sec: 14.6233 2021-11-27 21:31:59,838 [INFO] tensorflow: global_step/sec: 14.6233 INFO:tensorflow:global_step/sec: 14.4259 2021-11-27 21:31:59,977 [INFO] tensorflow: global_step/sec: 14.4259 INFO:tensorflow:global_step/sec: 13.6027 2021-11-27 21:32:00,124 [INFO] tensorflow: global_step/sec: 13.6027 2021-11-27 21:32:00,125 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 15/120: loss: 0.00160 learning rate: 0.00050 Time taken: 0:00:01.529787 ETA: 0:02:40.627667 INFO:tensorflow:global_step/sec: 14.8995 2021-11-27 21:32:00,258 [INFO] tensorflow: global_step/sec: 14.8995 INFO:tensorflow:global_step/sec: 15.1265 2021-11-27 21:32:00,390 [INFO] tensorflow: global_step/sec: 15.1265 INFO:tensorflow:global_step/sec: 14.4505 2021-11-27 21:32:00,528 [INFO] tensorflow: global_step/sec: 14.4505 INFO:tensorflow:global_step/sec: 14.0864 2021-11-27 21:32:00,670 [INFO] tensorflow: global_step/sec: 14.0864 INFO:tensorflow:global_step/sec: 14.3071 2021-11-27 21:32:00,810 [INFO] tensorflow: global_step/sec: 14.3071 INFO:tensorflow:global_step/sec: 13.9509 2021-11-27 21:32:00,954 [INFO] tensorflow: global_step/sec: 13.9509 INFO:tensorflow:global_step/sec: 14.6024 2021-11-27 21:32:01,091 [INFO] tensorflow: global_step/sec: 14.6024 INFO:tensorflow:global_step/sec: 13.9412 2021-11-27 21:32:01,234 [INFO] tensorflow: global_step/sec: 13.9412 INFO:tensorflow:global_step/sec: 14.4016 2021-11-27 21:32:01,373 [INFO] tensorflow: global_step/sec: 14.4016 2021-11-27 21:32:01,444 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.423 INFO:tensorflow:global_step/sec: 14.4972 2021-11-27 21:32:01,511 [INFO] tensorflow: global_step/sec: 14.4972 INFO:tensorflow:global_step/sec: 13.7768 2021-11-27 21:32:01,656 [INFO] tensorflow: global_step/sec: 13.7768 2021-11-27 21:32:01,657 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 16/120: loss: 0.00166 learning rate: 0.00050 Time taken: 0:00:01.534032 ETA: 0:02:39.539289 INFO:tensorflow:global_step/sec: 14.623 2021-11-27 21:32:01,793 [INFO] tensorflow: global_step/sec: 14.623 INFO:tensorflow:global_step/sec: 14.4643 2021-11-27 21:32:01,931 [INFO] tensorflow: global_step/sec: 14.4643 INFO:tensorflow:global_step/sec: 14.1679 2021-11-27 21:32:02,072 [INFO] tensorflow: global_step/sec: 14.1679 INFO:tensorflow:global_step/sec: 14.551 2021-11-27 21:32:02,210 [INFO] tensorflow: global_step/sec: 14.551 INFO:tensorflow:global_step/sec: 14.2581 2021-11-27 21:32:02,350 [INFO] tensorflow: global_step/sec: 14.2581 INFO:tensorflow:global_step/sec: 14.6262 2021-11-27 21:32:02,487 [INFO] tensorflow: global_step/sec: 14.6262 INFO:tensorflow:global_step/sec: 14.7346 2021-11-27 21:32:02,622 [INFO] tensorflow: global_step/sec: 14.7346 INFO:tensorflow:global_step/sec: 14.8959 2021-11-27 21:32:02,757 [INFO] tensorflow: global_step/sec: 14.8959 INFO:tensorflow:global_step/sec: 14.6362 2021-11-27 21:32:02,893 [INFO] tensorflow: global_step/sec: 14.6362 INFO:tensorflow:global_step/sec: 14.6286 2021-11-27 21:32:03,030 [INFO] tensorflow: global_step/sec: 14.6286 INFO:tensorflow:global_step/sec: 14.1794 2021-11-27 21:32:03,171 [INFO] tensorflow: global_step/sec: 14.1794 2021-11-27 21:32:03,172 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 17/120: loss: 0.00210 learning rate: 0.00050 Time taken: 0:00:01.513803 ETA: 0:02:35.921710 2021-11-27 21:32:03,172 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.879 INFO:tensorflow:global_step/sec: 15.2497 2021-11-27 21:32:03,302 [INFO] tensorflow: global_step/sec: 15.2497 INFO:tensorflow:global_step/sec: 14.751 2021-11-27 21:32:03,438 [INFO] tensorflow: global_step/sec: 14.751 INFO:tensorflow:global_step/sec: 14.3858 2021-11-27 21:32:03,577 [INFO] tensorflow: global_step/sec: 14.3858 INFO:tensorflow:global_step/sec: 14.5876 2021-11-27 21:32:03,714 [INFO] tensorflow: global_step/sec: 14.5876 INFO:tensorflow:global_step/sec: 14.332 2021-11-27 21:32:03,853 [INFO] tensorflow: global_step/sec: 14.332 INFO:tensorflow:global_step/sec: 14.9141 2021-11-27 21:32:03,988 [INFO] tensorflow: global_step/sec: 14.9141 INFO:tensorflow:global_step/sec: 14.3155 2021-11-27 21:32:04,127 [INFO] tensorflow: global_step/sec: 14.3155 INFO:tensorflow:global_step/sec: 14.4214 2021-11-27 21:32:04,266 [INFO] tensorflow: global_step/sec: 14.4214 INFO:tensorflow:epoch = 17.772727272727273, learning_rate = 0.00049999997, loss = 0.00184356, step = 391 (5.129 sec) 2021-11-27 21:32:04,336 [INFO] tensorflow: epoch = 17.772727272727273, learning_rate = 0.00049999997, loss = 0.00184356, step = 391 (5.129 sec) INFO:tensorflow:global_step/sec: 14.5394 2021-11-27 21:32:04,404 [INFO] tensorflow: global_step/sec: 14.5394 INFO:tensorflow:global_step/sec: 15.1057 2021-11-27 21:32:04,536 [INFO] tensorflow: global_step/sec: 15.1057 INFO:tensorflow:global_step/sec: 14.4818 2021-11-27 21:32:04,674 [INFO] tensorflow: global_step/sec: 14.4818 2021-11-27 21:32:04,675 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 18/120: loss: 0.00177 learning rate: 0.00050 Time taken: 0:00:01.499717 ETA: 0:02:32.971085 INFO:tensorflow:global_step/sec: 14.3802 2021-11-27 21:32:04,813 [INFO] tensorflow: global_step/sec: 14.3802 2021-11-27 21:32:04,879 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.591 INFO:tensorflow:global_step/sec: 14.8187 2021-11-27 21:32:04,948 [INFO] tensorflow: global_step/sec: 14.8187 INFO:tensorflow:global_step/sec: 14.4605 2021-11-27 21:32:05,086 [INFO] tensorflow: global_step/sec: 14.4605 INFO:tensorflow:global_step/sec: 14.082 2021-11-27 21:32:05,228 [INFO] tensorflow: global_step/sec: 14.082 INFO:tensorflow:global_step/sec: 14.5303 2021-11-27 21:32:05,366 [INFO] tensorflow: global_step/sec: 14.5303 INFO:tensorflow:global_step/sec: 14.7418 2021-11-27 21:32:05,502 [INFO] tensorflow: global_step/sec: 14.7418 INFO:tensorflow:global_step/sec: 14.7793 2021-11-27 21:32:05,637 [INFO] tensorflow: global_step/sec: 14.7793 INFO:tensorflow:global_step/sec: 14.2898 2021-11-27 21:32:05,777 [INFO] tensorflow: global_step/sec: 14.2898 INFO:tensorflow:global_step/sec: 14.1046 2021-11-27 21:32:05,919 [INFO] tensorflow: global_step/sec: 14.1046 INFO:tensorflow:global_step/sec: 14.5612 2021-11-27 21:32:06,056 [INFO] tensorflow: global_step/sec: 14.5612 INFO:tensorflow:global_step/sec: 13.5439 2021-11-27 21:32:06,204 [INFO] tensorflow: global_step/sec: 13.5439 2021-11-27 21:32:06,205 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 19/120: loss: 0.00155 learning rate: 0.00050 Time taken: 0:00:01.529584 ETA: 0:02:34.488001 INFO:tensorflow:global_step/sec: 14.3055 2021-11-27 21:32:06,344 [INFO] tensorflow: global_step/sec: 14.3055 INFO:tensorflow:global_step/sec: 14.9522 2021-11-27 21:32:06,477 [INFO] tensorflow: global_step/sec: 14.9522 INFO:tensorflow:global_step/sec: 15.0328 2021-11-27 21:32:06,610 [INFO] tensorflow: global_step/sec: 15.0328 2021-11-27 21:32:06,611 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.729 INFO:tensorflow:global_step/sec: 14.9099 2021-11-27 21:32:06,745 [INFO] tensorflow: global_step/sec: 14.9099 INFO:tensorflow:global_step/sec: 14.4578 2021-11-27 21:32:06,883 [INFO] tensorflow: global_step/sec: 14.4578 INFO:tensorflow:global_step/sec: 14.2583 2021-11-27 21:32:07,023 [INFO] tensorflow: global_step/sec: 14.2583 INFO:tensorflow:global_step/sec: 14.6553 2021-11-27 21:32:07,160 [INFO] tensorflow: global_step/sec: 14.6553 INFO:tensorflow:global_step/sec: 14.273 2021-11-27 21:32:07,300 [INFO] tensorflow: global_step/sec: 14.273 INFO:tensorflow:global_step/sec: 14.8591 2021-11-27 21:32:07,434 [INFO] tensorflow: global_step/sec: 14.8591 INFO:tensorflow:global_step/sec: 14.1223 2021-11-27 21:32:07,576 [INFO] tensorflow: global_step/sec: 14.1223 INFO:tensorflow:Saving checkpoints for step-440. 2021-11-27 21:32:07,645 [INFO] tensorflow: Saving checkpoints for step-440. INFO:tensorflow:epoch = 20.0, learning_rate = 0.00049999997, loss = 0.0016232943, step = 440 (5.737 sec) 2021-11-27 21:32:10,073 [INFO] tensorflow: epoch = 20.0, learning_rate = 0.00049999997, loss = 0.0016232943, step = 440 (5.737 sec) INFO:tensorflow:global_step/sec: 0.800898 2021-11-27 21:32:10,073 [INFO] tensorflow: global_step/sec: 0.800898 2021-11-27 21:32:10,074 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 20/120: loss: 0.00162 learning rate: 0.00050 Time taken: 0:00:03.864767 ETA: 0:06:26.476707 INFO:tensorflow:global_step/sec: 13.666 2021-11-27 21:32:10,220 [INFO] tensorflow: global_step/sec: 13.666 INFO:tensorflow:global_step/sec: 14.9399 2021-11-27 21:32:10,353 [INFO] tensorflow: global_step/sec: 14.9399 INFO:tensorflow:global_step/sec: 14.9097 2021-11-27 21:32:10,488 [INFO] tensorflow: global_step/sec: 14.9097 INFO:tensorflow:global_step/sec: 14.3653 2021-11-27 21:32:10,627 [INFO] tensorflow: global_step/sec: 14.3653 2021-11-27 21:32:10,694 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 24.493 INFO:tensorflow:global_step/sec: 14.5623 2021-11-27 21:32:10,764 [INFO] tensorflow: global_step/sec: 14.5623 INFO:tensorflow:global_step/sec: 14.6957 2021-11-27 21:32:10,900 [INFO] tensorflow: global_step/sec: 14.6957 INFO:tensorflow:global_step/sec: 14.3693 2021-11-27 21:32:11,039 [INFO] tensorflow: global_step/sec: 14.3693 INFO:tensorflow:global_step/sec: 13.984 2021-11-27 21:32:11,182 [INFO] tensorflow: global_step/sec: 13.984 INFO:tensorflow:global_step/sec: 14.5958 2021-11-27 21:32:11,319 [INFO] tensorflow: global_step/sec: 14.5958 INFO:tensorflow:global_step/sec: 15.2889 2021-11-27 21:32:11,450 [INFO] tensorflow: global_step/sec: 15.2889 INFO:tensorflow:global_step/sec: 13.7548 2021-11-27 21:32:11,596 [INFO] tensorflow: global_step/sec: 13.7548 2021-11-27 21:32:11,597 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 21/120: loss: 0.00229 learning rate: 0.00050 Time taken: 0:00:01.522311 ETA: 0:02:30.708833 INFO:tensorflow:global_step/sec: 14.492 2021-11-27 21:32:11,734 [INFO] tensorflow: global_step/sec: 14.492 INFO:tensorflow:global_step/sec: 15.1391 2021-11-27 21:32:11,866 [INFO] tensorflow: global_step/sec: 15.1391 INFO:tensorflow:global_step/sec: 13.8737 2021-11-27 21:32:12,010 [INFO] tensorflow: global_step/sec: 13.8737 INFO:tensorflow:global_step/sec: 13.928 2021-11-27 21:32:12,154 [INFO] tensorflow: global_step/sec: 13.928 INFO:tensorflow:global_step/sec: 14.206 2021-11-27 21:32:12,294 [INFO] tensorflow: global_step/sec: 14.206 INFO:tensorflow:global_step/sec: 14.4087 2021-11-27 21:32:12,433 [INFO] tensorflow: global_step/sec: 14.4087 2021-11-27 21:32:12,434 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.502 INFO:tensorflow:global_step/sec: 14.5344 2021-11-27 21:32:12,571 [INFO] tensorflow: global_step/sec: 14.5344 INFO:tensorflow:global_step/sec: 14.5272 2021-11-27 21:32:12,708 [INFO] tensorflow: global_step/sec: 14.5272 INFO:tensorflow:global_step/sec: 14.8935 2021-11-27 21:32:12,843 [INFO] tensorflow: global_step/sec: 14.8935 INFO:tensorflow:global_step/sec: 14.9485 2021-11-27 21:32:12,976 [INFO] tensorflow: global_step/sec: 14.9485 INFO:tensorflow:global_step/sec: 13.8758 2021-11-27 21:32:13,121 [INFO] tensorflow: global_step/sec: 13.8758 2021-11-27 21:32:13,122 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 22/120: loss: 0.00173 learning rate: 0.00050 Time taken: 0:00:01.525494 ETA: 0:02:29.498375 INFO:tensorflow:global_step/sec: 14.3331 2021-11-27 21:32:13,260 [INFO] tensorflow: global_step/sec: 14.3331 INFO:tensorflow:global_step/sec: 14.1705 2021-11-27 21:32:13,401 [INFO] tensorflow: global_step/sec: 14.1705 INFO:tensorflow:global_step/sec: 14.2864 2021-11-27 21:32:13,541 [INFO] tensorflow: global_step/sec: 14.2864 INFO:tensorflow:global_step/sec: 14.1544 2021-11-27 21:32:13,683 [INFO] tensorflow: global_step/sec: 14.1544 INFO:tensorflow:global_step/sec: 13.8234 2021-11-27 21:32:13,827 [INFO] tensorflow: global_step/sec: 13.8234 INFO:tensorflow:global_step/sec: 14.503 2021-11-27 21:32:13,965 [INFO] tensorflow: global_step/sec: 14.503 INFO:tensorflow:global_step/sec: 14.7921 2021-11-27 21:32:14,100 [INFO] tensorflow: global_step/sec: 14.7921 2021-11-27 21:32:14,170 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.592 INFO:tensorflow:global_step/sec: 14.3793 2021-11-27 21:32:14,239 [INFO] tensorflow: global_step/sec: 14.3793 INFO:tensorflow:global_step/sec: 14.3092 2021-11-27 21:32:14,379 [INFO] tensorflow: global_step/sec: 14.3092 INFO:tensorflow:global_step/sec: 14.3303 2021-11-27 21:32:14,519 [INFO] tensorflow: global_step/sec: 14.3303 INFO:tensorflow:global_step/sec: 13.5587 2021-11-27 21:32:14,666 [INFO] tensorflow: global_step/sec: 13.5587 2021-11-27 21:32:14,667 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 23/120: loss: 0.00144 learning rate: 0.00050 Time taken: 0:00:01.541562 ETA: 0:02:29.531499 INFO:tensorflow:global_step/sec: 13.9933 2021-11-27 21:32:14,809 [INFO] tensorflow: global_step/sec: 13.9933 INFO:tensorflow:global_step/sec: 13.9764 2021-11-27 21:32:14,952 [INFO] tensorflow: global_step/sec: 13.9764 INFO:tensorflow:global_step/sec: 14.0544 2021-11-27 21:32:15,095 [INFO] tensorflow: global_step/sec: 14.0544 INFO:tensorflow:epoch = 23.31818181818182, learning_rate = 0.00049999997, loss = 0.0017488953, step = 513 (5.090 sec) 2021-11-27 21:32:15,163 [INFO] tensorflow: epoch = 23.31818181818182, learning_rate = 0.00049999997, loss = 0.0017488953, step = 513 (5.090 sec) INFO:tensorflow:global_step/sec: 14.6985 2021-11-27 21:32:15,231 [INFO] tensorflow: global_step/sec: 14.6985 INFO:tensorflow:global_step/sec: 14.7618 2021-11-27 21:32:15,366 [INFO] tensorflow: global_step/sec: 14.7618 INFO:tensorflow:global_step/sec: 14.8918 2021-11-27 21:32:15,500 [INFO] tensorflow: global_step/sec: 14.8918 INFO:tensorflow:global_step/sec: 15.0697 2021-11-27 21:32:15,633 [INFO] tensorflow: global_step/sec: 15.0697 INFO:tensorflow:global_step/sec: 14.4424 2021-11-27 21:32:15,772 [INFO] tensorflow: global_step/sec: 14.4424 INFO:tensorflow:global_step/sec: 14.2045 2021-11-27 21:32:15,912 [INFO] tensorflow: global_step/sec: 14.2045 2021-11-27 21:32:15,913 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.385 INFO:tensorflow:global_step/sec: 14.202 2021-11-27 21:32:16,053 [INFO] tensorflow: global_step/sec: 14.202 INFO:tensorflow:global_step/sec: 12.8793 2021-11-27 21:32:16,209 [INFO] tensorflow: global_step/sec: 12.8793 2021-11-27 21:32:16,209 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 24/120: loss: 0.00166 learning rate: 0.00050 Time taken: 0:00:01.541709 ETA: 0:02:28.004082 INFO:tensorflow:global_step/sec: 14.3241 2021-11-27 21:32:16,348 [INFO] tensorflow: global_step/sec: 14.3241 INFO:tensorflow:global_step/sec: 14.7039 2021-11-27 21:32:16,484 [INFO] tensorflow: global_step/sec: 14.7039 INFO:tensorflow:global_step/sec: 14.7066 2021-11-27 21:32:16,620 [INFO] tensorflow: global_step/sec: 14.7066 INFO:tensorflow:global_step/sec: 14.8244 2021-11-27 21:32:16,755 [INFO] tensorflow: global_step/sec: 14.8244 INFO:tensorflow:global_step/sec: 14.7138 2021-11-27 21:32:16,891 [INFO] tensorflow: global_step/sec: 14.7138 INFO:tensorflow:global_step/sec: 14.6269 2021-11-27 21:32:17,028 [INFO] tensorflow: global_step/sec: 14.6269 INFO:tensorflow:global_step/sec: 14.7153 2021-11-27 21:32:17,164 [INFO] tensorflow: global_step/sec: 14.7153 INFO:tensorflow:global_step/sec: 14.2557 2021-11-27 21:32:17,304 [INFO] tensorflow: global_step/sec: 14.2557 INFO:tensorflow:global_step/sec: 14.6244 2021-11-27 21:32:17,441 [INFO] tensorflow: global_step/sec: 14.6244 INFO:tensorflow:global_step/sec: 14.3159 2021-11-27 21:32:17,580 [INFO] tensorflow: global_step/sec: 14.3159 2021-11-27 21:32:17,663 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.162 INFO:tensorflow:global_step/sec: 13.1499 2021-11-27 21:32:17,733 [INFO] tensorflow: global_step/sec: 13.1499 2021-11-27 21:32:17,734 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 25/120: loss: 0.00148 learning rate: 0.00050 Time taken: 0:00:01.523090 ETA: 0:02:24.693562 INFO:tensorflow:global_step/sec: 14.4335 2021-11-27 21:32:17,871 [INFO] tensorflow: global_step/sec: 14.4335 INFO:tensorflow:global_step/sec: 15.031 2021-11-27 21:32:18,004 [INFO] tensorflow: global_step/sec: 15.031 INFO:tensorflow:global_step/sec: 14.7769 2021-11-27 21:32:18,140 [INFO] tensorflow: global_step/sec: 14.7769 INFO:tensorflow:global_step/sec: 14.1323 2021-11-27 21:32:18,281 [INFO] tensorflow: global_step/sec: 14.1323 INFO:tensorflow:global_step/sec: 14.3947 2021-11-27 21:32:18,420 [INFO] tensorflow: global_step/sec: 14.3947 INFO:tensorflow:global_step/sec: 14.551 2021-11-27 21:32:18,557 [INFO] tensorflow: global_step/sec: 14.551 INFO:tensorflow:global_step/sec: 14.9708 2021-11-27 21:32:18,691 [INFO] tensorflow: global_step/sec: 14.9708 INFO:tensorflow:global_step/sec: 14.3743 2021-11-27 21:32:18,830 [INFO] tensorflow: global_step/sec: 14.3743 INFO:tensorflow:global_step/sec: 14.4519 2021-11-27 21:32:18,969 [INFO] tensorflow: global_step/sec: 14.4519 INFO:tensorflow:global_step/sec: 14.5481 2021-11-27 21:32:19,106 [INFO] tensorflow: global_step/sec: 14.5481 INFO:tensorflow:global_step/sec: 13.6372 2021-11-27 21:32:19,253 [INFO] tensorflow: global_step/sec: 13.6372 2021-11-27 21:32:19,253 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 26/120: loss: 0.00157 learning rate: 0.00050 Time taken: 0:00:01.516972 ETA: 0:02:22.595352 INFO:tensorflow:global_step/sec: 14.6464 2021-11-27 21:32:19,389 [INFO] tensorflow: global_step/sec: 14.6464 2021-11-27 21:32:19,390 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.953 INFO:tensorflow:global_step/sec: 14.2493 2021-11-27 21:32:19,530 [INFO] tensorflow: global_step/sec: 14.2493 INFO:tensorflow:global_step/sec: 14.8253 2021-11-27 21:32:19,665 [INFO] tensorflow: global_step/sec: 14.8253 INFO:tensorflow:global_step/sec: 14.0242 2021-11-27 21:32:19,807 [INFO] tensorflow: global_step/sec: 14.0242 INFO:tensorflow:global_step/sec: 14.6664 2021-11-27 21:32:19,944 [INFO] tensorflow: global_step/sec: 14.6664 INFO:tensorflow:global_step/sec: 14.3821 2021-11-27 21:32:20,083 [INFO] tensorflow: global_step/sec: 14.3821 INFO:tensorflow:global_step/sec: 14.4664 2021-11-27 21:32:20,221 [INFO] tensorflow: global_step/sec: 14.4664 INFO:tensorflow:epoch = 26.681818181818183, learning_rate = 0.00049999997, loss = 0.0014593615, step = 587 (5.125 sec) 2021-11-27 21:32:20,288 [INFO] tensorflow: epoch = 26.681818181818183, learning_rate = 0.00049999997, loss = 0.0014593615, step = 587 (5.125 sec) INFO:tensorflow:global_step/sec: 14.8458 2021-11-27 21:32:20,356 [INFO] tensorflow: global_step/sec: 14.8458 INFO:tensorflow:global_step/sec: 14.5087 2021-11-27 21:32:20,493 [INFO] tensorflow: global_step/sec: 14.5087 INFO:tensorflow:global_step/sec: 14.4732 2021-11-27 21:32:20,632 [INFO] tensorflow: global_step/sec: 14.4732 INFO:tensorflow:global_step/sec: 13.9724 2021-11-27 21:32:20,775 [INFO] tensorflow: global_step/sec: 13.9724 2021-11-27 21:32:20,776 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 27/120: loss: 0.00143 learning rate: 0.00050 Time taken: 0:00:01.524051 ETA: 0:02:21.736716 INFO:tensorflow:global_step/sec: 14.4074 2021-11-27 21:32:20,914 [INFO] tensorflow: global_step/sec: 14.4074 INFO:tensorflow:global_step/sec: 14.6238 2021-11-27 21:32:21,050 [INFO] tensorflow: global_step/sec: 14.6238 2021-11-27 21:32:21,116 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.933 INFO:tensorflow:global_step/sec: 14.7618 2021-11-27 21:32:21,186 [INFO] tensorflow: global_step/sec: 14.7618 INFO:tensorflow:global_step/sec: 14.0194 2021-11-27 21:32:21,328 [INFO] tensorflow: global_step/sec: 14.0194 INFO:tensorflow:global_step/sec: 14.3016 2021-11-27 21:32:21,468 [INFO] tensorflow: global_step/sec: 14.3016 INFO:tensorflow:global_step/sec: 14.8373 2021-11-27 21:32:21,603 [INFO] tensorflow: global_step/sec: 14.8373 INFO:tensorflow:global_step/sec: 14.8671 2021-11-27 21:32:21,738 [INFO] tensorflow: global_step/sec: 14.8671 INFO:tensorflow:global_step/sec: 13.9839 2021-11-27 21:32:21,881 [INFO] tensorflow: global_step/sec: 13.9839 INFO:tensorflow:global_step/sec: 14.1962 2021-11-27 21:32:22,021 [INFO] tensorflow: global_step/sec: 14.1962 INFO:tensorflow:global_step/sec: 14.8889 2021-11-27 21:32:22,156 [INFO] tensorflow: global_step/sec: 14.8889 INFO:tensorflow:global_step/sec: 13.3134 2021-11-27 21:32:22,306 [INFO] tensorflow: global_step/sec: 13.3134 2021-11-27 21:32:22,307 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 28/120: loss: 0.00134 learning rate: 0.00050 Time taken: 0:00:01.526674 ETA: 0:02:20.454011 INFO:tensorflow:global_step/sec: 14.4676 2021-11-27 21:32:22,444 [INFO] tensorflow: global_step/sec: 14.4676 INFO:tensorflow:global_step/sec: 14.7996 2021-11-27 21:32:22,579 [INFO] tensorflow: global_step/sec: 14.7996 INFO:tensorflow:global_step/sec: 15.207 2021-11-27 21:32:22,711 [INFO] tensorflow: global_step/sec: 15.207 INFO:tensorflow:global_step/sec: 14.943 2021-11-27 21:32:22,845 [INFO] tensorflow: global_step/sec: 14.943 2021-11-27 21:32:22,845 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.845 INFO:tensorflow:global_step/sec: 14.829 2021-11-27 21:32:22,980 [INFO] tensorflow: global_step/sec: 14.829 INFO:tensorflow:global_step/sec: 15.0299 2021-11-27 21:32:23,113 [INFO] tensorflow: global_step/sec: 15.0299 INFO:tensorflow:global_step/sec: 14.1244 2021-11-27 21:32:23,254 [INFO] tensorflow: global_step/sec: 14.1244 INFO:tensorflow:global_step/sec: 14.6959 2021-11-27 21:32:23,390 [INFO] tensorflow: global_step/sec: 14.6959 INFO:tensorflow:global_step/sec: 14.0629 2021-11-27 21:32:23,533 [INFO] tensorflow: global_step/sec: 14.0629 INFO:tensorflow:global_step/sec: 13.7648 2021-11-27 21:32:23,678 [INFO] tensorflow: global_step/sec: 13.7648 INFO:tensorflow:global_step/sec: 13.2653 2021-11-27 21:32:23,829 [INFO] tensorflow: global_step/sec: 13.2653 2021-11-27 21:32:23,829 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 29/120: loss: 0.00164 learning rate: 0.00050 Time taken: 0:00:01.520847 ETA: 0:02:18.397041 INFO:tensorflow:global_step/sec: 15.3221 2021-11-27 21:32:23,959 [INFO] tensorflow: global_step/sec: 15.3221 INFO:tensorflow:global_step/sec: 14.2741 2021-11-27 21:32:24,099 [INFO] tensorflow: global_step/sec: 14.2741 INFO:tensorflow:global_step/sec: 14.2907 2021-11-27 21:32:24,239 [INFO] tensorflow: global_step/sec: 14.2907 INFO:tensorflow:global_step/sec: 14.322 2021-11-27 21:32:24,379 [INFO] tensorflow: global_step/sec: 14.322 INFO:tensorflow:global_step/sec: 14.2586 2021-11-27 21:32:24,519 [INFO] tensorflow: global_step/sec: 14.2586 2021-11-27 21:32:24,586 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.456 INFO:tensorflow:global_step/sec: 14.6974 2021-11-27 21:32:24,655 [INFO] tensorflow: global_step/sec: 14.6974 INFO:tensorflow:global_step/sec: 14.0924 2021-11-27 21:32:24,797 [INFO] tensorflow: global_step/sec: 14.0924 INFO:tensorflow:global_step/sec: 13.8409 2021-11-27 21:32:24,942 [INFO] tensorflow: global_step/sec: 13.8409 INFO:tensorflow:global_step/sec: 13.9689 2021-11-27 21:32:25,085 [INFO] tensorflow: global_step/sec: 13.9689 INFO:tensorflow:global_step/sec: 14.7609 2021-11-27 21:32:25,220 [INFO] tensorflow: global_step/sec: 14.7609 INFO:tensorflow:Saving checkpoints for step-660. 2021-11-27 21:32:25,291 [INFO] tensorflow: Saving checkpoints for step-660. 2021-11-27 21:32:27,694 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 9464/9464 [00:00<00:00, 25950.90it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 8228/8228 [00:00<00:00, 28442.31it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 2382/2382 [00:00<00:00, 26669.74it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 11667/11667 [00:00<00:00, 28879.89it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 11897/11897 [00:00<00:00, 30530.80it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 4009/4009 [00:00<00:00, 24358.89it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 9895/9895 [00:00<00:00, 38853.75it/s] Epoch 30/120 ========================= Validation cost: 0.001164 Mean average_precision (in %): 4.2231 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 0.657461 floor 0 palette 0.00523879 pillar 1.31196 pushcart 0 rackframe 6.2239 rackshelf 9.30193 wall 20.5074 Median Inference Time: 0.007165 INFO:tensorflow:epoch = 30.0, learning_rate = 0.00049999997, loss = 0.0014004486, step = 660 (18.097 sec) 2021-11-27 21:32:38,384 [INFO] tensorflow: epoch = 30.0, learning_rate = 0.00049999997, loss = 0.0014004486, step = 660 (18.097 sec) INFO:tensorflow:global_step/sec: 0.151918 2021-11-27 21:32:38,385 [INFO] tensorflow: global_step/sec: 0.151918 2021-11-27 21:32:38,386 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 30/120: loss: 0.00140 learning rate: 0.00050 Time taken: 0:00:14.554359 ETA: 0:21:49.892349 INFO:tensorflow:global_step/sec: 14.4657 2021-11-27 21:32:38,524 [INFO] tensorflow: global_step/sec: 14.4657 INFO:tensorflow:global_step/sec: 14.4099 2021-11-27 21:32:38,663 [INFO] tensorflow: global_step/sec: 14.4099 INFO:tensorflow:global_step/sec: 14.5693 2021-11-27 21:32:38,800 [INFO] tensorflow: global_step/sec: 14.5693 INFO:tensorflow:global_step/sec: 14.0068 2021-11-27 21:32:38,943 [INFO] tensorflow: global_step/sec: 14.0068 INFO:tensorflow:global_step/sec: 14.1569 2021-11-27 21:32:39,084 [INFO] tensorflow: global_step/sec: 14.1569 INFO:tensorflow:global_step/sec: 14.267 2021-11-27 21:32:39,224 [INFO] tensorflow: global_step/sec: 14.267 INFO:tensorflow:global_step/sec: 14.4686 2021-11-27 21:32:39,362 [INFO] tensorflow: global_step/sec: 14.4686 2021-11-27 21:32:39,363 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 6.767 INFO:tensorflow:global_step/sec: 14.7445 2021-11-27 21:32:39,498 [INFO] tensorflow: global_step/sec: 14.7445 INFO:tensorflow:global_step/sec: 14.5212 2021-11-27 21:32:39,636 [INFO] tensorflow: global_step/sec: 14.5212 INFO:tensorflow:global_step/sec: 14.4805 2021-11-27 21:32:39,774 [INFO] tensorflow: global_step/sec: 14.4805 INFO:tensorflow:global_step/sec: 14.3056 2021-11-27 21:32:39,914 [INFO] tensorflow: global_step/sec: 14.3056 2021-11-27 21:32:39,915 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 31/120: loss: 0.00156 learning rate: 0.00050 Time taken: 0:00:01.531411 ETA: 0:02:16.295594 INFO:tensorflow:global_step/sec: 14.1456 2021-11-27 21:32:40,055 [INFO] tensorflow: global_step/sec: 14.1456 INFO:tensorflow:global_step/sec: 15.1835 2021-11-27 21:32:40,187 [INFO] tensorflow: global_step/sec: 15.1835 INFO:tensorflow:global_step/sec: 14.5779 2021-11-27 21:32:40,324 [INFO] tensorflow: global_step/sec: 14.5779 INFO:tensorflow:global_step/sec: 15.3496 2021-11-27 21:32:40,454 [INFO] tensorflow: global_step/sec: 15.3496 INFO:tensorflow:global_step/sec: 15.2895 2021-11-27 21:32:40,585 [INFO] tensorflow: global_step/sec: 15.2895 INFO:tensorflow:global_step/sec: 14.6721 2021-11-27 21:32:40,721 [INFO] tensorflow: global_step/sec: 14.6721 INFO:tensorflow:global_step/sec: 14.1121 2021-11-27 21:32:40,863 [INFO] tensorflow: global_step/sec: 14.1121 INFO:tensorflow:global_step/sec: 14.6013 2021-11-27 21:32:41,000 [INFO] tensorflow: global_step/sec: 14.6013 2021-11-27 21:32:41,068 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.664 INFO:tensorflow:global_step/sec: 14.5962 2021-11-27 21:32:41,137 [INFO] tensorflow: global_step/sec: 14.5962 INFO:tensorflow:global_step/sec: 14.263 2021-11-27 21:32:41,277 [INFO] tensorflow: global_step/sec: 14.263 INFO:tensorflow:global_step/sec: 14.2234 2021-11-27 21:32:41,418 [INFO] tensorflow: global_step/sec: 14.2234 2021-11-27 21:32:41,419 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 32/120: loss: 0.00154 learning rate: 0.00050 Time taken: 0:00:01.503738 ETA: 0:02:12.328959 INFO:tensorflow:global_step/sec: 15.118 2021-11-27 21:32:41,550 [INFO] tensorflow: global_step/sec: 15.118 INFO:tensorflow:global_step/sec: 14.6076 2021-11-27 21:32:41,687 [INFO] tensorflow: global_step/sec: 14.6076 INFO:tensorflow:global_step/sec: 14.7102 2021-11-27 21:32:41,823 [INFO] tensorflow: global_step/sec: 14.7102 INFO:tensorflow:global_step/sec: 14.309 2021-11-27 21:32:41,963 [INFO] tensorflow: global_step/sec: 14.309 INFO:tensorflow:global_step/sec: 14.4039 2021-11-27 21:32:42,102 [INFO] tensorflow: global_step/sec: 14.4039 INFO:tensorflow:global_step/sec: 14.7045 2021-11-27 21:32:42,238 [INFO] tensorflow: global_step/sec: 14.7045 INFO:tensorflow:global_step/sec: 14.5524 2021-11-27 21:32:42,375 [INFO] tensorflow: global_step/sec: 14.5524 INFO:tensorflow:global_step/sec: 14.9722 2021-11-27 21:32:42,509 [INFO] tensorflow: global_step/sec: 14.9722 INFO:tensorflow:global_step/sec: 14.4851 2021-11-27 21:32:42,647 [INFO] tensorflow: global_step/sec: 14.4851 INFO:tensorflow:global_step/sec: 15.1488 2021-11-27 21:32:42,779 [INFO] tensorflow: global_step/sec: 15.1488 2021-11-27 21:32:42,780 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.443 INFO:tensorflow:global_step/sec: 13.2843 2021-11-27 21:32:42,929 [INFO] tensorflow: global_step/sec: 13.2843 2021-11-27 21:32:42,930 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 33/120: loss: 0.00141 learning rate: 0.00050 Time taken: 0:00:01.502839 ETA: 0:02:10.746980 INFO:tensorflow:global_step/sec: 14.3123 2021-11-27 21:32:43,069 [INFO] tensorflow: global_step/sec: 14.3123 INFO:tensorflow:global_step/sec: 14.4227 2021-11-27 21:32:43,208 [INFO] tensorflow: global_step/sec: 14.4227 INFO:tensorflow:global_step/sec: 14.7635 2021-11-27 21:32:43,343 [INFO] tensorflow: global_step/sec: 14.7635 INFO:tensorflow:epoch = 33.36363636363637, learning_rate = 0.00049999997, loss = 0.0013472163, step = 734 (5.094 sec) 2021-11-27 21:32:43,478 [INFO] tensorflow: epoch = 33.36363636363637, learning_rate = 0.00049999997, loss = 0.0013472163, step = 734 (5.094 sec) INFO:tensorflow:global_step/sec: 14.6789 2021-11-27 21:32:43,479 [INFO] tensorflow: global_step/sec: 14.6789 INFO:tensorflow:global_step/sec: 14.5483 2021-11-27 21:32:43,617 [INFO] tensorflow: global_step/sec: 14.5483 INFO:tensorflow:global_step/sec: 13.9031 2021-11-27 21:32:43,761 [INFO] tensorflow: global_step/sec: 13.9031 INFO:tensorflow:global_step/sec: 14.922 2021-11-27 21:32:43,895 [INFO] tensorflow: global_step/sec: 14.922 INFO:tensorflow:global_step/sec: 14.8578 2021-11-27 21:32:44,029 [INFO] tensorflow: global_step/sec: 14.8578 INFO:tensorflow:global_step/sec: 14.8988 2021-11-27 21:32:44,164 [INFO] tensorflow: global_step/sec: 14.8988 INFO:tensorflow:global_step/sec: 14.5407 2021-11-27 21:32:44,301 [INFO] tensorflow: global_step/sec: 14.5407 INFO:tensorflow:global_step/sec: 14.3613 2021-11-27 21:32:44,440 [INFO] tensorflow: global_step/sec: 14.3613 2021-11-27 21:32:44,441 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 34/120: loss: 0.00140 learning rate: 0.00050 Time taken: 0:00:01.515900 ETA: 0:02:10.367371 2021-11-27 21:32:44,504 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.017 INFO:tensorflow:global_step/sec: 15.458 2021-11-27 21:32:44,570 [INFO] tensorflow: global_step/sec: 15.458 INFO:tensorflow:global_step/sec: 14.9633 2021-11-27 21:32:44,703 [INFO] tensorflow: global_step/sec: 14.9633 INFO:tensorflow:global_step/sec: 14.3656 2021-11-27 21:32:44,843 [INFO] tensorflow: global_step/sec: 14.3656 INFO:tensorflow:global_step/sec: 14.0648 2021-11-27 21:32:44,985 [INFO] tensorflow: global_step/sec: 14.0648 INFO:tensorflow:global_step/sec: 14.613 2021-11-27 21:32:45,122 [INFO] tensorflow: global_step/sec: 14.613 INFO:tensorflow:global_step/sec: 13.8544 2021-11-27 21:32:45,266 [INFO] tensorflow: global_step/sec: 13.8544 INFO:tensorflow:global_step/sec: 14.6963 2021-11-27 21:32:45,402 [INFO] tensorflow: global_step/sec: 14.6963 INFO:tensorflow:global_step/sec: 14.4442 2021-11-27 21:32:45,541 [INFO] tensorflow: global_step/sec: 14.4442 INFO:tensorflow:global_step/sec: 14.3702 2021-11-27 21:32:45,680 [INFO] tensorflow: global_step/sec: 14.3702 INFO:tensorflow:global_step/sec: 14.3116 2021-11-27 21:32:45,820 [INFO] tensorflow: global_step/sec: 14.3116 INFO:tensorflow:global_step/sec: 13.2295 2021-11-27 21:32:45,971 [INFO] tensorflow: global_step/sec: 13.2295 2021-11-27 21:32:45,972 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 35/120: loss: 0.00158 learning rate: 0.00050 Time taken: 0:00:01.526463 ETA: 0:02:09.749378 INFO:tensorflow:global_step/sec: 14.85 2021-11-27 21:32:46,106 [INFO] tensorflow: global_step/sec: 14.85 INFO:tensorflow:global_step/sec: 15.0526 2021-11-27 21:32:46,238 [INFO] tensorflow: global_step/sec: 15.0526 2021-11-27 21:32:46,239 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.636 INFO:tensorflow:global_step/sec: 14.4186 2021-11-27 21:32:46,377 [INFO] tensorflow: global_step/sec: 14.4186 INFO:tensorflow:global_step/sec: 14.1258 2021-11-27 21:32:46,519 [INFO] tensorflow: global_step/sec: 14.1258 INFO:tensorflow:global_step/sec: 14.3816 2021-11-27 21:32:46,658 [INFO] tensorflow: global_step/sec: 14.3816 INFO:tensorflow:global_step/sec: 14.8252 2021-11-27 21:32:46,793 [INFO] tensorflow: global_step/sec: 14.8252 INFO:tensorflow:global_step/sec: 15.1449 2021-11-27 21:32:46,925 [INFO] tensorflow: global_step/sec: 15.1449 INFO:tensorflow:global_step/sec: 14.7781 2021-11-27 21:32:47,060 [INFO] tensorflow: global_step/sec: 14.7781 INFO:tensorflow:global_step/sec: 14.1028 2021-11-27 21:32:47,202 [INFO] tensorflow: global_step/sec: 14.1028 INFO:tensorflow:global_step/sec: 14.7033 2021-11-27 21:32:47,338 [INFO] tensorflow: global_step/sec: 14.7033 INFO:tensorflow:global_step/sec: 14.0873 2021-11-27 21:32:47,480 [INFO] tensorflow: global_step/sec: 14.0873 2021-11-27 21:32:47,481 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 36/120: loss: 0.00146 learning rate: 0.00050 Time taken: 0:00:01.506683 ETA: 0:02:06.561341 INFO:tensorflow:global_step/sec: 14.5565 2021-11-27 21:32:47,617 [INFO] tensorflow: global_step/sec: 14.5565 INFO:tensorflow:global_step/sec: 14.7497 2021-11-27 21:32:47,753 [INFO] tensorflow: global_step/sec: 14.7497 INFO:tensorflow:global_step/sec: 14.8356 2021-11-27 21:32:47,888 [INFO] tensorflow: global_step/sec: 14.8356 2021-11-27 21:32:47,953 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.350 INFO:tensorflow:global_step/sec: 14.6259 2021-11-27 21:32:48,024 [INFO] tensorflow: global_step/sec: 14.6259 INFO:tensorflow:global_step/sec: 14.6353 2021-11-27 21:32:48,161 [INFO] tensorflow: global_step/sec: 14.6353 INFO:tensorflow:global_step/sec: 14.5341 2021-11-27 21:32:48,299 [INFO] tensorflow: global_step/sec: 14.5341 INFO:tensorflow:global_step/sec: 14.7215 2021-11-27 21:32:48,434 [INFO] tensorflow: global_step/sec: 14.7215 INFO:tensorflow:epoch = 36.72727272727273, learning_rate = 0.00049999997, loss = 0.0014747924, step = 808 (5.095 sec) 2021-11-27 21:32:48,573 [INFO] tensorflow: epoch = 36.72727272727273, learning_rate = 0.00049999997, loss = 0.0014747924, step = 808 (5.095 sec) INFO:tensorflow:global_step/sec: 14.3285 2021-11-27 21:32:48,574 [INFO] tensorflow: global_step/sec: 14.3285 INFO:tensorflow:global_step/sec: 14.5799 2021-11-27 21:32:48,711 [INFO] tensorflow: global_step/sec: 14.5799 INFO:tensorflow:global_step/sec: 14.1664 2021-11-27 21:32:48,852 [INFO] tensorflow: global_step/sec: 14.1664 INFO:tensorflow:global_step/sec: 13.7631 2021-11-27 21:32:48,998 [INFO] tensorflow: global_step/sec: 13.7631 2021-11-27 21:32:48,999 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 37/120: loss: 0.00185 learning rate: 0.00050 Time taken: 0:00:01.516000 ETA: 0:02:05.827963 INFO:tensorflow:global_step/sec: 14.835 2021-11-27 21:32:49,133 [INFO] tensorflow: global_step/sec: 14.835 INFO:tensorflow:global_step/sec: 14.273 2021-11-27 21:32:49,273 [INFO] tensorflow: global_step/sec: 14.273 INFO:tensorflow:global_step/sec: 14.5869 2021-11-27 21:32:49,410 [INFO] tensorflow: global_step/sec: 14.5869 INFO:tensorflow:global_step/sec: 14.4334 2021-11-27 21:32:49,548 [INFO] tensorflow: global_step/sec: 14.4334 INFO:tensorflow:global_step/sec: 14.936 2021-11-27 21:32:49,682 [INFO] tensorflow: global_step/sec: 14.936 2021-11-27 21:32:49,683 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.834 INFO:tensorflow:global_step/sec: 14.3397 2021-11-27 21:32:49,822 [INFO] tensorflow: global_step/sec: 14.3397 INFO:tensorflow:global_step/sec: 14.25 2021-11-27 21:32:49,962 [INFO] tensorflow: global_step/sec: 14.25 INFO:tensorflow:global_step/sec: 13.8079 2021-11-27 21:32:50,107 [INFO] tensorflow: global_step/sec: 13.8079 INFO:tensorflow:global_step/sec: 14.0843 2021-11-27 21:32:50,249 [INFO] tensorflow: global_step/sec: 14.0843 INFO:tensorflow:global_step/sec: 14.2765 2021-11-27 21:32:50,389 [INFO] tensorflow: global_step/sec: 14.2765 INFO:tensorflow:global_step/sec: 13.5643 2021-11-27 21:32:50,536 [INFO] tensorflow: global_step/sec: 13.5643 2021-11-27 21:32:50,538 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 38/120: loss: 0.00147 learning rate: 0.00050 Time taken: 0:00:01.539168 ETA: 0:02:06.211747 INFO:tensorflow:global_step/sec: 14.3483 2021-11-27 21:32:50,676 [INFO] tensorflow: global_step/sec: 14.3483 INFO:tensorflow:global_step/sec: 14.4771 2021-11-27 21:32:50,814 [INFO] tensorflow: global_step/sec: 14.4771 INFO:tensorflow:global_step/sec: 14.7469 2021-11-27 21:32:50,950 [INFO] tensorflow: global_step/sec: 14.7469 INFO:tensorflow:global_step/sec: 14.0668 2021-11-27 21:32:51,092 [INFO] tensorflow: global_step/sec: 14.0668 INFO:tensorflow:global_step/sec: 14.661 2021-11-27 21:32:51,228 [INFO] tensorflow: global_step/sec: 14.661 INFO:tensorflow:global_step/sec: 14.2397 2021-11-27 21:32:51,369 [INFO] tensorflow: global_step/sec: 14.2397 2021-11-27 21:32:51,438 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 56.994 INFO:tensorflow:global_step/sec: 14.2795 2021-11-27 21:32:51,509 [INFO] tensorflow: global_step/sec: 14.2795 INFO:tensorflow:global_step/sec: 13.9655 2021-11-27 21:32:51,652 [INFO] tensorflow: global_step/sec: 13.9655 INFO:tensorflow:global_step/sec: 13.8627 2021-11-27 21:32:51,796 [INFO] tensorflow: global_step/sec: 13.8627 INFO:tensorflow:global_step/sec: 14.2911 2021-11-27 21:32:51,936 [INFO] tensorflow: global_step/sec: 14.2911 INFO:tensorflow:global_step/sec: 13.1637 2021-11-27 21:32:52,088 [INFO] tensorflow: global_step/sec: 13.1637 2021-11-27 21:32:52,090 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 39/120: loss: 0.00161 learning rate: 0.00050 Time taken: 0:00:01.547016 ETA: 0:02:05.308288 INFO:tensorflow:global_step/sec: 14.8911 2021-11-27 21:32:52,222 [INFO] tensorflow: global_step/sec: 14.8911 INFO:tensorflow:global_step/sec: 14.5099 2021-11-27 21:32:52,360 [INFO] tensorflow: global_step/sec: 14.5099 INFO:tensorflow:global_step/sec: 13.5787 2021-11-27 21:32:52,508 [INFO] tensorflow: global_step/sec: 13.5787 INFO:tensorflow:global_step/sec: 14.1389 2021-11-27 21:32:52,649 [INFO] tensorflow: global_step/sec: 14.1389 INFO:tensorflow:global_step/sec: 13.9978 2021-11-27 21:32:52,792 [INFO] tensorflow: global_step/sec: 13.9978 INFO:tensorflow:global_step/sec: 14.7987 2021-11-27 21:32:52,927 [INFO] tensorflow: global_step/sec: 14.7987 INFO:tensorflow:global_step/sec: 15.0165 2021-11-27 21:32:53,060 [INFO] tensorflow: global_step/sec: 15.0165 INFO:tensorflow:global_step/sec: 14.6274 2021-11-27 21:32:53,197 [INFO] tensorflow: global_step/sec: 14.6274 2021-11-27 21:32:53,198 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 56.824 INFO:tensorflow:global_step/sec: 14.5524 2021-11-27 21:32:53,334 [INFO] tensorflow: global_step/sec: 14.5524 INFO:tensorflow:global_step/sec: 14.8787 2021-11-27 21:32:53,469 [INFO] tensorflow: global_step/sec: 14.8787 INFO:tensorflow:Saving checkpoints for step-880. 2021-11-27 21:32:53,538 [INFO] tensorflow: Saving checkpoints for step-880. 2021-11-27 21:32:56,039 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 4330/4330 [00:00<00:00, 27824.98it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 9054/9054 [00:00<00:00, 29263.29it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 1661/1661 [00:00<00:00, 25930.76it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 13296/13296 [00:00<00:00, 30918.94it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 8373/8373 [00:00<00:00, 29561.52it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 3676/3676 [00:00<00:00, 24088.14it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 7359/7359 [00:00<00:00, 38038.78it/s] Epoch 40/120 ========================= Validation cost: 0.001069 Mean average_precision (in %): 6.1684 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 2.42723 floor 0 palette 0.0348023 pillar 4.67769 pushcart 0 rackframe 13.4735 rackshelf 15.5739 wall 19.3285 Median Inference Time: 0.007937 INFO:tensorflow:epoch = 40.0, learning_rate = 0.00049999997, loss = 0.0016446046, step = 880 (16.673 sec) 2021-11-27 21:33:05,246 [INFO] tensorflow: epoch = 40.0, learning_rate = 0.00049999997, loss = 0.0016446046, step = 880 (16.673 sec) INFO:tensorflow:global_step/sec: 0.169804 2021-11-27 21:33:05,247 [INFO] tensorflow: global_step/sec: 0.169804 2021-11-27 21:33:05,248 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 40/120: loss: 0.00164 learning rate: 0.00050 Time taken: 0:00:13.158530 ETA: 0:17:32.682362 INFO:tensorflow:global_step/sec: 14.6689 2021-11-27 21:33:05,383 [INFO] tensorflow: global_step/sec: 14.6689 INFO:tensorflow:global_step/sec: 14.1188 2021-11-27 21:33:05,525 [INFO] tensorflow: global_step/sec: 14.1188 INFO:tensorflow:global_step/sec: 14.3951 2021-11-27 21:33:05,664 [INFO] tensorflow: global_step/sec: 14.3951 INFO:tensorflow:global_step/sec: 14.7127 2021-11-27 21:33:05,800 [INFO] tensorflow: global_step/sec: 14.7127 INFO:tensorflow:global_step/sec: 14.3691 2021-11-27 21:33:05,939 [INFO] tensorflow: global_step/sec: 14.3691 INFO:tensorflow:global_step/sec: 14.4377 2021-11-27 21:33:06,078 [INFO] tensorflow: global_step/sec: 14.4377 INFO:tensorflow:global_step/sec: 14.6455 2021-11-27 21:33:06,214 [INFO] tensorflow: global_step/sec: 14.6455 INFO:tensorflow:global_step/sec: 14.9074 2021-11-27 21:33:06,348 [INFO] tensorflow: global_step/sec: 14.9074 INFO:tensorflow:global_step/sec: 15.0927 2021-11-27 21:33:06,481 [INFO] tensorflow: global_step/sec: 15.0927 2021-11-27 21:33:06,551 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 7.489 INFO:tensorflow:global_step/sec: 14.2229 2021-11-27 21:33:06,622 [INFO] tensorflow: global_step/sec: 14.2229 INFO:tensorflow:global_step/sec: 14.0467 2021-11-27 21:33:06,764 [INFO] tensorflow: global_step/sec: 14.0467 2021-11-27 21:33:06,765 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 41/120: loss: 0.00151 learning rate: 0.00050 Time taken: 0:00:01.516923 ETA: 0:01:59.836951 INFO:tensorflow:global_step/sec: 15.0784 2021-11-27 21:33:06,897 [INFO] tensorflow: global_step/sec: 15.0784 INFO:tensorflow:global_step/sec: 13.5394 2021-11-27 21:33:07,044 [INFO] tensorflow: global_step/sec: 13.5394 INFO:tensorflow:global_step/sec: 14.6299 2021-11-27 21:33:07,181 [INFO] tensorflow: global_step/sec: 14.6299 INFO:tensorflow:global_step/sec: 14.3833 2021-11-27 21:33:07,320 [INFO] tensorflow: global_step/sec: 14.3833 INFO:tensorflow:global_step/sec: 15.0823 2021-11-27 21:33:07,453 [INFO] tensorflow: global_step/sec: 15.0823 INFO:tensorflow:global_step/sec: 14.3516 2021-11-27 21:33:07,592 [INFO] tensorflow: global_step/sec: 14.3516 INFO:tensorflow:global_step/sec: 15.2871 2021-11-27 21:33:07,723 [INFO] tensorflow: global_step/sec: 15.2871 INFO:tensorflow:global_step/sec: 14.7135 2021-11-27 21:33:07,859 [INFO] tensorflow: global_step/sec: 14.7135 INFO:tensorflow:global_step/sec: 14.7307 2021-11-27 21:33:07,995 [INFO] tensorflow: global_step/sec: 14.7307 INFO:tensorflow:global_step/sec: 14.8146 2021-11-27 21:33:08,130 [INFO] tensorflow: global_step/sec: 14.8146 INFO:tensorflow:global_step/sec: 14.0035 2021-11-27 21:33:08,272 [INFO] tensorflow: global_step/sec: 14.0035 2021-11-27 21:33:08,274 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 42/120: loss: 0.00125 learning rate: 0.00050 Time taken: 0:00:01.509022 ETA: 0:01:57.703697 2021-11-27 21:33:08,274 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.063 INFO:tensorflow:global_step/sec: 14.2453 2021-11-27 21:33:08,413 [INFO] tensorflow: global_step/sec: 14.2453 INFO:tensorflow:global_step/sec: 14.7175 2021-11-27 21:33:08,549 [INFO] tensorflow: global_step/sec: 14.7175 INFO:tensorflow:global_step/sec: 14.4183 2021-11-27 21:33:08,687 [INFO] tensorflow: global_step/sec: 14.4183 INFO:tensorflow:global_step/sec: 14.4027 2021-11-27 21:33:08,826 [INFO] tensorflow: global_step/sec: 14.4027 INFO:tensorflow:global_step/sec: 14.6654 2021-11-27 21:33:08,963 [INFO] tensorflow: global_step/sec: 14.6654 INFO:tensorflow:global_step/sec: 15.2233 2021-11-27 21:33:09,094 [INFO] tensorflow: global_step/sec: 15.2233 INFO:tensorflow:global_step/sec: 14.8415 2021-11-27 21:33:09,229 [INFO] tensorflow: global_step/sec: 14.8415 INFO:tensorflow:global_step/sec: 15.3095 2021-11-27 21:33:09,359 [INFO] tensorflow: global_step/sec: 15.3095 INFO:tensorflow:global_step/sec: 15.1184 2021-11-27 21:33:09,492 [INFO] tensorflow: global_step/sec: 15.1184 INFO:tensorflow:global_step/sec: 14.5763 2021-11-27 21:33:09,629 [INFO] tensorflow: global_step/sec: 14.5763 INFO:tensorflow:global_step/sec: 13.8235 2021-11-27 21:33:09,774 [INFO] tensorflow: global_step/sec: 13.8235 2021-11-27 21:33:09,775 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 43/120: loss: 0.00168 learning rate: 0.00050 Time taken: 0:00:01.495542 ETA: 0:01:55.156756 INFO:tensorflow:global_step/sec: 14.6323 2021-11-27 21:33:09,910 [INFO] tensorflow: global_step/sec: 14.6323 2021-11-27 21:33:09,979 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.642 INFO:tensorflow:global_step/sec: 14.4616 2021-11-27 21:33:10,048 [INFO] tensorflow: global_step/sec: 14.4616 INFO:tensorflow:global_step/sec: 14.4352 2021-11-27 21:33:10,187 [INFO] tensorflow: global_step/sec: 14.4352 INFO:tensorflow:epoch = 43.36363636363637, learning_rate = 0.00049999997, loss = 0.0011689283, step = 954 (5.074 sec) 2021-11-27 21:33:10,320 [INFO] tensorflow: epoch = 43.36363636363637, learning_rate = 0.00049999997, loss = 0.0011689283, step = 954 (5.074 sec) INFO:tensorflow:global_step/sec: 14.9045 2021-11-27 21:33:10,321 [INFO] tensorflow: global_step/sec: 14.9045 INFO:tensorflow:global_step/sec: 14.8267 2021-11-27 21:33:10,456 [INFO] tensorflow: global_step/sec: 14.8267 INFO:tensorflow:global_step/sec: 14.887 2021-11-27 21:33:10,591 [INFO] tensorflow: global_step/sec: 14.887 INFO:tensorflow:global_step/sec: 14.6449 2021-11-27 21:33:10,727 [INFO] tensorflow: global_step/sec: 14.6449 INFO:tensorflow:global_step/sec: 14.5802 2021-11-27 21:33:10,864 [INFO] tensorflow: global_step/sec: 14.5802 INFO:tensorflow:global_step/sec: 14.649 2021-11-27 21:33:11,001 [INFO] tensorflow: global_step/sec: 14.649 INFO:tensorflow:global_step/sec: 15.0163 2021-11-27 21:33:11,134 [INFO] tensorflow: global_step/sec: 15.0163 INFO:tensorflow:global_step/sec: 13.89 2021-11-27 21:33:11,278 [INFO] tensorflow: global_step/sec: 13.89 2021-11-27 21:33:11,279 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 44/120: loss: 0.00138 learning rate: 0.00050 Time taken: 0:00:01.502695 ETA: 0:01:54.204808 INFO:tensorflow:global_step/sec: 14.5376 2021-11-27 21:33:11,416 [INFO] tensorflow: global_step/sec: 14.5376 INFO:tensorflow:global_step/sec: 14.9906 2021-11-27 21:33:11,549 [INFO] tensorflow: global_step/sec: 14.9906 INFO:tensorflow:global_step/sec: 14.9057 2021-11-27 21:33:11,683 [INFO] tensorflow: global_step/sec: 14.9057 2021-11-27 21:33:11,684 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.680 INFO:tensorflow:global_step/sec: 15.1208 2021-11-27 21:33:11,815 [INFO] tensorflow: global_step/sec: 15.1208 INFO:tensorflow:global_step/sec: 14.828 2021-11-27 21:33:11,950 [INFO] tensorflow: global_step/sec: 14.828 INFO:tensorflow:global_step/sec: 14.5413 2021-11-27 21:33:12,088 [INFO] tensorflow: global_step/sec: 14.5413 INFO:tensorflow:global_step/sec: 14.3019 2021-11-27 21:33:12,228 [INFO] tensorflow: global_step/sec: 14.3019 INFO:tensorflow:global_step/sec: 14.7241 2021-11-27 21:33:12,363 [INFO] tensorflow: global_step/sec: 14.7241 INFO:tensorflow:global_step/sec: 14.7053 2021-11-27 21:33:12,499 [INFO] tensorflow: global_step/sec: 14.7053 INFO:tensorflow:global_step/sec: 14.6245 2021-11-27 21:33:12,636 [INFO] tensorflow: global_step/sec: 14.6245 INFO:tensorflow:global_step/sec: 14.0469 2021-11-27 21:33:12,779 [INFO] tensorflow: global_step/sec: 14.0469 2021-11-27 21:33:12,779 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 45/120: loss: 0.00129 learning rate: 0.00050 Time taken: 0:00:01.500749 ETA: 0:01:52.556165 INFO:tensorflow:global_step/sec: 14.6207 2021-11-27 21:33:12,915 [INFO] tensorflow: global_step/sec: 14.6207 INFO:tensorflow:global_step/sec: 14.2684 2021-11-27 21:33:13,056 [INFO] tensorflow: global_step/sec: 14.2684 INFO:tensorflow:global_step/sec: 14.1099 2021-11-27 21:33:13,197 [INFO] tensorflow: global_step/sec: 14.1099 INFO:tensorflow:global_step/sec: 14.601 2021-11-27 21:33:13,334 [INFO] tensorflow: global_step/sec: 14.601 2021-11-27 21:33:13,402 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.228 INFO:tensorflow:global_step/sec: 14.7052 2021-11-27 21:33:13,470 [INFO] tensorflow: global_step/sec: 14.7052 INFO:tensorflow:global_step/sec: 14.3695 2021-11-27 21:33:13,609 [INFO] tensorflow: global_step/sec: 14.3695 INFO:tensorflow:global_step/sec: 14.5011 2021-11-27 21:33:13,747 [INFO] tensorflow: global_step/sec: 14.5011 INFO:tensorflow:global_step/sec: 14.2794 2021-11-27 21:33:13,887 [INFO] tensorflow: global_step/sec: 14.2794 INFO:tensorflow:global_step/sec: 14.4875 2021-11-27 21:33:14,026 [INFO] tensorflow: global_step/sec: 14.4875 INFO:tensorflow:global_step/sec: 14.6722 2021-11-27 21:33:14,162 [INFO] tensorflow: global_step/sec: 14.6722 INFO:tensorflow:global_step/sec: 14.064 2021-11-27 21:33:14,304 [INFO] tensorflow: global_step/sec: 14.064 2021-11-27 21:33:14,305 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 46/120: loss: 0.00145 learning rate: 0.00050 Time taken: 0:00:01.526521 ETA: 0:01:52.962587 INFO:tensorflow:global_step/sec: 14.5126 2021-11-27 21:33:14,442 [INFO] tensorflow: global_step/sec: 14.5126 INFO:tensorflow:global_step/sec: 13.7883 2021-11-27 21:33:14,587 [INFO] tensorflow: global_step/sec: 13.7883 INFO:tensorflow:global_step/sec: 14.328 2021-11-27 21:33:14,726 [INFO] tensorflow: global_step/sec: 14.328 INFO:tensorflow:global_step/sec: 14.7833 2021-11-27 21:33:14,862 [INFO] tensorflow: global_step/sec: 14.7833 INFO:tensorflow:global_step/sec: 14.4733 2021-11-27 21:33:15,000 [INFO] tensorflow: global_step/sec: 14.4733 INFO:tensorflow:global_step/sec: 15.3278 2021-11-27 21:33:15,130 [INFO] tensorflow: global_step/sec: 15.3278 2021-11-27 21:33:15,131 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.833 INFO:tensorflow:global_step/sec: 15.042 2021-11-27 21:33:15,263 [INFO] tensorflow: global_step/sec: 15.042 INFO:tensorflow:epoch = 46.72727272727273, learning_rate = 0.00049999997, loss = 0.0013563591, step = 1028 (5.081 sec) 2021-11-27 21:33:15,401 [INFO] tensorflow: epoch = 46.72727272727273, learning_rate = 0.00049999997, loss = 0.0013563591, step = 1028 (5.081 sec) INFO:tensorflow:global_step/sec: 14.4092 2021-11-27 21:33:15,402 [INFO] tensorflow: global_step/sec: 14.4092 INFO:tensorflow:global_step/sec: 14.5178 2021-11-27 21:33:15,540 [INFO] tensorflow: global_step/sec: 14.5178 INFO:tensorflow:global_step/sec: 14.4055 2021-11-27 21:33:15,679 [INFO] tensorflow: global_step/sec: 14.4055 INFO:tensorflow:global_step/sec: 14.1935 2021-11-27 21:33:15,820 [INFO] tensorflow: global_step/sec: 14.1935 2021-11-27 21:33:15,821 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 47/120: loss: 0.00134 learning rate: 0.00050 Time taken: 0:00:01.514091 ETA: 0:01:50.528644 INFO:tensorflow:global_step/sec: 14.7633 2021-11-27 21:33:15,955 [INFO] tensorflow: global_step/sec: 14.7633 INFO:tensorflow:global_step/sec: 14.9801 2021-11-27 21:33:16,089 [INFO] tensorflow: global_step/sec: 14.9801 INFO:tensorflow:global_step/sec: 14.8696 2021-11-27 21:33:16,223 [INFO] tensorflow: global_step/sec: 14.8696 INFO:tensorflow:global_step/sec: 14.4198 2021-11-27 21:33:16,362 [INFO] tensorflow: global_step/sec: 14.4198 INFO:tensorflow:global_step/sec: 14.3697 2021-11-27 21:33:16,501 [INFO] tensorflow: global_step/sec: 14.3697 INFO:tensorflow:global_step/sec: 14.6518 2021-11-27 21:33:16,638 [INFO] tensorflow: global_step/sec: 14.6518 INFO:tensorflow:global_step/sec: 14.6741 2021-11-27 21:33:16,774 [INFO] tensorflow: global_step/sec: 14.6741 2021-11-27 21:33:16,842 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.461 INFO:tensorflow:global_step/sec: 14.6539 2021-11-27 21:33:16,910 [INFO] tensorflow: global_step/sec: 14.6539 INFO:tensorflow:global_step/sec: 14.5254 2021-11-27 21:33:17,048 [INFO] tensorflow: global_step/sec: 14.5254 INFO:tensorflow:global_step/sec: 13.5828 2021-11-27 21:33:17,195 [INFO] tensorflow: global_step/sec: 13.5828 INFO:tensorflow:global_step/sec: 13.3352 2021-11-27 21:33:17,345 [INFO] tensorflow: global_step/sec: 13.3352 2021-11-27 21:33:17,346 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 48/120: loss: 0.00141 learning rate: 0.00050 Time taken: 0:00:01.521384 ETA: 0:01:49.539682 INFO:tensorflow:global_step/sec: 14.2792 2021-11-27 21:33:17,485 [INFO] tensorflow: global_step/sec: 14.2792 INFO:tensorflow:global_step/sec: 14.968 2021-11-27 21:33:17,619 [INFO] tensorflow: global_step/sec: 14.968 INFO:tensorflow:global_step/sec: 14.8724 2021-11-27 21:33:17,753 [INFO] tensorflow: global_step/sec: 14.8724 INFO:tensorflow:global_step/sec: 14.6931 2021-11-27 21:33:17,890 [INFO] tensorflow: global_step/sec: 14.6931 INFO:tensorflow:global_step/sec: 14.7765 2021-11-27 21:33:18,025 [INFO] tensorflow: global_step/sec: 14.7765 INFO:tensorflow:global_step/sec: 14.2299 2021-11-27 21:33:18,165 [INFO] tensorflow: global_step/sec: 14.2299 INFO:tensorflow:global_step/sec: 14.5137 2021-11-27 21:33:18,303 [INFO] tensorflow: global_step/sec: 14.5137 INFO:tensorflow:global_step/sec: 14.1807 2021-11-27 21:33:18,444 [INFO] tensorflow: global_step/sec: 14.1807 INFO:tensorflow:global_step/sec: 14.9438 2021-11-27 21:33:18,578 [INFO] tensorflow: global_step/sec: 14.9438 2021-11-27 21:33:18,579 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.576 INFO:tensorflow:global_step/sec: 14.3488 2021-11-27 21:33:18,717 [INFO] tensorflow: global_step/sec: 14.3488 INFO:tensorflow:global_step/sec: 13.2164 2021-11-27 21:33:18,869 [INFO] tensorflow: global_step/sec: 13.2164 2021-11-27 21:33:18,870 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 49/120: loss: 0.00120 learning rate: 0.00050 Time taken: 0:00:01.521893 ETA: 0:01:48.054388 INFO:tensorflow:global_step/sec: 15.5876 2021-11-27 21:33:18,997 [INFO] tensorflow: global_step/sec: 15.5876 INFO:tensorflow:global_step/sec: 14.0888 2021-11-27 21:33:19,139 [INFO] tensorflow: global_step/sec: 14.0888 INFO:tensorflow:global_step/sec: 14.3642 2021-11-27 21:33:19,278 [INFO] tensorflow: global_step/sec: 14.3642 INFO:tensorflow:global_step/sec: 14.677 2021-11-27 21:33:19,415 [INFO] tensorflow: global_step/sec: 14.677 INFO:tensorflow:global_step/sec: 14.908 2021-11-27 21:33:19,549 [INFO] tensorflow: global_step/sec: 14.908 INFO:tensorflow:global_step/sec: 14.4925 2021-11-27 21:33:19,687 [INFO] tensorflow: global_step/sec: 14.4925 INFO:tensorflow:global_step/sec: 14.0443 2021-11-27 21:33:19,829 [INFO] tensorflow: global_step/sec: 14.0443 INFO:tensorflow:global_step/sec: 14.4353 2021-11-27 21:33:19,968 [INFO] tensorflow: global_step/sec: 14.4353 INFO:tensorflow:global_step/sec: 14.8685 2021-11-27 21:33:20,102 [INFO] tensorflow: global_step/sec: 14.8685 INFO:tensorflow:global_step/sec: 14.9292 2021-11-27 21:33:20,236 [INFO] tensorflow: global_step/sec: 14.9292 INFO:tensorflow:Saving checkpoints for step-1100. 2021-11-27 21:33:20,301 [INFO] tensorflow: Saving checkpoints for step-1100. WARNING:tensorflow:Ignoring: /tmp/tmpsfb6vaed; No such file or directory 2021-11-27 21:33:20,397 [WARNING] tensorflow: Ignoring: /tmp/tmpsfb6vaed; No such file or directory 2021-11-27 21:33:22,688 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 2494/2494 [00:00<00:00, 27644.71it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 7938/7938 [00:00<00:00, 29075.50it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 1117/1117 [00:00<00:00, 25596.68it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 12650/12650 [00:00<00:00, 30824.90it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 3730/3730 [00:00<00:00, 30261.88it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 2686/2686 [00:00<00:00, 23651.51it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 5494/5494 [00:00<00:00, 36513.88it/s] Epoch 50/120 ========================= Validation cost: 0.000885 Mean average_precision (in %): 8.5120 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 6.51931 floor 0 palette 0.0310058 pillar 9.62457 pushcart 0 rackframe 17.0854 rackshelf 22.4368 wall 20.9107 Median Inference Time: 0.007654 2021-11-27 21:33:30,380 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 8.474 INFO:tensorflow:epoch = 50.0, learning_rate = 0.00049999997, loss = 0.0012902536, step = 1100 (15.046 sec) 2021-11-27 21:33:30,447 [INFO] tensorflow: epoch = 50.0, learning_rate = 0.00049999997, loss = 0.0012902536, step = 1100 (15.046 sec) INFO:tensorflow:global_step/sec: 0.19585 2021-11-27 21:33:30,448 [INFO] tensorflow: global_step/sec: 0.19585 2021-11-27 21:33:30,449 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 50/120: loss: 0.00129 learning rate: 0.00050 Time taken: 0:00:11.578965 ETA: 0:13:30.527546 INFO:tensorflow:global_step/sec: 14.1983 2021-11-27 21:33:30,589 [INFO] tensorflow: global_step/sec: 14.1983 INFO:tensorflow:global_step/sec: 14.5205 2021-11-27 21:33:30,727 [INFO] tensorflow: global_step/sec: 14.5205 INFO:tensorflow:global_step/sec: 14.2919 2021-11-27 21:33:30,867 [INFO] tensorflow: global_step/sec: 14.2919 INFO:tensorflow:global_step/sec: 14.8691 2021-11-27 21:33:31,001 [INFO] tensorflow: global_step/sec: 14.8691 INFO:tensorflow:global_step/sec: 14.7885 2021-11-27 21:33:31,136 [INFO] tensorflow: global_step/sec: 14.7885 INFO:tensorflow:global_step/sec: 14.2814 2021-11-27 21:33:31,276 [INFO] tensorflow: global_step/sec: 14.2814 INFO:tensorflow:global_step/sec: 15.189 2021-11-27 21:33:31,408 [INFO] tensorflow: global_step/sec: 15.189 INFO:tensorflow:global_step/sec: 14.6988 2021-11-27 21:33:31,544 [INFO] tensorflow: global_step/sec: 14.6988 INFO:tensorflow:global_step/sec: 14.3512 2021-11-27 21:33:31,684 [INFO] tensorflow: global_step/sec: 14.3512 INFO:tensorflow:global_step/sec: 14.9409 2021-11-27 21:33:31,817 [INFO] tensorflow: global_step/sec: 14.9409 INFO:tensorflow:global_step/sec: 13.5658 2021-11-27 21:33:31,965 [INFO] tensorflow: global_step/sec: 13.5658 2021-11-27 21:33:31,966 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 51/120: loss: 0.00139 learning rate: 0.00050 Time taken: 0:00:01.514344 ETA: 0:01:44.489734 INFO:tensorflow:global_step/sec: 14.9051 2021-11-27 21:33:32,099 [INFO] tensorflow: global_step/sec: 14.9051 2021-11-27 21:33:32,100 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.182 INFO:tensorflow:global_step/sec: 14.706 2021-11-27 21:33:32,235 [INFO] tensorflow: global_step/sec: 14.706 INFO:tensorflow:global_step/sec: 14.6407 2021-11-27 21:33:32,372 [INFO] tensorflow: global_step/sec: 14.6407 INFO:tensorflow:global_step/sec: 15.2104 2021-11-27 21:33:32,503 [INFO] tensorflow: global_step/sec: 15.2104 INFO:tensorflow:global_step/sec: 14.7969 2021-11-27 21:33:32,638 [INFO] tensorflow: global_step/sec: 14.7969 INFO:tensorflow:global_step/sec: 15.3496 2021-11-27 21:33:32,769 [INFO] tensorflow: global_step/sec: 15.3496 INFO:tensorflow:global_step/sec: 14.49 2021-11-27 21:33:32,907 [INFO] tensorflow: global_step/sec: 14.49 INFO:tensorflow:global_step/sec: 14.5508 2021-11-27 21:33:33,044 [INFO] tensorflow: global_step/sec: 14.5508 INFO:tensorflow:global_step/sec: 14.5053 2021-11-27 21:33:33,182 [INFO] tensorflow: global_step/sec: 14.5053 INFO:tensorflow:global_step/sec: 15.0849 2021-11-27 21:33:33,315 [INFO] tensorflow: global_step/sec: 15.0849 INFO:tensorflow:global_step/sec: 14.0417 2021-11-27 21:33:33,457 [INFO] tensorflow: global_step/sec: 14.0417 2021-11-27 21:33:33,458 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 52/120: loss: 0.00132 learning rate: 0.00050 Time taken: 0:00:01.492121 ETA: 0:01:41.464227 INFO:tensorflow:global_step/sec: 14.4571 2021-11-27 21:33:33,595 [INFO] tensorflow: global_step/sec: 14.4571 INFO:tensorflow:global_step/sec: 14.5691 2021-11-27 21:33:33,733 [INFO] tensorflow: global_step/sec: 14.5691 2021-11-27 21:33:33,801 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.801 INFO:tensorflow:global_step/sec: 14.2178 2021-11-27 21:33:33,873 [INFO] tensorflow: global_step/sec: 14.2178 INFO:tensorflow:global_step/sec: 14.1132 2021-11-27 21:33:34,015 [INFO] tensorflow: global_step/sec: 14.1132 INFO:tensorflow:global_step/sec: 14.3817 2021-11-27 21:33:34,154 [INFO] tensorflow: global_step/sec: 14.3817 INFO:tensorflow:global_step/sec: 14.8803 2021-11-27 21:33:34,288 [INFO] tensorflow: global_step/sec: 14.8803 INFO:tensorflow:global_step/sec: 14.1958 2021-11-27 21:33:34,429 [INFO] tensorflow: global_step/sec: 14.1958 INFO:tensorflow:global_step/sec: 14.7728 2021-11-27 21:33:34,565 [INFO] tensorflow: global_step/sec: 14.7728 INFO:tensorflow:global_step/sec: 13.882 2021-11-27 21:33:34,709 [INFO] tensorflow: global_step/sec: 13.882 INFO:tensorflow:global_step/sec: 14.4162 2021-11-27 21:33:34,847 [INFO] tensorflow: global_step/sec: 14.4162 INFO:tensorflow:global_step/sec: 15.0644 2021-11-27 21:33:34,980 [INFO] tensorflow: global_step/sec: 15.0644 2021-11-27 21:33:34,981 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 53/120: loss: 0.00155 learning rate: 0.00050 Time taken: 0:00:01.523912 ETA: 0:01:42.102133 INFO:tensorflow:global_step/sec: 14.9325 2021-11-27 21:33:35,114 [INFO] tensorflow: global_step/sec: 14.9325 INFO:tensorflow:global_step/sec: 13.6267 2021-11-27 21:33:35,261 [INFO] tensorflow: global_step/sec: 13.6267 INFO:tensorflow:global_step/sec: 14.4439 2021-11-27 21:33:35,399 [INFO] tensorflow: global_step/sec: 14.4439 INFO:tensorflow:epoch = 53.36363636363637, learning_rate = 0.00049999997, loss = 0.0015671041, step = 1174 (5.095 sec) 2021-11-27 21:33:35,542 [INFO] tensorflow: epoch = 53.36363636363637, learning_rate = 0.00049999997, loss = 0.0015671041, step = 1174 (5.095 sec) INFO:tensorflow:global_step/sec: 13.9204 2021-11-27 21:33:35,543 [INFO] tensorflow: global_step/sec: 13.9204 2021-11-27 21:33:35,544 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.388 INFO:tensorflow:global_step/sec: 15.1313 2021-11-27 21:33:35,675 [INFO] tensorflow: global_step/sec: 15.1313 INFO:tensorflow:global_step/sec: 14.0623 2021-11-27 21:33:35,817 [INFO] tensorflow: global_step/sec: 14.0623 INFO:tensorflow:global_step/sec: 14.245 2021-11-27 21:33:35,958 [INFO] tensorflow: global_step/sec: 14.245 INFO:tensorflow:global_step/sec: 14.8979 2021-11-27 21:33:36,092 [INFO] tensorflow: global_step/sec: 14.8979 INFO:tensorflow:global_step/sec: 13.5534 2021-11-27 21:33:36,240 [INFO] tensorflow: global_step/sec: 13.5534 INFO:tensorflow:global_step/sec: 13.8358 2021-11-27 21:33:36,384 [INFO] tensorflow: global_step/sec: 13.8358 INFO:tensorflow:global_step/sec: 13.4675 2021-11-27 21:33:36,533 [INFO] tensorflow: global_step/sec: 13.4675 2021-11-27 21:33:36,534 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 54/120: loss: 0.00139 learning rate: 0.00050 Time taken: 0:00:01.544009 ETA: 0:01:41.904576 INFO:tensorflow:global_step/sec: 14.913 2021-11-27 21:33:36,667 [INFO] tensorflow: global_step/sec: 14.913 INFO:tensorflow:global_step/sec: 15.1723 2021-11-27 21:33:36,799 [INFO] tensorflow: global_step/sec: 15.1723 INFO:tensorflow:global_step/sec: 14.7418 2021-11-27 21:33:36,934 [INFO] tensorflow: global_step/sec: 14.7418 INFO:tensorflow:global_step/sec: 14.8257 2021-11-27 21:33:37,069 [INFO] tensorflow: global_step/sec: 14.8257 INFO:tensorflow:global_step/sec: 14.4484 2021-11-27 21:33:37,208 [INFO] tensorflow: global_step/sec: 14.4484 2021-11-27 21:33:37,278 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.698 INFO:tensorflow:global_step/sec: 14.3609 2021-11-27 21:33:37,347 [INFO] tensorflow: global_step/sec: 14.3609 INFO:tensorflow:global_step/sec: 14.6544 2021-11-27 21:33:37,483 [INFO] tensorflow: global_step/sec: 14.6544 INFO:tensorflow:global_step/sec: 14.3337 2021-11-27 21:33:37,623 [INFO] tensorflow: global_step/sec: 14.3337 INFO:tensorflow:global_step/sec: 15.0066 2021-11-27 21:33:37,756 [INFO] tensorflow: global_step/sec: 15.0066 INFO:tensorflow:global_step/sec: 13.9024 2021-11-27 21:33:37,900 [INFO] tensorflow: global_step/sec: 13.9024 INFO:tensorflow:global_step/sec: 14.1419 2021-11-27 21:33:38,041 [INFO] tensorflow: global_step/sec: 14.1419 2021-11-27 21:33:38,043 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 55/120: loss: 0.00153 learning rate: 0.00050 Time taken: 0:00:01.511989 ETA: 0:01:38.279277 INFO:tensorflow:global_step/sec: 14.3633 2021-11-27 21:33:38,181 [INFO] tensorflow: global_step/sec: 14.3633 INFO:tensorflow:global_step/sec: 14.9576 2021-11-27 21:33:38,314 [INFO] tensorflow: global_step/sec: 14.9576 INFO:tensorflow:global_step/sec: 15.1663 2021-11-27 21:33:38,446 [INFO] tensorflow: global_step/sec: 15.1663 INFO:tensorflow:global_step/sec: 14.5145 2021-11-27 21:33:38,584 [INFO] tensorflow: global_step/sec: 14.5145 INFO:tensorflow:global_step/sec: 14.6171 2021-11-27 21:33:38,721 [INFO] tensorflow: global_step/sec: 14.6171 INFO:tensorflow:global_step/sec: 14.1905 2021-11-27 21:33:38,862 [INFO] tensorflow: global_step/sec: 14.1905 INFO:tensorflow:global_step/sec: 14.0799 2021-11-27 21:33:39,004 [INFO] tensorflow: global_step/sec: 14.0799 2021-11-27 21:33:39,005 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.910 INFO:tensorflow:global_step/sec: 14.5196 2021-11-27 21:33:39,142 [INFO] tensorflow: global_step/sec: 14.5196 INFO:tensorflow:global_step/sec: 15.2052 2021-11-27 21:33:39,273 [INFO] tensorflow: global_step/sec: 15.2052 INFO:tensorflow:global_step/sec: 14.7164 2021-11-27 21:33:39,409 [INFO] tensorflow: global_step/sec: 14.7164 INFO:tensorflow:global_step/sec: 14.3408 2021-11-27 21:33:39,549 [INFO] tensorflow: global_step/sec: 14.3408 2021-11-27 21:33:39,550 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 56/120: loss: 0.00129 learning rate: 0.00050 Time taken: 0:00:01.503366 ETA: 0:01:36.215393 INFO:tensorflow:global_step/sec: 15.0761 2021-11-27 21:33:39,681 [INFO] tensorflow: global_step/sec: 15.0761 INFO:tensorflow:global_step/sec: 14.5313 2021-11-27 21:33:39,819 [INFO] tensorflow: global_step/sec: 14.5313 INFO:tensorflow:global_step/sec: 14.1581 2021-11-27 21:33:39,960 [INFO] tensorflow: global_step/sec: 14.1581 INFO:tensorflow:global_step/sec: 15.0281 2021-11-27 21:33:40,093 [INFO] tensorflow: global_step/sec: 15.0281 INFO:tensorflow:global_step/sec: 14.4851 2021-11-27 21:33:40,231 [INFO] tensorflow: global_step/sec: 14.4851 INFO:tensorflow:global_step/sec: 14.5866 2021-11-27 21:33:40,368 [INFO] tensorflow: global_step/sec: 14.5866 INFO:tensorflow:global_step/sec: 14.3521 2021-11-27 21:33:40,508 [INFO] tensorflow: global_step/sec: 14.3521 INFO:tensorflow:epoch = 56.72727272727273, learning_rate = 0.00049999997, loss = 0.0015351584, step = 1248 (5.100 sec) 2021-11-27 21:33:40,642 [INFO] tensorflow: epoch = 56.72727272727273, learning_rate = 0.00049999997, loss = 0.0015351584, step = 1248 (5.100 sec) INFO:tensorflow:global_step/sec: 14.7948 2021-11-27 21:33:40,643 [INFO] tensorflow: global_step/sec: 14.7948 2021-11-27 21:33:40,709 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.683 INFO:tensorflow:global_step/sec: 14.304 2021-11-27 21:33:40,783 [INFO] tensorflow: global_step/sec: 14.304 INFO:tensorflow:global_step/sec: 14.3902 2021-11-27 21:33:40,922 [INFO] tensorflow: global_step/sec: 14.3902 INFO:tensorflow:global_step/sec: 13.755 2021-11-27 21:33:41,067 [INFO] tensorflow: global_step/sec: 13.755 2021-11-27 21:33:41,068 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 57/120: loss: 0.00155 learning rate: 0.00050 Time taken: 0:00:01.519072 ETA: 0:01:35.701509 INFO:tensorflow:global_step/sec: 14.761 2021-11-27 21:33:41,203 [INFO] tensorflow: global_step/sec: 14.761 INFO:tensorflow:global_step/sec: 14.7625 2021-11-27 21:33:41,338 [INFO] tensorflow: global_step/sec: 14.7625 INFO:tensorflow:global_step/sec: 14.8115 2021-11-27 21:33:41,473 [INFO] tensorflow: global_step/sec: 14.8115 INFO:tensorflow:global_step/sec: 13.8933 2021-11-27 21:33:41,617 [INFO] tensorflow: global_step/sec: 13.8933 INFO:tensorflow:global_step/sec: 13.9201 2021-11-27 21:33:41,761 [INFO] tensorflow: global_step/sec: 13.9201 INFO:tensorflow:global_step/sec: 14.4722 2021-11-27 21:33:41,899 [INFO] tensorflow: global_step/sec: 14.4722 INFO:tensorflow:global_step/sec: 14.1865 2021-11-27 21:33:42,040 [INFO] tensorflow: global_step/sec: 14.1865 INFO:tensorflow:global_step/sec: 14.6606 2021-11-27 21:33:42,176 [INFO] tensorflow: global_step/sec: 14.6606 INFO:tensorflow:global_step/sec: 14.9574 2021-11-27 21:33:42,310 [INFO] tensorflow: global_step/sec: 14.9574 INFO:tensorflow:global_step/sec: 14.4513 2021-11-27 21:33:42,448 [INFO] tensorflow: global_step/sec: 14.4513 2021-11-27 21:33:42,449 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.476 INFO:tensorflow:global_step/sec: 13.3929 2021-11-27 21:33:42,598 [INFO] tensorflow: global_step/sec: 13.3929 2021-11-27 21:33:42,599 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 58/120: loss: 0.00148 learning rate: 0.00050 Time taken: 0:00:01.527693 ETA: 0:01:34.716938 INFO:tensorflow:global_step/sec: 14.7503 2021-11-27 21:33:42,733 [INFO] tensorflow: global_step/sec: 14.7503 INFO:tensorflow:global_step/sec: 14.3179 2021-11-27 21:33:42,873 [INFO] tensorflow: global_step/sec: 14.3179 INFO:tensorflow:global_step/sec: 14.5708 2021-11-27 21:33:43,010 [INFO] tensorflow: global_step/sec: 14.5708 INFO:tensorflow:global_step/sec: 14.463 2021-11-27 21:33:43,149 [INFO] tensorflow: global_step/sec: 14.463 INFO:tensorflow:global_step/sec: 14.7799 2021-11-27 21:33:43,284 [INFO] tensorflow: global_step/sec: 14.7799 INFO:tensorflow:global_step/sec: 14.8605 2021-11-27 21:33:43,419 [INFO] tensorflow: global_step/sec: 14.8605 INFO:tensorflow:global_step/sec: 15.2307 2021-11-27 21:33:43,550 [INFO] tensorflow: global_step/sec: 15.2307 INFO:tensorflow:global_step/sec: 14.6198 2021-11-27 21:33:43,687 [INFO] tensorflow: global_step/sec: 14.6198 INFO:tensorflow:global_step/sec: 14.6943 2021-11-27 21:33:43,823 [INFO] tensorflow: global_step/sec: 14.6943 INFO:tensorflow:global_step/sec: 15.3027 2021-11-27 21:33:43,953 [INFO] tensorflow: global_step/sec: 15.3027 INFO:tensorflow:global_step/sec: 14.2585 2021-11-27 21:33:44,094 [INFO] tensorflow: global_step/sec: 14.2585 2021-11-27 21:33:44,095 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 59/120: loss: 0.00151 learning rate: 0.00050 Time taken: 0:00:01.495363 ETA: 0:01:31.217143 2021-11-27 21:33:44,161 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.454 INFO:tensorflow:global_step/sec: 14.9341 2021-11-27 21:33:44,228 [INFO] tensorflow: global_step/sec: 14.9341 INFO:tensorflow:global_step/sec: 14.5881 2021-11-27 21:33:44,365 [INFO] tensorflow: global_step/sec: 14.5881 INFO:tensorflow:global_step/sec: 14.4416 2021-11-27 21:33:44,503 [INFO] tensorflow: global_step/sec: 14.4416 INFO:tensorflow:global_step/sec: 14.8175 2021-11-27 21:33:44,638 [INFO] tensorflow: global_step/sec: 14.8175 INFO:tensorflow:global_step/sec: 14.8709 2021-11-27 21:33:44,773 [INFO] tensorflow: global_step/sec: 14.8709 INFO:tensorflow:global_step/sec: 14.5072 2021-11-27 21:33:44,911 [INFO] tensorflow: global_step/sec: 14.5072 INFO:tensorflow:global_step/sec: 15.1607 2021-11-27 21:33:45,042 [INFO] tensorflow: global_step/sec: 15.1607 INFO:tensorflow:global_step/sec: 15.0658 2021-11-27 21:33:45,175 [INFO] tensorflow: global_step/sec: 15.0658 INFO:tensorflow:global_step/sec: 14.855 2021-11-27 21:33:45,310 [INFO] tensorflow: global_step/sec: 14.855 INFO:tensorflow:global_step/sec: 14.5366 2021-11-27 21:33:45,447 [INFO] tensorflow: global_step/sec: 14.5366 INFO:tensorflow:Saving checkpoints for step-1320. 2021-11-27 21:33:45,516 [INFO] tensorflow: Saving checkpoints for step-1320. WARNING:tensorflow:Ignoring: /tmp/tmp74wm50jo; No such file or directory 2021-11-27 21:33:45,617 [WARNING] tensorflow: Ignoring: /tmp/tmp74wm50jo; No such file or directory 2021-11-27 21:33:47,983 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 2297/2297 [00:00<00:00, 25240.81it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 9125/9125 [00:00<00:00, 27755.90it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 1392/1392 [00:00<00:00, 24972.40it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 13010/13010 [00:00<00:00, 29365.38it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 2259/2259 [00:00<00:00, 26658.26it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 2538/2538 [00:00<00:00, 24626.54it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 10772/10772 [00:00<00:00, 40784.59it/s] Epoch 60/120 ========================= Validation cost: 0.000975 Mean average_precision (in %): 10.1440 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 3.48893 floor 0 palette 0.200376 pillar 6.69095 pushcart 0 rackframe 19.7687 rackshelf 34.2332 wall 26.9136 Median Inference Time: 0.008690 INFO:tensorflow:epoch = 60.0, learning_rate = 0.00049999997, loss = 0.0014266176, step = 1320 (15.120 sec) 2021-11-27 21:33:55,762 [INFO] tensorflow: epoch = 60.0, learning_rate = 0.00049999997, loss = 0.0014266176, step = 1320 (15.120 sec) INFO:tensorflow:global_step/sec: 0.193885 2021-11-27 21:33:55,763 [INFO] tensorflow: global_step/sec: 0.193885 2021-11-27 21:33:55,764 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 60/120: loss: 0.00143 learning rate: 0.00050 Time taken: 0:00:11.666830 ETA: 0:11:40.009789 INFO:tensorflow:global_step/sec: 14.7872 2021-11-27 21:33:55,898 [INFO] tensorflow: global_step/sec: 14.7872 INFO:tensorflow:global_step/sec: 14.4633 2021-11-27 21:33:56,036 [INFO] tensorflow: global_step/sec: 14.4633 2021-11-27 21:33:56,037 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 8.420 INFO:tensorflow:global_step/sec: 14.5349 2021-11-27 21:33:56,174 [INFO] tensorflow: global_step/sec: 14.5349 INFO:tensorflow:global_step/sec: 14.286 2021-11-27 21:33:56,314 [INFO] tensorflow: global_step/sec: 14.286 INFO:tensorflow:global_step/sec: 14.7936 2021-11-27 21:33:56,449 [INFO] tensorflow: global_step/sec: 14.7936 INFO:tensorflow:global_step/sec: 14.6724 2021-11-27 21:33:56,585 [INFO] tensorflow: global_step/sec: 14.6724 INFO:tensorflow:global_step/sec: 14.963 2021-11-27 21:33:56,719 [INFO] tensorflow: global_step/sec: 14.963 INFO:tensorflow:global_step/sec: 14.7648 2021-11-27 21:33:56,855 [INFO] tensorflow: global_step/sec: 14.7648 INFO:tensorflow:global_step/sec: 15.0408 2021-11-27 21:33:56,988 [INFO] tensorflow: global_step/sec: 15.0408 INFO:tensorflow:global_step/sec: 14.432 2021-11-27 21:33:57,126 [INFO] tensorflow: global_step/sec: 14.432 INFO:tensorflow:global_step/sec: 13.9501 2021-11-27 21:33:57,270 [INFO] tensorflow: global_step/sec: 13.9501 2021-11-27 21:33:57,271 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 61/120: loss: 0.00132 learning rate: 0.00050 Time taken: 0:00:01.509826 ETA: 0:01:29.079759 INFO:tensorflow:global_step/sec: 14.4909 2021-11-27 21:33:57,408 [INFO] tensorflow: global_step/sec: 14.4909 INFO:tensorflow:global_step/sec: 15.0177 2021-11-27 21:33:57,541 [INFO] tensorflow: global_step/sec: 15.0177 INFO:tensorflow:global_step/sec: 14.6552 2021-11-27 21:33:57,677 [INFO] tensorflow: global_step/sec: 14.6552 2021-11-27 21:33:57,747 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.489 INFO:tensorflow:global_step/sec: 14.3625 2021-11-27 21:33:57,816 [INFO] tensorflow: global_step/sec: 14.3625 INFO:tensorflow:global_step/sec: 14.8119 2021-11-27 21:33:57,951 [INFO] tensorflow: global_step/sec: 14.8119 INFO:tensorflow:global_step/sec: 13.9939 2021-11-27 21:33:58,094 [INFO] tensorflow: global_step/sec: 13.9939 INFO:tensorflow:global_step/sec: 14.699 2021-11-27 21:33:58,230 [INFO] tensorflow: global_step/sec: 14.699 INFO:tensorflow:global_step/sec: 14.7073 2021-11-27 21:33:58,366 [INFO] tensorflow: global_step/sec: 14.7073 INFO:tensorflow:global_step/sec: 15.3871 2021-11-27 21:33:58,496 [INFO] tensorflow: global_step/sec: 15.3871 INFO:tensorflow:global_step/sec: 14.9723 2021-11-27 21:33:58,630 [INFO] tensorflow: global_step/sec: 14.9723 INFO:tensorflow:global_step/sec: 14.2827 2021-11-27 21:33:58,770 [INFO] tensorflow: global_step/sec: 14.2827 2021-11-27 21:33:58,771 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 62/120: loss: 0.00138 learning rate: 0.00050 Time taken: 0:00:01.494721 ETA: 0:01:26.693814 INFO:tensorflow:global_step/sec: 14.4427 2021-11-27 21:33:58,908 [INFO] tensorflow: global_step/sec: 14.4427 INFO:tensorflow:global_step/sec: 14.0075 2021-11-27 21:33:59,051 [INFO] tensorflow: global_step/sec: 14.0075 INFO:tensorflow:global_step/sec: 14.571 2021-11-27 21:33:59,189 [INFO] tensorflow: global_step/sec: 14.571 INFO:tensorflow:global_step/sec: 14.5474 2021-11-27 21:33:59,326 [INFO] tensorflow: global_step/sec: 14.5474 INFO:tensorflow:global_step/sec: 14.6023 2021-11-27 21:33:59,463 [INFO] tensorflow: global_step/sec: 14.6023 2021-11-27 21:33:59,464 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.266 INFO:tensorflow:global_step/sec: 14.4687 2021-11-27 21:33:59,601 [INFO] tensorflow: global_step/sec: 14.4687 INFO:tensorflow:global_step/sec: 14.2795 2021-11-27 21:33:59,741 [INFO] tensorflow: global_step/sec: 14.2795 INFO:tensorflow:global_step/sec: 14.1805 2021-11-27 21:33:59,882 [INFO] tensorflow: global_step/sec: 14.1805 INFO:tensorflow:global_step/sec: 14.4587 2021-11-27 21:34:00,021 [INFO] tensorflow: global_step/sec: 14.4587 INFO:tensorflow:global_step/sec: 14.6281 2021-11-27 21:34:00,157 [INFO] tensorflow: global_step/sec: 14.6281 INFO:tensorflow:global_step/sec: 14.199 2021-11-27 21:34:00,298 [INFO] tensorflow: global_step/sec: 14.199 2021-11-27 21:34:00,299 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 63/120: loss: 0.00152 learning rate: 0.00050 Time taken: 0:00:01.528007 ETA: 0:01:27.096401 INFO:tensorflow:global_step/sec: 15.1165 2021-11-27 21:34:00,430 [INFO] tensorflow: global_step/sec: 15.1165 INFO:tensorflow:global_step/sec: 14.651 2021-11-27 21:34:00,567 [INFO] tensorflow: global_step/sec: 14.651 INFO:tensorflow:global_step/sec: 15.2323 2021-11-27 21:34:00,698 [INFO] tensorflow: global_step/sec: 15.2323 INFO:tensorflow:epoch = 63.36363636363637, learning_rate = 0.00049999997, loss = 0.0015953407, step = 1394 (5.071 sec) 2021-11-27 21:34:00,832 [INFO] tensorflow: epoch = 63.36363636363637, learning_rate = 0.00049999997, loss = 0.0015953407, step = 1394 (5.071 sec) INFO:tensorflow:global_step/sec: 14.7972 2021-11-27 21:34:00,833 [INFO] tensorflow: global_step/sec: 14.7972 INFO:tensorflow:global_step/sec: 14.4147 2021-11-27 21:34:00,972 [INFO] tensorflow: global_step/sec: 14.4147 INFO:tensorflow:global_step/sec: 14.5532 2021-11-27 21:34:01,110 [INFO] tensorflow: global_step/sec: 14.5532 2021-11-27 21:34:01,179 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.329 INFO:tensorflow:global_step/sec: 14.0159 2021-11-27 21:34:01,252 [INFO] tensorflow: global_step/sec: 14.0159 INFO:tensorflow:global_step/sec: 14.8762 2021-11-27 21:34:01,387 [INFO] tensorflow: global_step/sec: 14.8762 INFO:tensorflow:global_step/sec: 14.9651 2021-11-27 21:34:01,520 [INFO] tensorflow: global_step/sec: 14.9651 INFO:tensorflow:global_step/sec: 14.8619 2021-11-27 21:34:01,655 [INFO] tensorflow: global_step/sec: 14.8619 INFO:tensorflow:global_step/sec: 14.4586 2021-11-27 21:34:01,793 [INFO] tensorflow: global_step/sec: 14.4586 2021-11-27 21:34:01,794 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 64/120: loss: 0.00158 learning rate: 0.00050 Time taken: 0:00:01.494732 ETA: 0:01:23.705000 INFO:tensorflow:global_step/sec: 14.57 2021-11-27 21:34:01,931 [INFO] tensorflow: global_step/sec: 14.57 INFO:tensorflow:global_step/sec: 15.0004 2021-11-27 21:34:02,064 [INFO] tensorflow: global_step/sec: 15.0004 INFO:tensorflow:global_step/sec: 14.5424 2021-11-27 21:34:02,201 [INFO] tensorflow: global_step/sec: 14.5424 INFO:tensorflow:global_step/sec: 14.3588 2021-11-27 21:34:02,341 [INFO] tensorflow: global_step/sec: 14.3588 INFO:tensorflow:global_step/sec: 14.7167 2021-11-27 21:34:02,477 [INFO] tensorflow: global_step/sec: 14.7167 INFO:tensorflow:global_step/sec: 14.7886 2021-11-27 21:34:02,612 [INFO] tensorflow: global_step/sec: 14.7886 INFO:tensorflow:global_step/sec: 14.397 2021-11-27 21:34:02,751 [INFO] tensorflow: global_step/sec: 14.397 INFO:tensorflow:global_step/sec: 14.6402 2021-11-27 21:34:02,887 [INFO] tensorflow: global_step/sec: 14.6402 2021-11-27 21:34:02,888 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.511 INFO:tensorflow:global_step/sec: 13.7666 2021-11-27 21:34:03,033 [INFO] tensorflow: global_step/sec: 13.7666 INFO:tensorflow:global_step/sec: 14.9609 2021-11-27 21:34:03,166 [INFO] tensorflow: global_step/sec: 14.9609 INFO:tensorflow:global_step/sec: 13.4594 2021-11-27 21:34:03,315 [INFO] tensorflow: global_step/sec: 13.4594 2021-11-27 21:34:03,317 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 65/120: loss: 0.00134 learning rate: 0.00050 Time taken: 0:00:01.514543 ETA: 0:01:23.299855 INFO:tensorflow:global_step/sec: 14.6825 2021-11-27 21:34:03,451 [INFO] tensorflow: global_step/sec: 14.6825 INFO:tensorflow:global_step/sec: 13.662 2021-11-27 21:34:03,598 [INFO] tensorflow: global_step/sec: 13.662 INFO:tensorflow:global_step/sec: 14.2616 2021-11-27 21:34:03,738 [INFO] tensorflow: global_step/sec: 14.2616 INFO:tensorflow:global_step/sec: 14.3427 2021-11-27 21:34:03,877 [INFO] tensorflow: global_step/sec: 14.3427 INFO:tensorflow:global_step/sec: 14.0508 2021-11-27 21:34:04,020 [INFO] tensorflow: global_step/sec: 14.0508 INFO:tensorflow:global_step/sec: 13.8025 2021-11-27 21:34:04,164 [INFO] tensorflow: global_step/sec: 13.8025 INFO:tensorflow:global_step/sec: 13.9506 2021-11-27 21:34:04,308 [INFO] tensorflow: global_step/sec: 13.9506 INFO:tensorflow:global_step/sec: 14.5483 2021-11-27 21:34:04,445 [INFO] tensorflow: global_step/sec: 14.5483 INFO:tensorflow:global_step/sec: 13.6996 2021-11-27 21:34:04,591 [INFO] tensorflow: global_step/sec: 13.6996 2021-11-27 21:34:04,662 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 56.385 INFO:tensorflow:global_step/sec: 14.1634 2021-11-27 21:34:04,733 [INFO] tensorflow: global_step/sec: 14.1634 INFO:tensorflow:global_step/sec: 13.6234 2021-11-27 21:34:04,879 [INFO] tensorflow: global_step/sec: 13.6234 2021-11-27 21:34:04,881 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 66/120: loss: 0.00124 learning rate: 0.00050 Time taken: 0:00:01.562478 ETA: 0:01:24.373828 INFO:tensorflow:global_step/sec: 14.7475 2021-11-27 21:34:05,015 [INFO] tensorflow: global_step/sec: 14.7475 INFO:tensorflow:global_step/sec: 14.5771 2021-11-27 21:34:05,152 [INFO] tensorflow: global_step/sec: 14.5771 INFO:tensorflow:global_step/sec: 13.9188 2021-11-27 21:34:05,296 [INFO] tensorflow: global_step/sec: 13.9188 INFO:tensorflow:global_step/sec: 14.4473 2021-11-27 21:34:05,434 [INFO] tensorflow: global_step/sec: 14.4473 INFO:tensorflow:global_step/sec: 14.6541 2021-11-27 21:34:05,571 [INFO] tensorflow: global_step/sec: 14.6541 INFO:tensorflow:global_step/sec: 14.5884 2021-11-27 21:34:05,708 [INFO] tensorflow: global_step/sec: 14.5884 INFO:tensorflow:global_step/sec: 14.0189 2021-11-27 21:34:05,851 [INFO] tensorflow: global_step/sec: 14.0189 INFO:tensorflow:epoch = 66.68181818181819, learning_rate = 0.00049999997, loss = 0.0015700122, step = 1467 (5.090 sec) 2021-11-27 21:34:05,922 [INFO] tensorflow: epoch = 66.68181818181819, learning_rate = 0.00049999997, loss = 0.0015700122, step = 1467 (5.090 sec) INFO:tensorflow:global_step/sec: 14.047 2021-11-27 21:34:05,993 [INFO] tensorflow: global_step/sec: 14.047 INFO:tensorflow:global_step/sec: 14.1691 2021-11-27 21:34:06,134 [INFO] tensorflow: global_step/sec: 14.1691 INFO:tensorflow:global_step/sec: 13.9246 2021-11-27 21:34:06,278 [INFO] tensorflow: global_step/sec: 13.9246 INFO:tensorflow:global_step/sec: 13.2248 2021-11-27 21:34:06,429 [INFO] tensorflow: global_step/sec: 13.2248 2021-11-27 21:34:06,430 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 67/120: loss: 0.00128 learning rate: 0.00050 Time taken: 0:00:01.548004 ETA: 0:01:22.044195 2021-11-27 21:34:06,430 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 56.566 INFO:tensorflow:global_step/sec: 14.2627 2021-11-27 21:34:06,569 [INFO] tensorflow: global_step/sec: 14.2627 INFO:tensorflow:global_step/sec: 14.5494 2021-11-27 21:34:06,707 [INFO] tensorflow: global_step/sec: 14.5494 INFO:tensorflow:global_step/sec: 14.3561 2021-11-27 21:34:06,846 [INFO] tensorflow: global_step/sec: 14.3561 INFO:tensorflow:global_step/sec: 14.9612 2021-11-27 21:34:06,980 [INFO] tensorflow: global_step/sec: 14.9612 INFO:tensorflow:global_step/sec: 14.6478 2021-11-27 21:34:07,116 [INFO] tensorflow: global_step/sec: 14.6478 INFO:tensorflow:global_step/sec: 14.3624 2021-11-27 21:34:07,255 [INFO] tensorflow: global_step/sec: 14.3624 INFO:tensorflow:global_step/sec: 14.6491 2021-11-27 21:34:07,392 [INFO] tensorflow: global_step/sec: 14.6491 INFO:tensorflow:global_step/sec: 14.3361 2021-11-27 21:34:07,531 [INFO] tensorflow: global_step/sec: 14.3361 INFO:tensorflow:global_step/sec: 14.5416 2021-11-27 21:34:07,669 [INFO] tensorflow: global_step/sec: 14.5416 INFO:tensorflow:global_step/sec: 13.5281 2021-11-27 21:34:07,817 [INFO] tensorflow: global_step/sec: 13.5281 INFO:tensorflow:global_step/sec: 13.5429 2021-11-27 21:34:07,965 [INFO] tensorflow: global_step/sec: 13.5429 2021-11-27 21:34:07,966 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 68/120: loss: 0.00117 learning rate: 0.00050 Time taken: 0:00:01.531856 ETA: 0:01:19.656528 INFO:tensorflow:global_step/sec: 14.4414 2021-11-27 21:34:08,103 [INFO] tensorflow: global_step/sec: 14.4414 2021-11-27 21:34:08,173 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.403 INFO:tensorflow:global_step/sec: 14.1548 2021-11-27 21:34:08,244 [INFO] tensorflow: global_step/sec: 14.1548 INFO:tensorflow:global_step/sec: 14.5714 2021-11-27 21:34:08,382 [INFO] tensorflow: global_step/sec: 14.5714 INFO:tensorflow:global_step/sec: 14.1127 2021-11-27 21:34:08,523 [INFO] tensorflow: global_step/sec: 14.1127 INFO:tensorflow:global_step/sec: 14.6206 2021-11-27 21:34:08,660 [INFO] tensorflow: global_step/sec: 14.6206 INFO:tensorflow:global_step/sec: 14.6829 2021-11-27 21:34:08,796 [INFO] tensorflow: global_step/sec: 14.6829 INFO:tensorflow:global_step/sec: 14.1628 2021-11-27 21:34:08,937 [INFO] tensorflow: global_step/sec: 14.1628 INFO:tensorflow:global_step/sec: 14.0238 2021-11-27 21:34:09,080 [INFO] tensorflow: global_step/sec: 14.0238 INFO:tensorflow:global_step/sec: 14.3273 2021-11-27 21:34:09,220 [INFO] tensorflow: global_step/sec: 14.3273 INFO:tensorflow:global_step/sec: 14.6254 2021-11-27 21:34:09,356 [INFO] tensorflow: global_step/sec: 14.6254 INFO:tensorflow:global_step/sec: 13.9285 2021-11-27 21:34:09,500 [INFO] tensorflow: global_step/sec: 13.9285 2021-11-27 21:34:09,501 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 69/120: loss: 0.00114 learning rate: 0.00050 Time taken: 0:00:01.539276 ETA: 0:01:18.503094 INFO:tensorflow:global_step/sec: 13.9658 2021-11-27 21:34:09,643 [INFO] tensorflow: global_step/sec: 13.9658 INFO:tensorflow:global_step/sec: 14.5352 2021-11-27 21:34:09,781 [INFO] tensorflow: global_step/sec: 14.5352 INFO:tensorflow:global_step/sec: 14.4218 2021-11-27 21:34:09,919 [INFO] tensorflow: global_step/sec: 14.4218 2021-11-27 21:34:09,920 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.232 INFO:tensorflow:global_step/sec: 14.9071 2021-11-27 21:34:10,054 [INFO] tensorflow: global_step/sec: 14.9071 INFO:tensorflow:global_step/sec: 15.1406 2021-11-27 21:34:10,186 [INFO] tensorflow: global_step/sec: 15.1406 INFO:tensorflow:global_step/sec: 14.9649 2021-11-27 21:34:10,319 [INFO] tensorflow: global_step/sec: 14.9649 INFO:tensorflow:global_step/sec: 15.2856 2021-11-27 21:34:10,450 [INFO] tensorflow: global_step/sec: 15.2856 INFO:tensorflow:global_step/sec: 14.8341 2021-11-27 21:34:10,585 [INFO] tensorflow: global_step/sec: 14.8341 INFO:tensorflow:global_step/sec: 14.4841 2021-11-27 21:34:10,723 [INFO] tensorflow: global_step/sec: 14.4841 INFO:tensorflow:global_step/sec: 14.5442 2021-11-27 21:34:10,861 [INFO] tensorflow: global_step/sec: 14.5442 INFO:tensorflow:Saving checkpoints for step-1540. 2021-11-27 21:34:10,929 [INFO] tensorflow: Saving checkpoints for step-1540. WARNING:tensorflow:Ignoring: /tmp/tmpvpflokst; No such file or directory 2021-11-27 21:34:11,026 [WARNING] tensorflow: Ignoring: /tmp/tmpvpflokst; No such file or directory 2021-11-27 21:34:13,381 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 2346/2346 [00:00<00:00, 25264.88it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 6486/6486 [00:00<00:00, 26272.45it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 1366/1366 [00:00<00:00, 24581.45it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 11294/11294 [00:00<00:00, 26045.82it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 1633/1633 [00:00<00:00, 25001.00it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 2259/2259 [00:00<00:00, 23735.57it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 7430/7430 [00:00<00:00, 35866.04it/s] Epoch 70/120 ========================= Validation cost: 0.000967 Mean average_precision (in %): 12.0589 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 11.3192 floor 0 palette 0.58884 pillar 8.05643 pushcart 0 rackframe 24.3459 rackshelf 36.9012 wall 27.319 Median Inference Time: 0.007168 INFO:tensorflow:epoch = 70.0, learning_rate = 0.00049999997, loss = 0.0012142942, step = 1540 (14.693 sec) 2021-11-27 21:34:20,615 [INFO] tensorflow: epoch = 70.0, learning_rate = 0.00049999997, loss = 0.0012142942, step = 1540 (14.693 sec) INFO:tensorflow:global_step/sec: 0.20501 2021-11-27 21:34:20,616 [INFO] tensorflow: global_step/sec: 0.20501 2021-11-27 21:34:20,618 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 70/120: loss: 0.00121 learning rate: 0.00050 Time taken: 0:00:11.112018 ETA: 0:09:15.600917 INFO:tensorflow:global_step/sec: 13.776 2021-11-27 21:34:20,761 [INFO] tensorflow: global_step/sec: 13.776 INFO:tensorflow:global_step/sec: 14.4703 2021-11-27 21:34:20,900 [INFO] tensorflow: global_step/sec: 14.4703 INFO:tensorflow:global_step/sec: 14.5335 2021-11-27 21:34:21,037 [INFO] tensorflow: global_step/sec: 14.5335 INFO:tensorflow:global_step/sec: 15.0228 2021-11-27 21:34:21,170 [INFO] tensorflow: global_step/sec: 15.0228 2021-11-27 21:34:21,240 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 8.834 INFO:tensorflow:global_step/sec: 14.2342 2021-11-27 21:34:21,311 [INFO] tensorflow: global_step/sec: 14.2342 INFO:tensorflow:global_step/sec: 14.0878 2021-11-27 21:34:21,453 [INFO] tensorflow: global_step/sec: 14.0878 INFO:tensorflow:global_step/sec: 14.4293 2021-11-27 21:34:21,591 [INFO] tensorflow: global_step/sec: 14.4293 INFO:tensorflow:global_step/sec: 14.688 2021-11-27 21:34:21,728 [INFO] tensorflow: global_step/sec: 14.688 INFO:tensorflow:global_step/sec: 14.3982 2021-11-27 21:34:21,867 [INFO] tensorflow: global_step/sec: 14.3982 INFO:tensorflow:global_step/sec: 14.4479 2021-11-27 21:34:22,005 [INFO] tensorflow: global_step/sec: 14.4479 INFO:tensorflow:global_step/sec: 14.0586 2021-11-27 21:34:22,147 [INFO] tensorflow: global_step/sec: 14.0586 2021-11-27 21:34:22,148 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 71/120: loss: 0.00137 learning rate: 0.00050 Time taken: 0:00:01.530263 ETA: 0:01:14.982896 INFO:tensorflow:global_step/sec: 14.5517 2021-11-27 21:34:22,285 [INFO] tensorflow: global_step/sec: 14.5517 INFO:tensorflow:global_step/sec: 14.3151 2021-11-27 21:34:22,424 [INFO] tensorflow: global_step/sec: 14.3151 INFO:tensorflow:global_step/sec: 15.027 2021-11-27 21:34:22,557 [INFO] tensorflow: global_step/sec: 15.027 INFO:tensorflow:global_step/sec: 15.0643 2021-11-27 21:34:22,690 [INFO] tensorflow: global_step/sec: 15.0643 INFO:tensorflow:global_step/sec: 15.4816 2021-11-27 21:34:22,819 [INFO] tensorflow: global_step/sec: 15.4816 INFO:tensorflow:global_step/sec: 14.5782 2021-11-27 21:34:22,957 [INFO] tensorflow: global_step/sec: 14.5782 2021-11-27 21:34:22,957 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.240 INFO:tensorflow:global_step/sec: 14.4347 2021-11-27 21:34:23,095 [INFO] tensorflow: global_step/sec: 14.4347 INFO:tensorflow:global_step/sec: 14.7888 2021-11-27 21:34:23,230 [INFO] tensorflow: global_step/sec: 14.7888 INFO:tensorflow:global_step/sec: 14.7487 2021-11-27 21:34:23,366 [INFO] tensorflow: global_step/sec: 14.7487 INFO:tensorflow:global_step/sec: 14.8161 2021-11-27 21:34:23,501 [INFO] tensorflow: global_step/sec: 14.8161 INFO:tensorflow:global_step/sec: 14.4414 2021-11-27 21:34:23,639 [INFO] tensorflow: global_step/sec: 14.4414 2021-11-27 21:34:23,641 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 72/120: loss: 0.00114 learning rate: 0.00050 Time taken: 0:00:01.495012 ETA: 0:01:11.760590 INFO:tensorflow:global_step/sec: 14.3069 2021-11-27 21:34:23,779 [INFO] tensorflow: global_step/sec: 14.3069 INFO:tensorflow:global_step/sec: 14.1935 2021-11-27 21:34:23,920 [INFO] tensorflow: global_step/sec: 14.1935 INFO:tensorflow:global_step/sec: 14.8528 2021-11-27 21:34:24,055 [INFO] tensorflow: global_step/sec: 14.8528 INFO:tensorflow:global_step/sec: 14.3566 2021-11-27 21:34:24,194 [INFO] tensorflow: global_step/sec: 14.3566 INFO:tensorflow:global_step/sec: 14.8619 2021-11-27 21:34:24,329 [INFO] tensorflow: global_step/sec: 14.8619 INFO:tensorflow:global_step/sec: 15.3738 2021-11-27 21:34:24,459 [INFO] tensorflow: global_step/sec: 15.3738 INFO:tensorflow:global_step/sec: 14.9988 2021-11-27 21:34:24,592 [INFO] tensorflow: global_step/sec: 14.9988 2021-11-27 21:34:24,661 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.708 INFO:tensorflow:global_step/sec: 14.3551 2021-11-27 21:34:24,732 [INFO] tensorflow: global_step/sec: 14.3551 INFO:tensorflow:global_step/sec: 14.6924 2021-11-27 21:34:24,868 [INFO] tensorflow: global_step/sec: 14.6924 INFO:tensorflow:global_step/sec: 14.3516 2021-11-27 21:34:25,007 [INFO] tensorflow: global_step/sec: 14.3516 INFO:tensorflow:global_step/sec: 13.0972 2021-11-27 21:34:25,160 [INFO] tensorflow: global_step/sec: 13.0972 2021-11-27 21:34:25,161 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 73/120: loss: 0.00124 learning rate: 0.00050 Time taken: 0:00:01.513754 ETA: 0:01:11.146455 INFO:tensorflow:global_step/sec: 13.6495 2021-11-27 21:34:25,306 [INFO] tensorflow: global_step/sec: 13.6495 INFO:tensorflow:global_step/sec: 14.3687 2021-11-27 21:34:25,445 [INFO] tensorflow: global_step/sec: 14.3687 INFO:tensorflow:global_step/sec: 14.519 2021-11-27 21:34:25,583 [INFO] tensorflow: global_step/sec: 14.519 INFO:tensorflow:epoch = 73.36363636363636, learning_rate = 0.00049999997, loss = 0.0014130131, step = 1614 (5.101 sec) 2021-11-27 21:34:25,716 [INFO] tensorflow: epoch = 73.36363636363636, learning_rate = 0.00049999997, loss = 0.0014130131, step = 1614 (5.101 sec) INFO:tensorflow:global_step/sec: 14.9241 2021-11-27 21:34:25,717 [INFO] tensorflow: global_step/sec: 14.9241 INFO:tensorflow:global_step/sec: 14.7477 2021-11-27 21:34:25,853 [INFO] tensorflow: global_step/sec: 14.7477 INFO:tensorflow:global_step/sec: 14.3344 2021-11-27 21:34:25,992 [INFO] tensorflow: global_step/sec: 14.3344 INFO:tensorflow:global_step/sec: 14.4996 2021-11-27 21:34:26,130 [INFO] tensorflow: global_step/sec: 14.4996 INFO:tensorflow:global_step/sec: 14.8608 2021-11-27 21:34:26,265 [INFO] tensorflow: global_step/sec: 14.8608 INFO:tensorflow:global_step/sec: 14.4108 2021-11-27 21:34:26,404 [INFO] tensorflow: global_step/sec: 14.4108 2021-11-27 21:34:26,404 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.381 INFO:tensorflow:global_step/sec: 14.2613 2021-11-27 21:34:26,544 [INFO] tensorflow: global_step/sec: 14.2613 INFO:tensorflow:global_step/sec: 13.998 2021-11-27 21:34:26,687 [INFO] tensorflow: global_step/sec: 13.998 2021-11-27 21:34:26,688 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 74/120: loss: 0.00122 learning rate: 0.00050 Time taken: 0:00:01.528346 ETA: 0:01:10.303919 INFO:tensorflow:global_step/sec: 14.2722 2021-11-27 21:34:26,827 [INFO] tensorflow: global_step/sec: 14.2722 INFO:tensorflow:global_step/sec: 14.412 2021-11-27 21:34:26,966 [INFO] tensorflow: global_step/sec: 14.412 INFO:tensorflow:global_step/sec: 14.3109 2021-11-27 21:34:27,105 [INFO] tensorflow: global_step/sec: 14.3109 INFO:tensorflow:global_step/sec: 14.6225 2021-11-27 21:34:27,242 [INFO] tensorflow: global_step/sec: 14.6225 INFO:tensorflow:global_step/sec: 14.0999 2021-11-27 21:34:27,384 [INFO] tensorflow: global_step/sec: 14.0999 INFO:tensorflow:global_step/sec: 14.8791 2021-11-27 21:34:27,518 [INFO] tensorflow: global_step/sec: 14.8791 INFO:tensorflow:global_step/sec: 14.4281 2021-11-27 21:34:27,657 [INFO] tensorflow: global_step/sec: 14.4281 INFO:tensorflow:global_step/sec: 14.3792 2021-11-27 21:34:27,796 [INFO] tensorflow: global_step/sec: 14.3792 INFO:tensorflow:global_step/sec: 15.1858 2021-11-27 21:34:27,928 [INFO] tensorflow: global_step/sec: 15.1858 INFO:tensorflow:global_step/sec: 14.9495 2021-11-27 21:34:28,062 [INFO] tensorflow: global_step/sec: 14.9495 2021-11-27 21:34:28,137 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.738 INFO:tensorflow:global_step/sec: 13.426 2021-11-27 21:34:28,211 [INFO] tensorflow: global_step/sec: 13.426 2021-11-27 21:34:28,212 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 75/120: loss: 0.00146 learning rate: 0.00050 Time taken: 0:00:01.515880 ETA: 0:01:08.214605 INFO:tensorflow:global_step/sec: 14.5916 2021-11-27 21:34:28,348 [INFO] tensorflow: global_step/sec: 14.5916 INFO:tensorflow:global_step/sec: 13.9949 2021-11-27 21:34:28,491 [INFO] tensorflow: global_step/sec: 13.9949 INFO:tensorflow:global_step/sec: 14.6617 2021-11-27 21:34:28,627 [INFO] tensorflow: global_step/sec: 14.6617 INFO:tensorflow:global_step/sec: 12.6905 2021-11-27 21:34:28,785 [INFO] tensorflow: global_step/sec: 12.6905 INFO:tensorflow:global_step/sec: 14.5777 2021-11-27 21:34:28,922 [INFO] tensorflow: global_step/sec: 14.5777 INFO:tensorflow:global_step/sec: 14.3469 2021-11-27 21:34:29,061 [INFO] tensorflow: global_step/sec: 14.3469 INFO:tensorflow:global_step/sec: 14.4457 2021-11-27 21:34:29,200 [INFO] tensorflow: global_step/sec: 14.4457 INFO:tensorflow:global_step/sec: 14.2087 2021-11-27 21:34:29,340 [INFO] tensorflow: global_step/sec: 14.2087 INFO:tensorflow:global_step/sec: 13.8875 2021-11-27 21:34:29,484 [INFO] tensorflow: global_step/sec: 13.8875 INFO:tensorflow:global_step/sec: 14.5319 2021-11-27 21:34:29,622 [INFO] tensorflow: global_step/sec: 14.5319 INFO:tensorflow:global_step/sec: 14.0259 2021-11-27 21:34:29,765 [INFO] tensorflow: global_step/sec: 14.0259 2021-11-27 21:34:29,766 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 76/120: loss: 0.00117 learning rate: 0.00050 Time taken: 0:00:01.555900 ETA: 0:01:08.459604 INFO:tensorflow:global_step/sec: 14.8202 2021-11-27 21:34:29,900 [INFO] tensorflow: global_step/sec: 14.8202 2021-11-27 21:34:29,900 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 56.760 INFO:tensorflow:global_step/sec: 14.9207 2021-11-27 21:34:30,034 [INFO] tensorflow: global_step/sec: 14.9207 INFO:tensorflow:global_step/sec: 14.5463 2021-11-27 21:34:30,171 [INFO] tensorflow: global_step/sec: 14.5463 INFO:tensorflow:global_step/sec: 14.4229 2021-11-27 21:34:30,310 [INFO] tensorflow: global_step/sec: 14.4229 INFO:tensorflow:global_step/sec: 14.949 2021-11-27 21:34:30,444 [INFO] tensorflow: global_step/sec: 14.949 INFO:tensorflow:global_step/sec: 14.6615 2021-11-27 21:34:30,580 [INFO] tensorflow: global_step/sec: 14.6615 INFO:tensorflow:global_step/sec: 15.0605 2021-11-27 21:34:30,713 [INFO] tensorflow: global_step/sec: 15.0605 INFO:tensorflow:epoch = 76.72727272727273, learning_rate = 0.00049999997, loss = 0.0012775091, step = 1688 (5.132 sec) 2021-11-27 21:34:30,848 [INFO] tensorflow: epoch = 76.72727272727273, learning_rate = 0.00049999997, loss = 0.0012775091, step = 1688 (5.132 sec) INFO:tensorflow:global_step/sec: 14.6622 2021-11-27 21:34:30,849 [INFO] tensorflow: global_step/sec: 14.6622 INFO:tensorflow:global_step/sec: 14.5107 2021-11-27 21:34:30,987 [INFO] tensorflow: global_step/sec: 14.5107 INFO:tensorflow:global_step/sec: 14.4567 2021-11-27 21:34:31,125 [INFO] tensorflow: global_step/sec: 14.4567 INFO:tensorflow:global_step/sec: 14.1026 2021-11-27 21:34:31,267 [INFO] tensorflow: global_step/sec: 14.1026 2021-11-27 21:34:31,268 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 77/120: loss: 0.00115 learning rate: 0.00050 Time taken: 0:00:01.501561 ETA: 0:01:04.567130 INFO:tensorflow:global_step/sec: 14.3782 2021-11-27 21:34:31,406 [INFO] tensorflow: global_step/sec: 14.3782 INFO:tensorflow:global_step/sec: 14.88 2021-11-27 21:34:31,541 [INFO] tensorflow: global_step/sec: 14.88 2021-11-27 21:34:31,606 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.644 INFO:tensorflow:global_step/sec: 15.1397 2021-11-27 21:34:31,673 [INFO] tensorflow: global_step/sec: 15.1397 INFO:tensorflow:global_step/sec: 13.9983 2021-11-27 21:34:31,816 [INFO] tensorflow: global_step/sec: 13.9983 INFO:tensorflow:global_step/sec: 14.7001 2021-11-27 21:34:31,952 [INFO] tensorflow: global_step/sec: 14.7001 INFO:tensorflow:global_step/sec: 14.054 2021-11-27 21:34:32,094 [INFO] tensorflow: global_step/sec: 14.054 INFO:tensorflow:global_step/sec: 14.7756 2021-11-27 21:34:32,229 [INFO] tensorflow: global_step/sec: 14.7756 INFO:tensorflow:global_step/sec: 14.2503 2021-11-27 21:34:32,370 [INFO] tensorflow: global_step/sec: 14.2503 INFO:tensorflow:global_step/sec: 14.7584 2021-11-27 21:34:32,505 [INFO] tensorflow: global_step/sec: 14.7584 INFO:tensorflow:global_step/sec: 14.4373 2021-11-27 21:34:32,644 [INFO] tensorflow: global_step/sec: 14.4373 INFO:tensorflow:global_step/sec: 13.5848 2021-11-27 21:34:32,791 [INFO] tensorflow: global_step/sec: 13.5848 2021-11-27 21:34:32,792 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 78/120: loss: 0.00139 learning rate: 0.00050 Time taken: 0:00:01.521880 ETA: 0:01:03.918946 INFO:tensorflow:global_step/sec: 14.8891 2021-11-27 21:34:32,925 [INFO] tensorflow: global_step/sec: 14.8891 INFO:tensorflow:global_step/sec: 14.9327 2021-11-27 21:34:33,059 [INFO] tensorflow: global_step/sec: 14.9327 INFO:tensorflow:global_step/sec: 14.9107 2021-11-27 21:34:33,193 [INFO] tensorflow: global_step/sec: 14.9107 INFO:tensorflow:global_step/sec: 14.9896 2021-11-27 21:34:33,327 [INFO] tensorflow: global_step/sec: 14.9896 2021-11-27 21:34:33,328 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.073 INFO:tensorflow:global_step/sec: 14.3774 2021-11-27 21:34:33,466 [INFO] tensorflow: global_step/sec: 14.3774 INFO:tensorflow:global_step/sec: 14.2351 2021-11-27 21:34:33,606 [INFO] tensorflow: global_step/sec: 14.2351 INFO:tensorflow:global_step/sec: 14.9278 2021-11-27 21:34:33,740 [INFO] tensorflow: global_step/sec: 14.9278 INFO:tensorflow:global_step/sec: 14.0899 2021-11-27 21:34:33,882 [INFO] tensorflow: global_step/sec: 14.0899 INFO:tensorflow:global_step/sec: 15.2613 2021-11-27 21:34:34,013 [INFO] tensorflow: global_step/sec: 15.2613 INFO:tensorflow:global_step/sec: 14.5882 2021-11-27 21:34:34,150 [INFO] tensorflow: global_step/sec: 14.5882 INFO:tensorflow:global_step/sec: 14.2557 2021-11-27 21:34:34,291 [INFO] tensorflow: global_step/sec: 14.2557 2021-11-27 21:34:34,292 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 79/120: loss: 0.00119 learning rate: 0.00050 Time taken: 0:00:01.498712 ETA: 0:01:01.447175 INFO:tensorflow:global_step/sec: 14.3685 2021-11-27 21:34:34,430 [INFO] tensorflow: global_step/sec: 14.3685 INFO:tensorflow:global_step/sec: 14.7481 2021-11-27 21:34:34,566 [INFO] tensorflow: global_step/sec: 14.7481 INFO:tensorflow:global_step/sec: 14.2165 2021-11-27 21:34:34,706 [INFO] tensorflow: global_step/sec: 14.2165 INFO:tensorflow:global_step/sec: 14.2292 2021-11-27 21:34:34,847 [INFO] tensorflow: global_step/sec: 14.2292 INFO:tensorflow:global_step/sec: 14.6549 2021-11-27 21:34:34,983 [INFO] tensorflow: global_step/sec: 14.6549 2021-11-27 21:34:35,053 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.972 INFO:tensorflow:global_step/sec: 14.3731 2021-11-27 21:34:35,122 [INFO] tensorflow: global_step/sec: 14.3731 INFO:tensorflow:global_step/sec: 14.8295 2021-11-27 21:34:35,257 [INFO] tensorflow: global_step/sec: 14.8295 INFO:tensorflow:global_step/sec: 14.4415 2021-11-27 21:34:35,396 [INFO] tensorflow: global_step/sec: 14.4415 INFO:tensorflow:global_step/sec: 14.2979 2021-11-27 21:34:35,536 [INFO] tensorflow: global_step/sec: 14.2979 INFO:tensorflow:global_step/sec: 14.9839 2021-11-27 21:34:35,669 [INFO] tensorflow: global_step/sec: 14.9839 INFO:tensorflow:Saving checkpoints for step-1760. 2021-11-27 21:34:35,736 [INFO] tensorflow: Saving checkpoints for step-1760. WARNING:tensorflow:Ignoring: /tmp/tmpekj3crvr; No such file or directory 2021-11-27 21:34:35,830 [WARNING] tensorflow: Ignoring: /tmp/tmpekj3crvr; No such file or directory 2021-11-27 21:34:38,126 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 1627/1627 [00:00<00:00, 24505.02it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 5925/5925 [00:00<00:00, 27407.25it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 906/906 [00:00<00:00, 23760.94it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 12133/12133 [00:00<00:00, 29910.78it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 1348/1348 [00:00<00:00, 24285.88it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 2479/2479 [00:00<00:00, 22614.22it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 9584/9584 [00:00<00:00, 44486.04it/s] Epoch 80/120 ========================= Validation cost: 0.000840 Mean average_precision (in %): 13.8389 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 11.8029 floor 0 palette 0.137305 pillar 18.2058 pushcart 0 rackframe 23.6567 rackshelf 43.7159 wall 27.0316 Median Inference Time: 0.008084 INFO:tensorflow:epoch = 80.0, learning_rate = 0.00049999997, loss = 0.0011845097, step = 1760 (13.873 sec) 2021-11-27 21:34:44,721 [INFO] tensorflow: epoch = 80.0, learning_rate = 0.00049999997, loss = 0.0011845097, step = 1760 (13.873 sec) INFO:tensorflow:global_step/sec: 0.220905 2021-11-27 21:34:44,723 [INFO] tensorflow: global_step/sec: 0.220905 2021-11-27 21:34:44,724 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 80/120: loss: 0.00118 learning rate: 0.00050 Time taken: 0:00:10.425916 ETA: 0:06:57.036638 INFO:tensorflow:global_step/sec: 14.2907 2021-11-27 21:34:44,863 [INFO] tensorflow: global_step/sec: 14.2907 INFO:tensorflow:global_step/sec: 14.0531 2021-11-27 21:34:45,005 [INFO] tensorflow: global_step/sec: 14.0531 INFO:tensorflow:global_step/sec: 14.8085 2021-11-27 21:34:45,140 [INFO] tensorflow: global_step/sec: 14.8085 INFO:tensorflow:global_step/sec: 14.7211 2021-11-27 21:34:45,276 [INFO] tensorflow: global_step/sec: 14.7211 INFO:tensorflow:global_step/sec: 14.6629 2021-11-27 21:34:45,412 [INFO] tensorflow: global_step/sec: 14.6629 INFO:tensorflow:global_step/sec: 14.6983 2021-11-27 21:34:45,548 [INFO] tensorflow: global_step/sec: 14.6983 INFO:tensorflow:global_step/sec: 15.3822 2021-11-27 21:34:45,678 [INFO] tensorflow: global_step/sec: 15.3822 2021-11-27 21:34:45,679 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 9.411 INFO:tensorflow:global_step/sec: 14.8743 2021-11-27 21:34:45,813 [INFO] tensorflow: global_step/sec: 14.8743 INFO:tensorflow:global_step/sec: 14.7434 2021-11-27 21:34:45,949 [INFO] tensorflow: global_step/sec: 14.7434 INFO:tensorflow:global_step/sec: 14.5496 2021-11-27 21:34:46,086 [INFO] tensorflow: global_step/sec: 14.5496 INFO:tensorflow:global_step/sec: 13.3026 2021-11-27 21:34:46,236 [INFO] tensorflow: global_step/sec: 13.3026 2021-11-27 21:34:46,238 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 81/120: loss: 0.00114 learning rate: 0.00050 Time taken: 0:00:01.513497 ETA: 0:00:59.026397 INFO:tensorflow:global_step/sec: 14.3686 2021-11-27 21:34:46,376 [INFO] tensorflow: global_step/sec: 14.3686 INFO:tensorflow:global_step/sec: 14.3921 2021-11-27 21:34:46,515 [INFO] tensorflow: global_step/sec: 14.3921 INFO:tensorflow:global_step/sec: 14.979 2021-11-27 21:34:46,648 [INFO] tensorflow: global_step/sec: 14.979 INFO:tensorflow:global_step/sec: 14.5853 2021-11-27 21:34:46,785 [INFO] tensorflow: global_step/sec: 14.5853 INFO:tensorflow:global_step/sec: 14.4833 2021-11-27 21:34:46,923 [INFO] tensorflow: global_step/sec: 14.4833 INFO:tensorflow:global_step/sec: 14.4501 2021-11-27 21:34:47,062 [INFO] tensorflow: global_step/sec: 14.4501 INFO:tensorflow:global_step/sec: 14.9246 2021-11-27 21:34:47,196 [INFO] tensorflow: global_step/sec: 14.9246 INFO:tensorflow:global_step/sec: 14.2703 2021-11-27 21:34:47,336 [INFO] tensorflow: global_step/sec: 14.2703 2021-11-27 21:34:47,405 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.979 INFO:tensorflow:global_step/sec: 14.1464 2021-11-27 21:34:47,477 [INFO] tensorflow: global_step/sec: 14.1464 INFO:tensorflow:global_step/sec: 15.0662 2021-11-27 21:34:47,610 [INFO] tensorflow: global_step/sec: 15.0662 INFO:tensorflow:global_step/sec: 13.8454 2021-11-27 21:34:47,754 [INFO] tensorflow: global_step/sec: 13.8454 2021-11-27 21:34:47,755 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 82/120: loss: 0.00141 learning rate: 0.00050 Time taken: 0:00:01.518401 ETA: 0:00:57.699225 INFO:tensorflow:global_step/sec: 14.2523 2021-11-27 21:34:47,895 [INFO] tensorflow: global_step/sec: 14.2523 INFO:tensorflow:global_step/sec: 15.1105 2021-11-27 21:34:48,027 [INFO] tensorflow: global_step/sec: 15.1105 INFO:tensorflow:global_step/sec: 14.1727 2021-11-27 21:34:48,168 [INFO] tensorflow: global_step/sec: 14.1727 INFO:tensorflow:global_step/sec: 14.8777 2021-11-27 21:34:48,303 [INFO] tensorflow: global_step/sec: 14.8777 INFO:tensorflow:global_step/sec: 14.8525 2021-11-27 21:34:48,437 [INFO] tensorflow: global_step/sec: 14.8525 INFO:tensorflow:global_step/sec: 14.8566 2021-11-27 21:34:48,572 [INFO] tensorflow: global_step/sec: 14.8566 INFO:tensorflow:global_step/sec: 14.4531 2021-11-27 21:34:48,710 [INFO] tensorflow: global_step/sec: 14.4531 INFO:tensorflow:global_step/sec: 14.6003 2021-11-27 21:34:48,847 [INFO] tensorflow: global_step/sec: 14.6003 INFO:tensorflow:global_step/sec: 15.058 2021-11-27 21:34:48,980 [INFO] tensorflow: global_step/sec: 15.058 INFO:tensorflow:global_step/sec: 14.7304 2021-11-27 21:34:49,116 [INFO] tensorflow: global_step/sec: 14.7304 2021-11-27 21:34:49,116 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.430 INFO:tensorflow:global_step/sec: 13.1519 2021-11-27 21:34:49,268 [INFO] tensorflow: global_step/sec: 13.1519 2021-11-27 21:34:49,269 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 83/120: loss: 0.00171 learning rate: 0.00050 Time taken: 0:00:01.513774 ETA: 0:00:56.009653 INFO:tensorflow:global_step/sec: 14.3226 2021-11-27 21:34:49,408 [INFO] tensorflow: global_step/sec: 14.3226 INFO:tensorflow:global_step/sec: 14.8665 2021-11-27 21:34:49,542 [INFO] tensorflow: global_step/sec: 14.8665 INFO:tensorflow:global_step/sec: 14.5181 2021-11-27 21:34:49,680 [INFO] tensorflow: global_step/sec: 14.5181 INFO:tensorflow:epoch = 83.36363636363636, learning_rate = 0.00049999997, loss = 0.0014218773, step = 1834 (5.094 sec) 2021-11-27 21:34:49,815 [INFO] tensorflow: epoch = 83.36363636363636, learning_rate = 0.00049999997, loss = 0.0014218773, step = 1834 (5.094 sec) INFO:tensorflow:global_step/sec: 14.6294 2021-11-27 21:34:49,817 [INFO] tensorflow: global_step/sec: 14.6294 INFO:tensorflow:global_step/sec: 14.379 2021-11-27 21:34:49,956 [INFO] tensorflow: global_step/sec: 14.379 INFO:tensorflow:global_step/sec: 14.461 2021-11-27 21:34:50,094 [INFO] tensorflow: global_step/sec: 14.461 INFO:tensorflow:global_step/sec: 15.2834 2021-11-27 21:34:50,225 [INFO] tensorflow: global_step/sec: 15.2834 INFO:tensorflow:global_step/sec: 13.7457 2021-11-27 21:34:50,370 [INFO] tensorflow: global_step/sec: 13.7457 INFO:tensorflow:global_step/sec: 14.677 2021-11-27 21:34:50,507 [INFO] tensorflow: global_step/sec: 14.677 INFO:tensorflow:global_step/sec: 13.8616 2021-11-27 21:34:50,651 [INFO] tensorflow: global_step/sec: 13.8616 INFO:tensorflow:global_step/sec: 13.7561 2021-11-27 21:34:50,796 [INFO] tensorflow: global_step/sec: 13.7561 2021-11-27 21:34:50,798 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 84/120: loss: 0.00156 learning rate: 0.00050 Time taken: 0:00:01.524529 ETA: 0:00:54.883026 2021-11-27 21:34:50,863 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.268 INFO:tensorflow:global_step/sec: 14.2628 2021-11-27 21:34:50,937 [INFO] tensorflow: global_step/sec: 14.2628 INFO:tensorflow:global_step/sec: 14.663 2021-11-27 21:34:51,073 [INFO] tensorflow: global_step/sec: 14.663 INFO:tensorflow:global_step/sec: 14.3061 2021-11-27 21:34:51,213 [INFO] tensorflow: global_step/sec: 14.3061 INFO:tensorflow:global_step/sec: 15.0433 2021-11-27 21:34:51,346 [INFO] tensorflow: global_step/sec: 15.0433 INFO:tensorflow:global_step/sec: 15.1654 2021-11-27 21:34:51,478 [INFO] tensorflow: global_step/sec: 15.1654 INFO:tensorflow:global_step/sec: 14.5132 2021-11-27 21:34:51,615 [INFO] tensorflow: global_step/sec: 14.5132 INFO:tensorflow:global_step/sec: 14.744 2021-11-27 21:34:51,751 [INFO] tensorflow: global_step/sec: 14.744 INFO:tensorflow:global_step/sec: 14.5801 2021-11-27 21:34:51,888 [INFO] tensorflow: global_step/sec: 14.5801 INFO:tensorflow:global_step/sec: 14.4494 2021-11-27 21:34:52,027 [INFO] tensorflow: global_step/sec: 14.4494 INFO:tensorflow:global_step/sec: 14.5113 2021-11-27 21:34:52,164 [INFO] tensorflow: global_step/sec: 14.5113 INFO:tensorflow:global_step/sec: 13.8281 2021-11-27 21:34:52,309 [INFO] tensorflow: global_step/sec: 13.8281 2021-11-27 21:34:52,310 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 85/120: loss: 0.00105 learning rate: 0.00044 Time taken: 0:00:01.513268 ETA: 0:00:52.964396 INFO:tensorflow:global_step/sec: 15.1926 2021-11-27 21:34:52,441 [INFO] tensorflow: global_step/sec: 15.1926 INFO:tensorflow:global_step/sec: 14.6098 2021-11-27 21:34:52,578 [INFO] tensorflow: global_step/sec: 14.6098 2021-11-27 21:34:52,578 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.308 INFO:tensorflow:global_step/sec: 14.4815 2021-11-27 21:34:52,716 [INFO] tensorflow: global_step/sec: 14.4815 INFO:tensorflow:global_step/sec: 14.1837 2021-11-27 21:34:52,857 [INFO] tensorflow: global_step/sec: 14.1837 INFO:tensorflow:global_step/sec: 14.6783 2021-11-27 21:34:52,993 [INFO] tensorflow: global_step/sec: 14.6783 INFO:tensorflow:global_step/sec: 14.2366 2021-11-27 21:34:53,133 [INFO] tensorflow: global_step/sec: 14.2366 INFO:tensorflow:global_step/sec: 15.2271 2021-11-27 21:34:53,265 [INFO] tensorflow: global_step/sec: 15.2271 INFO:tensorflow:global_step/sec: 14.6873 2021-11-27 21:34:53,401 [INFO] tensorflow: global_step/sec: 14.6873 INFO:tensorflow:global_step/sec: 14.457 2021-11-27 21:34:53,539 [INFO] tensorflow: global_step/sec: 14.457 INFO:tensorflow:global_step/sec: 15.2939 2021-11-27 21:34:53,670 [INFO] tensorflow: global_step/sec: 15.2939 INFO:tensorflow:global_step/sec: 13.6832 2021-11-27 21:34:53,816 [INFO] tensorflow: global_step/sec: 13.6832 2021-11-27 21:34:53,817 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 86/120: loss: 0.00135 learning rate: 0.00039 Time taken: 0:00:01.503986 ETA: 0:00:51.135512 INFO:tensorflow:global_step/sec: 13.9949 2021-11-27 21:34:53,959 [INFO] tensorflow: global_step/sec: 13.9949 INFO:tensorflow:global_step/sec: 14.6031 2021-11-27 21:34:54,096 [INFO] tensorflow: global_step/sec: 14.6031 INFO:tensorflow:global_step/sec: 15.2417 2021-11-27 21:34:54,227 [INFO] tensorflow: global_step/sec: 15.2417 2021-11-27 21:34:54,295 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.279 INFO:tensorflow:global_step/sec: 14.8025 2021-11-27 21:34:54,362 [INFO] tensorflow: global_step/sec: 14.8025 INFO:tensorflow:global_step/sec: 14.5147 2021-11-27 21:34:54,500 [INFO] tensorflow: global_step/sec: 14.5147 INFO:tensorflow:global_step/sec: 14.8458 2021-11-27 21:34:54,635 [INFO] tensorflow: global_step/sec: 14.8458 INFO:tensorflow:global_step/sec: 14.0443 2021-11-27 21:34:54,777 [INFO] tensorflow: global_step/sec: 14.0443 INFO:tensorflow:epoch = 86.72727272727273, learning_rate = 0.00035274026, loss = 0.0015209467, step = 1908 (5.102 sec) 2021-11-27 21:34:54,918 [INFO] tensorflow: epoch = 86.72727272727273, learning_rate = 0.00035274026, loss = 0.0015209467, step = 1908 (5.102 sec) INFO:tensorflow:global_step/sec: 14.118 2021-11-27 21:34:54,919 [INFO] tensorflow: global_step/sec: 14.118 INFO:tensorflow:global_step/sec: 14.1637 2021-11-27 21:34:55,060 [INFO] tensorflow: global_step/sec: 14.1637 INFO:tensorflow:global_step/sec: 15.1012 2021-11-27 21:34:55,193 [INFO] tensorflow: global_step/sec: 15.1012 INFO:tensorflow:global_step/sec: 14.113 2021-11-27 21:34:55,334 [INFO] tensorflow: global_step/sec: 14.113 2021-11-27 21:34:55,336 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 87/120: loss: 0.00118 learning rate: 0.00034 Time taken: 0:00:01.517369 ETA: 0:00:50.073178 INFO:tensorflow:global_step/sec: 14.3843 2021-11-27 21:34:55,473 [INFO] tensorflow: global_step/sec: 14.3843 INFO:tensorflow:global_step/sec: 14.3993 2021-11-27 21:34:55,612 [INFO] tensorflow: global_step/sec: 14.3993 INFO:tensorflow:global_step/sec: 14.8829 2021-11-27 21:34:55,747 [INFO] tensorflow: global_step/sec: 14.8829 INFO:tensorflow:global_step/sec: 14.4747 2021-11-27 21:34:55,885 [INFO] tensorflow: global_step/sec: 14.4747 INFO:tensorflow:global_step/sec: 14.7838 2021-11-27 21:34:56,020 [INFO] tensorflow: global_step/sec: 14.7838 2021-11-27 21:34:56,021 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.935 INFO:tensorflow:global_step/sec: 14.9223 2021-11-27 21:34:56,154 [INFO] tensorflow: global_step/sec: 14.9223 INFO:tensorflow:global_step/sec: 14.0139 2021-11-27 21:34:56,297 [INFO] tensorflow: global_step/sec: 14.0139 INFO:tensorflow:global_step/sec: 14.3331 2021-11-27 21:34:56,436 [INFO] tensorflow: global_step/sec: 14.3331 INFO:tensorflow:global_step/sec: 14.0461 2021-11-27 21:34:56,579 [INFO] tensorflow: global_step/sec: 14.0461 INFO:tensorflow:global_step/sec: 14.122 2021-11-27 21:34:56,720 [INFO] tensorflow: global_step/sec: 14.122 INFO:tensorflow:global_step/sec: 13.6772 2021-11-27 21:34:56,867 [INFO] tensorflow: global_step/sec: 13.6772 2021-11-27 21:34:56,868 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 88/120: loss: 0.00126 learning rate: 0.00030 Time taken: 0:00:01.529029 ETA: 0:00:48.928925 INFO:tensorflow:global_step/sec: 14.526 2021-11-27 21:34:57,004 [INFO] tensorflow: global_step/sec: 14.526 INFO:tensorflow:global_step/sec: 14.7041 2021-11-27 21:34:57,140 [INFO] tensorflow: global_step/sec: 14.7041 INFO:tensorflow:global_step/sec: 14.6253 2021-11-27 21:34:57,277 [INFO] tensorflow: global_step/sec: 14.6253 INFO:tensorflow:global_step/sec: 15.0615 2021-11-27 21:34:57,410 [INFO] tensorflow: global_step/sec: 15.0615 INFO:tensorflow:global_step/sec: 15.1054 2021-11-27 21:34:57,542 [INFO] tensorflow: global_step/sec: 15.1054 INFO:tensorflow:global_step/sec: 14.7487 2021-11-27 21:34:57,678 [INFO] tensorflow: global_step/sec: 14.7487 2021-11-27 21:34:57,745 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.002 INFO:tensorflow:global_step/sec: 14.3573 2021-11-27 21:34:57,817 [INFO] tensorflow: global_step/sec: 14.3573 INFO:tensorflow:global_step/sec: 14.3066 2021-11-27 21:34:57,957 [INFO] tensorflow: global_step/sec: 14.3066 INFO:tensorflow:global_step/sec: 14.4128 2021-11-27 21:34:58,096 [INFO] tensorflow: global_step/sec: 14.4128 INFO:tensorflow:global_step/sec: 14.5603 2021-11-27 21:34:58,233 [INFO] tensorflow: global_step/sec: 14.5603 INFO:tensorflow:global_step/sec: 14.186 2021-11-27 21:34:58,374 [INFO] tensorflow: global_step/sec: 14.186 2021-11-27 21:34:58,375 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 89/120: loss: 0.00119 learning rate: 0.00026 Time taken: 0:00:01.506305 ETA: 0:00:46.695454 INFO:tensorflow:global_step/sec: 14.9008 2021-11-27 21:34:58,508 [INFO] tensorflow: global_step/sec: 14.9008 INFO:tensorflow:global_step/sec: 14.5099 2021-11-27 21:34:58,646 [INFO] tensorflow: global_step/sec: 14.5099 INFO:tensorflow:global_step/sec: 14.4364 2021-11-27 21:34:58,785 [INFO] tensorflow: global_step/sec: 14.4364 INFO:tensorflow:global_step/sec: 14.6457 2021-11-27 21:34:58,921 [INFO] tensorflow: global_step/sec: 14.6457 INFO:tensorflow:global_step/sec: 14.1405 2021-11-27 21:34:59,063 [INFO] tensorflow: global_step/sec: 14.1405 INFO:tensorflow:global_step/sec: 14.0703 2021-11-27 21:34:59,205 [INFO] tensorflow: global_step/sec: 14.0703 INFO:tensorflow:global_step/sec: 14.4632 2021-11-27 21:34:59,343 [INFO] tensorflow: global_step/sec: 14.4632 INFO:tensorflow:global_step/sec: 14.4054 2021-11-27 21:34:59,482 [INFO] tensorflow: global_step/sec: 14.4054 2021-11-27 21:34:59,483 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.577 INFO:tensorflow:global_step/sec: 14.6121 2021-11-27 21:34:59,619 [INFO] tensorflow: global_step/sec: 14.6121 INFO:tensorflow:global_step/sec: 15.0874 2021-11-27 21:34:59,751 [INFO] tensorflow: global_step/sec: 15.0874 INFO:tensorflow:Saving checkpoints for step-1980. 2021-11-27 21:34:59,817 [INFO] tensorflow: Saving checkpoints for step-1980. WARNING:tensorflow:Ignoring: /tmp/tmp3pkl2y1h; No such file or directory 2021-11-27 21:34:59,912 [WARNING] tensorflow: Ignoring: /tmp/tmp3pkl2y1h; No such file or directory 2021-11-27 21:35:02,234 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 1647/1647 [00:00<00:00, 24082.34it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 5875/5875 [00:00<00:00, 27444.22it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 763/763 [00:00<00:00, 24181.70it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 11353/11353 [00:00<00:00, 31859.56it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 841/841 [00:00<00:00, 25584.48it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 1649/1649 [00:00<00:00, 24725.47it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 9459/9459 [00:00<00:00, 46659.50it/s] Epoch 90/120 ========================= Validation cost: 0.000776 Mean average_precision (in %): 13.8909 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 12.5771 floor 0 palette 0.441823 pillar 29.1041 pushcart 0 rackframe 21.7961 rackshelf 37.7476 wall 23.3511 Median Inference Time: 0.008147 INFO:tensorflow:epoch = 90.0, learning_rate = 0.00023207937, loss = 0.0013222524, step = 1980 (13.464 sec) 2021-11-27 21:35:08,382 [INFO] tensorflow: epoch = 90.0, learning_rate = 0.00023207937, loss = 0.0013222524, step = 1980 (13.464 sec) INFO:tensorflow:global_step/sec: 0.231708 2021-11-27 21:35:08,383 [INFO] tensorflow: global_step/sec: 0.231708 2021-11-27 21:35:08,384 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 90/120: loss: 0.00132 learning rate: 0.00023 Time taken: 0:00:10.008223 ETA: 0:05:00.246699 INFO:tensorflow:global_step/sec: 14.7286 2021-11-27 21:35:08,519 [INFO] tensorflow: global_step/sec: 14.7286 INFO:tensorflow:global_step/sec: 14.8704 2021-11-27 21:35:08,653 [INFO] tensorflow: global_step/sec: 14.8704 INFO:tensorflow:global_step/sec: 14.237 2021-11-27 21:35:08,794 [INFO] tensorflow: global_step/sec: 14.237 INFO:tensorflow:global_step/sec: 14.3318 2021-11-27 21:35:08,933 [INFO] tensorflow: global_step/sec: 14.3318 INFO:tensorflow:global_step/sec: 14.9688 2021-11-27 21:35:09,067 [INFO] tensorflow: global_step/sec: 14.9688 INFO:tensorflow:global_step/sec: 14.7558 2021-11-27 21:35:09,202 [INFO] tensorflow: global_step/sec: 14.7558 INFO:tensorflow:global_step/sec: 14.8532 2021-11-27 21:35:09,337 [INFO] tensorflow: global_step/sec: 14.8532 INFO:tensorflow:global_step/sec: 14.9078 2021-11-27 21:35:09,471 [INFO] tensorflow: global_step/sec: 14.9078 INFO:tensorflow:global_step/sec: 14.9954 2021-11-27 21:35:09,605 [INFO] tensorflow: global_step/sec: 14.9954 2021-11-27 21:35:09,682 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 9.805 INFO:tensorflow:global_step/sec: 13.7895 2021-11-27 21:35:09,750 [INFO] tensorflow: global_step/sec: 13.7895 INFO:tensorflow:global_step/sec: 14.0646 2021-11-27 21:35:09,892 [INFO] tensorflow: global_step/sec: 14.0646 2021-11-27 21:35:09,892 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 91/120: loss: 0.00137 learning rate: 0.00020 Time taken: 0:00:01.505357 ETA: 0:00:43.655340 INFO:tensorflow:global_step/sec: 13.7243 2021-11-27 21:35:10,038 [INFO] tensorflow: global_step/sec: 13.7243 INFO:tensorflow:global_step/sec: 14.1102 2021-11-27 21:35:10,179 [INFO] tensorflow: global_step/sec: 14.1102 INFO:tensorflow:global_step/sec: 14.4371 2021-11-27 21:35:10,318 [INFO] tensorflow: global_step/sec: 14.4371 INFO:tensorflow:global_step/sec: 14.5002 2021-11-27 21:35:10,456 [INFO] tensorflow: global_step/sec: 14.5002 INFO:tensorflow:global_step/sec: 14.7695 2021-11-27 21:35:10,591 [INFO] tensorflow: global_step/sec: 14.7695 INFO:tensorflow:global_step/sec: 14.7612 2021-11-27 21:35:10,727 [INFO] tensorflow: global_step/sec: 14.7612 INFO:tensorflow:global_step/sec: 14.4225 2021-11-27 21:35:10,865 [INFO] tensorflow: global_step/sec: 14.4225 INFO:tensorflow:global_step/sec: 14.1809 2021-11-27 21:35:11,006 [INFO] tensorflow: global_step/sec: 14.1809 INFO:tensorflow:global_step/sec: 14.3277 2021-11-27 21:35:11,146 [INFO] tensorflow: global_step/sec: 14.3277 INFO:tensorflow:global_step/sec: 14.7207 2021-11-27 21:35:11,282 [INFO] tensorflow: global_step/sec: 14.7207 INFO:tensorflow:global_step/sec: 13.8577 2021-11-27 21:35:11,426 [INFO] tensorflow: global_step/sec: 13.8577 2021-11-27 21:35:11,427 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 92/120: loss: 0.00125 learning rate: 0.00018 Time taken: 0:00:01.534882 ETA: 0:00:42.976698 2021-11-27 21:35:11,427 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.297 INFO:tensorflow:global_step/sec: 14.1337 2021-11-27 21:35:11,568 [INFO] tensorflow: global_step/sec: 14.1337 INFO:tensorflow:global_step/sec: 14.4379 2021-11-27 21:35:11,706 [INFO] tensorflow: global_step/sec: 14.4379 INFO:tensorflow:global_step/sec: 14.5835 2021-11-27 21:35:11,843 [INFO] tensorflow: global_step/sec: 14.5835 INFO:tensorflow:global_step/sec: 14.5368 2021-11-27 21:35:11,981 [INFO] tensorflow: global_step/sec: 14.5368 INFO:tensorflow:global_step/sec: 14.039 2021-11-27 21:35:12,123 [INFO] tensorflow: global_step/sec: 14.039 INFO:tensorflow:global_step/sec: 14.961 2021-11-27 21:35:12,257 [INFO] tensorflow: global_step/sec: 14.961 INFO:tensorflow:global_step/sec: 14.8857 2021-11-27 21:35:12,391 [INFO] tensorflow: global_step/sec: 14.8857 INFO:tensorflow:global_step/sec: 14.3697 2021-11-27 21:35:12,531 [INFO] tensorflow: global_step/sec: 14.3697 INFO:tensorflow:global_step/sec: 14.7029 2021-11-27 21:35:12,667 [INFO] tensorflow: global_step/sec: 14.7029 INFO:tensorflow:global_step/sec: 13.7024 2021-11-27 21:35:12,813 [INFO] tensorflow: global_step/sec: 13.7024 INFO:tensorflow:global_step/sec: 14.0539 2021-11-27 21:35:12,955 [INFO] tensorflow: global_step/sec: 14.0539 2021-11-27 21:35:12,956 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 93/120: loss: 0.00135 learning rate: 0.00016 Time taken: 0:00:01.524205 ETA: 0:00:41.153541 INFO:tensorflow:global_step/sec: 14.6214 2021-11-27 21:35:13,092 [INFO] tensorflow: global_step/sec: 14.6214 2021-11-27 21:35:13,157 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.841 INFO:tensorflow:global_step/sec: 14.991 2021-11-27 21:35:13,225 [INFO] tensorflow: global_step/sec: 14.991 INFO:tensorflow:global_step/sec: 15.045 2021-11-27 21:35:13,358 [INFO] tensorflow: global_step/sec: 15.045 INFO:tensorflow:epoch = 93.36363636363636, learning_rate = 0.00015092737, loss = 0.0013996409, step = 2054 (5.109 sec) 2021-11-27 21:35:13,491 [INFO] tensorflow: epoch = 93.36363636363636, learning_rate = 0.00015092737, loss = 0.0013996409, step = 2054 (5.109 sec) INFO:tensorflow:global_step/sec: 14.8748 2021-11-27 21:35:13,492 [INFO] tensorflow: global_step/sec: 14.8748 INFO:tensorflow:global_step/sec: 15.429 2021-11-27 21:35:13,622 [INFO] tensorflow: global_step/sec: 15.429 INFO:tensorflow:global_step/sec: 14.8657 2021-11-27 21:35:13,757 [INFO] tensorflow: global_step/sec: 14.8657 INFO:tensorflow:global_step/sec: 14.5304 2021-11-27 21:35:13,894 [INFO] tensorflow: global_step/sec: 14.5304 INFO:tensorflow:global_step/sec: 15.2951 2021-11-27 21:35:14,025 [INFO] tensorflow: global_step/sec: 15.2951 INFO:tensorflow:global_step/sec: 15.1826 2021-11-27 21:35:14,157 [INFO] tensorflow: global_step/sec: 15.1826 INFO:tensorflow:global_step/sec: 14.2937 2021-11-27 21:35:14,297 [INFO] tensorflow: global_step/sec: 14.2937 INFO:tensorflow:global_step/sec: 13.9578 2021-11-27 21:35:14,440 [INFO] tensorflow: global_step/sec: 13.9578 2021-11-27 21:35:14,441 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 94/120: loss: 0.00135 learning rate: 0.00014 Time taken: 0:00:01.479801 ETA: 0:00:38.474837 INFO:tensorflow:global_step/sec: 14.8581 2021-11-27 21:35:14,575 [INFO] tensorflow: global_step/sec: 14.8581 INFO:tensorflow:global_step/sec: 14.3782 2021-11-27 21:35:14,714 [INFO] tensorflow: global_step/sec: 14.3782 INFO:tensorflow:global_step/sec: 15.0407 2021-11-27 21:35:14,847 [INFO] tensorflow: global_step/sec: 15.0407 2021-11-27 21:35:14,848 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.153 INFO:tensorflow:global_step/sec: 14.9827 2021-11-27 21:35:14,980 [INFO] tensorflow: global_step/sec: 14.9827 INFO:tensorflow:global_step/sec: 14.7556 2021-11-27 21:35:15,116 [INFO] tensorflow: global_step/sec: 14.7556 INFO:tensorflow:global_step/sec: 15.1277 2021-11-27 21:35:15,248 [INFO] tensorflow: global_step/sec: 15.1277 INFO:tensorflow:global_step/sec: 14.8112 2021-11-27 21:35:15,383 [INFO] tensorflow: global_step/sec: 14.8112 INFO:tensorflow:global_step/sec: 15.1719 2021-11-27 21:35:15,515 [INFO] tensorflow: global_step/sec: 15.1719 INFO:tensorflow:global_step/sec: 14.2263 2021-11-27 21:35:15,655 [INFO] tensorflow: global_step/sec: 14.2263 INFO:tensorflow:global_step/sec: 14.8977 2021-11-27 21:35:15,790 [INFO] tensorflow: global_step/sec: 14.8977 INFO:tensorflow:global_step/sec: 13.9151 2021-11-27 21:35:15,933 [INFO] tensorflow: global_step/sec: 13.9151 2021-11-27 21:35:15,934 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 95/120: loss: 0.00113 learning rate: 0.00012 Time taken: 0:00:01.496423 ETA: 0:00:37.410563 INFO:tensorflow:global_step/sec: 14.3405 2021-11-27 21:35:16,073 [INFO] tensorflow: global_step/sec: 14.3405 INFO:tensorflow:global_step/sec: 14.9439 2021-11-27 21:35:16,207 [INFO] tensorflow: global_step/sec: 14.9439 INFO:tensorflow:global_step/sec: 15.0325 2021-11-27 21:35:16,340 [INFO] tensorflow: global_step/sec: 15.0325 INFO:tensorflow:global_step/sec: 14.7437 2021-11-27 21:35:16,475 [INFO] tensorflow: global_step/sec: 14.7437 2021-11-27 21:35:16,540 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.093 INFO:tensorflow:global_step/sec: 14.5183 2021-11-27 21:35:16,613 [INFO] tensorflow: global_step/sec: 14.5183 INFO:tensorflow:global_step/sec: 14.6761 2021-11-27 21:35:16,749 [INFO] tensorflow: global_step/sec: 14.6761 INFO:tensorflow:global_step/sec: 14.2031 2021-11-27 21:35:16,890 [INFO] tensorflow: global_step/sec: 14.2031 INFO:tensorflow:global_step/sec: 15.091 2021-11-27 21:35:17,023 [INFO] tensorflow: global_step/sec: 15.091 INFO:tensorflow:global_step/sec: 14.4802 2021-11-27 21:35:17,161 [INFO] tensorflow: global_step/sec: 14.4802 INFO:tensorflow:global_step/sec: 14.8266 2021-11-27 21:35:17,296 [INFO] tensorflow: global_step/sec: 14.8266 INFO:tensorflow:global_step/sec: 13.8621 2021-11-27 21:35:17,440 [INFO] tensorflow: global_step/sec: 13.8621 2021-11-27 21:35:17,441 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 96/120: loss: 0.00121 learning rate: 0.00011 Time taken: 0:00:01.506193 ETA: 0:00:36.148630 INFO:tensorflow:global_step/sec: 14.4166 2021-11-27 21:35:17,579 [INFO] tensorflow: global_step/sec: 14.4166 INFO:tensorflow:global_step/sec: 14.8186 2021-11-27 21:35:17,714 [INFO] tensorflow: global_step/sec: 14.8186 INFO:tensorflow:global_step/sec: 14.0358 2021-11-27 21:35:17,856 [INFO] tensorflow: global_step/sec: 14.0358 INFO:tensorflow:global_step/sec: 14.5551 2021-11-27 21:35:17,994 [INFO] tensorflow: global_step/sec: 14.5551 INFO:tensorflow:global_step/sec: 14.868 2021-11-27 21:35:18,128 [INFO] tensorflow: global_step/sec: 14.868 INFO:tensorflow:global_step/sec: 14.9172 2021-11-27 21:35:18,262 [INFO] tensorflow: global_step/sec: 14.9172 2021-11-27 21:35:18,263 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.060 INFO:tensorflow:global_step/sec: 14.5207 2021-11-27 21:35:18,400 [INFO] tensorflow: global_step/sec: 14.5207 INFO:tensorflow:global_step/sec: 14.3903 2021-11-27 21:35:18,539 [INFO] tensorflow: global_step/sec: 14.3903 INFO:tensorflow:epoch = 96.77272727272728, learning_rate = 9.7583026e-05, loss = 0.0013394309, step = 2129 (5.117 sec) 2021-11-27 21:35:18,609 [INFO] tensorflow: epoch = 96.77272727272728, learning_rate = 9.7583026e-05, loss = 0.0013394309, step = 2129 (5.117 sec) INFO:tensorflow:global_step/sec: 14.5563 2021-11-27 21:35:18,676 [INFO] tensorflow: global_step/sec: 14.5563 INFO:tensorflow:global_step/sec: 14.7789 2021-11-27 21:35:18,812 [INFO] tensorflow: global_step/sec: 14.7789 INFO:tensorflow:global_step/sec: 14.0031 2021-11-27 21:35:18,954 [INFO] tensorflow: global_step/sec: 14.0031 2021-11-27 21:35:18,956 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 97/120: loss: 0.00141 learning rate: 0.00009 Time taken: 0:00:01.512452 ETA: 0:00:34.786388 INFO:tensorflow:global_step/sec: 14.9382 2021-11-27 21:35:19,088 [INFO] tensorflow: global_step/sec: 14.9382 INFO:tensorflow:global_step/sec: 15.3043 2021-11-27 21:35:19,219 [INFO] tensorflow: global_step/sec: 15.3043 INFO:tensorflow:global_step/sec: 14.5213 2021-11-27 21:35:19,357 [INFO] tensorflow: global_step/sec: 14.5213 INFO:tensorflow:global_step/sec: 13.9693 2021-11-27 21:35:19,500 [INFO] tensorflow: global_step/sec: 13.9693 INFO:tensorflow:global_step/sec: 14.5096 2021-11-27 21:35:19,638 [INFO] tensorflow: global_step/sec: 14.5096 INFO:tensorflow:global_step/sec: 14.6345 2021-11-27 21:35:19,774 [INFO] tensorflow: global_step/sec: 14.6345 INFO:tensorflow:global_step/sec: 14.7515 2021-11-27 21:35:19,910 [INFO] tensorflow: global_step/sec: 14.7515 2021-11-27 21:35:19,978 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.330 INFO:tensorflow:global_step/sec: 14.5179 2021-11-27 21:35:20,048 [INFO] tensorflow: global_step/sec: 14.5179 INFO:tensorflow:global_step/sec: 14.4686 2021-11-27 21:35:20,186 [INFO] tensorflow: global_step/sec: 14.4686 INFO:tensorflow:global_step/sec: 13.6545 2021-11-27 21:35:20,332 [INFO] tensorflow: global_step/sec: 13.6545 INFO:tensorflow:global_step/sec: 13.7842 2021-11-27 21:35:20,478 [INFO] tensorflow: global_step/sec: 13.7842 2021-11-27 21:35:20,479 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 98/120: loss: 0.00117 learning rate: 0.00008 Time taken: 0:00:01.519034 ETA: 0:00:33.418756 INFO:tensorflow:global_step/sec: 14.7348 2021-11-27 21:35:20,613 [INFO] tensorflow: global_step/sec: 14.7348 INFO:tensorflow:global_step/sec: 13.7975 2021-11-27 21:35:20,758 [INFO] tensorflow: global_step/sec: 13.7975 INFO:tensorflow:global_step/sec: 14.1297 2021-11-27 21:35:20,900 [INFO] tensorflow: global_step/sec: 14.1297 INFO:tensorflow:global_step/sec: 14.7217 2021-11-27 21:35:21,036 [INFO] tensorflow: global_step/sec: 14.7217 INFO:tensorflow:global_step/sec: 14.2836 2021-11-27 21:35:21,176 [INFO] tensorflow: global_step/sec: 14.2836 INFO:tensorflow:global_step/sec: 14.0326 2021-11-27 21:35:21,318 [INFO] tensorflow: global_step/sec: 14.0326 INFO:tensorflow:global_step/sec: 14.2434 2021-11-27 21:35:21,459 [INFO] tensorflow: global_step/sec: 14.2434 INFO:tensorflow:global_step/sec: 14.3313 2021-11-27 21:35:21,598 [INFO] tensorflow: global_step/sec: 14.3313 INFO:tensorflow:global_step/sec: 14.5912 2021-11-27 21:35:21,735 [INFO] tensorflow: global_step/sec: 14.5912 2021-11-27 21:35:21,736 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 56.877 INFO:tensorflow:global_step/sec: 15.0834 2021-11-27 21:35:21,868 [INFO] tensorflow: global_step/sec: 15.0834 INFO:tensorflow:global_step/sec: 13.3732 2021-11-27 21:35:22,017 [INFO] tensorflow: global_step/sec: 13.3732 2021-11-27 21:35:22,018 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 99/120: loss: 0.00128 learning rate: 0.00007 Time taken: 0:00:01.537152 ETA: 0:00:32.280188 INFO:tensorflow:global_step/sec: 14.1282 2021-11-27 21:35:22,159 [INFO] tensorflow: global_step/sec: 14.1282 INFO:tensorflow:global_step/sec: 13.4403 2021-11-27 21:35:22,308 [INFO] tensorflow: global_step/sec: 13.4403 INFO:tensorflow:global_step/sec: 14.0766 2021-11-27 21:35:22,450 [INFO] tensorflow: global_step/sec: 14.0766 INFO:tensorflow:global_step/sec: 14.4103 2021-11-27 21:35:22,589 [INFO] tensorflow: global_step/sec: 14.4103 INFO:tensorflow:global_step/sec: 14.6719 2021-11-27 21:35:22,725 [INFO] tensorflow: global_step/sec: 14.6719 INFO:tensorflow:global_step/sec: 14.4152 2021-11-27 21:35:22,864 [INFO] tensorflow: global_step/sec: 14.4152 INFO:tensorflow:global_step/sec: 15.1272 2021-11-27 21:35:22,996 [INFO] tensorflow: global_step/sec: 15.1272 INFO:tensorflow:global_step/sec: 14.5333 2021-11-27 21:35:23,133 [INFO] tensorflow: global_step/sec: 14.5333 INFO:tensorflow:global_step/sec: 14.3483 2021-11-27 21:35:23,273 [INFO] tensorflow: global_step/sec: 14.3483 INFO:tensorflow:global_step/sec: 14.3102 2021-11-27 21:35:23,413 [INFO] tensorflow: global_step/sec: 14.3102 INFO:tensorflow:Saving checkpoints for step-2200. 2021-11-27 21:35:23,480 [INFO] tensorflow: Saving checkpoints for step-2200. WARNING:tensorflow:Ignoring: /tmp/tmp8a1h3_i_; No such file or directory 2021-11-27 21:35:23,575 [WARNING] tensorflow: Ignoring: /tmp/tmp8a1h3_i_; No such file or directory 2021-11-27 21:35:25,910 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 1822/1822 [00:00<00:00, 22950.88it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 5876/5876 [00:00<00:00, 27574.04it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 806/806 [00:00<00:00, 24645.58it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 11124/11124 [00:00<00:00, 30912.46it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 799/799 [00:00<00:00, 23863.01it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 1690/1690 [00:00<00:00, 23003.97it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 9019/9019 [00:00<00:00, 39716.72it/s] Epoch 100/120 ========================= Validation cost: 0.000779 Mean average_precision (in %): 14.6698 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 21.653 floor 0 palette 0.330446 pillar 20.8337 pushcart 0 rackframe 26.1576 rackshelf 38.0292 wall 25.0239 Median Inference Time: 0.007951 2021-11-27 21:35:32,175 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 9.580 INFO:tensorflow:epoch = 100.0, learning_rate = 6.457747e-05, loss = 0.0013396268, step = 2200 (13.636 sec) 2021-11-27 21:35:32,244 [INFO] tensorflow: epoch = 100.0, learning_rate = 6.457747e-05, loss = 0.0013396268, step = 2200 (13.636 sec) INFO:tensorflow:global_step/sec: 0.226428 2021-11-27 21:35:32,245 [INFO] tensorflow: global_step/sec: 0.226428 2021-11-27 21:35:32,247 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 100/120: loss: 0.00134 learning rate: 0.00006 Time taken: 0:00:10.228996 ETA: 0:03:24.579926 INFO:tensorflow:global_step/sec: 13.6637 2021-11-27 21:35:32,392 [INFO] tensorflow: global_step/sec: 13.6637 INFO:tensorflow:global_step/sec: 14.6139 2021-11-27 21:35:32,529 [INFO] tensorflow: global_step/sec: 14.6139 INFO:tensorflow:global_step/sec: 14.3413 2021-11-27 21:35:32,668 [INFO] tensorflow: global_step/sec: 14.3413 INFO:tensorflow:global_step/sec: 14.6871 2021-11-27 21:35:32,804 [INFO] tensorflow: global_step/sec: 14.6871 INFO:tensorflow:global_step/sec: 14.1301 2021-11-27 21:35:32,946 [INFO] tensorflow: global_step/sec: 14.1301 INFO:tensorflow:global_step/sec: 14.109 2021-11-27 21:35:33,088 [INFO] tensorflow: global_step/sec: 14.109 INFO:tensorflow:global_step/sec: 15.0507 2021-11-27 21:35:33,220 [INFO] tensorflow: global_step/sec: 15.0507 INFO:tensorflow:global_step/sec: 14.0124 2021-11-27 21:35:33,363 [INFO] tensorflow: global_step/sec: 14.0124 INFO:tensorflow:global_step/sec: 14.5852 2021-11-27 21:35:33,500 [INFO] tensorflow: global_step/sec: 14.5852 INFO:tensorflow:global_step/sec: 14.6492 2021-11-27 21:35:33,637 [INFO] tensorflow: global_step/sec: 14.6492 INFO:tensorflow:global_step/sec: 14.0557 2021-11-27 21:35:33,779 [INFO] tensorflow: global_step/sec: 14.0557 2021-11-27 21:35:33,781 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 101/120: loss: 0.00114 learning rate: 0.00006 Time taken: 0:00:01.532828 ETA: 0:00:29.123729 INFO:tensorflow:global_step/sec: 13.9943 2021-11-27 21:35:33,922 [INFO] tensorflow: global_step/sec: 13.9943 2021-11-27 21:35:33,923 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.268 INFO:tensorflow:global_step/sec: 14.3667 2021-11-27 21:35:34,061 [INFO] tensorflow: global_step/sec: 14.3667 INFO:tensorflow:global_step/sec: 14.418 2021-11-27 21:35:34,200 [INFO] tensorflow: global_step/sec: 14.418 INFO:tensorflow:global_step/sec: 15.0591 2021-11-27 21:35:34,333 [INFO] tensorflow: global_step/sec: 15.0591 INFO:tensorflow:global_step/sec: 15.318 2021-11-27 21:35:34,463 [INFO] tensorflow: global_step/sec: 15.318 INFO:tensorflow:global_step/sec: 15.2168 2021-11-27 21:35:34,595 [INFO] tensorflow: global_step/sec: 15.2168 INFO:tensorflow:global_step/sec: 14.9169 2021-11-27 21:35:34,729 [INFO] tensorflow: global_step/sec: 14.9169 INFO:tensorflow:global_step/sec: 14.4049 2021-11-27 21:35:34,868 [INFO] tensorflow: global_step/sec: 14.4049 INFO:tensorflow:global_step/sec: 14.2974 2021-11-27 21:35:35,008 [INFO] tensorflow: global_step/sec: 14.2974 INFO:tensorflow:global_step/sec: 15.1179 2021-11-27 21:35:35,140 [INFO] tensorflow: global_step/sec: 15.1179 INFO:tensorflow:global_step/sec: 13.916 2021-11-27 21:35:35,284 [INFO] tensorflow: global_step/sec: 13.916 2021-11-27 21:35:35,285 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 102/120: loss: 0.00132 learning rate: 0.00005 Time taken: 0:00:01.499300 ETA: 0:00:26.987391 INFO:tensorflow:global_step/sec: 14.2846 2021-11-27 21:35:35,424 [INFO] tensorflow: global_step/sec: 14.2846 INFO:tensorflow:global_step/sec: 14.8159 2021-11-27 21:35:35,559 [INFO] tensorflow: global_step/sec: 14.8159 2021-11-27 21:35:35,629 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.616 INFO:tensorflow:global_step/sec: 14.0791 2021-11-27 21:35:35,701 [INFO] tensorflow: global_step/sec: 14.0791 INFO:tensorflow:global_step/sec: 14.041 2021-11-27 21:35:35,843 [INFO] tensorflow: global_step/sec: 14.041 INFO:tensorflow:global_step/sec: 14.7212 2021-11-27 21:35:35,979 [INFO] tensorflow: global_step/sec: 14.7212 INFO:tensorflow:global_step/sec: 14.8507 2021-11-27 21:35:36,114 [INFO] tensorflow: global_step/sec: 14.8507 INFO:tensorflow:global_step/sec: 15.1198 2021-11-27 21:35:36,246 [INFO] tensorflow: global_step/sec: 15.1198 INFO:tensorflow:global_step/sec: 14.5406 2021-11-27 21:35:36,383 [INFO] tensorflow: global_step/sec: 14.5406 INFO:tensorflow:global_step/sec: 15.185 2021-11-27 21:35:36,515 [INFO] tensorflow: global_step/sec: 15.185 INFO:tensorflow:global_step/sec: 14.9202 2021-11-27 21:35:36,649 [INFO] tensorflow: global_step/sec: 14.9202 INFO:tensorflow:global_step/sec: 13.2881 2021-11-27 21:35:36,800 [INFO] tensorflow: global_step/sec: 13.2881 2021-11-27 21:35:36,801 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 103/120: loss: 0.00107 learning rate: 0.00004 Time taken: 0:00:01.515983 ETA: 0:00:25.771705 INFO:tensorflow:global_step/sec: 14.3614 2021-11-27 21:35:36,939 [INFO] tensorflow: global_step/sec: 14.3614 INFO:tensorflow:global_step/sec: 14.68 2021-11-27 21:35:37,075 [INFO] tensorflow: global_step/sec: 14.68 INFO:tensorflow:global_step/sec: 14.847 2021-11-27 21:35:37,210 [INFO] tensorflow: global_step/sec: 14.847 INFO:tensorflow:epoch = 103.36363636363636, learning_rate = 4.199648e-05, loss = 0.0011573608, step = 2274 (5.101 sec) 2021-11-27 21:35:37,345 [INFO] tensorflow: epoch = 103.36363636363636, learning_rate = 4.199648e-05, loss = 0.0011573608, step = 2274 (5.101 sec) INFO:tensorflow:global_step/sec: 14.7002 2021-11-27 21:35:37,346 [INFO] tensorflow: global_step/sec: 14.7002 2021-11-27 21:35:37,347 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.240 INFO:tensorflow:global_step/sec: 14.6742 2021-11-27 21:35:37,482 [INFO] tensorflow: global_step/sec: 14.6742 INFO:tensorflow:global_step/sec: 14.9433 2021-11-27 21:35:37,616 [INFO] tensorflow: global_step/sec: 14.9433 INFO:tensorflow:global_step/sec: 14.5832 2021-11-27 21:35:37,753 [INFO] tensorflow: global_step/sec: 14.5832 INFO:tensorflow:global_step/sec: 14.5704 2021-11-27 21:35:37,891 [INFO] tensorflow: global_step/sec: 14.5704 INFO:tensorflow:global_step/sec: 14.5203 2021-11-27 21:35:38,028 [INFO] tensorflow: global_step/sec: 14.5203 INFO:tensorflow:global_step/sec: 14.524 2021-11-27 21:35:38,166 [INFO] tensorflow: global_step/sec: 14.524 INFO:tensorflow:global_step/sec: 14.2234 2021-11-27 21:35:38,307 [INFO] tensorflow: global_step/sec: 14.2234 2021-11-27 21:35:38,308 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 104/120: loss: 0.00120 learning rate: 0.00004 Time taken: 0:00:01.509660 ETA: 0:00:24.154564 INFO:tensorflow:global_step/sec: 14.7124 2021-11-27 21:35:38,443 [INFO] tensorflow: global_step/sec: 14.7124 INFO:tensorflow:global_step/sec: 14.3736 2021-11-27 21:35:38,582 [INFO] tensorflow: global_step/sec: 14.3736 INFO:tensorflow:global_step/sec: 14.8888 2021-11-27 21:35:38,716 [INFO] tensorflow: global_step/sec: 14.8888 INFO:tensorflow:global_step/sec: 14.4475 2021-11-27 21:35:38,854 [INFO] tensorflow: global_step/sec: 14.4475 INFO:tensorflow:global_step/sec: 14.5671 2021-11-27 21:35:38,992 [INFO] tensorflow: global_step/sec: 14.5671 2021-11-27 21:35:39,059 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.434 INFO:tensorflow:global_step/sec: 14.6847 2021-11-27 21:35:39,128 [INFO] tensorflow: global_step/sec: 14.6847 INFO:tensorflow:global_step/sec: 14.7299 2021-11-27 21:35:39,264 [INFO] tensorflow: global_step/sec: 14.7299 INFO:tensorflow:global_step/sec: 14.7238 2021-11-27 21:35:39,400 [INFO] tensorflow: global_step/sec: 14.7238 INFO:tensorflow:global_step/sec: 14.4188 2021-11-27 21:35:39,538 [INFO] tensorflow: global_step/sec: 14.4188 INFO:tensorflow:global_step/sec: 15.2661 2021-11-27 21:35:39,669 [INFO] tensorflow: global_step/sec: 15.2661 INFO:tensorflow:global_step/sec: 14.3406 2021-11-27 21:35:39,809 [INFO] tensorflow: global_step/sec: 14.3406 2021-11-27 21:35:39,810 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 105/120: loss: 0.00117 learning rate: 0.00003 Time taken: 0:00:01.497093 ETA: 0:00:22.456398 INFO:tensorflow:global_step/sec: 14.3046 2021-11-27 21:35:39,949 [INFO] tensorflow: global_step/sec: 14.3046 INFO:tensorflow:global_step/sec: 14.2752 2021-11-27 21:35:40,089 [INFO] tensorflow: global_step/sec: 14.2752 INFO:tensorflow:global_step/sec: 14.2779 2021-11-27 21:35:40,229 [INFO] tensorflow: global_step/sec: 14.2779 INFO:tensorflow:global_step/sec: 12.8602 2021-11-27 21:35:40,384 [INFO] tensorflow: global_step/sec: 12.8602 INFO:tensorflow:global_step/sec: 14.6077 2021-11-27 21:35:40,521 [INFO] tensorflow: global_step/sec: 14.6077 INFO:tensorflow:global_step/sec: 14.5911 2021-11-27 21:35:40,658 [INFO] tensorflow: global_step/sec: 14.5911 INFO:tensorflow:global_step/sec: 14.6743 2021-11-27 21:35:40,795 [INFO] tensorflow: global_step/sec: 14.6743 2021-11-27 21:35:40,796 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.588 INFO:tensorflow:global_step/sec: 14.1359 2021-11-27 21:35:40,936 [INFO] tensorflow: global_step/sec: 14.1359 INFO:tensorflow:global_step/sec: 14.4868 2021-11-27 21:35:41,074 [INFO] tensorflow: global_step/sec: 14.4868 INFO:tensorflow:global_step/sec: 14.2378 2021-11-27 21:35:41,214 [INFO] tensorflow: global_step/sec: 14.2378 INFO:tensorflow:global_step/sec: 13.1142 2021-11-27 21:35:41,367 [INFO] tensorflow: global_step/sec: 13.1142 2021-11-27 21:35:41,368 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 106/120: loss: 0.00113 learning rate: 0.00003 Time taken: 0:00:01.550979 ETA: 0:00:21.713708 INFO:tensorflow:global_step/sec: 14.7387 2021-11-27 21:35:41,503 [INFO] tensorflow: global_step/sec: 14.7387 INFO:tensorflow:global_step/sec: 14.5735 2021-11-27 21:35:41,640 [INFO] tensorflow: global_step/sec: 14.5735 INFO:tensorflow:global_step/sec: 14.4609 2021-11-27 21:35:41,778 [INFO] tensorflow: global_step/sec: 14.4609 INFO:tensorflow:global_step/sec: 15.0615 2021-11-27 21:35:41,911 [INFO] tensorflow: global_step/sec: 15.0615 INFO:tensorflow:global_step/sec: 14.6288 2021-11-27 21:35:42,048 [INFO] tensorflow: global_step/sec: 14.6288 INFO:tensorflow:global_step/sec: 15.0564 2021-11-27 21:35:42,181 [INFO] tensorflow: global_step/sec: 15.0564 INFO:tensorflow:global_step/sec: 14.7608 2021-11-27 21:35:42,316 [INFO] tensorflow: global_step/sec: 14.7608 INFO:tensorflow:epoch = 106.72727272727273, learning_rate = 2.7311375e-05, loss = 0.0011277084, step = 2348 (5.107 sec) 2021-11-27 21:35:42,452 [INFO] tensorflow: epoch = 106.72727272727273, learning_rate = 2.7311375e-05, loss = 0.0011277084, step = 2348 (5.107 sec) INFO:tensorflow:global_step/sec: 14.6291 2021-11-27 21:35:42,453 [INFO] tensorflow: global_step/sec: 14.6291 2021-11-27 21:35:42,527 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.776 INFO:tensorflow:global_step/sec: 14.0281 2021-11-27 21:35:42,595 [INFO] tensorflow: global_step/sec: 14.0281 INFO:tensorflow:global_step/sec: 15.2541 2021-11-27 21:35:42,727 [INFO] tensorflow: global_step/sec: 15.2541 INFO:tensorflow:global_step/sec: 13.6049 2021-11-27 21:35:42,874 [INFO] tensorflow: global_step/sec: 13.6049 2021-11-27 21:35:42,875 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 107/120: loss: 0.00121 learning rate: 0.00003 Time taken: 0:00:01.508691 ETA: 0:00:19.612987 INFO:tensorflow:global_step/sec: 14.4248 2021-11-27 21:35:43,012 [INFO] tensorflow: global_step/sec: 14.4248 INFO:tensorflow:global_step/sec: 14.5617 2021-11-27 21:35:43,149 [INFO] tensorflow: global_step/sec: 14.5617 INFO:tensorflow:global_step/sec: 14.477 2021-11-27 21:35:43,288 [INFO] tensorflow: global_step/sec: 14.477 INFO:tensorflow:global_step/sec: 14.6861 2021-11-27 21:35:43,424 [INFO] tensorflow: global_step/sec: 14.6861 INFO:tensorflow:global_step/sec: 14.8778 2021-11-27 21:35:43,558 [INFO] tensorflow: global_step/sec: 14.8778 INFO:tensorflow:global_step/sec: 14.6676 2021-11-27 21:35:43,695 [INFO] tensorflow: global_step/sec: 14.6676 INFO:tensorflow:global_step/sec: 14.4735 2021-11-27 21:35:43,833 [INFO] tensorflow: global_step/sec: 14.4735 INFO:tensorflow:global_step/sec: 14.6515 2021-11-27 21:35:43,969 [INFO] tensorflow: global_step/sec: 14.6515 INFO:tensorflow:global_step/sec: 14.3164 2021-11-27 21:35:44,109 [INFO] tensorflow: global_step/sec: 14.3164 INFO:tensorflow:global_step/sec: 14.6862 2021-11-27 21:35:44,245 [INFO] tensorflow: global_step/sec: 14.6862 2021-11-27 21:35:44,246 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.168 INFO:tensorflow:global_step/sec: 13.7198 2021-11-27 21:35:44,391 [INFO] tensorflow: global_step/sec: 13.7198 2021-11-27 21:35:44,392 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 108/120: loss: 0.00130 learning rate: 0.00002 Time taken: 0:00:01.517764 ETA: 0:00:18.213169 INFO:tensorflow:global_step/sec: 14.5431 2021-11-27 21:35:44,528 [INFO] tensorflow: global_step/sec: 14.5431 INFO:tensorflow:global_step/sec: 15.0616 2021-11-27 21:35:44,661 [INFO] tensorflow: global_step/sec: 15.0616 INFO:tensorflow:global_step/sec: 15.0603 2021-11-27 21:35:44,794 [INFO] tensorflow: global_step/sec: 15.0603 INFO:tensorflow:global_step/sec: 14.5943 2021-11-27 21:35:44,931 [INFO] tensorflow: global_step/sec: 14.5943 INFO:tensorflow:global_step/sec: 14.8102 2021-11-27 21:35:45,066 [INFO] tensorflow: global_step/sec: 14.8102 INFO:tensorflow:global_step/sec: 14.6508 2021-11-27 21:35:45,203 [INFO] tensorflow: global_step/sec: 14.6508 INFO:tensorflow:global_step/sec: 14.6347 2021-11-27 21:35:45,339 [INFO] tensorflow: global_step/sec: 14.6347 INFO:tensorflow:global_step/sec: 14.0861 2021-11-27 21:35:45,481 [INFO] tensorflow: global_step/sec: 14.0861 INFO:tensorflow:global_step/sec: 14.2082 2021-11-27 21:35:45,622 [INFO] tensorflow: global_step/sec: 14.2082 INFO:tensorflow:global_step/sec: 14.8151 2021-11-27 21:35:45,757 [INFO] tensorflow: global_step/sec: 14.8151 INFO:tensorflow:global_step/sec: 14.045 2021-11-27 21:35:45,899 [INFO] tensorflow: global_step/sec: 14.045 2021-11-27 21:35:45,901 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 109/120: loss: 0.00124 learning rate: 0.00002 Time taken: 0:00:01.505586 ETA: 0:00:16.561448 2021-11-27 21:35:45,966 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.176 INFO:tensorflow:global_step/sec: 14.3847 2021-11-27 21:35:46,038 [INFO] tensorflow: global_step/sec: 14.3847 INFO:tensorflow:global_step/sec: 13.7534 2021-11-27 21:35:46,184 [INFO] tensorflow: global_step/sec: 13.7534 INFO:tensorflow:global_step/sec: 14.4915 2021-11-27 21:35:46,322 [INFO] tensorflow: global_step/sec: 14.4915 INFO:tensorflow:global_step/sec: 13.9169 2021-11-27 21:35:46,466 [INFO] tensorflow: global_step/sec: 13.9169 INFO:tensorflow:global_step/sec: 15.2077 2021-11-27 21:35:46,597 [INFO] tensorflow: global_step/sec: 15.2077 INFO:tensorflow:global_step/sec: 14.4556 2021-11-27 21:35:46,736 [INFO] tensorflow: global_step/sec: 14.4556 INFO:tensorflow:global_step/sec: 14.8107 2021-11-27 21:35:46,871 [INFO] tensorflow: global_step/sec: 14.8107 INFO:tensorflow:global_step/sec: 14.3055 2021-11-27 21:35:47,010 [INFO] tensorflow: global_step/sec: 14.3055 INFO:tensorflow:global_step/sec: 14.1957 2021-11-27 21:35:47,151 [INFO] tensorflow: global_step/sec: 14.1957 INFO:tensorflow:global_step/sec: 14.3315 2021-11-27 21:35:47,291 [INFO] tensorflow: global_step/sec: 14.3315 INFO:tensorflow:Saving checkpoints for step-2420. 2021-11-27 21:35:47,360 [INFO] tensorflow: Saving checkpoints for step-2420. WARNING:tensorflow:Ignoring: /tmp/tmpz90rnvlh; No such file or directory 2021-11-27 21:35:47,457 [WARNING] tensorflow: Ignoring: /tmp/tmpz90rnvlh; No such file or directory 2021-11-27 21:35:49,844 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 1760/1760 [00:00<00:00, 24874.90it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 5767/5767 [00:00<00:00, 26724.34it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 817/817 [00:00<00:00, 23928.62it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 10932/10932 [00:00<00:00, 30652.30it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 860/860 [00:00<00:00, 23725.62it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 1724/1724 [00:00<00:00, 22774.88it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 8834/8834 [00:00<00:00, 40835.35it/s] Epoch 110/120 ========================= Validation cost: 0.000783 Mean average_precision (in %): 15.8793 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 18.5792 floor 0 palette 0.665045 pillar 24.7584 pushcart 0 rackframe 27.9509 rackshelf 45.0106 wall 25.9497 Median Inference Time: 0.007589 INFO:tensorflow:epoch = 110.0, learning_rate = 1.7969083e-05, loss = 0.0011130697, step = 2420 (13.516 sec) 2021-11-27 21:35:55,968 [INFO] tensorflow: epoch = 110.0, learning_rate = 1.7969083e-05, loss = 0.0011130697, step = 2420 (13.516 sec) INFO:tensorflow:global_step/sec: 0.230465 2021-11-27 21:35:55,969 [INFO] tensorflow: global_step/sec: 0.230465 2021-11-27 21:35:55,970 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 110/120: loss: 0.00111 learning rate: 0.00002 Time taken: 0:00:10.068641 ETA: 0:01:40.686409 INFO:tensorflow:global_step/sec: 14.0386 2021-11-27 21:35:56,111 [INFO] tensorflow: global_step/sec: 14.0386 INFO:tensorflow:global_step/sec: 14.6238 2021-11-27 21:35:56,248 [INFO] tensorflow: global_step/sec: 14.6238 2021-11-27 21:35:56,249 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 9.725 INFO:tensorflow:global_step/sec: 14.9234 2021-11-27 21:35:56,382 [INFO] tensorflow: global_step/sec: 14.9234 INFO:tensorflow:global_step/sec: 15.0584 2021-11-27 21:35:56,515 [INFO] tensorflow: global_step/sec: 15.0584 INFO:tensorflow:global_step/sec: 14.9962 2021-11-27 21:35:56,648 [INFO] tensorflow: global_step/sec: 14.9962 INFO:tensorflow:global_step/sec: 14.4897 2021-11-27 21:35:56,786 [INFO] tensorflow: global_step/sec: 14.4897 INFO:tensorflow:global_step/sec: 14.6054 2021-11-27 21:35:56,923 [INFO] tensorflow: global_step/sec: 14.6054 INFO:tensorflow:global_step/sec: 14.3985 2021-11-27 21:35:57,062 [INFO] tensorflow: global_step/sec: 14.3985 INFO:tensorflow:global_step/sec: 14.5792 2021-11-27 21:35:57,199 [INFO] tensorflow: global_step/sec: 14.5792 INFO:tensorflow:global_step/sec: 14.5466 2021-11-27 21:35:57,337 [INFO] tensorflow: global_step/sec: 14.5466 INFO:tensorflow:global_step/sec: 14.108 2021-11-27 21:35:57,479 [INFO] tensorflow: global_step/sec: 14.108 2021-11-27 21:35:57,480 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 111/120: loss: 0.00134 learning rate: 0.00002 Time taken: 0:00:01.508971 ETA: 0:00:13.580737 INFO:tensorflow:global_step/sec: 13.8962 2021-11-27 21:35:57,623 [INFO] tensorflow: global_step/sec: 13.8962 INFO:tensorflow:global_step/sec: 15.2558 2021-11-27 21:35:57,754 [INFO] tensorflow: global_step/sec: 15.2558 INFO:tensorflow:global_step/sec: 14.4751 2021-11-27 21:35:57,892 [INFO] tensorflow: global_step/sec: 14.4751 2021-11-27 21:35:57,961 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.426 INFO:tensorflow:global_step/sec: 14.7563 2021-11-27 21:35:58,027 [INFO] tensorflow: global_step/sec: 14.7563 INFO:tensorflow:global_step/sec: 14.4116 2021-11-27 21:35:58,166 [INFO] tensorflow: global_step/sec: 14.4116 INFO:tensorflow:global_step/sec: 14.6728 2021-11-27 21:35:58,302 [INFO] tensorflow: global_step/sec: 14.6728 INFO:tensorflow:global_step/sec: 14.155 2021-11-27 21:35:58,444 [INFO] tensorflow: global_step/sec: 14.155 INFO:tensorflow:global_step/sec: 14.6222 2021-11-27 21:35:58,580 [INFO] tensorflow: global_step/sec: 14.6222 INFO:tensorflow:global_step/sec: 15.0452 2021-11-27 21:35:58,713 [INFO] tensorflow: global_step/sec: 15.0452 INFO:tensorflow:global_step/sec: 14.3194 2021-11-27 21:35:58,853 [INFO] tensorflow: global_step/sec: 14.3194 INFO:tensorflow:global_step/sec: 14.1126 2021-11-27 21:35:58,995 [INFO] tensorflow: global_step/sec: 14.1126 2021-11-27 21:35:58,996 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 112/120: loss: 0.00123 learning rate: 0.00001 Time taken: 0:00:01.513649 ETA: 0:00:12.109188 INFO:tensorflow:global_step/sec: 15.1151 2021-11-27 21:35:59,127 [INFO] tensorflow: global_step/sec: 15.1151 INFO:tensorflow:global_step/sec: 14.6876 2021-11-27 21:35:59,263 [INFO] tensorflow: global_step/sec: 14.6876 INFO:tensorflow:global_step/sec: 14.0524 2021-11-27 21:35:59,406 [INFO] tensorflow: global_step/sec: 14.0524 INFO:tensorflow:global_step/sec: 14.547 2021-11-27 21:35:59,543 [INFO] tensorflow: global_step/sec: 14.547 INFO:tensorflow:global_step/sec: 14.772 2021-11-27 21:35:59,679 [INFO] tensorflow: global_step/sec: 14.772 2021-11-27 21:35:59,679 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.208 INFO:tensorflow:global_step/sec: 14.3154 2021-11-27 21:35:59,818 [INFO] tensorflow: global_step/sec: 14.3154 INFO:tensorflow:global_step/sec: 14.9752 2021-11-27 21:35:59,952 [INFO] tensorflow: global_step/sec: 14.9752 INFO:tensorflow:global_step/sec: 14.2423 2021-11-27 21:36:00,092 [INFO] tensorflow: global_step/sec: 14.2423 INFO:tensorflow:global_step/sec: 15.0859 2021-11-27 21:36:00,225 [INFO] tensorflow: global_step/sec: 15.0859 INFO:tensorflow:global_step/sec: 14.384 2021-11-27 21:36:00,364 [INFO] tensorflow: global_step/sec: 14.384 INFO:tensorflow:global_step/sec: 13.4957 2021-11-27 21:36:00,512 [INFO] tensorflow: global_step/sec: 13.4957 2021-11-27 21:36:00,513 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 113/120: loss: 0.00116 learning rate: 0.00001 Time taken: 0:00:01.511973 ETA: 0:00:10.583814 INFO:tensorflow:global_step/sec: 14.4038 2021-11-27 21:36:00,651 [INFO] tensorflow: global_step/sec: 14.4038 INFO:tensorflow:global_step/sec: 14.575 2021-11-27 21:36:00,788 [INFO] tensorflow: global_step/sec: 14.575 INFO:tensorflow:global_step/sec: 14.5516 2021-11-27 21:36:00,926 [INFO] tensorflow: global_step/sec: 14.5516 INFO:tensorflow:epoch = 113.36363636363636, learning_rate = 1.168576e-05, loss = 0.001296784, step = 2494 (5.100 sec) 2021-11-27 21:36:01,067 [INFO] tensorflow: epoch = 113.36363636363636, learning_rate = 1.168576e-05, loss = 0.001296784, step = 2494 (5.100 sec) INFO:tensorflow:global_step/sec: 14.0108 2021-11-27 21:36:01,068 [INFO] tensorflow: global_step/sec: 14.0108 INFO:tensorflow:global_step/sec: 14.9295 2021-11-27 21:36:01,202 [INFO] tensorflow: global_step/sec: 14.9295 INFO:tensorflow:global_step/sec: 14.5619 2021-11-27 21:36:01,340 [INFO] tensorflow: global_step/sec: 14.5619 2021-11-27 21:36:01,409 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.840 INFO:tensorflow:global_step/sec: 14.1717 2021-11-27 21:36:01,481 [INFO] tensorflow: global_step/sec: 14.1717 INFO:tensorflow:global_step/sec: 14.1797 2021-11-27 21:36:01,622 [INFO] tensorflow: global_step/sec: 14.1797 INFO:tensorflow:global_step/sec: 15.052 2021-11-27 21:36:01,755 [INFO] tensorflow: global_step/sec: 15.052 INFO:tensorflow:global_step/sec: 14.9264 2021-11-27 21:36:01,889 [INFO] tensorflow: global_step/sec: 14.9264 INFO:tensorflow:global_step/sec: 13.5556 2021-11-27 21:36:02,036 [INFO] tensorflow: global_step/sec: 13.5556 2021-11-27 21:36:02,038 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 114/120: loss: 0.00119 learning rate: 0.00001 Time taken: 0:00:01.523275 ETA: 0:00:09.139651 INFO:tensorflow:global_step/sec: 14.282 2021-11-27 21:36:02,176 [INFO] tensorflow: global_step/sec: 14.282 INFO:tensorflow:global_step/sec: 14.2101 2021-11-27 21:36:02,317 [INFO] tensorflow: global_step/sec: 14.2101 INFO:tensorflow:global_step/sec: 14.6109 2021-11-27 21:36:02,454 [INFO] tensorflow: global_step/sec: 14.6109 INFO:tensorflow:global_step/sec: 14.6366 2021-11-27 21:36:02,590 [INFO] tensorflow: global_step/sec: 14.6366 INFO:tensorflow:global_step/sec: 14.2613 2021-11-27 21:36:02,731 [INFO] tensorflow: global_step/sec: 14.2613 INFO:tensorflow:global_step/sec: 14.6908 2021-11-27 21:36:02,867 [INFO] tensorflow: global_step/sec: 14.6908 INFO:tensorflow:global_step/sec: 14.262 2021-11-27 21:36:03,007 [INFO] tensorflow: global_step/sec: 14.262 INFO:tensorflow:global_step/sec: 14.4426 2021-11-27 21:36:03,146 [INFO] tensorflow: global_step/sec: 14.4426 2021-11-27 21:36:03,146 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.568 INFO:tensorflow:global_step/sec: 14.7975 2021-11-27 21:36:03,281 [INFO] tensorflow: global_step/sec: 14.7975 INFO:tensorflow:global_step/sec: 14.638 2021-11-27 21:36:03,417 [INFO] tensorflow: global_step/sec: 14.638 INFO:tensorflow:global_step/sec: 14.1673 2021-11-27 21:36:03,559 [INFO] tensorflow: global_step/sec: 14.1673 2021-11-27 21:36:03,560 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 115/120: loss: 0.00119 learning rate: 0.00001 Time taken: 0:00:01.521498 ETA: 0:00:07.607490 INFO:tensorflow:global_step/sec: 14.2907 2021-11-27 21:36:03,698 [INFO] tensorflow: global_step/sec: 14.2907 INFO:tensorflow:global_step/sec: 14.6035 2021-11-27 21:36:03,835 [INFO] tensorflow: global_step/sec: 14.6035 INFO:tensorflow:global_step/sec: 14.4161 2021-11-27 21:36:03,974 [INFO] tensorflow: global_step/sec: 14.4161 INFO:tensorflow:global_step/sec: 15.1211 2021-11-27 21:36:04,106 [INFO] tensorflow: global_step/sec: 15.1211 INFO:tensorflow:global_step/sec: 14.6253 2021-11-27 21:36:04,243 [INFO] tensorflow: global_step/sec: 14.6253 INFO:tensorflow:global_step/sec: 14.5254 2021-11-27 21:36:04,381 [INFO] tensorflow: global_step/sec: 14.5254 INFO:tensorflow:global_step/sec: 14.308 2021-11-27 21:36:04,521 [INFO] tensorflow: global_step/sec: 14.308 INFO:tensorflow:global_step/sec: 14.8227 2021-11-27 21:36:04,656 [INFO] tensorflow: global_step/sec: 14.8227 INFO:tensorflow:global_step/sec: 14.3412 2021-11-27 21:36:04,795 [INFO] tensorflow: global_step/sec: 14.3412 2021-11-27 21:36:04,862 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.297 INFO:tensorflow:global_step/sec: 14.4972 2021-11-27 21:36:04,933 [INFO] tensorflow: global_step/sec: 14.4972 INFO:tensorflow:global_step/sec: 13.8729 2021-11-27 21:36:05,077 [INFO] tensorflow: global_step/sec: 13.8729 2021-11-27 21:36:05,078 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 116/120: loss: 0.00121 learning rate: 0.00001 Time taken: 0:00:01.517640 ETA: 0:00:06.070560 INFO:tensorflow:global_step/sec: 14.8861 2021-11-27 21:36:05,211 [INFO] tensorflow: global_step/sec: 14.8861 INFO:tensorflow:global_step/sec: 14.3998 2021-11-27 21:36:05,350 [INFO] tensorflow: global_step/sec: 14.3998 INFO:tensorflow:global_step/sec: 14.2438 2021-11-27 21:36:05,491 [INFO] tensorflow: global_step/sec: 14.2438 INFO:tensorflow:global_step/sec: 14.1094 2021-11-27 21:36:05,633 [INFO] tensorflow: global_step/sec: 14.1094 INFO:tensorflow:global_step/sec: 13.9956 2021-11-27 21:36:05,775 [INFO] tensorflow: global_step/sec: 13.9956 INFO:tensorflow:global_step/sec: 14.6737 2021-11-27 21:36:05,912 [INFO] tensorflow: global_step/sec: 14.6737 INFO:tensorflow:global_step/sec: 14.1703 2021-11-27 21:36:06,053 [INFO] tensorflow: global_step/sec: 14.1703 INFO:tensorflow:epoch = 116.72727272727273, learning_rate = 7.5995595e-06, loss = 0.0012394936, step = 2568 (5.124 sec) 2021-11-27 21:36:06,191 [INFO] tensorflow: epoch = 116.72727272727273, learning_rate = 7.5995595e-06, loss = 0.0012394936, step = 2568 (5.124 sec) INFO:tensorflow:global_step/sec: 14.3231 2021-11-27 21:36:06,193 [INFO] tensorflow: global_step/sec: 14.3231 INFO:tensorflow:global_step/sec: 14.611 2021-11-27 21:36:06,329 [INFO] tensorflow: global_step/sec: 14.611 INFO:tensorflow:global_step/sec: 14.8816 2021-11-27 21:36:06,464 [INFO] tensorflow: global_step/sec: 14.8816 INFO:tensorflow:global_step/sec: 13.4691 2021-11-27 21:36:06,612 [INFO] tensorflow: global_step/sec: 13.4691 2021-11-27 21:36:06,613 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 117/120: loss: 0.00138 learning rate: 0.00001 Time taken: 0:00:01.534928 ETA: 0:00:04.604785 2021-11-27 21:36:06,613 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.105 INFO:tensorflow:global_step/sec: 14.7677 2021-11-27 21:36:06,748 [INFO] tensorflow: global_step/sec: 14.7677 INFO:tensorflow:global_step/sec: 14.1354 2021-11-27 21:36:06,889 [INFO] tensorflow: global_step/sec: 14.1354 INFO:tensorflow:global_step/sec: 14.3794 2021-11-27 21:36:07,028 [INFO] tensorflow: global_step/sec: 14.3794 INFO:tensorflow:global_step/sec: 14.2387 2021-11-27 21:36:07,169 [INFO] tensorflow: global_step/sec: 14.2387 INFO:tensorflow:global_step/sec: 14.4183 2021-11-27 21:36:07,308 [INFO] tensorflow: global_step/sec: 14.4183 INFO:tensorflow:global_step/sec: 14.5625 2021-11-27 21:36:07,445 [INFO] tensorflow: global_step/sec: 14.5625 INFO:tensorflow:global_step/sec: 14.7991 2021-11-27 21:36:07,580 [INFO] tensorflow: global_step/sec: 14.7991 INFO:tensorflow:global_step/sec: 13.978 2021-11-27 21:36:07,723 [INFO] tensorflow: global_step/sec: 13.978 INFO:tensorflow:global_step/sec: 13.9176 2021-11-27 21:36:07,867 [INFO] tensorflow: global_step/sec: 13.9176 INFO:tensorflow:global_step/sec: 14.3272 2021-11-27 21:36:08,006 [INFO] tensorflow: global_step/sec: 14.3272 INFO:tensorflow:global_step/sec: 13.9617 2021-11-27 21:36:08,150 [INFO] tensorflow: global_step/sec: 13.9617 2021-11-27 21:36:08,150 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 118/120: loss: 0.00145 learning rate: 0.00001 Time taken: 0:00:01.533602 ETA: 0:00:03.067203 INFO:tensorflow:global_step/sec: 14.3395 2021-11-27 21:36:08,289 [INFO] tensorflow: global_step/sec: 14.3395 2021-11-27 21:36:08,357 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.347 INFO:tensorflow:global_step/sec: 14.0976 2021-11-27 21:36:08,431 [INFO] tensorflow: global_step/sec: 14.0976 INFO:tensorflow:global_step/sec: 14.6155 2021-11-27 21:36:08,568 [INFO] tensorflow: global_step/sec: 14.6155 INFO:tensorflow:global_step/sec: 14.7138 2021-11-27 21:36:08,704 [INFO] tensorflow: global_step/sec: 14.7138 INFO:tensorflow:global_step/sec: 14.8451 2021-11-27 21:36:08,838 [INFO] tensorflow: global_step/sec: 14.8451 INFO:tensorflow:global_step/sec: 14.41 2021-11-27 21:36:08,977 [INFO] tensorflow: global_step/sec: 14.41 INFO:tensorflow:global_step/sec: 13.8988 2021-11-27 21:36:09,121 [INFO] tensorflow: global_step/sec: 13.8988 INFO:tensorflow:global_step/sec: 14.2431 2021-11-27 21:36:09,262 [INFO] tensorflow: global_step/sec: 14.2431 INFO:tensorflow:global_step/sec: 14.5307 2021-11-27 21:36:09,399 [INFO] tensorflow: global_step/sec: 14.5307 INFO:tensorflow:global_step/sec: 14.5938 2021-11-27 21:36:09,536 [INFO] tensorflow: global_step/sec: 14.5938 INFO:tensorflow:global_step/sec: 13.8167 2021-11-27 21:36:09,681 [INFO] tensorflow: global_step/sec: 13.8167 2021-11-27 21:36:09,682 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 119/120: loss: 0.00121 learning rate: 0.00001 Time taken: 0:00:01.529356 ETA: 0:00:01.529356 INFO:tensorflow:global_step/sec: 14.7229 2021-11-27 21:36:09,817 [INFO] tensorflow: global_step/sec: 14.7229 INFO:tensorflow:global_step/sec: 14.6472 2021-11-27 21:36:09,953 [INFO] tensorflow: global_step/sec: 14.6472 INFO:tensorflow:global_step/sec: 14.428 2021-11-27 21:36:10,092 [INFO] tensorflow: global_step/sec: 14.428 2021-11-27 21:36:10,093 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.627 INFO:tensorflow:global_step/sec: 14.2148 2021-11-27 21:36:10,233 [INFO] tensorflow: global_step/sec: 14.2148 INFO:tensorflow:global_step/sec: 14.3256 2021-11-27 21:36:10,372 [INFO] tensorflow: global_step/sec: 14.3256 INFO:tensorflow:global_step/sec: 14.4748 2021-11-27 21:36:10,510 [INFO] tensorflow: global_step/sec: 14.4748 INFO:tensorflow:global_step/sec: 15.2355 2021-11-27 21:36:10,642 [INFO] tensorflow: global_step/sec: 15.2355 INFO:tensorflow:global_step/sec: 15.0577 2021-11-27 21:36:10,775 [INFO] tensorflow: global_step/sec: 15.0577 INFO:tensorflow:global_step/sec: 14.5631 2021-11-27 21:36:10,912 [INFO] tensorflow: global_step/sec: 14.5631 INFO:tensorflow:global_step/sec: 14.3989 2021-11-27 21:36:11,051 [INFO] tensorflow: global_step/sec: 14.3989 INFO:tensorflow:Saving checkpoints for step-2640. 2021-11-27 21:36:11,121 [INFO] tensorflow: Saving checkpoints for step-2640. WARNING:tensorflow:Ignoring: /tmp/tmp604f7xq1; No such file or directory 2021-11-27 21:36:11,218 [WARNING] tensorflow: Ignoring: /tmp/tmp604f7xq1; No such file or directory 2021-11-27 21:36:13,520 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 1652/1652 [00:00<00:00, 24822.55it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 5352/5352 [00:00<00:00, 28319.69it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 743/743 [00:00<00:00, 24934.13it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 11263/11263 [00:00<00:00, 30549.78it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 665/665 [00:00<00:00, 25427.90it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 1576/1576 [00:00<00:00, 23787.28it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 8785/8785 [00:00<00:00, 41250.82it/s] Epoch 120/120 ========================= Validation cost: 0.000682 Mean average_precision (in %): 16.7417 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 24.4347 floor 0 palette 1.55316 pillar 31.1881 pushcart 0 rackframe 26.8855 rackshelf 43.3584 wall 23.2551 Median Inference Time: 0.007639 WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:95: The name tf.reset_default_graph is deprecated. Please use tf.compat.v1.reset_default_graph instead. 2021-11-27 21:36:19,837 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:95: The name tf.reset_default_graph is deprecated. Please use tf.compat.v1.reset_default_graph instead. WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:98: The name tf.placeholder_with_default is deprecated. Please use tf.compat.v1.placeholder_with_default instead. 2021-11-27 21:36:19,837 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:98: The name tf.placeholder_with_default is deprecated. Please use tf.compat.v1.placeholder_with_default instead. 2021-11-27 21:36:19,839 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.627 Time taken to run __main__:main: 0:05:15.499475. 2021-11-27 16:36:21,873 [INFO] tlt.components.docker_handler.docker_handler: Stopping container.
pantelis-classes/omniverse-ai/training_output/dataset1/train_prune_1_summary.txt
Mean average_precision (in %): 21.7641 Mean average_precision (in %): 21.1592 Mean average_precision (in %): 24.4442 Mean average_precision (in %): 26.8432 Mean average_precision (in %): 27.0035 Mean average_precision (in %): 28.1822 Mean average_precision (in %): 28.8910 Mean average_precision (in %): 30.8107 Mean average_precision (in %): 32.1409 Mean average_precision (in %): 30.6785 Validation cost: 0.000636 Validation cost: 0.000671 Validation cost: 0.000479 Validation cost: 0.000544 Validation cost: 0.000533 Validation cost: 0.000479 Validation cost: 0.000422 Validation cost: 0.000361 Validation cost: 0.000356 Validation cost: 0.000278
pantelis-classes/omniverse-ai/training_output/dataset1/train_prune_1.txt
2021-11-27 17:09:53,809 [INFO] root: Registry: ['nvcr.io'] 2021-11-27 17:09:53,862 [INFO] tlt.components.instance_handler.local_instance: Running command in container: nvcr.io/nvidia/tao/tao-toolkit-tf:v3.21.11-tf1.15.4-py3 Matplotlib created a temporary config/cache directory at /tmp/matplotlib-1kd6oqh2 because the default path (/.config/matplotlib) is not a writable directory; it is highly recommended to set the MPLCONFIGDIR environment variable to a writable directory, in particular to speed up the import of Matplotlib and to better support multiprocessing. Using TensorFlow backend. WARNING:tensorflow:Deprecation warnings have been disabled. Set TF_ENABLE_DEPRECATION_WARNINGS=1 to re-enable them. Using TensorFlow backend. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:43: The name tf.train.SessionRunHook is deprecated. Please use tf.estimator.SessionRunHook instead. 2021-11-27 22:09:58,345 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:43: The name tf.train.SessionRunHook is deprecated. Please use tf.estimator.SessionRunHook instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/checkpoint_saver_hook.py:25: The name tf.train.CheckpointSaverHook is deprecated. Please use tf.estimator.CheckpointSaverHook instead. 2021-11-27 22:09:58,440 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/checkpoint_saver_hook.py:25: The name tf.train.CheckpointSaverHook is deprecated. Please use tf.estimator.CheckpointSaverHook instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/scripts/train.py:69: The name tf.logging.set_verbosity is deprecated. Please use tf.compat.v1.logging.set_verbosity instead. 2021-11-27 22:09:58,442 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/scripts/train.py:69: The name tf.logging.set_verbosity is deprecated. Please use tf.compat.v1.logging.set_verbosity instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/scripts/train.py:69: The name tf.logging.INFO is deprecated. Please use tf.compat.v1.logging.INFO instead. 2021-11-27 22:09:58,442 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/scripts/train.py:69: The name tf.logging.INFO is deprecated. Please use tf.compat.v1.logging.INFO instead. WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/horovod/tensorflow/__init__.py:117: The name tf.global_variables is deprecated. Please use tf.compat.v1.global_variables instead. 2021-11-27 22:09:58,447 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/horovod/tensorflow/__init__.py:117: The name tf.global_variables is deprecated. Please use tf.compat.v1.global_variables instead. WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/horovod/tensorflow/__init__.py:143: The name tf.get_default_graph is deprecated. Please use tf.compat.v1.get_default_graph instead. 2021-11-27 22:09:58,447 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/horovod/tensorflow/__init__.py:143: The name tf.get_default_graph is deprecated. Please use tf.compat.v1.get_default_graph instead. 2021-11-27 22:09:58,711 [INFO] __main__: Loading experiment spec at /workspace/tao-experiments/detectnet_v2/specs/detectnet_v2_retrain_resnet18_kitti.txt. 2021-11-27 22:09:58,712 [INFO] iva.detectnet_v2.spec_handler.spec_loader: Merging specification from /workspace/tao-experiments/detectnet_v2/specs/detectnet_v2_retrain_resnet18_kitti.txt 2021-11-27 22:09:58,809 [INFO] __main__: Cannot iterate over exactly 86 samples with a batch size of 4; each epoch will therefore take one extra step. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:107: The name tf.variable_scope is deprecated. Please use tf.compat.v1.variable_scope instead. 2021-11-27 22:09:58,812 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:107: The name tf.variable_scope is deprecated. Please use tf.compat.v1.variable_scope instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:110: The name tf.get_variable is deprecated. Please use tf.compat.v1.get_variable instead. 2021-11-27 22:09:58,812 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:110: The name tf.get_variable is deprecated. Please use tf.compat.v1.get_variable instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:113: The name tf.assign is deprecated. Please use tf.compat.v1.assign instead. 2021-11-27 22:09:58,814 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:113: The name tf.assign is deprecated. Please use tf.compat.v1.assign instead. WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:517: The name tf.placeholder is deprecated. Please use tf.compat.v1.placeholder instead. 2021-11-27 22:09:59,233 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:517: The name tf.placeholder is deprecated. Please use tf.compat.v1.placeholder instead. WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:4138: The name tf.random_uniform is deprecated. Please use tf.random.uniform instead. 2021-11-27 22:09:59,246 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:4138: The name tf.random_uniform is deprecated. Please use tf.random.uniform instead. WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:1834: The name tf.nn.fused_batch_norm is deprecated. Please use tf.compat.v1.nn.fused_batch_norm instead. 2021-11-27 22:09:59,260 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:1834: The name tf.nn.fused_batch_norm is deprecated. Please use tf.compat.v1.nn.fused_batch_norm instead. WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:174: The name tf.get_default_session is deprecated. Please use tf.compat.v1.get_default_session instead. 2021-11-27 22:09:59,773 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:174: The name tf.get_default_session is deprecated. Please use tf.compat.v1.get_default_session instead. WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:199: The name tf.is_variable_initialized is deprecated. Please use tf.compat.v1.is_variable_initialized instead. 2021-11-27 22:09:59,773 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:199: The name tf.is_variable_initialized is deprecated. Please use tf.compat.v1.is_variable_initialized instead. WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:206: The name tf.variables_initializer is deprecated. Please use tf.compat.v1.variables_initializer instead. 2021-11-27 22:09:59,886 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:206: The name tf.variables_initializer is deprecated. Please use tf.compat.v1.variables_initializer instead. /usr/local/lib/python3.6/dist-packages/keras/engine/saving.py:292: UserWarning: No training configuration found in save file: the model was *not* compiled. Compile it manually. warnings.warn('No training configuration found in save file: ' 2021-11-27 22:10:00,086 [INFO] iva.detectnet_v2.objectives.bbox_objective: Default L1 loss function will be used. __________________________________________________________________________________________________ Layer (type) Output Shape Param # Connected to ================================================================================================== input_1 (InputLayer) (None, 3, 384, 1248) 0 __________________________________________________________________________________________________ conv1 (Conv2D) (None, 64, 192, 624) 9472 input_1[0][0] __________________________________________________________________________________________________ bn_conv1 (BatchNormalization) (None, 64, 192, 624) 256 conv1[0][0] __________________________________________________________________________________________________ activation_1 (Activation) (None, 64, 192, 624) 0 bn_conv1[0][0] __________________________________________________________________________________________________ block_1a_conv_1 (Conv2D) (None, 64, 96, 312) 36928 activation_1[0][0] __________________________________________________________________________________________________ block_1a_bn_1 (BatchNormalizati (None, 64, 96, 312) 256 block_1a_conv_1[0][0] __________________________________________________________________________________________________ block_1a_relu_1 (Activation) (None, 64, 96, 312) 0 block_1a_bn_1[0][0] __________________________________________________________________________________________________ block_1a_conv_2 (Conv2D) (None, 64, 96, 312) 36928 block_1a_relu_1[0][0] __________________________________________________________________________________________________ block_1a_conv_shortcut (Conv2D) (None, 64, 96, 312) 4160 activation_1[0][0] __________________________________________________________________________________________________ block_1a_bn_2 (BatchNormalizati (None, 64, 96, 312) 256 block_1a_conv_2[0][0] __________________________________________________________________________________________________ block_1a_bn_shortcut (BatchNorm (None, 64, 96, 312) 256 block_1a_conv_shortcut[0][0] __________________________________________________________________________________________________ add_1 (Add) (None, 64, 96, 312) 0 block_1a_bn_2[0][0] block_1a_bn_shortcut[0][0] __________________________________________________________________________________________________ block_1a_relu (Activation) (None, 64, 96, 312) 0 add_1[0][0] __________________________________________________________________________________________________ block_1b_conv_1 (Conv2D) (None, 64, 96, 312) 36928 block_1a_relu[0][0] __________________________________________________________________________________________________ block_1b_bn_1 (BatchNormalizati (None, 64, 96, 312) 256 block_1b_conv_1[0][0] __________________________________________________________________________________________________ block_1b_relu_1 (Activation) (None, 64, 96, 312) 0 block_1b_bn_1[0][0] __________________________________________________________________________________________________ block_1b_conv_2 (Conv2D) (None, 64, 96, 312) 36928 block_1b_relu_1[0][0] __________________________________________________________________________________________________ block_1b_bn_2 (BatchNormalizati (None, 64, 96, 312) 256 block_1b_conv_2[0][0] __________________________________________________________________________________________________ add_2 (Add) (None, 64, 96, 312) 0 block_1b_bn_2[0][0] block_1a_relu[0][0] __________________________________________________________________________________________________ block_1b_relu (Activation) (None, 64, 96, 312) 0 add_2[0][0] __________________________________________________________________________________________________ block_2a_conv_1 (Conv2D) (None, 128, 48, 156) 73856 block_1b_relu[0][0] __________________________________________________________________________________________________ block_2a_bn_1 (BatchNormalizati (None, 128, 48, 156) 512 block_2a_conv_1[0][0] __________________________________________________________________________________________________ block_2a_relu_1 (Activation) (None, 128, 48, 156) 0 block_2a_bn_1[0][0] __________________________________________________________________________________________________ block_2a_conv_2 (Conv2D) (None, 128, 48, 156) 147584 block_2a_relu_1[0][0] __________________________________________________________________________________________________ block_2a_conv_shortcut (Conv2D) (None, 128, 48, 156) 8320 block_1b_relu[0][0] __________________________________________________________________________________________________ block_2a_bn_2 (BatchNormalizati (None, 128, 48, 156) 512 block_2a_conv_2[0][0] __________________________________________________________________________________________________ block_2a_bn_shortcut (BatchNorm (None, 128, 48, 156) 512 block_2a_conv_shortcut[0][0] __________________________________________________________________________________________________ add_3 (Add) (None, 128, 48, 156) 0 block_2a_bn_2[0][0] block_2a_bn_shortcut[0][0] __________________________________________________________________________________________________ block_2a_relu (Activation) (None, 128, 48, 156) 0 add_3[0][0] __________________________________________________________________________________________________ block_2b_conv_1 (Conv2D) (None, 128, 48, 156) 147584 block_2a_relu[0][0] __________________________________________________________________________________________________ block_2b_bn_1 (BatchNormalizati (None, 128, 48, 156) 512 block_2b_conv_1[0][0] __________________________________________________________________________________________________ block_2b_relu_1 (Activation) (None, 128, 48, 156) 0 block_2b_bn_1[0][0] __________________________________________________________________________________________________ block_2b_conv_2 (Conv2D) (None, 128, 48, 156) 147584 block_2b_relu_1[0][0] __________________________________________________________________________________________________ block_2b_bn_2 (BatchNormalizati (None, 128, 48, 156) 512 block_2b_conv_2[0][0] __________________________________________________________________________________________________ add_4 (Add) (None, 128, 48, 156) 0 block_2b_bn_2[0][0] block_2a_relu[0][0] __________________________________________________________________________________________________ block_2b_relu (Activation) (None, 128, 48, 156) 0 add_4[0][0] __________________________________________________________________________________________________ block_3a_conv_1 (Conv2D) (None, 256, 24, 78) 295168 block_2b_relu[0][0] __________________________________________________________________________________________________ block_3a_bn_1 (BatchNormalizati (None, 256, 24, 78) 1024 block_3a_conv_1[0][0] __________________________________________________________________________________________________ block_3a_relu_1 (Activation) (None, 256, 24, 78) 0 block_3a_bn_1[0][0] __________________________________________________________________________________________________ block_3a_conv_2 (Conv2D) (None, 256, 24, 78) 590080 block_3a_relu_1[0][0] __________________________________________________________________________________________________ block_3a_conv_shortcut (Conv2D) (None, 256, 24, 78) 33024 block_2b_relu[0][0] __________________________________________________________________________________________________ block_3a_bn_2 (BatchNormalizati (None, 256, 24, 78) 1024 block_3a_conv_2[0][0] __________________________________________________________________________________________________ block_3a_bn_shortcut (BatchNorm (None, 256, 24, 78) 1024 block_3a_conv_shortcut[0][0] __________________________________________________________________________________________________ add_5 (Add) (None, 256, 24, 78) 0 block_3a_bn_2[0][0] block_3a_bn_shortcut[0][0] __________________________________________________________________________________________________ block_3a_relu (Activation) (None, 256, 24, 78) 0 add_5[0][0] __________________________________________________________________________________________________ block_3b_conv_1 (Conv2D) (None, 256, 24, 78) 590080 block_3a_relu[0][0] __________________________________________________________________________________________________ block_3b_bn_1 (BatchNormalizati (None, 256, 24, 78) 1024 block_3b_conv_1[0][0] __________________________________________________________________________________________________ block_3b_relu_1 (Activation) (None, 256, 24, 78) 0 block_3b_bn_1[0][0] __________________________________________________________________________________________________ block_3b_conv_2 (Conv2D) (None, 256, 24, 78) 590080 block_3b_relu_1[0][0] __________________________________________________________________________________________________ block_3b_bn_2 (BatchNormalizati (None, 256, 24, 78) 1024 block_3b_conv_2[0][0] __________________________________________________________________________________________________ add_6 (Add) (None, 256, 24, 78) 0 block_3b_bn_2[0][0] block_3a_relu[0][0] __________________________________________________________________________________________________ block_3b_relu (Activation) (None, 256, 24, 78) 0 add_6[0][0] __________________________________________________________________________________________________ block_4a_conv_1 (Conv2D) (None, 512, 24, 78) 1180160 block_3b_relu[0][0] __________________________________________________________________________________________________ block_4a_bn_1 (BatchNormalizati (None, 512, 24, 78) 2048 block_4a_conv_1[0][0] __________________________________________________________________________________________________ block_4a_relu_1 (Activation) (None, 512, 24, 78) 0 block_4a_bn_1[0][0] __________________________________________________________________________________________________ block_4a_conv_2 (Conv2D) (None, 512, 24, 78) 2359808 block_4a_relu_1[0][0] __________________________________________________________________________________________________ block_4a_conv_shortcut (Conv2D) (None, 512, 24, 78) 131584 block_3b_relu[0][0] __________________________________________________________________________________________________ block_4a_bn_2 (BatchNormalizati (None, 512, 24, 78) 2048 block_4a_conv_2[0][0] __________________________________________________________________________________________________ block_4a_bn_shortcut (BatchNorm (None, 512, 24, 78) 2048 block_4a_conv_shortcut[0][0] __________________________________________________________________________________________________ add_7 (Add) (None, 512, 24, 78) 0 block_4a_bn_2[0][0] block_4a_bn_shortcut[0][0] __________________________________________________________________________________________________ block_4a_relu (Activation) (None, 512, 24, 78) 0 add_7[0][0] __________________________________________________________________________________________________ block_4b_conv_1 (Conv2D) (None, 512, 24, 78) 2359808 block_4a_relu[0][0] __________________________________________________________________________________________________ block_4b_bn_1 (BatchNormalizati (None, 512, 24, 78) 2048 block_4b_conv_1[0][0] __________________________________________________________________________________________________ block_4b_relu_1 (Activation) (None, 512, 24, 78) 0 block_4b_bn_1[0][0] __________________________________________________________________________________________________ block_4b_conv_2 (Conv2D) (None, 512, 24, 78) 2359808 block_4b_relu_1[0][0] __________________________________________________________________________________________________ block_4b_bn_2 (BatchNormalizati (None, 512, 24, 78) 2048 block_4b_conv_2[0][0] __________________________________________________________________________________________________ add_8 (Add) (None, 512, 24, 78) 0 block_4b_bn_2[0][0] block_4a_relu[0][0] __________________________________________________________________________________________________ block_4b_relu (Activation) (None, 512, 24, 78) 0 add_8[0][0] __________________________________________________________________________________________________ output_bbox (Conv2D) (None, 36, 24, 78) 18468 block_4b_relu[0][0] __________________________________________________________________________________________________ output_cov (Conv2D) (None, 9, 24, 78) 4617 block_4b_relu[0][0] ================================================================================================== Total params: 11,218,413 Trainable params: 11,208,685 Non-trainable params: 9,728 __________________________________________________________________________________________________ 2021-11-27 22:10:00,888 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: Serial augmentation enabled = False 2021-11-27 22:10:00,888 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: Pseudo sharding enabled = False 2021-11-27 22:10:00,889 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: Max Image Dimensions (all sources): (0, 0) 2021-11-27 22:10:00,889 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: number of cpus: 16, io threads: 32, compute threads: 16, buffered batches: 4 2021-11-27 22:10:00,889 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: total dataset size 86, number of sources: 1, batch size per gpu: 4, steps: 22 WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/tensorflow_core/python/autograph/converters/directives.py:119: The name tf.set_random_seed is deprecated. Please use tf.compat.v1.set_random_seed instead. 2021-11-27 22:10:00,920 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/tensorflow_core/python/autograph/converters/directives.py:119: The name tf.set_random_seed is deprecated. Please use tf.compat.v1.set_random_seed instead. WARNING:tensorflow:Entity <bound method DriveNetTFRecordsParser.__call__ of <iva.detectnet_v2.dataloader.drivenet_dataloader.DriveNetTFRecordsParser object at 0x7f85a9c8c7f0>> could not be transformed and will be executed as-is. Please report this to the AutoGraph team. When filing the bug, set the verbosity to 10 (on Linux, `export AUTOGRAPH_VERBOSITY=10`) and attach the full output. Cause: Unable to locate the source code of <bound method DriveNetTFRecordsParser.__call__ of <iva.detectnet_v2.dataloader.drivenet_dataloader.DriveNetTFRecordsParser object at 0x7f85a9c8c7f0>>. Note that functions defined in certain environments, like the interactive Python shell do not expose their source code. If that is the case, you should to define them in a .py source file. If you are certain the code is graph-compatible, wrap the call using @tf.autograph.do_not_convert. Original error: could not get source code 2021-11-27 22:10:00,954 [WARNING] tensorflow: Entity <bound method DriveNetTFRecordsParser.__call__ of <iva.detectnet_v2.dataloader.drivenet_dataloader.DriveNetTFRecordsParser object at 0x7f85a9c8c7f0>> could not be transformed and will be executed as-is. Please report this to the AutoGraph team. When filing the bug, set the verbosity to 10 (on Linux, `export AUTOGRAPH_VERBOSITY=10`) and attach the full output. Cause: Unable to locate the source code of <bound method DriveNetTFRecordsParser.__call__ of <iva.detectnet_v2.dataloader.drivenet_dataloader.DriveNetTFRecordsParser object at 0x7f85a9c8c7f0>>. Note that functions defined in certain environments, like the interactive Python shell do not expose their source code. If that is the case, you should to define them in a .py source file. If you are certain the code is graph-compatible, wrap the call using @tf.autograph.do_not_convert. Original error: could not get source code 2021-11-27 22:10:00,967 [INFO] iva.detectnet_v2.dataloader.default_dataloader: Bounding box coordinates were detected in the input specification! Bboxes will be automatically converted to polygon coordinates. 2021-11-27 22:10:01,137 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: shuffle: True - shard 0 of 1 2021-11-27 22:10:01,141 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: sampling 1 datasets with weights: 2021-11-27 22:10:01,141 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: source: 0 weight: 1.000000 WARNING:tensorflow:Entity <bound method Processor.__call__ of <modulus.blocks.data_loaders.multi_source_loader.processors.asset_loader.AssetLoader object at 0x7f85e8be5860>> could not be transformed and will be executed as-is. Please report this to the AutoGraph team. When filing the bug, set the verbosity to 10 (on Linux, `export AUTOGRAPH_VERBOSITY=10`) and attach the full output. Cause: Unable to locate the source code of <bound method Processor.__call__ of <modulus.blocks.data_loaders.multi_source_loader.processors.asset_loader.AssetLoader object at 0x7f85e8be5860>>. Note that functions defined in certain environments, like the interactive Python shell do not expose their source code. If that is the case, you should to define them in a .py source file. If you are certain the code is graph-compatible, wrap the call using @tf.autograph.do_not_convert. Original error: could not get source code 2021-11-27 22:10:01,153 [WARNING] tensorflow: Entity <bound method Processor.__call__ of <modulus.blocks.data_loaders.multi_source_loader.processors.asset_loader.AssetLoader object at 0x7f85e8be5860>> could not be transformed and will be executed as-is. Please report this to the AutoGraph team. When filing the bug, set the verbosity to 10 (on Linux, `export AUTOGRAPH_VERBOSITY=10`) and attach the full output. Cause: Unable to locate the source code of <bound method Processor.__call__ of <modulus.blocks.data_loaders.multi_source_loader.processors.asset_loader.AssetLoader object at 0x7f85e8be5860>>. Note that functions defined in certain environments, like the interactive Python shell do not expose their source code. If that is the case, you should to define them in a .py source file. If you are certain the code is graph-compatible, wrap the call using @tf.autograph.do_not_convert. Original error: could not get source code 2021-11-27 22:10:01,400 [INFO] __main__: Found 86 samples in training set WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/rasterizers/bbox_rasterizer.py:347: The name tf.bincount is deprecated. Please use tf.math.bincount instead. 2021-11-27 22:10:01,471 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/rasterizers/bbox_rasterizer.py:347: The name tf.bincount is deprecated. Please use tf.math.bincount instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/training/training_proto_utilities.py:89: The name tf.train.get_or_create_global_step is deprecated. Please use tf.compat.v1.train.get_or_create_global_step instead. 2021-11-27 22:10:01,590 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/training/training_proto_utilities.py:89: The name tf.train.get_or_create_global_step is deprecated. Please use tf.compat.v1.train.get_or_create_global_step instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/training/training_proto_utilities.py:36: The name tf.train.AdamOptimizer is deprecated. Please use tf.compat.v1.train.AdamOptimizer instead. 2021-11-27 22:10:01,601 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/training/training_proto_utilities.py:36: The name tf.train.AdamOptimizer is deprecated. Please use tf.compat.v1.train.AdamOptimizer instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_functions.py:17: The name tf.log is deprecated. Please use tf.math.log instead. 2021-11-27 22:10:01,808 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_functions.py:17: The name tf.log is deprecated. Please use tf.math.log instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:235: The name tf.assign_add is deprecated. Please use tf.compat.v1.assign_add instead. 2021-11-27 22:10:01,902 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/cost_function/cost_auto_weight_hook.py:235: The name tf.assign_add is deprecated. Please use tf.compat.v1.assign_add instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/model/detectnet_model.py:591: The name tf.summary.scalar is deprecated. Please use tf.compat.v1.summary.scalar instead. 2021-11-27 22:10:01,920 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/model/detectnet_model.py:591: The name tf.summary.scalar is deprecated. Please use tf.compat.v1.summary.scalar instead. 2021-11-27 22:10:03,236 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: Serial augmentation enabled = False 2021-11-27 22:10:03,236 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: Pseudo sharding enabled = False 2021-11-27 22:10:03,236 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: Max Image Dimensions (all sources): (0, 0) 2021-11-27 22:10:03,236 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: number of cpus: 16, io threads: 32, compute threads: 16, buffered batches: 4 2021-11-27 22:10:03,236 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: total dataset size 14, number of sources: 1, batch size per gpu: 4, steps: 4 WARNING:tensorflow:Entity <bound method DriveNetTFRecordsParser.__call__ of <iva.detectnet_v2.dataloader.drivenet_dataloader.DriveNetTFRecordsParser object at 0x7f85a9c8c898>> could not be transformed and will be executed as-is. Please report this to the AutoGraph team. When filing the bug, set the verbosity to 10 (on Linux, `export AUTOGRAPH_VERBOSITY=10`) and attach the full output. Cause: Unable to locate the source code of <bound method DriveNetTFRecordsParser.__call__ of <iva.detectnet_v2.dataloader.drivenet_dataloader.DriveNetTFRecordsParser object at 0x7f85a9c8c898>>. Note that functions defined in certain environments, like the interactive Python shell do not expose their source code. If that is the case, you should to define them in a .py source file. If you are certain the code is graph-compatible, wrap the call using @tf.autograph.do_not_convert. Original error: could not get source code 2021-11-27 22:10:03,243 [WARNING] tensorflow: Entity <bound method DriveNetTFRecordsParser.__call__ of <iva.detectnet_v2.dataloader.drivenet_dataloader.DriveNetTFRecordsParser object at 0x7f85a9c8c898>> could not be transformed and will be executed as-is. Please report this to the AutoGraph team. When filing the bug, set the verbosity to 10 (on Linux, `export AUTOGRAPH_VERBOSITY=10`) and attach the full output. Cause: Unable to locate the source code of <bound method DriveNetTFRecordsParser.__call__ of <iva.detectnet_v2.dataloader.drivenet_dataloader.DriveNetTFRecordsParser object at 0x7f85a9c8c898>>. Note that functions defined in certain environments, like the interactive Python shell do not expose their source code. If that is the case, you should to define them in a .py source file. If you are certain the code is graph-compatible, wrap the call using @tf.autograph.do_not_convert. Original error: could not get source code 2021-11-27 22:10:03,259 [INFO] iva.detectnet_v2.dataloader.default_dataloader: Bounding box coordinates were detected in the input specification! Bboxes will be automatically converted to polygon coordinates. 2021-11-27 22:10:03,417 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: shuffle: False - shard 0 of 1 2021-11-27 22:10:03,420 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: sampling 1 datasets with weights: 2021-11-27 22:10:03,420 [INFO] modulus.blocks.data_loaders.multi_source_loader.data_loader: source: 0 weight: 1.000000 WARNING:tensorflow:Entity <bound method Processor.__call__ of <modulus.blocks.data_loaders.multi_source_loader.processors.asset_loader.AssetLoader object at 0x7f85704ce8d0>> could not be transformed and will be executed as-is. Please report this to the AutoGraph team. When filing the bug, set the verbosity to 10 (on Linux, `export AUTOGRAPH_VERBOSITY=10`) and attach the full output. Cause: Unable to locate the source code of <bound method Processor.__call__ of <modulus.blocks.data_loaders.multi_source_loader.processors.asset_loader.AssetLoader object at 0x7f85704ce8d0>>. Note that functions defined in certain environments, like the interactive Python shell do not expose their source code. If that is the case, you should to define them in a .py source file. If you are certain the code is graph-compatible, wrap the call using @tf.autograph.do_not_convert. Original error: could not get source code 2021-11-27 22:10:03,431 [WARNING] tensorflow: Entity <bound method Processor.__call__ of <modulus.blocks.data_loaders.multi_source_loader.processors.asset_loader.AssetLoader object at 0x7f85704ce8d0>> could not be transformed and will be executed as-is. Please report this to the AutoGraph team. When filing the bug, set the verbosity to 10 (on Linux, `export AUTOGRAPH_VERBOSITY=10`) and attach the full output. Cause: Unable to locate the source code of <bound method Processor.__call__ of <modulus.blocks.data_loaders.multi_source_loader.processors.asset_loader.AssetLoader object at 0x7f85704ce8d0>>. Note that functions defined in certain environments, like the interactive Python shell do not expose their source code. If that is the case, you should to define them in a .py source file. If you are certain the code is graph-compatible, wrap the call using @tf.autograph.do_not_convert. Original error: could not get source code 2021-11-27 22:10:03,590 [INFO] __main__: Found 14 samples in validation set WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/validation_hook.py:40: The name tf.summary.FileWriterCache is deprecated. Please use tf.compat.v1.summary.FileWriterCache instead. 2021-11-27 22:10:04,205 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/validation_hook.py:40: The name tf.summary.FileWriterCache is deprecated. Please use tf.compat.v1.summary.FileWriterCache instead. 2021-11-27 22:10:05,025 [INFO] __main__: Checkpoint interval: 10 WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/scripts/train.py:109: The name tf.train.Scaffold is deprecated. Please use tf.compat.v1.train.Scaffold instead. 2021-11-27 22:10:05,026 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/scripts/train.py:109: The name tf.train.Scaffold is deprecated. Please use tf.compat.v1.train.Scaffold instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/common/graph/initializers.py:14: The name tf.local_variables_initializer is deprecated. Please use tf.compat.v1.local_variables_initializer instead. 2021-11-27 22:10:05,026 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/common/graph/initializers.py:14: The name tf.local_variables_initializer is deprecated. Please use tf.compat.v1.local_variables_initializer instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/common/graph/initializers.py:15: The name tf.tables_initializer is deprecated. Please use tf.compat.v1.tables_initializer instead. 2021-11-27 22:10:05,026 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/common/graph/initializers.py:15: The name tf.tables_initializer is deprecated. Please use tf.compat.v1.tables_initializer instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/common/graph/initializers.py:16: The name tf.get_collection is deprecated. Please use tf.compat.v1.get_collection instead. 2021-11-27 22:10:05,027 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/common/graph/initializers.py:16: The name tf.get_collection is deprecated. Please use tf.compat.v1.get_collection instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/utils.py:59: The name tf.train.LoggingTensorHook is deprecated. Please use tf.estimator.LoggingTensorHook instead. 2021-11-27 22:10:05,028 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/utils.py:59: The name tf.train.LoggingTensorHook is deprecated. Please use tf.estimator.LoggingTensorHook instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/utils.py:60: The name tf.train.StopAtStepHook is deprecated. Please use tf.estimator.StopAtStepHook instead. 2021-11-27 22:10:05,028 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/utils.py:60: The name tf.train.StopAtStepHook is deprecated. Please use tf.estimator.StopAtStepHook instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/utils.py:73: The name tf.train.StepCounterHook is deprecated. Please use tf.estimator.StepCounterHook instead. 2021-11-27 22:10:05,028 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/utils.py:73: The name tf.train.StepCounterHook is deprecated. Please use tf.estimator.StepCounterHook instead. INFO:tensorflow:Create CheckpointSaverHook. 2021-11-27 22:10:05,028 [INFO] tensorflow: Create CheckpointSaverHook. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/utils.py:99: The name tf.train.SummarySaverHook is deprecated. Please use tf.estimator.SummarySaverHook instead. 2021-11-27 22:10:05,028 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/tfhooks/utils.py:99: The name tf.train.SummarySaverHook is deprecated. Please use tf.estimator.SummarySaverHook instead. WARNING:tensorflow:From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/training/utilities.py:140: The name tf.train.SingularMonitoredSession is deprecated. Please use tf.compat.v1.train.SingularMonitoredSession instead. 2021-11-27 22:10:05,029 [WARNING] tensorflow: From /opt/tlt/.cache/dazel/_dazel_tlt/75913d2aee35770fa76c4a63d877f3aa/execroot/ai_infra/bazel-out/k8-fastbuild/bin/magnet/packages/iva/build_wheel.runfiles/ai_infra/iva/detectnet_v2/training/utilities.py:140: The name tf.train.SingularMonitoredSession is deprecated. Please use tf.compat.v1.train.SingularMonitoredSession instead. INFO:tensorflow:Graph was finalized. 2021-11-27 22:10:05,573 [INFO] tensorflow: Graph was finalized. INFO:tensorflow:Running local_init_op. 2021-11-27 22:10:06,767 [INFO] tensorflow: Running local_init_op. INFO:tensorflow:Done running local_init_op. 2021-11-27 22:10:07,176 [INFO] tensorflow: Done running local_init_op. INFO:tensorflow:Saving checkpoints for step-0. 2021-11-27 22:10:11,761 [INFO] tensorflow: Saving checkpoints for step-0. INFO:tensorflow:epoch = 0.0, learning_rate = 4.9999994e-06, loss = 0.0057869037, step = 0 2021-11-27 22:10:27,132 [INFO] tensorflow: epoch = 0.0, learning_rate = 4.9999994e-06, loss = 0.0057869037, step = 0 2021-11-27 22:10:27,135 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 0/120: loss: 0.00579 learning rate: 0.00000 Time taken: 0:00:00 ETA: 0:00:00 2021-11-27 22:10:27,135 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 0.886 INFO:tensorflow:global_step/sec: 1.28718 2021-11-27 22:10:28,688 [INFO] tensorflow: global_step/sec: 1.28718 INFO:tensorflow:global_step/sec: 14.0748 2021-11-27 22:10:28,830 [INFO] tensorflow: global_step/sec: 14.0748 INFO:tensorflow:global_step/sec: 14.3482 2021-11-27 22:10:28,969 [INFO] tensorflow: global_step/sec: 14.3482 INFO:tensorflow:global_step/sec: 13.9133 2021-11-27 22:10:29,113 [INFO] tensorflow: global_step/sec: 13.9133 INFO:tensorflow:global_step/sec: 14.2399 2021-11-27 22:10:29,253 [INFO] tensorflow: global_step/sec: 14.2399 INFO:tensorflow:global_step/sec: 14.5412 2021-11-27 22:10:29,391 [INFO] tensorflow: global_step/sec: 14.5412 INFO:tensorflow:global_step/sec: 14.7486 2021-11-27 22:10:29,527 [INFO] tensorflow: global_step/sec: 14.7486 INFO:tensorflow:global_step/sec: 14.9261 2021-11-27 22:10:29,661 [INFO] tensorflow: global_step/sec: 14.9261 INFO:tensorflow:global_step/sec: 13.9907 2021-11-27 22:10:29,804 [INFO] tensorflow: global_step/sec: 13.9907 INFO:tensorflow:global_step/sec: 14.7185 2021-11-27 22:10:29,939 [INFO] tensorflow: global_step/sec: 14.7185 13aa653a306f:58:92 [0] NCCL INFO Bootstrap : Using lo:127.0.0.1<0> 13aa653a306f:58:92 [0] NCCL INFO NET/Plugin : Plugin load returned 0 : libnccl-net.so: cannot open shared object file: No such file or directory. 13aa653a306f:58:92 [0] NCCL INFO NET/IB : No device found. 13aa653a306f:58:92 [0] NCCL INFO NET/Socket : Using [0]lo:127.0.0.1<0> [1]eth0:172.17.0.2<0> 13aa653a306f:58:92 [0] NCCL INFO Using network Socket NCCL version 2.9.9+cuda11.3 13aa653a306f:58:92 [0] NCCL INFO Channel 00/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 01/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 02/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 03/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 04/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 05/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 06/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 07/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 08/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 09/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 10/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 11/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 12/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 13/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 14/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 15/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 16/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 17/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 18/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 19/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 20/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 21/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 22/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 23/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 24/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 25/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 26/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 27/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 28/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 29/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 30/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Channel 31/32 : 0 13aa653a306f:58:92 [0] NCCL INFO Trees [0] -1/-1/-1->0->-1 [1] -1/-1/-1->0->-1 [2] -1/-1/-1->0->-1 [3] -1/-1/-1->0->-1 [4] -1/-1/-1->0->-1 [5] -1/-1/-1->0->-1 [6] -1/-1/-1->0->-1 [7] -1/-1/-1->0->-1 [8] -1/-1/-1->0->-1 [9] -1/-1/-1->0->-1 [10] -1/-1/-1->0->-1 [11] -1/-1/-1->0->-1 [12] -1/-1/-1->0->-1 [13] -1/-1/-1->0->-1 [14] -1/-1/-1->0->-1 [15] -1/-1/-1->0->-1 [16] -1/-1/-1->0->-1 [17] -1/-1/-1->0->-1 [18] -1/-1/-1->0->-1 [19] -1/-1/-1->0->-1 [20] -1/-1/-1->0->-1 [21] -1/-1/-1->0->-1 [22] -1/-1/-1->0->-1 [23] -1/-1/-1->0->-1 [24] -1/-1/-1->0->-1 [25] -1/-1/-1->0->-1 [26] -1/-1/-1->0->-1 [27] -1/-1/-1->0->-1 [28] -1/-1/-1->0->-1 [29] -1/-1/-1->0->-1 [30] -1/-1/-1->0->-1 [31] -1/-1/-1->0->-1 13aa653a306f:58:92 [0] NCCL INFO Connected all rings 13aa653a306f:58:92 [0] NCCL INFO Connected all trees 13aa653a306f:58:92 [0] NCCL INFO 32 coll channels, 32 p2p channels, 32 p2p channels per peer 13aa653a306f:58:92 [0] NCCL INFO comm 0x7f85a777da10 rank 0 nranks 1 cudaDev 0 busId 9000 - Init COMPLETE INFO:tensorflow:global_step/sec: 4.76802 2021-11-27 22:10:30,359 [INFO] tensorflow: global_step/sec: 4.76802 2021-11-27 22:10:30,360 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 1/120: loss: 0.00117 learning rate: 0.00001 Time taken: 0:00:07.667110 ETA: 0:15:12.386114 INFO:tensorflow:global_step/sec: 14.1503 2021-11-27 22:10:30,500 [INFO] tensorflow: global_step/sec: 14.1503 2021-11-27 22:10:30,502 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 12.688 INFO:tensorflow:global_step/sec: 13.962 2021-11-27 22:10:30,643 [INFO] tensorflow: global_step/sec: 13.962 INFO:tensorflow:global_step/sec: 14.2076 2021-11-27 22:10:30,784 [INFO] tensorflow: global_step/sec: 14.2076 INFO:tensorflow:global_step/sec: 13.9978 2021-11-27 22:10:30,927 [INFO] tensorflow: global_step/sec: 13.9978 INFO:tensorflow:global_step/sec: 13.8975 2021-11-27 22:10:31,071 [INFO] tensorflow: global_step/sec: 13.8975 INFO:tensorflow:global_step/sec: 14.8656 2021-11-27 22:10:31,206 [INFO] tensorflow: global_step/sec: 14.8656 INFO:tensorflow:global_step/sec: 14.3368 2021-11-27 22:10:31,345 [INFO] tensorflow: global_step/sec: 14.3368 INFO:tensorflow:global_step/sec: 12.7762 2021-11-27 22:10:31,502 [INFO] tensorflow: global_step/sec: 12.7762 INFO:tensorflow:global_step/sec: 14.4759 2021-11-27 22:10:31,640 [INFO] tensorflow: global_step/sec: 14.4759 INFO:tensorflow:global_step/sec: 14.5683 2021-11-27 22:10:31,777 [INFO] tensorflow: global_step/sec: 14.5683 INFO:tensorflow:global_step/sec: 13.889 2021-11-27 22:10:31,921 [INFO] tensorflow: global_step/sec: 13.889 2021-11-27 22:10:31,922 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 2/120: loss: 0.00123 learning rate: 0.00001 Time taken: 0:00:01.565355 ETA: 0:03:04.711841 INFO:tensorflow:global_step/sec: 14.3858 2021-11-27 22:10:32,060 [INFO] tensorflow: global_step/sec: 14.3858 INFO:tensorflow:global_step/sec: 14.6394 2021-11-27 22:10:32,197 [INFO] tensorflow: global_step/sec: 14.6394 INFO:tensorflow:epoch = 2.2272727272727275, learning_rate = 1.1753905e-05, loss = 0.0011409044, step = 49 (5.136 sec) 2021-11-27 22:10:32,268 [INFO] tensorflow: epoch = 2.2272727272727275, learning_rate = 1.1753905e-05, loss = 0.0011409044, step = 49 (5.136 sec) 2021-11-27 22:10:32,268 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 56.623 INFO:tensorflow:global_step/sec: 14.1407 2021-11-27 22:10:32,338 [INFO] tensorflow: global_step/sec: 14.1407 INFO:tensorflow:global_step/sec: 14.5826 2021-11-27 22:10:32,475 [INFO] tensorflow: global_step/sec: 14.5826 INFO:tensorflow:global_step/sec: 14.2709 2021-11-27 22:10:32,615 [INFO] tensorflow: global_step/sec: 14.2709 INFO:tensorflow:global_step/sec: 14.667 2021-11-27 22:10:32,752 [INFO] tensorflow: global_step/sec: 14.667 INFO:tensorflow:global_step/sec: 14.2539 2021-11-27 22:10:32,892 [INFO] tensorflow: global_step/sec: 14.2539 INFO:tensorflow:global_step/sec: 14.0792 2021-11-27 22:10:33,034 [INFO] tensorflow: global_step/sec: 14.0792 INFO:tensorflow:global_step/sec: 14.1632 2021-11-27 22:10:33,175 [INFO] tensorflow: global_step/sec: 14.1632 INFO:tensorflow:global_step/sec: 14.6989 2021-11-27 22:10:33,311 [INFO] tensorflow: global_step/sec: 14.6989 INFO:tensorflow:global_step/sec: 13.6269 2021-11-27 22:10:33,458 [INFO] tensorflow: global_step/sec: 13.6269 2021-11-27 22:10:33,459 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 3/120: loss: 0.00113 learning rate: 0.00002 Time taken: 0:00:01.530060 ETA: 0:02:59.016998 INFO:tensorflow:global_step/sec: 14.4893 2021-11-27 22:10:33,596 [INFO] tensorflow: global_step/sec: 14.4893 INFO:tensorflow:global_step/sec: 14.6592 2021-11-27 22:10:33,733 [INFO] tensorflow: global_step/sec: 14.6592 INFO:tensorflow:global_step/sec: 14.2459 2021-11-27 22:10:33,873 [INFO] tensorflow: global_step/sec: 14.2459 INFO:tensorflow:global_step/sec: 14.5389 2021-11-27 22:10:34,011 [INFO] tensorflow: global_step/sec: 14.5389 2021-11-27 22:10:34,011 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.380 INFO:tensorflow:global_step/sec: 14.1133 2021-11-27 22:10:34,152 [INFO] tensorflow: global_step/sec: 14.1133 INFO:tensorflow:global_step/sec: 14.4133 2021-11-27 22:10:34,291 [INFO] tensorflow: global_step/sec: 14.4133 INFO:tensorflow:global_step/sec: 14.2858 2021-11-27 22:10:34,431 [INFO] tensorflow: global_step/sec: 14.2858 INFO:tensorflow:global_step/sec: 13.8519 2021-11-27 22:10:34,575 [INFO] tensorflow: global_step/sec: 13.8519 INFO:tensorflow:global_step/sec: 15.0399 2021-11-27 22:10:34,708 [INFO] tensorflow: global_step/sec: 15.0399 INFO:tensorflow:global_step/sec: 14.6715 2021-11-27 22:10:34,845 [INFO] tensorflow: global_step/sec: 14.6715 INFO:tensorflow:global_step/sec: 14.0326 2021-11-27 22:10:34,987 [INFO] tensorflow: global_step/sec: 14.0326 2021-11-27 22:10:34,989 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 4/120: loss: 0.00138 learning rate: 0.00002 Time taken: 0:00:01.529464 ETA: 0:02:57.417825 INFO:tensorflow:global_step/sec: 13.7093 2021-11-27 22:10:35,133 [INFO] tensorflow: global_step/sec: 13.7093 INFO:tensorflow:global_step/sec: 14.6254 2021-11-27 22:10:35,270 [INFO] tensorflow: global_step/sec: 14.6254 INFO:tensorflow:global_step/sec: 14.9256 2021-11-27 22:10:35,404 [INFO] tensorflow: global_step/sec: 14.9256 INFO:tensorflow:global_step/sec: 14.6991 2021-11-27 22:10:35,540 [INFO] tensorflow: global_step/sec: 14.6991 INFO:tensorflow:global_step/sec: 14.6541 2021-11-27 22:10:35,676 [INFO] tensorflow: global_step/sec: 14.6541 2021-11-27 22:10:35,745 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.687 INFO:tensorflow:global_step/sec: 14.5807 2021-11-27 22:10:35,814 [INFO] tensorflow: global_step/sec: 14.5807 INFO:tensorflow:global_step/sec: 14.7909 2021-11-27 22:10:35,949 [INFO] tensorflow: global_step/sec: 14.7909 INFO:tensorflow:global_step/sec: 14.7448 2021-11-27 22:10:36,084 [INFO] tensorflow: global_step/sec: 14.7448 INFO:tensorflow:global_step/sec: 14.5405 2021-11-27 22:10:36,222 [INFO] tensorflow: global_step/sec: 14.5405 INFO:tensorflow:global_step/sec: 14.6553 2021-11-27 22:10:36,358 [INFO] tensorflow: global_step/sec: 14.6553 INFO:tensorflow:global_step/sec: 14.2135 2021-11-27 22:10:36,499 [INFO] tensorflow: global_step/sec: 14.2135 2021-11-27 22:10:36,500 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 5/120: loss: 0.00136 learning rate: 0.00003 Time taken: 0:00:01.513087 ETA: 0:02:54.005009 INFO:tensorflow:global_step/sec: 14.3893 2021-11-27 22:10:36,638 [INFO] tensorflow: global_step/sec: 14.3893 INFO:tensorflow:global_step/sec: 14.7552 2021-11-27 22:10:36,774 [INFO] tensorflow: global_step/sec: 14.7552 INFO:tensorflow:global_step/sec: 15.0784 2021-11-27 22:10:36,906 [INFO] tensorflow: global_step/sec: 15.0784 INFO:tensorflow:global_step/sec: 14.8035 2021-11-27 22:10:37,041 [INFO] tensorflow: global_step/sec: 14.8035 INFO:tensorflow:global_step/sec: 14.7248 2021-11-27 22:10:37,177 [INFO] tensorflow: global_step/sec: 14.7248 INFO:tensorflow:global_step/sec: 15.2789 2021-11-27 22:10:37,308 [INFO] tensorflow: global_step/sec: 15.2789 INFO:tensorflow:epoch = 5.590909090909091, learning_rate = 4.273544e-05, loss = 0.0011919353, step = 123 (5.106 sec) 2021-11-27 22:10:37,375 [INFO] tensorflow: epoch = 5.590909090909091, learning_rate = 4.273544e-05, loss = 0.0011919353, step = 123 (5.106 sec) INFO:tensorflow:global_step/sec: 14.1974 2021-11-27 22:10:37,449 [INFO] tensorflow: global_step/sec: 14.1974 2021-11-27 22:10:37,450 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.682 INFO:tensorflow:global_step/sec: 14.4085 2021-11-27 22:10:37,588 [INFO] tensorflow: global_step/sec: 14.4085 INFO:tensorflow:global_step/sec: 14.2272 2021-11-27 22:10:37,728 [INFO] tensorflow: global_step/sec: 14.2272 INFO:tensorflow:global_step/sec: 14.009 2021-11-27 22:10:37,871 [INFO] tensorflow: global_step/sec: 14.009 INFO:tensorflow:global_step/sec: 13.9053 2021-11-27 22:10:38,015 [INFO] tensorflow: global_step/sec: 13.9053 2021-11-27 22:10:38,016 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 6/120: loss: 0.00127 learning rate: 0.00005 Time taken: 0:00:01.511400 ETA: 0:02:52.299653 INFO:tensorflow:global_step/sec: 14.4003 2021-11-27 22:10:38,154 [INFO] tensorflow: global_step/sec: 14.4003 INFO:tensorflow:global_step/sec: 14.2242 2021-11-27 22:10:38,295 [INFO] tensorflow: global_step/sec: 14.2242 INFO:tensorflow:global_step/sec: 13.7182 2021-11-27 22:10:38,440 [INFO] tensorflow: global_step/sec: 13.7182 INFO:tensorflow:global_step/sec: 14.6096 2021-11-27 22:10:38,577 [INFO] tensorflow: global_step/sec: 14.6096 INFO:tensorflow:global_step/sec: 13.9033 2021-11-27 22:10:38,721 [INFO] tensorflow: global_step/sec: 13.9033 INFO:tensorflow:global_step/sec: 14.3514 2021-11-27 22:10:38,860 [INFO] tensorflow: global_step/sec: 14.3514 INFO:tensorflow:global_step/sec: 14.5929 2021-11-27 22:10:38,997 [INFO] tensorflow: global_step/sec: 14.5929 INFO:tensorflow:global_step/sec: 14.5577 2021-11-27 22:10:39,135 [INFO] tensorflow: global_step/sec: 14.5577 2021-11-27 22:10:39,201 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.101 INFO:tensorflow:global_step/sec: 14.6615 2021-11-27 22:10:39,271 [INFO] tensorflow: global_step/sec: 14.6615 INFO:tensorflow:global_step/sec: 13.9038 2021-11-27 22:10:39,415 [INFO] tensorflow: global_step/sec: 13.9038 INFO:tensorflow:global_step/sec: 13.7495 2021-11-27 22:10:39,561 [INFO] tensorflow: global_step/sec: 13.7495 2021-11-27 22:10:39,562 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 7/120: loss: 0.00131 learning rate: 0.00007 Time taken: 0:00:01.544771 ETA: 0:02:54.559091 INFO:tensorflow:global_step/sec: 14.4595 2021-11-27 22:10:39,699 [INFO] tensorflow: global_step/sec: 14.4595 INFO:tensorflow:global_step/sec: 14.2927 2021-11-27 22:10:39,839 [INFO] tensorflow: global_step/sec: 14.2927 INFO:tensorflow:global_step/sec: 14.7751 2021-11-27 22:10:39,974 [INFO] tensorflow: global_step/sec: 14.7751 INFO:tensorflow:global_step/sec: 14.5882 2021-11-27 22:10:40,111 [INFO] tensorflow: global_step/sec: 14.5882 INFO:tensorflow:global_step/sec: 13.4683 2021-11-27 22:10:40,260 [INFO] tensorflow: global_step/sec: 13.4683 INFO:tensorflow:global_step/sec: 14.0951 2021-11-27 22:10:40,402 [INFO] tensorflow: global_step/sec: 14.0951 INFO:tensorflow:global_step/sec: 14.0164 2021-11-27 22:10:40,544 [INFO] tensorflow: global_step/sec: 14.0164 INFO:tensorflow:global_step/sec: 14.4133 2021-11-27 22:10:40,683 [INFO] tensorflow: global_step/sec: 14.4133 INFO:tensorflow:global_step/sec: 14.4137 2021-11-27 22:10:40,822 [INFO] tensorflow: global_step/sec: 14.4137 INFO:tensorflow:global_step/sec: 14.8374 2021-11-27 22:10:40,957 [INFO] tensorflow: global_step/sec: 14.8374 2021-11-27 22:10:40,957 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 56.960 INFO:tensorflow:global_step/sec: 13.769 2021-11-27 22:10:41,102 [INFO] tensorflow: global_step/sec: 13.769 2021-11-27 22:10:41,103 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 8/120: loss: 0.00133 learning rate: 0.00011 Time taken: 0:00:01.539389 ETA: 0:02:52.411583 INFO:tensorflow:global_step/sec: 14.8138 2021-11-27 22:10:41,237 [INFO] tensorflow: global_step/sec: 14.8138 INFO:tensorflow:global_step/sec: 14.8726 2021-11-27 22:10:41,371 [INFO] tensorflow: global_step/sec: 14.8726 INFO:tensorflow:global_step/sec: 14.3696 2021-11-27 22:10:41,511 [INFO] tensorflow: global_step/sec: 14.3696 INFO:tensorflow:global_step/sec: 13.1318 2021-11-27 22:10:41,663 [INFO] tensorflow: global_step/sec: 13.1318 INFO:tensorflow:global_step/sec: 14.2613 2021-11-27 22:10:41,803 [INFO] tensorflow: global_step/sec: 14.2613 INFO:tensorflow:global_step/sec: 14.157 2021-11-27 22:10:41,944 [INFO] tensorflow: global_step/sec: 14.157 INFO:tensorflow:global_step/sec: 14.4501 2021-11-27 22:10:42,083 [INFO] tensorflow: global_step/sec: 14.4501 INFO:tensorflow:global_step/sec: 14.2194 2021-11-27 22:10:42,223 [INFO] tensorflow: global_step/sec: 14.2194 INFO:tensorflow:global_step/sec: 14.7607 2021-11-27 22:10:42,359 [INFO] tensorflow: global_step/sec: 14.7607 INFO:tensorflow:epoch = 8.90909090909091, learning_rate = 0.00015269278, loss = 0.0012858632, step = 196 (5.115 sec) 2021-11-27 22:10:42,489 [INFO] tensorflow: epoch = 8.90909090909091, learning_rate = 0.00015269278, loss = 0.0012858632, step = 196 (5.115 sec) INFO:tensorflow:global_step/sec: 15.2785 2021-11-27 22:10:42,490 [INFO] tensorflow: global_step/sec: 15.2785 INFO:tensorflow:global_step/sec: 13.9753 2021-11-27 22:10:42,633 [INFO] tensorflow: global_step/sec: 13.9753 2021-11-27 22:10:42,634 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 9/120: loss: 0.00129 learning rate: 0.00016 Time taken: 0:00:01.528173 ETA: 0:02:49.627200 2021-11-27 22:10:42,702 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.329 INFO:tensorflow:global_step/sec: 14.7919 2021-11-27 22:10:42,768 [INFO] tensorflow: global_step/sec: 14.7919 INFO:tensorflow:global_step/sec: 15.2408 2021-11-27 22:10:42,899 [INFO] tensorflow: global_step/sec: 15.2408 INFO:tensorflow:global_step/sec: 15.0523 2021-11-27 22:10:43,032 [INFO] tensorflow: global_step/sec: 15.0523 INFO:tensorflow:global_step/sec: 15.2208 2021-11-27 22:10:43,164 [INFO] tensorflow: global_step/sec: 15.2208 INFO:tensorflow:global_step/sec: 15.4563 2021-11-27 22:10:43,293 [INFO] tensorflow: global_step/sec: 15.4563 INFO:tensorflow:global_step/sec: 15.1066 2021-11-27 22:10:43,425 [INFO] tensorflow: global_step/sec: 15.1066 INFO:tensorflow:global_step/sec: 15.342 2021-11-27 22:10:43,556 [INFO] tensorflow: global_step/sec: 15.342 INFO:tensorflow:global_step/sec: 14.7897 2021-11-27 22:10:43,691 [INFO] tensorflow: global_step/sec: 14.7897 INFO:tensorflow:global_step/sec: 15.075 2021-11-27 22:10:43,824 [INFO] tensorflow: global_step/sec: 15.075 INFO:tensorflow:global_step/sec: 14.805 2021-11-27 22:10:43,959 [INFO] tensorflow: global_step/sec: 14.805 INFO:tensorflow:Saving checkpoints for step-220. 2021-11-27 22:10:44,030 [INFO] tensorflow: Saving checkpoints for step-220. INFO:tensorflow:global_step/sec: 0.804096 2021-11-27 22:10:46,446 [INFO] tensorflow: global_step/sec: 0.804096 2021-11-27 22:10:46,447 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 10/120: loss: 0.00132 learning rate: 0.00023 Time taken: 0:00:03.811719 ETA: 0:06:59.289083 INFO:tensorflow:global_step/sec: 14.5069 2021-11-27 22:10:46,584 [INFO] tensorflow: global_step/sec: 14.5069 INFO:tensorflow:global_step/sec: 15.36 2021-11-27 22:10:46,714 [INFO] tensorflow: global_step/sec: 15.36 2021-11-27 22:10:46,715 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 24.920 INFO:tensorflow:global_step/sec: 14.9594 2021-11-27 22:10:46,848 [INFO] tensorflow: global_step/sec: 14.9594 INFO:tensorflow:global_step/sec: 15.2989 2021-11-27 22:10:46,979 [INFO] tensorflow: global_step/sec: 15.2989 INFO:tensorflow:global_step/sec: 15.0733 2021-11-27 22:10:47,111 [INFO] tensorflow: global_step/sec: 15.0733 INFO:tensorflow:global_step/sec: 14.8818 2021-11-27 22:10:47,246 [INFO] tensorflow: global_step/sec: 14.8818 INFO:tensorflow:global_step/sec: 14.7169 2021-11-27 22:10:47,382 [INFO] tensorflow: global_step/sec: 14.7169 INFO:tensorflow:global_step/sec: 15.3257 2021-11-27 22:10:47,512 [INFO] tensorflow: global_step/sec: 15.3257 INFO:tensorflow:epoch = 10.772727272727273, learning_rate = 0.00031219394, loss = 0.0011556421, step = 237 (5.089 sec) 2021-11-27 22:10:47,578 [INFO] tensorflow: epoch = 10.772727272727273, learning_rate = 0.00031219394, loss = 0.0011556421, step = 237 (5.089 sec) INFO:tensorflow:global_step/sec: 15.2045 2021-11-27 22:10:47,644 [INFO] tensorflow: global_step/sec: 15.2045 INFO:tensorflow:global_step/sec: 14.4798 2021-11-27 22:10:47,782 [INFO] tensorflow: global_step/sec: 14.4798 INFO:tensorflow:global_step/sec: 14.1615 2021-11-27 22:10:47,923 [INFO] tensorflow: global_step/sec: 14.1615 2021-11-27 22:10:47,924 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 11/120: loss: 0.00131 learning rate: 0.00034 Time taken: 0:00:01.477134 ETA: 0:02:41.007631 INFO:tensorflow:global_step/sec: 15.0237 2021-11-27 22:10:48,056 [INFO] tensorflow: global_step/sec: 15.0237 INFO:tensorflow:global_step/sec: 14.9112 2021-11-27 22:10:48,190 [INFO] tensorflow: global_step/sec: 14.9112 INFO:tensorflow:global_step/sec: 14.5709 2021-11-27 22:10:48,327 [INFO] tensorflow: global_step/sec: 14.5709 2021-11-27 22:10:48,394 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.565 INFO:tensorflow:global_step/sec: 15.2341 2021-11-27 22:10:48,459 [INFO] tensorflow: global_step/sec: 15.2341 INFO:tensorflow:global_step/sec: 14.2254 2021-11-27 22:10:48,599 [INFO] tensorflow: global_step/sec: 14.2254 INFO:tensorflow:global_step/sec: 15.0726 2021-11-27 22:10:48,732 [INFO] tensorflow: global_step/sec: 15.0726 INFO:tensorflow:global_step/sec: 15.1707 2021-11-27 22:10:48,864 [INFO] tensorflow: global_step/sec: 15.1707 INFO:tensorflow:global_step/sec: 14.9127 2021-11-27 22:10:48,998 [INFO] tensorflow: global_step/sec: 14.9127 INFO:tensorflow:global_step/sec: 14.8905 2021-11-27 22:10:49,132 [INFO] tensorflow: global_step/sec: 14.8905 INFO:tensorflow:global_step/sec: 14.5764 2021-11-27 22:10:49,270 [INFO] tensorflow: global_step/sec: 14.5764 INFO:tensorflow:global_step/sec: 14.5349 2021-11-27 22:10:49,407 [INFO] tensorflow: global_step/sec: 14.5349 2021-11-27 22:10:49,408 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 12/120: loss: 0.00111 learning rate: 0.00050 Time taken: 0:00:01.486349 ETA: 0:02:40.525652 INFO:tensorflow:global_step/sec: 15.4042 2021-11-27 22:10:49,537 [INFO] tensorflow: global_step/sec: 15.4042 INFO:tensorflow:global_step/sec: 14.9203 2021-11-27 22:10:49,671 [INFO] tensorflow: global_step/sec: 14.9203 INFO:tensorflow:global_step/sec: 15.0214 2021-11-27 22:10:49,804 [INFO] tensorflow: global_step/sec: 15.0214 INFO:tensorflow:global_step/sec: 14.6209 2021-11-27 22:10:49,941 [INFO] tensorflow: global_step/sec: 14.6209 INFO:tensorflow:global_step/sec: 14.5911 2021-11-27 22:10:50,078 [INFO] tensorflow: global_step/sec: 14.5911 2021-11-27 22:10:50,079 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.376 INFO:tensorflow:global_step/sec: 14.8204 2021-11-27 22:10:50,213 [INFO] tensorflow: global_step/sec: 14.8204 INFO:tensorflow:global_step/sec: 14.2833 2021-11-27 22:10:50,353 [INFO] tensorflow: global_step/sec: 14.2833 INFO:tensorflow:global_step/sec: 15.4894 2021-11-27 22:10:50,482 [INFO] tensorflow: global_step/sec: 15.4894 INFO:tensorflow:global_step/sec: 14.3047 2021-11-27 22:10:50,622 [INFO] tensorflow: global_step/sec: 14.3047 INFO:tensorflow:global_step/sec: 14.1951 2021-11-27 22:10:50,763 [INFO] tensorflow: global_step/sec: 14.1951 INFO:tensorflow:global_step/sec: 13.6938 2021-11-27 22:10:50,909 [INFO] tensorflow: global_step/sec: 13.6938 2021-11-27 22:10:50,910 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 13/120: loss: 0.00116 learning rate: 0.00050 Time taken: 0:00:01.494381 ETA: 0:02:39.898762 INFO:tensorflow:global_step/sec: 14.1955 2021-11-27 22:10:51,050 [INFO] tensorflow: global_step/sec: 14.1955 INFO:tensorflow:global_step/sec: 14.7576 2021-11-27 22:10:51,185 [INFO] tensorflow: global_step/sec: 14.7576 INFO:tensorflow:global_step/sec: 14.3278 2021-11-27 22:10:51,325 [INFO] tensorflow: global_step/sec: 14.3278 INFO:tensorflow:global_step/sec: 15.1063 2021-11-27 22:10:51,457 [INFO] tensorflow: global_step/sec: 15.1063 INFO:tensorflow:global_step/sec: 14.7967 2021-11-27 22:10:51,592 [INFO] tensorflow: global_step/sec: 14.7967 INFO:tensorflow:global_step/sec: 14.8827 2021-11-27 22:10:51,727 [INFO] tensorflow: global_step/sec: 14.8827 2021-11-27 22:10:51,793 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.327 INFO:tensorflow:global_step/sec: 15.4031 2021-11-27 22:10:51,857 [INFO] tensorflow: global_step/sec: 15.4031 INFO:tensorflow:global_step/sec: 15.2606 2021-11-27 22:10:51,988 [INFO] tensorflow: global_step/sec: 15.2606 INFO:tensorflow:global_step/sec: 14.7344 2021-11-27 22:10:52,123 [INFO] tensorflow: global_step/sec: 14.7344 INFO:tensorflow:global_step/sec: 14.9483 2021-11-27 22:10:52,257 [INFO] tensorflow: global_step/sec: 14.9483 INFO:tensorflow:global_step/sec: 13.5941 2021-11-27 22:10:52,404 [INFO] tensorflow: global_step/sec: 13.5941 2021-11-27 22:10:52,405 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 14/120: loss: 0.00146 learning rate: 0.00050 Time taken: 0:00:01.496245 ETA: 0:02:38.601935 INFO:tensorflow:global_step/sec: 14.9245 2021-11-27 22:10:52,538 [INFO] tensorflow: global_step/sec: 14.9245 INFO:tensorflow:epoch = 14.181818181818182, learning_rate = 0.00049999997, loss = 0.0012439513, step = 312 (5.092 sec) 2021-11-27 22:10:52,671 [INFO] tensorflow: epoch = 14.181818181818182, learning_rate = 0.00049999997, loss = 0.0012439513, step = 312 (5.092 sec) INFO:tensorflow:global_step/sec: 15.0076 2021-11-27 22:10:52,672 [INFO] tensorflow: global_step/sec: 15.0076 INFO:tensorflow:global_step/sec: 14.806 2021-11-27 22:10:52,807 [INFO] tensorflow: global_step/sec: 14.806 INFO:tensorflow:global_step/sec: 15.0689 2021-11-27 22:10:52,939 [INFO] tensorflow: global_step/sec: 15.0689 INFO:tensorflow:global_step/sec: 14.9115 2021-11-27 22:10:53,074 [INFO] tensorflow: global_step/sec: 14.9115 INFO:tensorflow:global_step/sec: 15.0047 2021-11-27 22:10:53,207 [INFO] tensorflow: global_step/sec: 15.0047 INFO:tensorflow:global_step/sec: 15.2311 2021-11-27 22:10:53,338 [INFO] tensorflow: global_step/sec: 15.2311 INFO:tensorflow:global_step/sec: 14.5435 2021-11-27 22:10:53,476 [INFO] tensorflow: global_step/sec: 14.5435 2021-11-27 22:10:53,476 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.427 INFO:tensorflow:global_step/sec: 14.9793 2021-11-27 22:10:53,609 [INFO] tensorflow: global_step/sec: 14.9793 INFO:tensorflow:global_step/sec: 13.478 2021-11-27 22:10:53,758 [INFO] tensorflow: global_step/sec: 13.478 INFO:tensorflow:global_step/sec: 14.0101 2021-11-27 22:10:53,900 [INFO] tensorflow: global_step/sec: 14.0101 2021-11-27 22:10:53,901 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 15/120: loss: 0.00104 learning rate: 0.00050 Time taken: 0:00:01.496183 ETA: 0:02:37.099231 INFO:tensorflow:global_step/sec: 14.6539 2021-11-27 22:10:54,037 [INFO] tensorflow: global_step/sec: 14.6539 INFO:tensorflow:global_step/sec: 14.8001 2021-11-27 22:10:54,172 [INFO] tensorflow: global_step/sec: 14.8001 INFO:tensorflow:global_step/sec: 14.6178 2021-11-27 22:10:54,309 [INFO] tensorflow: global_step/sec: 14.6178 INFO:tensorflow:global_step/sec: 14.7017 2021-11-27 22:10:54,445 [INFO] tensorflow: global_step/sec: 14.7017 INFO:tensorflow:global_step/sec: 14.7479 2021-11-27 22:10:54,580 [INFO] tensorflow: global_step/sec: 14.7479 INFO:tensorflow:global_step/sec: 15.1014 2021-11-27 22:10:54,713 [INFO] tensorflow: global_step/sec: 15.1014 INFO:tensorflow:global_step/sec: 15.1787 2021-11-27 22:10:54,845 [INFO] tensorflow: global_step/sec: 15.1787 INFO:tensorflow:global_step/sec: 15.4348 2021-11-27 22:10:54,974 [INFO] tensorflow: global_step/sec: 15.4348 INFO:tensorflow:global_step/sec: 15.1671 2021-11-27 22:10:55,106 [INFO] tensorflow: global_step/sec: 15.1671 2021-11-27 22:10:55,177 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.829 INFO:tensorflow:global_step/sec: 14.5169 2021-11-27 22:10:55,244 [INFO] tensorflow: global_step/sec: 14.5169 INFO:tensorflow:global_step/sec: 14.0111 2021-11-27 22:10:55,387 [INFO] tensorflow: global_step/sec: 14.0111 2021-11-27 22:10:55,388 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 16/120: loss: 0.00133 learning rate: 0.00050 Time taken: 0:00:01.484068 ETA: 0:02:34.343039 INFO:tensorflow:global_step/sec: 14.5858 2021-11-27 22:10:55,524 [INFO] tensorflow: global_step/sec: 14.5858 INFO:tensorflow:global_step/sec: 14.9213 2021-11-27 22:10:55,658 [INFO] tensorflow: global_step/sec: 14.9213 INFO:tensorflow:global_step/sec: 14.5842 2021-11-27 22:10:55,795 [INFO] tensorflow: global_step/sec: 14.5842 INFO:tensorflow:global_step/sec: 14.7638 2021-11-27 22:10:55,930 [INFO] tensorflow: global_step/sec: 14.7638 INFO:tensorflow:global_step/sec: 15.3309 2021-11-27 22:10:56,061 [INFO] tensorflow: global_step/sec: 15.3309 INFO:tensorflow:global_step/sec: 15.0181 2021-11-27 22:10:56,194 [INFO] tensorflow: global_step/sec: 15.0181 INFO:tensorflow:global_step/sec: 14.7474 2021-11-27 22:10:56,330 [INFO] tensorflow: global_step/sec: 14.7474 INFO:tensorflow:global_step/sec: 14.7127 2021-11-27 22:10:56,466 [INFO] tensorflow: global_step/sec: 14.7127 INFO:tensorflow:global_step/sec: 14.8873 2021-11-27 22:10:56,600 [INFO] tensorflow: global_step/sec: 14.8873 INFO:tensorflow:global_step/sec: 14.8903 2021-11-27 22:10:56,734 [INFO] tensorflow: global_step/sec: 14.8903 INFO:tensorflow:global_step/sec: 14.0736 2021-11-27 22:10:56,876 [INFO] tensorflow: global_step/sec: 14.0736 2021-11-27 22:10:56,877 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 17/120: loss: 0.00114 learning rate: 0.00050 Time taken: 0:00:01.489300 ETA: 0:02:33.397877 2021-11-27 22:10:56,877 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.805 INFO:tensorflow:global_step/sec: 15.3294 2021-11-27 22:10:57,007 [INFO] tensorflow: global_step/sec: 15.3294 INFO:tensorflow:global_step/sec: 14.3817 2021-11-27 22:10:57,146 [INFO] tensorflow: global_step/sec: 14.3817 INFO:tensorflow:global_step/sec: 14.464 2021-11-27 22:10:57,284 [INFO] tensorflow: global_step/sec: 14.464 INFO:tensorflow:global_step/sec: 14.8348 2021-11-27 22:10:57,419 [INFO] tensorflow: global_step/sec: 14.8348 INFO:tensorflow:global_step/sec: 14.8097 2021-11-27 22:10:57,554 [INFO] tensorflow: global_step/sec: 14.8097 INFO:tensorflow:global_step/sec: 14.6323 2021-11-27 22:10:57,691 [INFO] tensorflow: global_step/sec: 14.6323 INFO:tensorflow:epoch = 17.59090909090909, learning_rate = 0.00049999997, loss = 0.001189148, step = 387 (5.085 sec) 2021-11-27 22:10:57,756 [INFO] tensorflow: epoch = 17.59090909090909, learning_rate = 0.00049999997, loss = 0.001189148, step = 387 (5.085 sec) INFO:tensorflow:global_step/sec: 14.8551 2021-11-27 22:10:57,825 [INFO] tensorflow: global_step/sec: 14.8551 INFO:tensorflow:global_step/sec: 14.6664 2021-11-27 22:10:57,962 [INFO] tensorflow: global_step/sec: 14.6664 INFO:tensorflow:global_step/sec: 15.3873 2021-11-27 22:10:58,092 [INFO] tensorflow: global_step/sec: 15.3873 INFO:tensorflow:global_step/sec: 15.0927 2021-11-27 22:10:58,224 [INFO] tensorflow: global_step/sec: 15.0927 INFO:tensorflow:global_step/sec: 14.5683 2021-11-27 22:10:58,361 [INFO] tensorflow: global_step/sec: 14.5683 2021-11-27 22:10:58,362 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 18/120: loss: 0.00131 learning rate: 0.00050 Time taken: 0:00:01.484583 ETA: 0:02:31.427480 INFO:tensorflow:global_step/sec: 14.7218 2021-11-27 22:10:58,497 [INFO] tensorflow: global_step/sec: 14.7218 2021-11-27 22:10:58,566 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.217 INFO:tensorflow:global_step/sec: 14.806 2021-11-27 22:10:58,632 [INFO] tensorflow: global_step/sec: 14.806 INFO:tensorflow:global_step/sec: 14.0275 2021-11-27 22:10:58,775 [INFO] tensorflow: global_step/sec: 14.0275 INFO:tensorflow:global_step/sec: 15.1689 2021-11-27 22:10:58,907 [INFO] tensorflow: global_step/sec: 15.1689 INFO:tensorflow:global_step/sec: 15.0805 2021-11-27 22:10:59,039 [INFO] tensorflow: global_step/sec: 15.0805 INFO:tensorflow:global_step/sec: 14.2881 2021-11-27 22:10:59,179 [INFO] tensorflow: global_step/sec: 14.2881 INFO:tensorflow:global_step/sec: 14.0275 2021-11-27 22:10:59,322 [INFO] tensorflow: global_step/sec: 14.0275 INFO:tensorflow:global_step/sec: 14.6705 2021-11-27 22:10:59,458 [INFO] tensorflow: global_step/sec: 14.6705 INFO:tensorflow:global_step/sec: 14.514 2021-11-27 22:10:59,596 [INFO] tensorflow: global_step/sec: 14.514 INFO:tensorflow:global_step/sec: 14.3762 2021-11-27 22:10:59,735 [INFO] tensorflow: global_step/sec: 14.3762 INFO:tensorflow:global_step/sec: 13.6798 2021-11-27 22:10:59,881 [INFO] tensorflow: global_step/sec: 13.6798 2021-11-27 22:10:59,882 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 19/120: loss: 0.00119 learning rate: 0.00050 Time taken: 0:00:01.514112 ETA: 0:02:32.925336 INFO:tensorflow:global_step/sec: 14.9618 2021-11-27 22:11:00,015 [INFO] tensorflow: global_step/sec: 14.9618 INFO:tensorflow:global_step/sec: 15.0096 2021-11-27 22:11:00,148 [INFO] tensorflow: global_step/sec: 15.0096 INFO:tensorflow:global_step/sec: 14.5788 2021-11-27 22:11:00,286 [INFO] tensorflow: global_step/sec: 14.5788 2021-11-27 22:11:00,286 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.149 INFO:tensorflow:global_step/sec: 14.6819 2021-11-27 22:11:00,422 [INFO] tensorflow: global_step/sec: 14.6819 INFO:tensorflow:global_step/sec: 14.5409 2021-11-27 22:11:00,559 [INFO] tensorflow: global_step/sec: 14.5409 INFO:tensorflow:global_step/sec: 14.7161 2021-11-27 22:11:00,695 [INFO] tensorflow: global_step/sec: 14.7161 INFO:tensorflow:global_step/sec: 13.634 2021-11-27 22:11:00,842 [INFO] tensorflow: global_step/sec: 13.634 INFO:tensorflow:global_step/sec: 14.306 2021-11-27 22:11:00,982 [INFO] tensorflow: global_step/sec: 14.306 INFO:tensorflow:global_step/sec: 14.4262 2021-11-27 22:11:01,120 [INFO] tensorflow: global_step/sec: 14.4262 INFO:tensorflow:global_step/sec: 15.1324 2021-11-27 22:11:01,252 [INFO] tensorflow: global_step/sec: 15.1324 INFO:tensorflow:Saving checkpoints for step-440. 2021-11-27 22:11:01,320 [INFO] tensorflow: Saving checkpoints for step-440. INFO:tensorflow:epoch = 20.0, learning_rate = 0.00049999997, loss = 0.001208039, step = 440 (6.087 sec) 2021-11-27 22:11:03,843 [INFO] tensorflow: epoch = 20.0, learning_rate = 0.00049999997, loss = 0.001208039, step = 440 (6.087 sec) INFO:tensorflow:global_step/sec: 0.771886 2021-11-27 22:11:03,844 [INFO] tensorflow: global_step/sec: 0.771886 2021-11-27 22:11:03,844 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 20/120: loss: 0.00121 learning rate: 0.00050 Time taken: 0:00:03.959430 ETA: 0:06:35.942974 INFO:tensorflow:global_step/sec: 14.5814 2021-11-27 22:11:03,981 [INFO] tensorflow: global_step/sec: 14.5814 INFO:tensorflow:global_step/sec: 15.024 2021-11-27 22:11:04,114 [INFO] tensorflow: global_step/sec: 15.024 INFO:tensorflow:global_step/sec: 15.1106 2021-11-27 22:11:04,246 [INFO] tensorflow: global_step/sec: 15.1106 INFO:tensorflow:global_step/sec: 15.0744 2021-11-27 22:11:04,379 [INFO] tensorflow: global_step/sec: 15.0744 2021-11-27 22:11:04,446 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 24.045 INFO:tensorflow:global_step/sec: 14.9826 2021-11-27 22:11:04,512 [INFO] tensorflow: global_step/sec: 14.9826 INFO:tensorflow:global_step/sec: 14.8574 2021-11-27 22:11:04,647 [INFO] tensorflow: global_step/sec: 14.8574 INFO:tensorflow:global_step/sec: 15.2487 2021-11-27 22:11:04,778 [INFO] tensorflow: global_step/sec: 15.2487 INFO:tensorflow:global_step/sec: 15.1008 2021-11-27 22:11:04,911 [INFO] tensorflow: global_step/sec: 15.1008 INFO:tensorflow:global_step/sec: 14.9634 2021-11-27 22:11:05,044 [INFO] tensorflow: global_step/sec: 14.9634 INFO:tensorflow:global_step/sec: 15.1436 2021-11-27 22:11:05,176 [INFO] tensorflow: global_step/sec: 15.1436 INFO:tensorflow:global_step/sec: 14.1127 2021-11-27 22:11:05,318 [INFO] tensorflow: global_step/sec: 14.1127 2021-11-27 22:11:05,319 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 21/120: loss: 0.00110 learning rate: 0.00050 Time taken: 0:00:01.475779 ETA: 0:02:26.102103 INFO:tensorflow:global_step/sec: 15.0104 2021-11-27 22:11:05,451 [INFO] tensorflow: global_step/sec: 15.0104 INFO:tensorflow:global_step/sec: 14.8349 2021-11-27 22:11:05,586 [INFO] tensorflow: global_step/sec: 14.8349 INFO:tensorflow:global_step/sec: 15.1007 2021-11-27 22:11:05,718 [INFO] tensorflow: global_step/sec: 15.1007 INFO:tensorflow:global_step/sec: 15.3085 2021-11-27 22:11:05,849 [INFO] tensorflow: global_step/sec: 15.3085 INFO:tensorflow:global_step/sec: 14.8598 2021-11-27 22:11:05,984 [INFO] tensorflow: global_step/sec: 14.8598 INFO:tensorflow:global_step/sec: 15.1747 2021-11-27 22:11:06,116 [INFO] tensorflow: global_step/sec: 15.1747 2021-11-27 22:11:06,116 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.867 INFO:tensorflow:global_step/sec: 15.4283 2021-11-27 22:11:06,245 [INFO] tensorflow: global_step/sec: 15.4283 INFO:tensorflow:global_step/sec: 14.8456 2021-11-27 22:11:06,380 [INFO] tensorflow: global_step/sec: 14.8456 INFO:tensorflow:global_step/sec: 14.621 2021-11-27 22:11:06,517 [INFO] tensorflow: global_step/sec: 14.621 INFO:tensorflow:global_step/sec: 15.2191 2021-11-27 22:11:06,648 [INFO] tensorflow: global_step/sec: 15.2191 INFO:tensorflow:global_step/sec: 14.4144 2021-11-27 22:11:06,787 [INFO] tensorflow: global_step/sec: 14.4144 2021-11-27 22:11:06,788 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 22/120: loss: 0.00107 learning rate: 0.00050 Time taken: 0:00:01.468107 ETA: 0:02:23.874461 INFO:tensorflow:global_step/sec: 14.8922 2021-11-27 22:11:06,921 [INFO] tensorflow: global_step/sec: 14.8922 INFO:tensorflow:global_step/sec: 14.7515 2021-11-27 22:11:07,057 [INFO] tensorflow: global_step/sec: 14.7515 INFO:tensorflow:global_step/sec: 15.6782 2021-11-27 22:11:07,184 [INFO] tensorflow: global_step/sec: 15.6782 INFO:tensorflow:global_step/sec: 15.0898 2021-11-27 22:11:07,317 [INFO] tensorflow: global_step/sec: 15.0898 INFO:tensorflow:global_step/sec: 15.4073 2021-11-27 22:11:07,447 [INFO] tensorflow: global_step/sec: 15.4073 INFO:tensorflow:global_step/sec: 14.8505 2021-11-27 22:11:07,581 [INFO] tensorflow: global_step/sec: 14.8505 INFO:tensorflow:global_step/sec: 14.2411 2021-11-27 22:11:07,722 [INFO] tensorflow: global_step/sec: 14.2411 2021-11-27 22:11:07,791 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.726 INFO:tensorflow:global_step/sec: 14.6321 2021-11-27 22:11:07,858 [INFO] tensorflow: global_step/sec: 14.6321 INFO:tensorflow:global_step/sec: 14.8622 2021-11-27 22:11:07,993 [INFO] tensorflow: global_step/sec: 14.8622 INFO:tensorflow:global_step/sec: 15.2126 2021-11-27 22:11:08,124 [INFO] tensorflow: global_step/sec: 15.2126 INFO:tensorflow:global_step/sec: 14.4849 2021-11-27 22:11:08,263 [INFO] tensorflow: global_step/sec: 14.4849 2021-11-27 22:11:08,263 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 23/120: loss: 0.00113 learning rate: 0.00050 Time taken: 0:00:01.475924 ETA: 0:02:23.164653 INFO:tensorflow:global_step/sec: 14.6945 2021-11-27 22:11:08,399 [INFO] tensorflow: global_step/sec: 14.6945 INFO:tensorflow:global_step/sec: 14.4173 2021-11-27 22:11:08,537 [INFO] tensorflow: global_step/sec: 14.4173 INFO:tensorflow:global_step/sec: 14.4204 2021-11-27 22:11:08,676 [INFO] tensorflow: global_step/sec: 14.4204 INFO:tensorflow:global_step/sec: 14.8535 2021-11-27 22:11:08,811 [INFO] tensorflow: global_step/sec: 14.8535 INFO:tensorflow:epoch = 23.454545454545457, learning_rate = 0.00049999997, loss = 0.0012071719, step = 516 (5.108 sec) 2021-11-27 22:11:08,950 [INFO] tensorflow: epoch = 23.454545454545457, learning_rate = 0.00049999997, loss = 0.0012071719, step = 516 (5.108 sec) INFO:tensorflow:global_step/sec: 14.2175 2021-11-27 22:11:08,951 [INFO] tensorflow: global_step/sec: 14.2175 INFO:tensorflow:global_step/sec: 13.8923 2021-11-27 22:11:09,095 [INFO] tensorflow: global_step/sec: 13.8923 INFO:tensorflow:global_step/sec: 13.3226 2021-11-27 22:11:09,245 [INFO] tensorflow: global_step/sec: 13.3226 INFO:tensorflow:global_step/sec: 14.0777 2021-11-27 22:11:09,388 [INFO] tensorflow: global_step/sec: 14.0777 INFO:tensorflow:global_step/sec: 14.3473 2021-11-27 22:11:09,527 [INFO] tensorflow: global_step/sec: 14.3473 2021-11-27 22:11:09,528 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.583 INFO:tensorflow:global_step/sec: 14.9116 2021-11-27 22:11:09,661 [INFO] tensorflow: global_step/sec: 14.9116 INFO:tensorflow:global_step/sec: 14.2348 2021-11-27 22:11:09,802 [INFO] tensorflow: global_step/sec: 14.2348 2021-11-27 22:11:09,802 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 24/120: loss: 0.00094 learning rate: 0.00050 Time taken: 0:00:01.536662 ETA: 0:02:27.519539 INFO:tensorflow:global_step/sec: 14.5469 2021-11-27 22:11:09,939 [INFO] tensorflow: global_step/sec: 14.5469 INFO:tensorflow:global_step/sec: 15.4039 2021-11-27 22:11:10,069 [INFO] tensorflow: global_step/sec: 15.4039 INFO:tensorflow:global_step/sec: 15.254 2021-11-27 22:11:10,200 [INFO] tensorflow: global_step/sec: 15.254 INFO:tensorflow:global_step/sec: 15.0939 2021-11-27 22:11:10,332 [INFO] tensorflow: global_step/sec: 15.0939 INFO:tensorflow:global_step/sec: 14.794 2021-11-27 22:11:10,468 [INFO] tensorflow: global_step/sec: 14.794 INFO:tensorflow:global_step/sec: 14.2739 2021-11-27 22:11:10,608 [INFO] tensorflow: global_step/sec: 14.2739 INFO:tensorflow:global_step/sec: 15.3225 2021-11-27 22:11:10,738 [INFO] tensorflow: global_step/sec: 15.3225 INFO:tensorflow:global_step/sec: 15.3448 2021-11-27 22:11:10,869 [INFO] tensorflow: global_step/sec: 15.3448 INFO:tensorflow:global_step/sec: 14.8166 2021-11-27 22:11:11,004 [INFO] tensorflow: global_step/sec: 14.8166 INFO:tensorflow:global_step/sec: 14.9696 2021-11-27 22:11:11,137 [INFO] tensorflow: global_step/sec: 14.9696 2021-11-27 22:11:11,208 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.530 INFO:tensorflow:global_step/sec: 14.4151 2021-11-27 22:11:11,276 [INFO] tensorflow: global_step/sec: 14.4151 2021-11-27 22:11:11,277 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 25/120: loss: 0.00094 learning rate: 0.00050 Time taken: 0:00:01.472636 ETA: 0:02:19.900441 INFO:tensorflow:global_step/sec: 15.4258 2021-11-27 22:11:11,406 [INFO] tensorflow: global_step/sec: 15.4258 INFO:tensorflow:global_step/sec: 15.4728 2021-11-27 22:11:11,535 [INFO] tensorflow: global_step/sec: 15.4728 INFO:tensorflow:global_step/sec: 14.8293 2021-11-27 22:11:11,670 [INFO] tensorflow: global_step/sec: 14.8293 INFO:tensorflow:global_step/sec: 15.3561 2021-11-27 22:11:11,800 [INFO] tensorflow: global_step/sec: 15.3561 INFO:tensorflow:global_step/sec: 14.8311 2021-11-27 22:11:11,935 [INFO] tensorflow: global_step/sec: 14.8311 INFO:tensorflow:global_step/sec: 14.7323 2021-11-27 22:11:12,071 [INFO] tensorflow: global_step/sec: 14.7323 INFO:tensorflow:global_step/sec: 14.8343 2021-11-27 22:11:12,205 [INFO] tensorflow: global_step/sec: 14.8343 INFO:tensorflow:global_step/sec: 15.0212 2021-11-27 22:11:12,339 [INFO] tensorflow: global_step/sec: 15.0212 INFO:tensorflow:global_step/sec: 15.1847 2021-11-27 22:11:12,470 [INFO] tensorflow: global_step/sec: 15.1847 INFO:tensorflow:global_step/sec: 15.2379 2021-11-27 22:11:12,602 [INFO] tensorflow: global_step/sec: 15.2379 INFO:tensorflow:global_step/sec: 14.2188 2021-11-27 22:11:12,742 [INFO] tensorflow: global_step/sec: 14.2188 2021-11-27 22:11:12,743 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 26/120: loss: 0.00101 learning rate: 0.00050 Time taken: 0:00:01.464793 ETA: 0:02:17.690561 INFO:tensorflow:global_step/sec: 14.9314 2021-11-27 22:11:12,876 [INFO] tensorflow: global_step/sec: 14.9314 2021-11-27 22:11:12,877 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.974 INFO:tensorflow:global_step/sec: 14.3269 2021-11-27 22:11:13,016 [INFO] tensorflow: global_step/sec: 14.3269 INFO:tensorflow:global_step/sec: 15.3888 2021-11-27 22:11:13,146 [INFO] tensorflow: global_step/sec: 15.3888 INFO:tensorflow:global_step/sec: 14.7979 2021-11-27 22:11:13,281 [INFO] tensorflow: global_step/sec: 14.7979 INFO:tensorflow:global_step/sec: 14.0432 2021-11-27 22:11:13,423 [INFO] tensorflow: global_step/sec: 14.0432 INFO:tensorflow:global_step/sec: 14.9783 2021-11-27 22:11:13,557 [INFO] tensorflow: global_step/sec: 14.9783 INFO:tensorflow:global_step/sec: 15.5035 2021-11-27 22:11:13,686 [INFO] tensorflow: global_step/sec: 15.5035 INFO:tensorflow:global_step/sec: 13.7569 2021-11-27 22:11:13,831 [INFO] tensorflow: global_step/sec: 13.7569 INFO:tensorflow:global_step/sec: 14.9479 2021-11-27 22:11:13,965 [INFO] tensorflow: global_step/sec: 14.9479 INFO:tensorflow:epoch = 26.863636363636363, learning_rate = 0.00049999997, loss = 0.0008986265, step = 591 (5.084 sec) 2021-11-27 22:11:14,035 [INFO] tensorflow: epoch = 26.863636363636363, learning_rate = 0.00049999997, loss = 0.0008986265, step = 591 (5.084 sec) INFO:tensorflow:global_step/sec: 14.6121 2021-11-27 22:11:14,102 [INFO] tensorflow: global_step/sec: 14.6121 INFO:tensorflow:global_step/sec: 13.803 2021-11-27 22:11:14,247 [INFO] tensorflow: global_step/sec: 13.803 2021-11-27 22:11:14,248 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 27/120: loss: 0.00126 learning rate: 0.00050 Time taken: 0:00:01.501443 ETA: 0:02:19.634213 INFO:tensorflow:global_step/sec: 14.2036 2021-11-27 22:11:14,388 [INFO] tensorflow: global_step/sec: 14.2036 INFO:tensorflow:global_step/sec: 13.9564 2021-11-27 22:11:14,531 [INFO] tensorflow: global_step/sec: 13.9564 2021-11-27 22:11:14,600 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.040 INFO:tensorflow:global_step/sec: 14.8303 2021-11-27 22:11:14,666 [INFO] tensorflow: global_step/sec: 14.8303 INFO:tensorflow:global_step/sec: 14.7463 2021-11-27 22:11:14,801 [INFO] tensorflow: global_step/sec: 14.7463 INFO:tensorflow:global_step/sec: 14.3704 2021-11-27 22:11:14,941 [INFO] tensorflow: global_step/sec: 14.3704 INFO:tensorflow:global_step/sec: 14.1758 2021-11-27 22:11:15,082 [INFO] tensorflow: global_step/sec: 14.1758 INFO:tensorflow:global_step/sec: 14.3686 2021-11-27 22:11:15,221 [INFO] tensorflow: global_step/sec: 14.3686 INFO:tensorflow:global_step/sec: 14.562 2021-11-27 22:11:15,358 [INFO] tensorflow: global_step/sec: 14.562 INFO:tensorflow:global_step/sec: 14.8184 2021-11-27 22:11:15,493 [INFO] tensorflow: global_step/sec: 14.8184 INFO:tensorflow:global_step/sec: 14.508 2021-11-27 22:11:15,631 [INFO] tensorflow: global_step/sec: 14.508 INFO:tensorflow:global_step/sec: 13.4322 2021-11-27 22:11:15,780 [INFO] tensorflow: global_step/sec: 13.4322 2021-11-27 22:11:15,781 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 28/120: loss: 0.00106 learning rate: 0.00050 Time taken: 0:00:01.528614 ETA: 0:02:20.632470 INFO:tensorflow:global_step/sec: 14.566 2021-11-27 22:11:15,917 [INFO] tensorflow: global_step/sec: 14.566 INFO:tensorflow:global_step/sec: 14.862 2021-11-27 22:11:16,052 [INFO] tensorflow: global_step/sec: 14.862 INFO:tensorflow:global_step/sec: 14.9036 2021-11-27 22:11:16,186 [INFO] tensorflow: global_step/sec: 14.9036 INFO:tensorflow:global_step/sec: 14.8269 2021-11-27 22:11:16,321 [INFO] tensorflow: global_step/sec: 14.8269 2021-11-27 22:11:16,322 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.106 INFO:tensorflow:global_step/sec: 14.8342 2021-11-27 22:11:16,456 [INFO] tensorflow: global_step/sec: 14.8342 INFO:tensorflow:global_step/sec: 15.17 2021-11-27 22:11:16,588 [INFO] tensorflow: global_step/sec: 15.17 INFO:tensorflow:global_step/sec: 14.7169 2021-11-27 22:11:16,723 [INFO] tensorflow: global_step/sec: 14.7169 INFO:tensorflow:global_step/sec: 15.3192 2021-11-27 22:11:16,854 [INFO] tensorflow: global_step/sec: 15.3192 INFO:tensorflow:global_step/sec: 15.0176 2021-11-27 22:11:16,987 [INFO] tensorflow: global_step/sec: 15.0176 INFO:tensorflow:global_step/sec: 15.1061 2021-11-27 22:11:17,120 [INFO] tensorflow: global_step/sec: 15.1061 INFO:tensorflow:global_step/sec: 14.3527 2021-11-27 22:11:17,259 [INFO] tensorflow: global_step/sec: 14.3527 2021-11-27 22:11:17,260 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 29/120: loss: 0.00113 learning rate: 0.00050 Time taken: 0:00:01.482774 ETA: 0:02:14.932479 INFO:tensorflow:global_step/sec: 14.3115 2021-11-27 22:11:17,399 [INFO] tensorflow: global_step/sec: 14.3115 INFO:tensorflow:global_step/sec: 15.1028 2021-11-27 22:11:17,531 [INFO] tensorflow: global_step/sec: 15.1028 INFO:tensorflow:global_step/sec: 15.1985 2021-11-27 22:11:17,663 [INFO] tensorflow: global_step/sec: 15.1985 INFO:tensorflow:global_step/sec: 15.0616 2021-11-27 22:11:17,795 [INFO] tensorflow: global_step/sec: 15.0616 INFO:tensorflow:global_step/sec: 15.0648 2021-11-27 22:11:17,928 [INFO] tensorflow: global_step/sec: 15.0648 2021-11-27 22:11:17,993 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.826 INFO:tensorflow:global_step/sec: 15.0342 2021-11-27 22:11:18,061 [INFO] tensorflow: global_step/sec: 15.0342 INFO:tensorflow:global_step/sec: 15.4194 2021-11-27 22:11:18,191 [INFO] tensorflow: global_step/sec: 15.4194 INFO:tensorflow:global_step/sec: 14.9949 2021-11-27 22:11:18,324 [INFO] tensorflow: global_step/sec: 14.9949 INFO:tensorflow:global_step/sec: 15.3746 2021-11-27 22:11:18,454 [INFO] tensorflow: global_step/sec: 15.3746 INFO:tensorflow:global_step/sec: 14.5419 2021-11-27 22:11:18,592 [INFO] tensorflow: global_step/sec: 14.5419 INFO:tensorflow:Saving checkpoints for step-660. 2021-11-27 22:11:18,659 [INFO] tensorflow: Saving checkpoints for step-660. 2021-11-27 22:11:20,966 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 1324/1324 [00:00<00:00, 24445.17it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 312/312 [00:00<00:00, 24560.78it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 493/493 [00:00<00:00, 24947.72it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 2957/2957 [00:00<00:00, 26277.66it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 308/308 [00:00<00:00, 24123.20it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 1467/1467 [00:00<00:00, 23906.74it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 5428/5428 [00:00<00:00, 37996.65it/s] Epoch 30/120 ========================= Validation cost: 0.000636 Mean average_precision (in %): 21.7641 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 36.48 floor 0 palette 4.23729 pillar 46.1714 pushcart 0 rackframe 31.5046 rackshelf 43.4762 wall 34.0071 Median Inference Time: 0.007186 INFO:tensorflow:epoch = 30.0, learning_rate = 0.00049999997, loss = 0.0010661148, step = 660 (11.681 sec) 2021-11-27 22:11:25,716 [INFO] tensorflow: epoch = 30.0, learning_rate = 0.00049999997, loss = 0.0010661148, step = 660 (11.681 sec) INFO:tensorflow:global_step/sec: 0.280728 2021-11-27 22:11:25,716 [INFO] tensorflow: global_step/sec: 0.280728 2021-11-27 22:11:25,717 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 30/120: loss: 0.00107 learning rate: 0.00050 Time taken: 0:00:08.457013 ETA: 0:12:41.131139 INFO:tensorflow:global_step/sec: 14.6158 2021-11-27 22:11:25,853 [INFO] tensorflow: global_step/sec: 14.6158 INFO:tensorflow:global_step/sec: 15.3631 2021-11-27 22:11:25,983 [INFO] tensorflow: global_step/sec: 15.3631 INFO:tensorflow:global_step/sec: 15.403 2021-11-27 22:11:26,113 [INFO] tensorflow: global_step/sec: 15.403 INFO:tensorflow:global_step/sec: 14.9258 2021-11-27 22:11:26,247 [INFO] tensorflow: global_step/sec: 14.9258 INFO:tensorflow:global_step/sec: 15.5896 2021-11-27 22:11:26,375 [INFO] tensorflow: global_step/sec: 15.5896 INFO:tensorflow:global_step/sec: 15.1391 2021-11-27 22:11:26,508 [INFO] tensorflow: global_step/sec: 15.1391 INFO:tensorflow:global_step/sec: 15.2126 2021-11-27 22:11:26,639 [INFO] tensorflow: global_step/sec: 15.2126 2021-11-27 22:11:26,639 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 11.566 INFO:tensorflow:global_step/sec: 15.1938 2021-11-27 22:11:26,771 [INFO] tensorflow: global_step/sec: 15.1938 INFO:tensorflow:global_step/sec: 15.0149 2021-11-27 22:11:26,904 [INFO] tensorflow: global_step/sec: 15.0149 INFO:tensorflow:global_step/sec: 15.0113 2021-11-27 22:11:27,037 [INFO] tensorflow: global_step/sec: 15.0113 INFO:tensorflow:global_step/sec: 14.3837 2021-11-27 22:11:27,176 [INFO] tensorflow: global_step/sec: 14.3837 2021-11-27 22:11:27,177 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 31/120: loss: 0.00097 learning rate: 0.00050 Time taken: 0:00:01.459213 ETA: 0:02:09.869916 INFO:tensorflow:global_step/sec: 15.0813 2021-11-27 22:11:27,309 [INFO] tensorflow: global_step/sec: 15.0813 INFO:tensorflow:global_step/sec: 15.0764 2021-11-27 22:11:27,441 [INFO] tensorflow: global_step/sec: 15.0764 INFO:tensorflow:global_step/sec: 15.0761 2021-11-27 22:11:27,574 [INFO] tensorflow: global_step/sec: 15.0761 INFO:tensorflow:global_step/sec: 14.6736 2021-11-27 22:11:27,710 [INFO] tensorflow: global_step/sec: 14.6736 INFO:tensorflow:global_step/sec: 15.0927 2021-11-27 22:11:27,843 [INFO] tensorflow: global_step/sec: 15.0927 INFO:tensorflow:global_step/sec: 15.6125 2021-11-27 22:11:27,971 [INFO] tensorflow: global_step/sec: 15.6125 INFO:tensorflow:global_step/sec: 15.2638 2021-11-27 22:11:28,102 [INFO] tensorflow: global_step/sec: 15.2638 INFO:tensorflow:global_step/sec: 14.8265 2021-11-27 22:11:28,237 [INFO] tensorflow: global_step/sec: 14.8265 2021-11-27 22:11:28,304 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.083 INFO:tensorflow:global_step/sec: 15.2819 2021-11-27 22:11:28,368 [INFO] tensorflow: global_step/sec: 15.2819 INFO:tensorflow:global_step/sec: 16.0149 2021-11-27 22:11:28,493 [INFO] tensorflow: global_step/sec: 16.0149 INFO:tensorflow:global_step/sec: 14.1263 2021-11-27 22:11:28,634 [INFO] tensorflow: global_step/sec: 14.1263 2021-11-27 22:11:28,635 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 32/120: loss: 0.00104 learning rate: 0.00050 Time taken: 0:00:01.456547 ETA: 0:02:08.176180 INFO:tensorflow:global_step/sec: 15.3109 2021-11-27 22:11:28,765 [INFO] tensorflow: global_step/sec: 15.3109 INFO:tensorflow:global_step/sec: 14.6735 2021-11-27 22:11:28,901 [INFO] tensorflow: global_step/sec: 14.6735 INFO:tensorflow:global_step/sec: 15.0053 2021-11-27 22:11:29,034 [INFO] tensorflow: global_step/sec: 15.0053 INFO:tensorflow:global_step/sec: 15.0215 2021-11-27 22:11:29,168 [INFO] tensorflow: global_step/sec: 15.0215 INFO:tensorflow:global_step/sec: 15.5507 2021-11-27 22:11:29,296 [INFO] tensorflow: global_step/sec: 15.5507 INFO:tensorflow:global_step/sec: 14.7333 2021-11-27 22:11:29,432 [INFO] tensorflow: global_step/sec: 14.7333 INFO:tensorflow:global_step/sec: 15.1009 2021-11-27 22:11:29,564 [INFO] tensorflow: global_step/sec: 15.1009 INFO:tensorflow:global_step/sec: 14.8423 2021-11-27 22:11:29,699 [INFO] tensorflow: global_step/sec: 14.8423 INFO:tensorflow:global_step/sec: 15.1783 2021-11-27 22:11:29,831 [INFO] tensorflow: global_step/sec: 15.1783 INFO:tensorflow:global_step/sec: 14.637 2021-11-27 22:11:29,968 [INFO] tensorflow: global_step/sec: 14.637 2021-11-27 22:11:29,968 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.100 INFO:tensorflow:global_step/sec: 14.4493 2021-11-27 22:11:30,106 [INFO] tensorflow: global_step/sec: 14.4493 2021-11-27 22:11:30,107 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 33/120: loss: 0.00089 learning rate: 0.00050 Time taken: 0:00:01.468746 ETA: 0:02:07.780897 INFO:tensorflow:global_step/sec: 14.713 2021-11-27 22:11:30,242 [INFO] tensorflow: global_step/sec: 14.713 INFO:tensorflow:global_step/sec: 15.4372 2021-11-27 22:11:30,371 [INFO] tensorflow: global_step/sec: 15.4372 INFO:tensorflow:global_step/sec: 15.6585 2021-11-27 22:11:30,499 [INFO] tensorflow: global_step/sec: 15.6585 INFO:tensorflow:global_step/sec: 15.4361 2021-11-27 22:11:30,629 [INFO] tensorflow: global_step/sec: 15.4361 INFO:tensorflow:global_step/sec: 15.1946 2021-11-27 22:11:30,760 [INFO] tensorflow: global_step/sec: 15.1946 INFO:tensorflow:epoch = 33.5, learning_rate = 0.00049999997, loss = 0.00090900774, step = 737 (5.110 sec) 2021-11-27 22:11:30,826 [INFO] tensorflow: epoch = 33.5, learning_rate = 0.00049999997, loss = 0.00090900774, step = 737 (5.110 sec) INFO:tensorflow:global_step/sec: 15.2787 2021-11-27 22:11:30,891 [INFO] tensorflow: global_step/sec: 15.2787 INFO:tensorflow:global_step/sec: 15.1715 2021-11-27 22:11:31,023 [INFO] tensorflow: global_step/sec: 15.1715 INFO:tensorflow:global_step/sec: 15.1485 2021-11-27 22:11:31,155 [INFO] tensorflow: global_step/sec: 15.1485 INFO:tensorflow:global_step/sec: 15.1495 2021-11-27 22:11:31,287 [INFO] tensorflow: global_step/sec: 15.1495 INFO:tensorflow:global_step/sec: 14.8119 2021-11-27 22:11:31,422 [INFO] tensorflow: global_step/sec: 14.8119 INFO:tensorflow:global_step/sec: 14.4204 2021-11-27 22:11:31,561 [INFO] tensorflow: global_step/sec: 14.4204 2021-11-27 22:11:31,562 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 34/120: loss: 0.00103 learning rate: 0.00050 Time taken: 0:00:01.453940 ETA: 0:02:05.038812 2021-11-27 22:11:31,627 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.285 INFO:tensorflow:global_step/sec: 15.0805 2021-11-27 22:11:31,693 [INFO] tensorflow: global_step/sec: 15.0805 INFO:tensorflow:global_step/sec: 15.137 2021-11-27 22:11:31,826 [INFO] tensorflow: global_step/sec: 15.137 INFO:tensorflow:global_step/sec: 14.6606 2021-11-27 22:11:31,962 [INFO] tensorflow: global_step/sec: 14.6606 INFO:tensorflow:global_step/sec: 14.9212 2021-11-27 22:11:32,096 [INFO] tensorflow: global_step/sec: 14.9212 INFO:tensorflow:global_step/sec: 15.3908 2021-11-27 22:11:32,226 [INFO] tensorflow: global_step/sec: 15.3908 INFO:tensorflow:global_step/sec: 15.2564 2021-11-27 22:11:32,357 [INFO] tensorflow: global_step/sec: 15.2564 INFO:tensorflow:global_step/sec: 15.2172 2021-11-27 22:11:32,489 [INFO] tensorflow: global_step/sec: 15.2172 INFO:tensorflow:global_step/sec: 15.2882 2021-11-27 22:11:32,619 [INFO] tensorflow: global_step/sec: 15.2882 INFO:tensorflow:global_step/sec: 14.9088 2021-11-27 22:11:32,753 [INFO] tensorflow: global_step/sec: 14.9088 INFO:tensorflow:global_step/sec: 15.0959 2021-11-27 22:11:32,886 [INFO] tensorflow: global_step/sec: 15.0959 INFO:tensorflow:global_step/sec: 13.8828 2021-11-27 22:11:33,030 [INFO] tensorflow: global_step/sec: 13.8828 2021-11-27 22:11:33,031 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 35/120: loss: 0.00098 learning rate: 0.00050 Time taken: 0:00:01.464580 ETA: 0:02:04.489325 INFO:tensorflow:global_step/sec: 14.9529 2021-11-27 22:11:33,164 [INFO] tensorflow: global_step/sec: 14.9529 INFO:tensorflow:global_step/sec: 15.2116 2021-11-27 22:11:33,295 [INFO] tensorflow: global_step/sec: 15.2116 2021-11-27 22:11:33,296 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.932 INFO:tensorflow:global_step/sec: 15.5088 2021-11-27 22:11:33,424 [INFO] tensorflow: global_step/sec: 15.5088 INFO:tensorflow:global_step/sec: 15.1949 2021-11-27 22:11:33,556 [INFO] tensorflow: global_step/sec: 15.1949 INFO:tensorflow:global_step/sec: 15.218 2021-11-27 22:11:33,687 [INFO] tensorflow: global_step/sec: 15.218 INFO:tensorflow:global_step/sec: 14.9059 2021-11-27 22:11:33,821 [INFO] tensorflow: global_step/sec: 14.9059 INFO:tensorflow:global_step/sec: 15.2427 2021-11-27 22:11:33,953 [INFO] tensorflow: global_step/sec: 15.2427 INFO:tensorflow:global_step/sec: 15.2945 2021-11-27 22:11:34,083 [INFO] tensorflow: global_step/sec: 15.2945 INFO:tensorflow:global_step/sec: 14.6933 2021-11-27 22:11:34,220 [INFO] tensorflow: global_step/sec: 14.6933 INFO:tensorflow:global_step/sec: 15.1993 2021-11-27 22:11:34,351 [INFO] tensorflow: global_step/sec: 15.1993 INFO:tensorflow:global_step/sec: 14.3273 2021-11-27 22:11:34,491 [INFO] tensorflow: global_step/sec: 14.3273 2021-11-27 22:11:34,492 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 36/120: loss: 0.00096 learning rate: 0.00050 Time taken: 0:00:01.460090 ETA: 0:02:02.647593 INFO:tensorflow:global_step/sec: 14.8868 2021-11-27 22:11:34,625 [INFO] tensorflow: global_step/sec: 14.8868 INFO:tensorflow:global_step/sec: 14.8503 2021-11-27 22:11:34,760 [INFO] tensorflow: global_step/sec: 14.8503 INFO:tensorflow:global_step/sec: 14.9171 2021-11-27 22:11:34,894 [INFO] tensorflow: global_step/sec: 14.9171 2021-11-27 22:11:34,961 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.066 INFO:tensorflow:global_step/sec: 15.0057 2021-11-27 22:11:35,027 [INFO] tensorflow: global_step/sec: 15.0057 INFO:tensorflow:global_step/sec: 14.8709 2021-11-27 22:11:35,162 [INFO] tensorflow: global_step/sec: 14.8709 INFO:tensorflow:global_step/sec: 14.7456 2021-11-27 22:11:35,297 [INFO] tensorflow: global_step/sec: 14.7456 INFO:tensorflow:global_step/sec: 15.0414 2021-11-27 22:11:35,430 [INFO] tensorflow: global_step/sec: 15.0414 INFO:tensorflow:global_step/sec: 15.4691 2021-11-27 22:11:35,559 [INFO] tensorflow: global_step/sec: 15.4691 INFO:tensorflow:global_step/sec: 15.559 2021-11-27 22:11:35,688 [INFO] tensorflow: global_step/sec: 15.559 INFO:tensorflow:global_step/sec: 14.9614 2021-11-27 22:11:35,822 [INFO] tensorflow: global_step/sec: 14.9614 INFO:tensorflow:epoch = 37.0, learning_rate = 0.00049999997, loss = 0.0008655512, step = 814 (5.134 sec) 2021-11-27 22:11:35,959 [INFO] tensorflow: epoch = 37.0, learning_rate = 0.00049999997, loss = 0.0008655512, step = 814 (5.134 sec) INFO:tensorflow:global_step/sec: 14.4501 2021-11-27 22:11:35,960 [INFO] tensorflow: global_step/sec: 14.4501 2021-11-27 22:11:35,961 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 37/120: loss: 0.00087 learning rate: 0.00050 Time taken: 0:00:01.467804 ETA: 0:02:01.827708 INFO:tensorflow:global_step/sec: 15.2799 2021-11-27 22:11:36,091 [INFO] tensorflow: global_step/sec: 15.2799 INFO:tensorflow:global_step/sec: 14.9947 2021-11-27 22:11:36,224 [INFO] tensorflow: global_step/sec: 14.9947 INFO:tensorflow:global_step/sec: 15.4313 2021-11-27 22:11:36,354 [INFO] tensorflow: global_step/sec: 15.4313 INFO:tensorflow:global_step/sec: 15.3616 2021-11-27 22:11:36,484 [INFO] tensorflow: global_step/sec: 15.3616 INFO:tensorflow:global_step/sec: 15.0717 2021-11-27 22:11:36,617 [INFO] tensorflow: global_step/sec: 15.0717 2021-11-27 22:11:36,618 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.387 INFO:tensorflow:global_step/sec: 15.3582 2021-11-27 22:11:36,747 [INFO] tensorflow: global_step/sec: 15.3582 INFO:tensorflow:global_step/sec: 15.1001 2021-11-27 22:11:36,880 [INFO] tensorflow: global_step/sec: 15.1001 INFO:tensorflow:global_step/sec: 15.1579 2021-11-27 22:11:37,012 [INFO] tensorflow: global_step/sec: 15.1579 INFO:tensorflow:global_step/sec: 14.9862 2021-11-27 22:11:37,145 [INFO] tensorflow: global_step/sec: 14.9862 INFO:tensorflow:global_step/sec: 15.1072 2021-11-27 22:11:37,277 [INFO] tensorflow: global_step/sec: 15.1072 INFO:tensorflow:global_step/sec: 13.8528 2021-11-27 22:11:37,422 [INFO] tensorflow: global_step/sec: 13.8528 2021-11-27 22:11:37,423 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 38/120: loss: 0.00094 learning rate: 0.00050 Time taken: 0:00:01.461972 ETA: 0:01:59.881704 INFO:tensorflow:global_step/sec: 14.9911 2021-11-27 22:11:37,555 [INFO] tensorflow: global_step/sec: 14.9911 INFO:tensorflow:global_step/sec: 14.7256 2021-11-27 22:11:37,691 [INFO] tensorflow: global_step/sec: 14.7256 INFO:tensorflow:global_step/sec: 15.3151 2021-11-27 22:11:37,822 [INFO] tensorflow: global_step/sec: 15.3151 INFO:tensorflow:global_step/sec: 15.5691 2021-11-27 22:11:37,950 [INFO] tensorflow: global_step/sec: 15.5691 INFO:tensorflow:global_step/sec: 15.3719 2021-11-27 22:11:38,080 [INFO] tensorflow: global_step/sec: 15.3719 INFO:tensorflow:global_step/sec: 14.9469 2021-11-27 22:11:38,214 [INFO] tensorflow: global_step/sec: 14.9469 2021-11-27 22:11:38,280 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.161 INFO:tensorflow:global_step/sec: 15.1462 2021-11-27 22:11:38,346 [INFO] tensorflow: global_step/sec: 15.1462 INFO:tensorflow:global_step/sec: 15.398 2021-11-27 22:11:38,476 [INFO] tensorflow: global_step/sec: 15.398 INFO:tensorflow:global_step/sec: 14.9902 2021-11-27 22:11:38,609 [INFO] tensorflow: global_step/sec: 14.9902 INFO:tensorflow:global_step/sec: 15.1598 2021-11-27 22:11:38,741 [INFO] tensorflow: global_step/sec: 15.1598 INFO:tensorflow:global_step/sec: 14.5109 2021-11-27 22:11:38,879 [INFO] tensorflow: global_step/sec: 14.5109 2021-11-27 22:11:38,880 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 39/120: loss: 0.00096 learning rate: 0.00050 Time taken: 0:00:01.455826 ETA: 0:01:57.921890 INFO:tensorflow:global_step/sec: 14.7179 2021-11-27 22:11:39,015 [INFO] tensorflow: global_step/sec: 14.7179 INFO:tensorflow:global_step/sec: 15.1438 2021-11-27 22:11:39,147 [INFO] tensorflow: global_step/sec: 15.1438 INFO:tensorflow:global_step/sec: 15.1448 2021-11-27 22:11:39,279 [INFO] tensorflow: global_step/sec: 15.1448 INFO:tensorflow:global_step/sec: 15.0691 2021-11-27 22:11:39,412 [INFO] tensorflow: global_step/sec: 15.0691 INFO:tensorflow:global_step/sec: 15.0519 2021-11-27 22:11:39,545 [INFO] tensorflow: global_step/sec: 15.0519 INFO:tensorflow:global_step/sec: 15.5687 2021-11-27 22:11:39,673 [INFO] tensorflow: global_step/sec: 15.5687 INFO:tensorflow:global_step/sec: 15.4855 2021-11-27 22:11:39,802 [INFO] tensorflow: global_step/sec: 15.4855 INFO:tensorflow:global_step/sec: 15.1255 2021-11-27 22:11:39,934 [INFO] tensorflow: global_step/sec: 15.1255 2021-11-27 22:11:39,935 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.433 INFO:tensorflow:global_step/sec: 14.7001 2021-11-27 22:11:40,071 [INFO] tensorflow: global_step/sec: 14.7001 INFO:tensorflow:global_step/sec: 15.2318 2021-11-27 22:11:40,202 [INFO] tensorflow: global_step/sec: 15.2318 INFO:tensorflow:Saving checkpoints for step-880. 2021-11-27 22:11:40,266 [INFO] tensorflow: Saving checkpoints for step-880. 2021-11-27 22:11:42,590 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 1222/1222 [00:00<00:00, 23534.73it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 155/155 [00:00<00:00, 24321.63it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 545/545 [00:00<00:00, 23867.10it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 2017/2017 [00:00<00:00, 27095.91it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 459/459 [00:00<00:00, 24472.90it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 1452/1452 [00:00<00:00, 23857.51it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 3675/3675 [00:00<00:00, 38397.99it/s] Epoch 40/120 ========================= Validation cost: 0.000671 Mean average_precision (in %): 21.1592 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 21.043 floor 0 palette 5.8561 pillar 44.3434 pushcart 0 rackframe 34.715 rackshelf 50.6217 wall 33.8539 Median Inference Time: 0.007315 INFO:tensorflow:epoch = 40.0, learning_rate = 0.00049999997, loss = 0.0009999337, step = 880 (10.303 sec) 2021-11-27 22:11:46,263 [INFO] tensorflow: epoch = 40.0, learning_rate = 0.00049999997, loss = 0.0009999337, step = 880 (10.303 sec) INFO:tensorflow:global_step/sec: 0.329935 2021-11-27 22:11:46,264 [INFO] tensorflow: global_step/sec: 0.329935 2021-11-27 22:11:46,265 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 40/120: loss: 0.00100 learning rate: 0.00050 Time taken: 0:00:07.381091 ETA: 0:09:50.487289 INFO:tensorflow:global_step/sec: 15.1789 2021-11-27 22:11:46,395 [INFO] tensorflow: global_step/sec: 15.1789 INFO:tensorflow:global_step/sec: 15.2989 2021-11-27 22:11:46,526 [INFO] tensorflow: global_step/sec: 15.2989 INFO:tensorflow:global_step/sec: 15.0682 2021-11-27 22:11:46,659 [INFO] tensorflow: global_step/sec: 15.0682 INFO:tensorflow:global_step/sec: 15.0943 2021-11-27 22:11:46,791 [INFO] tensorflow: global_step/sec: 15.0943 INFO:tensorflow:global_step/sec: 15.1207 2021-11-27 22:11:46,924 [INFO] tensorflow: global_step/sec: 15.1207 INFO:tensorflow:global_step/sec: 14.9446 2021-11-27 22:11:47,057 [INFO] tensorflow: global_step/sec: 14.9446 INFO:tensorflow:global_step/sec: 15.088 2021-11-27 22:11:47,190 [INFO] tensorflow: global_step/sec: 15.088 INFO:tensorflow:global_step/sec: 15.0426 2021-11-27 22:11:47,323 [INFO] tensorflow: global_step/sec: 15.0426 INFO:tensorflow:global_step/sec: 14.9005 2021-11-27 22:11:47,457 [INFO] tensorflow: global_step/sec: 14.9005 2021-11-27 22:11:47,524 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 13.179 INFO:tensorflow:global_step/sec: 15.1584 2021-11-27 22:11:47,589 [INFO] tensorflow: global_step/sec: 15.1584 INFO:tensorflow:global_step/sec: 14.6073 2021-11-27 22:11:47,726 [INFO] tensorflow: global_step/sec: 14.6073 2021-11-27 22:11:47,727 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 41/120: loss: 0.00084 learning rate: 0.00050 Time taken: 0:00:01.464972 ETA: 0:01:55.732808 INFO:tensorflow:global_step/sec: 15.282 2021-11-27 22:11:47,857 [INFO] tensorflow: global_step/sec: 15.282 INFO:tensorflow:global_step/sec: 15.168 2021-11-27 22:11:47,989 [INFO] tensorflow: global_step/sec: 15.168 INFO:tensorflow:global_step/sec: 15.1081 2021-11-27 22:11:48,121 [INFO] tensorflow: global_step/sec: 15.1081 INFO:tensorflow:global_step/sec: 15.0112 2021-11-27 22:11:48,254 [INFO] tensorflow: global_step/sec: 15.0112 INFO:tensorflow:global_step/sec: 14.9168 2021-11-27 22:11:48,388 [INFO] tensorflow: global_step/sec: 14.9168 INFO:tensorflow:global_step/sec: 15.2759 2021-11-27 22:11:48,519 [INFO] tensorflow: global_step/sec: 15.2759 INFO:tensorflow:global_step/sec: 15.4619 2021-11-27 22:11:48,649 [INFO] tensorflow: global_step/sec: 15.4619 INFO:tensorflow:global_step/sec: 15.2158 2021-11-27 22:11:48,780 [INFO] tensorflow: global_step/sec: 15.2158 INFO:tensorflow:global_step/sec: 15.3261 2021-11-27 22:11:48,911 [INFO] tensorflow: global_step/sec: 15.3261 INFO:tensorflow:global_step/sec: 15.0754 2021-11-27 22:11:49,043 [INFO] tensorflow: global_step/sec: 15.0754 INFO:tensorflow:global_step/sec: 14.3537 2021-11-27 22:11:49,183 [INFO] tensorflow: global_step/sec: 14.3537 2021-11-27 22:11:49,184 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 42/120: loss: 0.00100 learning rate: 0.00050 Time taken: 0:00:01.452587 ETA: 0:01:53.301815 2021-11-27 22:11:49,184 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.245 INFO:tensorflow:global_step/sec: 14.9327 2021-11-27 22:11:49,317 [INFO] tensorflow: global_step/sec: 14.9327 INFO:tensorflow:global_step/sec: 15.3756 2021-11-27 22:11:49,447 [INFO] tensorflow: global_step/sec: 15.3756 INFO:tensorflow:global_step/sec: 15.3226 2021-11-27 22:11:49,577 [INFO] tensorflow: global_step/sec: 15.3226 INFO:tensorflow:global_step/sec: 15.5236 2021-11-27 22:11:49,706 [INFO] tensorflow: global_step/sec: 15.5236 INFO:tensorflow:global_step/sec: 15.1194 2021-11-27 22:11:49,838 [INFO] tensorflow: global_step/sec: 15.1194 INFO:tensorflow:global_step/sec: 15.2439 2021-11-27 22:11:49,970 [INFO] tensorflow: global_step/sec: 15.2439 INFO:tensorflow:global_step/sec: 14.6351 2021-11-27 22:11:50,106 [INFO] tensorflow: global_step/sec: 14.6351 INFO:tensorflow:global_step/sec: 14.9455 2021-11-27 22:11:50,240 [INFO] tensorflow: global_step/sec: 14.9455 INFO:tensorflow:global_step/sec: 14.9625 2021-11-27 22:11:50,374 [INFO] tensorflow: global_step/sec: 14.9625 INFO:tensorflow:global_step/sec: 15.0503 2021-11-27 22:11:50,507 [INFO] tensorflow: global_step/sec: 15.0503 INFO:tensorflow:global_step/sec: 14.0792 2021-11-27 22:11:50,649 [INFO] tensorflow: global_step/sec: 14.0792 2021-11-27 22:11:50,649 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 43/120: loss: 0.00087 learning rate: 0.00050 Time taken: 0:00:01.463979 ETA: 0:01:52.726402 INFO:tensorflow:global_step/sec: 15.0479 2021-11-27 22:11:50,782 [INFO] tensorflow: global_step/sec: 15.0479 2021-11-27 22:11:50,848 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.112 INFO:tensorflow:global_step/sec: 15.1267 2021-11-27 22:11:50,914 [INFO] tensorflow: global_step/sec: 15.1267 INFO:tensorflow:global_step/sec: 15.4693 2021-11-27 22:11:51,043 [INFO] tensorflow: global_step/sec: 15.4693 INFO:tensorflow:global_step/sec: 14.9862 2021-11-27 22:11:51,177 [INFO] tensorflow: global_step/sec: 14.9862 INFO:tensorflow:global_step/sec: 14.6079 2021-11-27 22:11:51,313 [INFO] tensorflow: global_step/sec: 14.6079 INFO:tensorflow:epoch = 43.5, learning_rate = 0.00049999997, loss = 0.00081038236, step = 957 (5.117 sec) 2021-11-27 22:11:51,380 [INFO] tensorflow: epoch = 43.5, learning_rate = 0.00049999997, loss = 0.00081038236, step = 957 (5.117 sec) INFO:tensorflow:global_step/sec: 15.1928 2021-11-27 22:11:51,445 [INFO] tensorflow: global_step/sec: 15.1928 INFO:tensorflow:global_step/sec: 14.8257 2021-11-27 22:11:51,580 [INFO] tensorflow: global_step/sec: 14.8257 INFO:tensorflow:global_step/sec: 15.0792 2021-11-27 22:11:51,713 [INFO] tensorflow: global_step/sec: 15.0792 INFO:tensorflow:global_step/sec: 15.1708 2021-11-27 22:11:51,844 [INFO] tensorflow: global_step/sec: 15.1708 INFO:tensorflow:global_step/sec: 15.0073 2021-11-27 22:11:51,978 [INFO] tensorflow: global_step/sec: 15.0073 INFO:tensorflow:global_step/sec: 13.7614 2021-11-27 22:11:52,123 [INFO] tensorflow: global_step/sec: 13.7614 2021-11-27 22:11:52,124 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 44/120: loss: 0.00098 learning rate: 0.00050 Time taken: 0:00:01.471652 ETA: 0:01:51.845554 INFO:tensorflow:global_step/sec: 15.1739 2021-11-27 22:11:52,255 [INFO] tensorflow: global_step/sec: 15.1739 INFO:tensorflow:global_step/sec: 14.9989 2021-11-27 22:11:52,388 [INFO] tensorflow: global_step/sec: 14.9989 INFO:tensorflow:global_step/sec: 15.459 2021-11-27 22:11:52,518 [INFO] tensorflow: global_step/sec: 15.459 2021-11-27 22:11:52,518 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.867 INFO:tensorflow:global_step/sec: 14.8956 2021-11-27 22:11:52,652 [INFO] tensorflow: global_step/sec: 14.8956 INFO:tensorflow:global_step/sec: 15.1938 2021-11-27 22:11:52,783 [INFO] tensorflow: global_step/sec: 15.1938 INFO:tensorflow:global_step/sec: 15.0278 2021-11-27 22:11:52,917 [INFO] tensorflow: global_step/sec: 15.0278 INFO:tensorflow:global_step/sec: 15.5823 2021-11-27 22:11:53,045 [INFO] tensorflow: global_step/sec: 15.5823 INFO:tensorflow:global_step/sec: 15.2012 2021-11-27 22:11:53,176 [INFO] tensorflow: global_step/sec: 15.2012 INFO:tensorflow:global_step/sec: 15.6249 2021-11-27 22:11:53,304 [INFO] tensorflow: global_step/sec: 15.6249 INFO:tensorflow:global_step/sec: 15.1907 2021-11-27 22:11:53,436 [INFO] tensorflow: global_step/sec: 15.1907 INFO:tensorflow:global_step/sec: 14.448 2021-11-27 22:11:53,575 [INFO] tensorflow: global_step/sec: 14.448 2021-11-27 22:11:53,576 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 45/120: loss: 0.00079 learning rate: 0.00050 Time taken: 0:00:01.451916 ETA: 0:01:48.893681 INFO:tensorflow:global_step/sec: 14.8185 2021-11-27 22:11:53,710 [INFO] tensorflow: global_step/sec: 14.8185 INFO:tensorflow:global_step/sec: 15.1671 2021-11-27 22:11:53,841 [INFO] tensorflow: global_step/sec: 15.1671 INFO:tensorflow:global_step/sec: 14.8818 2021-11-27 22:11:53,976 [INFO] tensorflow: global_step/sec: 14.8818 INFO:tensorflow:global_step/sec: 14.9848 2021-11-27 22:11:54,109 [INFO] tensorflow: global_step/sec: 14.9848 2021-11-27 22:11:54,174 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.394 INFO:tensorflow:global_step/sec: 15.5096 2021-11-27 22:11:54,238 [INFO] tensorflow: global_step/sec: 15.5096 INFO:tensorflow:global_step/sec: 14.907 2021-11-27 22:11:54,372 [INFO] tensorflow: global_step/sec: 14.907 INFO:tensorflow:global_step/sec: 15.0075 2021-11-27 22:11:54,506 [INFO] tensorflow: global_step/sec: 15.0075 INFO:tensorflow:global_step/sec: 14.7377 2021-11-27 22:11:54,641 [INFO] tensorflow: global_step/sec: 14.7377 INFO:tensorflow:global_step/sec: 15.2918 2021-11-27 22:11:54,772 [INFO] tensorflow: global_step/sec: 15.2918 INFO:tensorflow:global_step/sec: 14.9758 2021-11-27 22:11:54,906 [INFO] tensorflow: global_step/sec: 14.9758 INFO:tensorflow:global_step/sec: 14.3312 2021-11-27 22:11:55,045 [INFO] tensorflow: global_step/sec: 14.3312 2021-11-27 22:11:55,046 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 46/120: loss: 0.00084 learning rate: 0.00050 Time taken: 0:00:01.467359 ETA: 0:01:48.584553 INFO:tensorflow:global_step/sec: 15.3426 2021-11-27 22:11:55,176 [INFO] tensorflow: global_step/sec: 15.3426 INFO:tensorflow:global_step/sec: 14.9345 2021-11-27 22:11:55,309 [INFO] tensorflow: global_step/sec: 14.9345 INFO:tensorflow:global_step/sec: 15.1861 2021-11-27 22:11:55,441 [INFO] tensorflow: global_step/sec: 15.1861 INFO:tensorflow:global_step/sec: 15.0804 2021-11-27 22:11:55,574 [INFO] tensorflow: global_step/sec: 15.0804 INFO:tensorflow:global_step/sec: 15.0088 2021-11-27 22:11:55,707 [INFO] tensorflow: global_step/sec: 15.0088 INFO:tensorflow:global_step/sec: 15.1252 2021-11-27 22:11:55,839 [INFO] tensorflow: global_step/sec: 15.1252 2021-11-27 22:11:55,840 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.043 INFO:tensorflow:global_step/sec: 15.0408 2021-11-27 22:11:55,972 [INFO] tensorflow: global_step/sec: 15.0408 INFO:tensorflow:global_step/sec: 15.2532 2021-11-27 22:11:56,103 [INFO] tensorflow: global_step/sec: 15.2532 INFO:tensorflow:global_step/sec: 15.1086 2021-11-27 22:11:56,236 [INFO] tensorflow: global_step/sec: 15.1086 INFO:tensorflow:global_step/sec: 14.5805 2021-11-27 22:11:56,373 [INFO] tensorflow: global_step/sec: 14.5805 INFO:tensorflow:epoch = 47.0, learning_rate = 0.00049999997, loss = 0.0009138873, step = 1034 (5.125 sec) 2021-11-27 22:11:56,504 [INFO] tensorflow: epoch = 47.0, learning_rate = 0.00049999997, loss = 0.0009138873, step = 1034 (5.125 sec) INFO:tensorflow:global_step/sec: 15.1393 2021-11-27 22:11:56,505 [INFO] tensorflow: global_step/sec: 15.1393 2021-11-27 22:11:56,506 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 47/120: loss: 0.00091 learning rate: 0.00050 Time taken: 0:00:01.462579 ETA: 0:01:46.768250 INFO:tensorflow:global_step/sec: 15.2855 2021-11-27 22:11:56,636 [INFO] tensorflow: global_step/sec: 15.2855 INFO:tensorflow:global_step/sec: 15.0066 2021-11-27 22:11:56,769 [INFO] tensorflow: global_step/sec: 15.0066 INFO:tensorflow:global_step/sec: 14.7333 2021-11-27 22:11:56,905 [INFO] tensorflow: global_step/sec: 14.7333 INFO:tensorflow:global_step/sec: 15.3987 2021-11-27 22:11:57,035 [INFO] tensorflow: global_step/sec: 15.3987 INFO:tensorflow:global_step/sec: 15.3049 2021-11-27 22:11:57,165 [INFO] tensorflow: global_step/sec: 15.3049 INFO:tensorflow:global_step/sec: 15.299 2021-11-27 22:11:57,296 [INFO] tensorflow: global_step/sec: 15.299 INFO:tensorflow:global_step/sec: 14.9759 2021-11-27 22:11:57,430 [INFO] tensorflow: global_step/sec: 14.9759 2021-11-27 22:11:57,496 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.401 INFO:tensorflow:global_step/sec: 14.9869 2021-11-27 22:11:57,563 [INFO] tensorflow: global_step/sec: 14.9869 INFO:tensorflow:global_step/sec: 15.1593 2021-11-27 22:11:57,695 [INFO] tensorflow: global_step/sec: 15.1593 INFO:tensorflow:global_step/sec: 15.1397 2021-11-27 22:11:57,827 [INFO] tensorflow: global_step/sec: 15.1397 INFO:tensorflow:global_step/sec: 14.5672 2021-11-27 22:11:57,965 [INFO] tensorflow: global_step/sec: 14.5672 2021-11-27 22:11:57,965 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 48/120: loss: 0.00092 learning rate: 0.00050 Time taken: 0:00:01.456469 ETA: 0:01:44.865772 INFO:tensorflow:global_step/sec: 15.2014 2021-11-27 22:11:58,096 [INFO] tensorflow: global_step/sec: 15.2014 INFO:tensorflow:global_step/sec: 15.332 2021-11-27 22:11:58,227 [INFO] tensorflow: global_step/sec: 15.332 INFO:tensorflow:global_step/sec: 15.3564 2021-11-27 22:11:58,357 [INFO] tensorflow: global_step/sec: 15.3564 INFO:tensorflow:global_step/sec: 15.179 2021-11-27 22:11:58,489 [INFO] tensorflow: global_step/sec: 15.179 INFO:tensorflow:global_step/sec: 14.712 2021-11-27 22:11:58,624 [INFO] tensorflow: global_step/sec: 14.712 INFO:tensorflow:global_step/sec: 14.6408 2021-11-27 22:11:58,761 [INFO] tensorflow: global_step/sec: 14.6408 INFO:tensorflow:global_step/sec: 15.097 2021-11-27 22:11:58,894 [INFO] tensorflow: global_step/sec: 15.097 INFO:tensorflow:global_step/sec: 15.097 2021-11-27 22:11:59,026 [INFO] tensorflow: global_step/sec: 15.097 INFO:tensorflow:global_step/sec: 15.2985 2021-11-27 22:11:59,157 [INFO] tensorflow: global_step/sec: 15.2985 2021-11-27 22:11:59,158 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.190 INFO:tensorflow:global_step/sec: 14.9426 2021-11-27 22:11:59,291 [INFO] tensorflow: global_step/sec: 14.9426 INFO:tensorflow:global_step/sec: 14.4123 2021-11-27 22:11:59,429 [INFO] tensorflow: global_step/sec: 14.4123 2021-11-27 22:11:59,430 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 49/120: loss: 0.00074 learning rate: 0.00050 Time taken: 0:00:01.462435 ETA: 0:01:43.832852 INFO:tensorflow:global_step/sec: 15.0344 2021-11-27 22:11:59,562 [INFO] tensorflow: global_step/sec: 15.0344 INFO:tensorflow:global_step/sec: 15.1516 2021-11-27 22:11:59,694 [INFO] tensorflow: global_step/sec: 15.1516 INFO:tensorflow:global_step/sec: 15.2192 2021-11-27 22:11:59,826 [INFO] tensorflow: global_step/sec: 15.2192 INFO:tensorflow:global_step/sec: 15.3521 2021-11-27 22:11:59,956 [INFO] tensorflow: global_step/sec: 15.3521 INFO:tensorflow:global_step/sec: 14.5958 2021-11-27 22:12:00,093 [INFO] tensorflow: global_step/sec: 14.5958 INFO:tensorflow:global_step/sec: 15.7292 2021-11-27 22:12:00,220 [INFO] tensorflow: global_step/sec: 15.7292 INFO:tensorflow:global_step/sec: 14.8774 2021-11-27 22:12:00,355 [INFO] tensorflow: global_step/sec: 14.8774 INFO:tensorflow:global_step/sec: 14.8267 2021-11-27 22:12:00,490 [INFO] tensorflow: global_step/sec: 14.8267 INFO:tensorflow:global_step/sec: 15.1096 2021-11-27 22:12:00,622 [INFO] tensorflow: global_step/sec: 15.1096 INFO:tensorflow:global_step/sec: 14.847 2021-11-27 22:12:00,757 [INFO] tensorflow: global_step/sec: 14.847 INFO:tensorflow:Saving checkpoints for step-1100. 2021-11-27 22:12:00,823 [INFO] tensorflow: Saving checkpoints for step-1100. WARNING:tensorflow:Ignoring: /tmp/tmp0zria95g; No such file or directory 2021-11-27 22:12:00,910 [WARNING] tensorflow: Ignoring: /tmp/tmp0zria95g; No such file or directory 2021-11-27 22:12:03,172 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 801/801 [00:00<00:00, 21408.10it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 90/90 [00:00<00:00, 23497.50it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 239/239 [00:00<00:00, 24605.16it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 1302/1302 [00:00<00:00, 26501.78it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 303/303 [00:00<00:00, 24410.78it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 965/965 [00:00<00:00, 24058.20it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 3685/3685 [00:00<00:00, 36470.23it/s] Epoch 50/120 ========================= Validation cost: 0.000479 Mean average_precision (in %): 24.4442 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 41.4886 floor 0 palette 4.98866 pillar 53.2444 pushcart 0 rackframe 39.0402 rackshelf 48.8277 wall 32.4083 Median Inference Time: 0.007343 2021-11-27 22:12:06,058 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 14.492 INFO:tensorflow:epoch = 50.0, learning_rate = 0.00049999997, loss = 0.0010649569, step = 1100 (9.622 sec) 2021-11-27 22:12:06,126 [INFO] tensorflow: epoch = 50.0, learning_rate = 0.00049999997, loss = 0.0010649569, step = 1100 (9.622 sec) INFO:tensorflow:global_step/sec: 0.37245 2021-11-27 22:12:06,127 [INFO] tensorflow: global_step/sec: 0.37245 2021-11-27 22:12:06,127 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 50/120: loss: 0.00106 learning rate: 0.00050 Time taken: 0:00:06.694914 ETA: 0:07:48.643970 INFO:tensorflow:global_step/sec: 15.2352 2021-11-27 22:12:06,258 [INFO] tensorflow: global_step/sec: 15.2352 INFO:tensorflow:global_step/sec: 15.3075 2021-11-27 22:12:06,388 [INFO] tensorflow: global_step/sec: 15.3075 INFO:tensorflow:global_step/sec: 15.6479 2021-11-27 22:12:06,516 [INFO] tensorflow: global_step/sec: 15.6479 INFO:tensorflow:global_step/sec: 14.819 2021-11-27 22:12:06,651 [INFO] tensorflow: global_step/sec: 14.819 INFO:tensorflow:global_step/sec: 14.9812 2021-11-27 22:12:06,785 [INFO] tensorflow: global_step/sec: 14.9812 INFO:tensorflow:global_step/sec: 14.6868 2021-11-27 22:12:06,921 [INFO] tensorflow: global_step/sec: 14.6868 INFO:tensorflow:global_step/sec: 15.2648 2021-11-27 22:12:07,052 [INFO] tensorflow: global_step/sec: 15.2648 INFO:tensorflow:global_step/sec: 14.7162 2021-11-27 22:12:07,188 [INFO] tensorflow: global_step/sec: 14.7162 INFO:tensorflow:global_step/sec: 15.59 2021-11-27 22:12:07,316 [INFO] tensorflow: global_step/sec: 15.59 INFO:tensorflow:global_step/sec: 15.6763 2021-11-27 22:12:07,444 [INFO] tensorflow: global_step/sec: 15.6763 INFO:tensorflow:global_step/sec: 14.728 2021-11-27 22:12:07,579 [INFO] tensorflow: global_step/sec: 14.728 2021-11-27 22:12:07,580 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 51/120: loss: 0.00083 learning rate: 0.00050 Time taken: 0:00:01.450180 ETA: 0:01:40.062391 INFO:tensorflow:global_step/sec: 14.9589 2021-11-27 22:12:07,713 [INFO] tensorflow: global_step/sec: 14.9589 2021-11-27 22:12:07,714 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.457 INFO:tensorflow:global_step/sec: 15.3706 2021-11-27 22:12:07,843 [INFO] tensorflow: global_step/sec: 15.3706 INFO:tensorflow:global_step/sec: 15.2981 2021-11-27 22:12:07,974 [INFO] tensorflow: global_step/sec: 15.2981 INFO:tensorflow:global_step/sec: 14.7912 2021-11-27 22:12:08,109 [INFO] tensorflow: global_step/sec: 14.7912 INFO:tensorflow:global_step/sec: 14.6076 2021-11-27 22:12:08,246 [INFO] tensorflow: global_step/sec: 14.6076 INFO:tensorflow:global_step/sec: 15.0434 2021-11-27 22:12:08,379 [INFO] tensorflow: global_step/sec: 15.0434 INFO:tensorflow:global_step/sec: 15.4711 2021-11-27 22:12:08,508 [INFO] tensorflow: global_step/sec: 15.4711 INFO:tensorflow:global_step/sec: 15.2914 2021-11-27 22:12:08,639 [INFO] tensorflow: global_step/sec: 15.2914 INFO:tensorflow:global_step/sec: 15.0977 2021-11-27 22:12:08,772 [INFO] tensorflow: global_step/sec: 15.0977 INFO:tensorflow:global_step/sec: 15.1596 2021-11-27 22:12:08,904 [INFO] tensorflow: global_step/sec: 15.1596 INFO:tensorflow:global_step/sec: 13.9233 2021-11-27 22:12:09,047 [INFO] tensorflow: global_step/sec: 13.9233 2021-11-27 22:12:09,048 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 52/120: loss: 0.00088 learning rate: 0.00050 Time taken: 0:00:01.466222 ETA: 0:01:39.703099 INFO:tensorflow:global_step/sec: 15.4908 2021-11-27 22:12:09,176 [INFO] tensorflow: global_step/sec: 15.4908 INFO:tensorflow:global_step/sec: 14.9332 2021-11-27 22:12:09,310 [INFO] tensorflow: global_step/sec: 14.9332 2021-11-27 22:12:09,375 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.220 INFO:tensorflow:global_step/sec: 15.2218 2021-11-27 22:12:09,442 [INFO] tensorflow: global_step/sec: 15.2218 INFO:tensorflow:global_step/sec: 14.9859 2021-11-27 22:12:09,575 [INFO] tensorflow: global_step/sec: 14.9859 INFO:tensorflow:global_step/sec: 15.4823 2021-11-27 22:12:09,704 [INFO] tensorflow: global_step/sec: 15.4823 INFO:tensorflow:global_step/sec: 15.6199 2021-11-27 22:12:09,832 [INFO] tensorflow: global_step/sec: 15.6199 INFO:tensorflow:global_step/sec: 15.9041 2021-11-27 22:12:09,958 [INFO] tensorflow: global_step/sec: 15.9041 INFO:tensorflow:global_step/sec: 14.8429 2021-11-27 22:12:10,093 [INFO] tensorflow: global_step/sec: 14.8429 INFO:tensorflow:global_step/sec: 15.4095 2021-11-27 22:12:10,223 [INFO] tensorflow: global_step/sec: 15.4095 INFO:tensorflow:global_step/sec: 15.2428 2021-11-27 22:12:10,354 [INFO] tensorflow: global_step/sec: 15.2428 INFO:tensorflow:global_step/sec: 14.2094 2021-11-27 22:12:10,495 [INFO] tensorflow: global_step/sec: 14.2094 2021-11-27 22:12:10,496 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 53/120: loss: 0.00078 learning rate: 0.00050 Time taken: 0:00:01.447644 ETA: 0:01:36.992132 INFO:tensorflow:global_step/sec: 15.3816 2021-11-27 22:12:10,625 [INFO] tensorflow: global_step/sec: 15.3816 INFO:tensorflow:global_step/sec: 15.4565 2021-11-27 22:12:10,754 [INFO] tensorflow: global_step/sec: 15.4565 INFO:tensorflow:global_step/sec: 14.9284 2021-11-27 22:12:10,888 [INFO] tensorflow: global_step/sec: 14.9284 INFO:tensorflow:global_step/sec: 14.8126 2021-11-27 22:12:11,023 [INFO] tensorflow: global_step/sec: 14.8126 2021-11-27 22:12:11,024 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.652 INFO:tensorflow:global_step/sec: 15.4312 2021-11-27 22:12:11,153 [INFO] tensorflow: global_step/sec: 15.4312 INFO:tensorflow:epoch = 53.5, learning_rate = 0.00049999997, loss = 0.00094118493, step = 1177 (5.094 sec) 2021-11-27 22:12:11,220 [INFO] tensorflow: epoch = 53.5, learning_rate = 0.00049999997, loss = 0.00094118493, step = 1177 (5.094 sec) INFO:tensorflow:global_step/sec: 14.9147 2021-11-27 22:12:11,287 [INFO] tensorflow: global_step/sec: 14.9147 INFO:tensorflow:global_step/sec: 15.2435 2021-11-27 22:12:11,418 [INFO] tensorflow: global_step/sec: 15.2435 INFO:tensorflow:global_step/sec: 14.5334 2021-11-27 22:12:11,556 [INFO] tensorflow: global_step/sec: 14.5334 INFO:tensorflow:global_step/sec: 14.7962 2021-11-27 22:12:11,691 [INFO] tensorflow: global_step/sec: 14.7962 INFO:tensorflow:global_step/sec: 15.301 2021-11-27 22:12:11,821 [INFO] tensorflow: global_step/sec: 15.301 INFO:tensorflow:global_step/sec: 14.5375 2021-11-27 22:12:11,959 [INFO] tensorflow: global_step/sec: 14.5375 2021-11-27 22:12:11,960 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 54/120: loss: 0.00087 learning rate: 0.00050 Time taken: 0:00:01.463930 ETA: 0:01:36.619389 INFO:tensorflow:global_step/sec: 15.1491 2021-11-27 22:12:12,091 [INFO] tensorflow: global_step/sec: 15.1491 INFO:tensorflow:global_step/sec: 15.0707 2021-11-27 22:12:12,224 [INFO] tensorflow: global_step/sec: 15.0707 INFO:tensorflow:global_step/sec: 14.9959 2021-11-27 22:12:12,357 [INFO] tensorflow: global_step/sec: 14.9959 INFO:tensorflow:global_step/sec: 15.3094 2021-11-27 22:12:12,488 [INFO] tensorflow: global_step/sec: 15.3094 INFO:tensorflow:global_step/sec: 14.7646 2021-11-27 22:12:12,623 [INFO] tensorflow: global_step/sec: 14.7646 2021-11-27 22:12:12,689 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.081 INFO:tensorflow:global_step/sec: 15.362 2021-11-27 22:12:12,753 [INFO] tensorflow: global_step/sec: 15.362 INFO:tensorflow:global_step/sec: 14.7541 2021-11-27 22:12:12,889 [INFO] tensorflow: global_step/sec: 14.7541 INFO:tensorflow:global_step/sec: 14.8839 2021-11-27 22:12:13,023 [INFO] tensorflow: global_step/sec: 14.8839 INFO:tensorflow:global_step/sec: 15.0809 2021-11-27 22:12:13,156 [INFO] tensorflow: global_step/sec: 15.0809 INFO:tensorflow:global_step/sec: 14.9506 2021-11-27 22:12:13,290 [INFO] tensorflow: global_step/sec: 14.9506 INFO:tensorflow:global_step/sec: 14.6066 2021-11-27 22:12:13,427 [INFO] tensorflow: global_step/sec: 14.6066 2021-11-27 22:12:13,427 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 55/120: loss: 0.00078 learning rate: 0.00050 Time taken: 0:00:01.463731 ETA: 0:01:35.142534 INFO:tensorflow:global_step/sec: 13.25 2021-11-27 22:12:13,578 [INFO] tensorflow: global_step/sec: 13.25 INFO:tensorflow:global_step/sec: 15.171 2021-11-27 22:12:13,709 [INFO] tensorflow: global_step/sec: 15.171 INFO:tensorflow:global_step/sec: 15.0354 2021-11-27 22:12:13,842 [INFO] tensorflow: global_step/sec: 15.0354 INFO:tensorflow:global_step/sec: 15.6589 2021-11-27 22:12:13,970 [INFO] tensorflow: global_step/sec: 15.6589 INFO:tensorflow:global_step/sec: 15.3792 2021-11-27 22:12:14,100 [INFO] tensorflow: global_step/sec: 15.3792 INFO:tensorflow:global_step/sec: 15.1949 2021-11-27 22:12:14,232 [INFO] tensorflow: global_step/sec: 15.1949 INFO:tensorflow:global_step/sec: 15.0252 2021-11-27 22:12:14,365 [INFO] tensorflow: global_step/sec: 15.0252 2021-11-27 22:12:14,366 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.637 INFO:tensorflow:global_step/sec: 15.1619 2021-11-27 22:12:14,497 [INFO] tensorflow: global_step/sec: 15.1619 INFO:tensorflow:global_step/sec: 15.4137 2021-11-27 22:12:14,627 [INFO] tensorflow: global_step/sec: 15.4137 INFO:tensorflow:global_step/sec: 15.2072 2021-11-27 22:12:14,758 [INFO] tensorflow: global_step/sec: 15.2072 INFO:tensorflow:global_step/sec: 14.5832 2021-11-27 22:12:14,895 [INFO] tensorflow: global_step/sec: 14.5832 2021-11-27 22:12:14,896 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 56/120: loss: 0.00092 learning rate: 0.00050 Time taken: 0:00:01.466157 ETA: 0:01:33.834045 INFO:tensorflow:global_step/sec: 14.7921 2021-11-27 22:12:15,030 [INFO] tensorflow: global_step/sec: 14.7921 INFO:tensorflow:global_step/sec: 14.9331 2021-11-27 22:12:15,164 [INFO] tensorflow: global_step/sec: 14.9331 INFO:tensorflow:global_step/sec: 14.9091 2021-11-27 22:12:15,299 [INFO] tensorflow: global_step/sec: 14.9091 INFO:tensorflow:global_step/sec: 14.7242 2021-11-27 22:12:15,434 [INFO] tensorflow: global_step/sec: 14.7242 INFO:tensorflow:global_step/sec: 14.9121 2021-11-27 22:12:15,568 [INFO] tensorflow: global_step/sec: 14.9121 INFO:tensorflow:global_step/sec: 15.0135 2021-11-27 22:12:15,702 [INFO] tensorflow: global_step/sec: 15.0135 INFO:tensorflow:global_step/sec: 15.0289 2021-11-27 22:12:15,835 [INFO] tensorflow: global_step/sec: 15.0289 INFO:tensorflow:global_step/sec: 15.0823 2021-11-27 22:12:15,967 [INFO] tensorflow: global_step/sec: 15.0823 2021-11-27 22:12:16,032 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.020 INFO:tensorflow:global_step/sec: 14.9472 2021-11-27 22:12:16,101 [INFO] tensorflow: global_step/sec: 14.9472 INFO:tensorflow:global_step/sec: 15.1505 2021-11-27 22:12:16,233 [INFO] tensorflow: global_step/sec: 15.1505 INFO:tensorflow:epoch = 56.95454545454545, learning_rate = 0.00049999997, loss = 0.00086893945, step = 1253 (5.081 sec) 2021-11-27 22:12:16,301 [INFO] tensorflow: epoch = 56.95454545454545, learning_rate = 0.00049999997, loss = 0.00086893945, step = 1253 (5.081 sec) INFO:tensorflow:global_step/sec: 13.8847 2021-11-27 22:12:16,377 [INFO] tensorflow: global_step/sec: 13.8847 2021-11-27 22:12:16,378 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 57/120: loss: 0.00078 learning rate: 0.00050 Time taken: 0:00:01.478455 ETA: 0:01:33.142654 INFO:tensorflow:global_step/sec: 15.0431 2021-11-27 22:12:16,510 [INFO] tensorflow: global_step/sec: 15.0431 INFO:tensorflow:global_step/sec: 15.5716 2021-11-27 22:12:16,639 [INFO] tensorflow: global_step/sec: 15.5716 INFO:tensorflow:global_step/sec: 15.1448 2021-11-27 22:12:16,771 [INFO] tensorflow: global_step/sec: 15.1448 INFO:tensorflow:global_step/sec: 15.1011 2021-11-27 22:12:16,903 [INFO] tensorflow: global_step/sec: 15.1011 INFO:tensorflow:global_step/sec: 15.0432 2021-11-27 22:12:17,036 [INFO] tensorflow: global_step/sec: 15.0432 INFO:tensorflow:global_step/sec: 14.9499 2021-11-27 22:12:17,170 [INFO] tensorflow: global_step/sec: 14.9499 INFO:tensorflow:global_step/sec: 14.955 2021-11-27 22:12:17,304 [INFO] tensorflow: global_step/sec: 14.955 INFO:tensorflow:global_step/sec: 14.5574 2021-11-27 22:12:17,441 [INFO] tensorflow: global_step/sec: 14.5574 INFO:tensorflow:global_step/sec: 15.0822 2021-11-27 22:12:17,574 [INFO] tensorflow: global_step/sec: 15.0822 INFO:tensorflow:global_step/sec: 15.2021 2021-11-27 22:12:17,705 [INFO] tensorflow: global_step/sec: 15.2021 2021-11-27 22:12:17,706 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.766 INFO:tensorflow:global_step/sec: 14.7023 2021-11-27 22:12:17,841 [INFO] tensorflow: global_step/sec: 14.7023 2021-11-27 22:12:17,842 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 58/120: loss: 0.00093 learning rate: 0.00050 Time taken: 0:00:01.465820 ETA: 0:01:30.880859 INFO:tensorflow:global_step/sec: 15.1699 2021-11-27 22:12:17,973 [INFO] tensorflow: global_step/sec: 15.1699 INFO:tensorflow:global_step/sec: 15.1236 2021-11-27 22:12:18,105 [INFO] tensorflow: global_step/sec: 15.1236 INFO:tensorflow:global_step/sec: 15.2878 2021-11-27 22:12:18,236 [INFO] tensorflow: global_step/sec: 15.2878 INFO:tensorflow:global_step/sec: 15.0469 2021-11-27 22:12:18,369 [INFO] tensorflow: global_step/sec: 15.0469 INFO:tensorflow:global_step/sec: 14.8052 2021-11-27 22:12:18,504 [INFO] tensorflow: global_step/sec: 14.8052 INFO:tensorflow:global_step/sec: 15.0932 2021-11-27 22:12:18,637 [INFO] tensorflow: global_step/sec: 15.0932 INFO:tensorflow:global_step/sec: 14.9378 2021-11-27 22:12:18,770 [INFO] tensorflow: global_step/sec: 14.9378 INFO:tensorflow:global_step/sec: 14.6198 2021-11-27 22:12:18,907 [INFO] tensorflow: global_step/sec: 14.6198 INFO:tensorflow:global_step/sec: 15.4707 2021-11-27 22:12:19,037 [INFO] tensorflow: global_step/sec: 15.4707 INFO:tensorflow:global_step/sec: 14.4054 2021-11-27 22:12:19,175 [INFO] tensorflow: global_step/sec: 14.4054 INFO:tensorflow:global_step/sec: 14.4557 2021-11-27 22:12:19,314 [INFO] tensorflow: global_step/sec: 14.4557 2021-11-27 22:12:19,315 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 59/120: loss: 0.00093 learning rate: 0.00050 Time taken: 0:00:01.470789 ETA: 0:01:29.718141 2021-11-27 22:12:19,381 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.679 INFO:tensorflow:global_step/sec: 14.5913 2021-11-27 22:12:19,451 [INFO] tensorflow: global_step/sec: 14.5913 INFO:tensorflow:global_step/sec: 14.7346 2021-11-27 22:12:19,587 [INFO] tensorflow: global_step/sec: 14.7346 INFO:tensorflow:global_step/sec: 14.8875 2021-11-27 22:12:19,721 [INFO] tensorflow: global_step/sec: 14.8875 INFO:tensorflow:global_step/sec: 14.859 2021-11-27 22:12:19,855 [INFO] tensorflow: global_step/sec: 14.859 INFO:tensorflow:global_step/sec: 15.6333 2021-11-27 22:12:19,983 [INFO] tensorflow: global_step/sec: 15.6333 INFO:tensorflow:global_step/sec: 15.4073 2021-11-27 22:12:20,113 [INFO] tensorflow: global_step/sec: 15.4073 INFO:tensorflow:global_step/sec: 14.9848 2021-11-27 22:12:20,247 [INFO] tensorflow: global_step/sec: 14.9848 INFO:tensorflow:global_step/sec: 15.2503 2021-11-27 22:12:20,378 [INFO] tensorflow: global_step/sec: 15.2503 INFO:tensorflow:global_step/sec: 14.5828 2021-11-27 22:12:20,515 [INFO] tensorflow: global_step/sec: 14.5828 INFO:tensorflow:global_step/sec: 14.9752 2021-11-27 22:12:20,649 [INFO] tensorflow: global_step/sec: 14.9752 INFO:tensorflow:Saving checkpoints for step-1320. 2021-11-27 22:12:20,713 [INFO] tensorflow: Saving checkpoints for step-1320. WARNING:tensorflow:Ignoring: /tmp/tmp00e3fall; No such file or directory 2021-11-27 22:12:20,799 [WARNING] tensorflow: Ignoring: /tmp/tmp00e3fall; No such file or directory 2021-11-27 22:12:23,052 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 1126/1126 [00:00<00:00, 24527.07it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 119/119 [00:00<00:00, 23328.92it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 366/366 [00:00<00:00, 24577.18it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 1075/1075 [00:00<00:00, 25359.98it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 363/363 [00:00<00:00, 23733.94it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 1085/1085 [00:00<00:00, 23687.88it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 3902/3902 [00:00<00:00, 35894.43it/s] Epoch 60/120 ========================= Validation cost: 0.000544 Mean average_precision (in %): 26.8432 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 52.4472 floor 0 palette 7.28369 pillar 50.1653 pushcart 0 rackframe 40.2605 rackshelf 52.1553 wall 39.277 Median Inference Time: 0.007524 INFO:tensorflow:epoch = 60.0, learning_rate = 0.00049999997, loss = 0.00087940047, step = 1320 (9.752 sec) 2021-11-27 22:12:26,053 [INFO] tensorflow: epoch = 60.0, learning_rate = 0.00049999997, loss = 0.00087940047, step = 1320 (9.752 sec) INFO:tensorflow:global_step/sec: 0.370007 2021-11-27 22:12:26,054 [INFO] tensorflow: global_step/sec: 0.370007 2021-11-27 22:12:26,055 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 60/120: loss: 0.00088 learning rate: 0.00050 Time taken: 0:00:06.734482 ETA: 0:06:44.068937 INFO:tensorflow:global_step/sec: 14.7957 2021-11-27 22:12:26,189 [INFO] tensorflow: global_step/sec: 14.7957 INFO:tensorflow:global_step/sec: 15.1964 2021-11-27 22:12:26,321 [INFO] tensorflow: global_step/sec: 15.1964 2021-11-27 22:12:26,321 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 14.410 INFO:tensorflow:global_step/sec: 15.0273 2021-11-27 22:12:26,454 [INFO] tensorflow: global_step/sec: 15.0273 INFO:tensorflow:global_step/sec: 15.2797 2021-11-27 22:12:26,585 [INFO] tensorflow: global_step/sec: 15.2797 INFO:tensorflow:global_step/sec: 15.1838 2021-11-27 22:12:26,716 [INFO] tensorflow: global_step/sec: 15.1838 INFO:tensorflow:global_step/sec: 14.9278 2021-11-27 22:12:26,850 [INFO] tensorflow: global_step/sec: 14.9278 INFO:tensorflow:global_step/sec: 15.058 2021-11-27 22:12:26,983 [INFO] tensorflow: global_step/sec: 15.058 INFO:tensorflow:global_step/sec: 15.3988 2021-11-27 22:12:27,113 [INFO] tensorflow: global_step/sec: 15.3988 INFO:tensorflow:global_step/sec: 14.9069 2021-11-27 22:12:27,247 [INFO] tensorflow: global_step/sec: 14.9069 INFO:tensorflow:global_step/sec: 14.6136 2021-11-27 22:12:27,384 [INFO] tensorflow: global_step/sec: 14.6136 INFO:tensorflow:global_step/sec: 14.4648 2021-11-27 22:12:27,522 [INFO] tensorflow: global_step/sec: 14.4648 2021-11-27 22:12:27,523 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 61/120: loss: 0.00089 learning rate: 0.00050 Time taken: 0:00:01.471548 ETA: 0:01:26.821309 INFO:tensorflow:global_step/sec: 15.1275 2021-11-27 22:12:27,655 [INFO] tensorflow: global_step/sec: 15.1275 INFO:tensorflow:global_step/sec: 14.369 2021-11-27 22:12:27,794 [INFO] tensorflow: global_step/sec: 14.369 INFO:tensorflow:global_step/sec: 15.3824 2021-11-27 22:12:27,924 [INFO] tensorflow: global_step/sec: 15.3824 2021-11-27 22:12:27,989 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.972 INFO:tensorflow:global_step/sec: 15.3686 2021-11-27 22:12:28,054 [INFO] tensorflow: global_step/sec: 15.3686 INFO:tensorflow:global_step/sec: 14.5108 2021-11-27 22:12:28,192 [INFO] tensorflow: global_step/sec: 14.5108 INFO:tensorflow:global_step/sec: 14.9015 2021-11-27 22:12:28,326 [INFO] tensorflow: global_step/sec: 14.9015 INFO:tensorflow:global_step/sec: 15.707 2021-11-27 22:12:28,453 [INFO] tensorflow: global_step/sec: 15.707 INFO:tensorflow:global_step/sec: 15.6036 2021-11-27 22:12:28,581 [INFO] tensorflow: global_step/sec: 15.6036 INFO:tensorflow:global_step/sec: 15.1193 2021-11-27 22:12:28,714 [INFO] tensorflow: global_step/sec: 15.1193 INFO:tensorflow:global_step/sec: 15.076 2021-11-27 22:12:28,846 [INFO] tensorflow: global_step/sec: 15.076 INFO:tensorflow:global_step/sec: 15.2381 2021-11-27 22:12:28,978 [INFO] tensorflow: global_step/sec: 15.2381 2021-11-27 22:12:28,979 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 62/120: loss: 0.00095 learning rate: 0.00050 Time taken: 0:00:01.458882 ETA: 0:01:24.615134 INFO:tensorflow:global_step/sec: 15.0636 2021-11-27 22:12:29,110 [INFO] tensorflow: global_step/sec: 15.0636 INFO:tensorflow:global_step/sec: 14.9533 2021-11-27 22:12:29,244 [INFO] tensorflow: global_step/sec: 14.9533 INFO:tensorflow:global_step/sec: 14.7151 2021-11-27 22:12:29,380 [INFO] tensorflow: global_step/sec: 14.7151 INFO:tensorflow:global_step/sec: 15.2775 2021-11-27 22:12:29,511 [INFO] tensorflow: global_step/sec: 15.2775 INFO:tensorflow:global_step/sec: 14.775 2021-11-27 22:12:29,646 [INFO] tensorflow: global_step/sec: 14.775 2021-11-27 22:12:29,647 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.337 INFO:tensorflow:global_step/sec: 15.0148 2021-11-27 22:12:29,780 [INFO] tensorflow: global_step/sec: 15.0148 INFO:tensorflow:global_step/sec: 14.2722 2021-11-27 22:12:29,920 [INFO] tensorflow: global_step/sec: 14.2722 INFO:tensorflow:global_step/sec: 14.7711 2021-11-27 22:12:30,055 [INFO] tensorflow: global_step/sec: 14.7711 INFO:tensorflow:global_step/sec: 15.5212 2021-11-27 22:12:30,184 [INFO] tensorflow: global_step/sec: 15.5212 INFO:tensorflow:global_step/sec: 15.5013 2021-11-27 22:12:30,313 [INFO] tensorflow: global_step/sec: 15.5013 INFO:tensorflow:global_step/sec: 14.6775 2021-11-27 22:12:30,449 [INFO] tensorflow: global_step/sec: 14.6775 2021-11-27 22:12:30,450 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 63/120: loss: 0.00100 learning rate: 0.00050 Time taken: 0:00:01.466209 ETA: 0:01:23.573936 INFO:tensorflow:global_step/sec: 14.7514 2021-11-27 22:12:30,585 [INFO] tensorflow: global_step/sec: 14.7514 INFO:tensorflow:global_step/sec: 14.8264 2021-11-27 22:12:30,720 [INFO] tensorflow: global_step/sec: 14.8264 INFO:tensorflow:global_step/sec: 15.134 2021-11-27 22:12:30,852 [INFO] tensorflow: global_step/sec: 15.134 INFO:tensorflow:global_step/sec: 14.8385 2021-11-27 22:12:30,987 [INFO] tensorflow: global_step/sec: 14.8385 INFO:tensorflow:global_step/sec: 15.2822 2021-11-27 22:12:31,117 [INFO] tensorflow: global_step/sec: 15.2822 INFO:tensorflow:epoch = 63.5, learning_rate = 0.00049999997, loss = 0.00069937564, step = 1397 (5.130 sec) 2021-11-27 22:12:31,184 [INFO] tensorflow: epoch = 63.5, learning_rate = 0.00049999997, loss = 0.00069937564, step = 1397 (5.130 sec) INFO:tensorflow:global_step/sec: 15.0908 2021-11-27 22:12:31,250 [INFO] tensorflow: global_step/sec: 15.0908 2021-11-27 22:12:31,318 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.845 INFO:tensorflow:global_step/sec: 14.6565 2021-11-27 22:12:31,386 [INFO] tensorflow: global_step/sec: 14.6565 INFO:tensorflow:global_step/sec: 15.3194 2021-11-27 22:12:31,517 [INFO] tensorflow: global_step/sec: 15.3194 INFO:tensorflow:global_step/sec: 15.3984 2021-11-27 22:12:31,647 [INFO] tensorflow: global_step/sec: 15.3984 INFO:tensorflow:global_step/sec: 15.313 2021-11-27 22:12:31,777 [INFO] tensorflow: global_step/sec: 15.313 INFO:tensorflow:global_step/sec: 14.3433 2021-11-27 22:12:31,917 [INFO] tensorflow: global_step/sec: 14.3433 2021-11-27 22:12:31,918 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 64/120: loss: 0.00082 learning rate: 0.00050 Time taken: 0:00:01.468210 ETA: 0:01:22.219732 INFO:tensorflow:global_step/sec: 15.3212 2021-11-27 22:12:32,047 [INFO] tensorflow: global_step/sec: 15.3212 INFO:tensorflow:global_step/sec: 14.91 2021-11-27 22:12:32,182 [INFO] tensorflow: global_step/sec: 14.91 INFO:tensorflow:global_step/sec: 15.1005 2021-11-27 22:12:32,314 [INFO] tensorflow: global_step/sec: 15.1005 INFO:tensorflow:global_step/sec: 14.7625 2021-11-27 22:12:32,450 [INFO] tensorflow: global_step/sec: 14.7625 INFO:tensorflow:global_step/sec: 14.7939 2021-11-27 22:12:32,585 [INFO] tensorflow: global_step/sec: 14.7939 INFO:tensorflow:global_step/sec: 15.3502 2021-11-27 22:12:32,715 [INFO] tensorflow: global_step/sec: 15.3502 INFO:tensorflow:global_step/sec: 15.1412 2021-11-27 22:12:32,847 [INFO] tensorflow: global_step/sec: 15.1412 INFO:tensorflow:global_step/sec: 14.9473 2021-11-27 22:12:32,981 [INFO] tensorflow: global_step/sec: 14.9473 2021-11-27 22:12:32,982 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.132 INFO:tensorflow:global_step/sec: 14.8914 2021-11-27 22:12:33,115 [INFO] tensorflow: global_step/sec: 14.8914 INFO:tensorflow:global_step/sec: 15.3056 2021-11-27 22:12:33,246 [INFO] tensorflow: global_step/sec: 15.3056 INFO:tensorflow:global_step/sec: 14.1316 2021-11-27 22:12:33,387 [INFO] tensorflow: global_step/sec: 14.1316 2021-11-27 22:12:33,389 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 65/120: loss: 0.00073 learning rate: 0.00050 Time taken: 0:00:01.467547 ETA: 0:01:20.715108 INFO:tensorflow:global_step/sec: 15.1364 2021-11-27 22:12:33,520 [INFO] tensorflow: global_step/sec: 15.1364 INFO:tensorflow:global_step/sec: 15.2039 2021-11-27 22:12:33,651 [INFO] tensorflow: global_step/sec: 15.2039 INFO:tensorflow:global_step/sec: 14.9706 2021-11-27 22:12:33,785 [INFO] tensorflow: global_step/sec: 14.9706 INFO:tensorflow:global_step/sec: 15.3865 2021-11-27 22:12:33,915 [INFO] tensorflow: global_step/sec: 15.3865 INFO:tensorflow:global_step/sec: 14.5854 2021-11-27 22:12:34,052 [INFO] tensorflow: global_step/sec: 14.5854 INFO:tensorflow:global_step/sec: 15.3522 2021-11-27 22:12:34,182 [INFO] tensorflow: global_step/sec: 15.3522 INFO:tensorflow:global_step/sec: 14.9313 2021-11-27 22:12:34,316 [INFO] tensorflow: global_step/sec: 14.9313 INFO:tensorflow:global_step/sec: 14.3697 2021-11-27 22:12:34,455 [INFO] tensorflow: global_step/sec: 14.3697 INFO:tensorflow:global_step/sec: 15.0508 2021-11-27 22:12:34,588 [INFO] tensorflow: global_step/sec: 15.0508 2021-11-27 22:12:34,654 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.797 INFO:tensorflow:global_step/sec: 14.5865 2021-11-27 22:12:34,725 [INFO] tensorflow: global_step/sec: 14.5865 INFO:tensorflow:global_step/sec: 13.3584 2021-11-27 22:12:34,875 [INFO] tensorflow: global_step/sec: 13.3584 2021-11-27 22:12:34,876 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 66/120: loss: 0.00079 learning rate: 0.00050 Time taken: 0:00:01.478570 ETA: 0:01:19.842766 INFO:tensorflow:global_step/sec: 13.9818 2021-11-27 22:12:35,018 [INFO] tensorflow: global_step/sec: 13.9818 INFO:tensorflow:global_step/sec: 14.2815 2021-11-27 22:12:35,158 [INFO] tensorflow: global_step/sec: 14.2815 INFO:tensorflow:global_step/sec: 14.1985 2021-11-27 22:12:35,299 [INFO] tensorflow: global_step/sec: 14.1985 INFO:tensorflow:global_step/sec: 14.4695 2021-11-27 22:12:35,437 [INFO] tensorflow: global_step/sec: 14.4695 INFO:tensorflow:global_step/sec: 14.5869 2021-11-27 22:12:35,574 [INFO] tensorflow: global_step/sec: 14.5869 INFO:tensorflow:global_step/sec: 15.5514 2021-11-27 22:12:35,703 [INFO] tensorflow: global_step/sec: 15.5514 INFO:tensorflow:global_step/sec: 14.9359 2021-11-27 22:12:35,837 [INFO] tensorflow: global_step/sec: 14.9359 INFO:tensorflow:global_step/sec: 14.7137 2021-11-27 22:12:35,973 [INFO] tensorflow: global_step/sec: 14.7137 INFO:tensorflow:global_step/sec: 13.9985 2021-11-27 22:12:36,116 [INFO] tensorflow: global_step/sec: 13.9985 INFO:tensorflow:global_step/sec: 14.7891 2021-11-27 22:12:36,251 [INFO] tensorflow: global_step/sec: 14.7891 INFO:tensorflow:epoch = 66.95454545454545, learning_rate = 0.00049999997, loss = 0.00080842694, step = 1473 (5.140 sec) 2021-11-27 22:12:36,324 [INFO] tensorflow: epoch = 66.95454545454545, learning_rate = 0.00049999997, loss = 0.00080842694, step = 1473 (5.140 sec) INFO:tensorflow:global_step/sec: 13.1274 2021-11-27 22:12:36,403 [INFO] tensorflow: global_step/sec: 13.1274 2021-11-27 22:12:36,404 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 67/120: loss: 0.00080 learning rate: 0.00050 Time taken: 0:00:01.529250 ETA: 0:01:21.050270 2021-11-27 22:12:36,404 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.154 INFO:tensorflow:global_step/sec: 14.5124 2021-11-27 22:12:36,541 [INFO] tensorflow: global_step/sec: 14.5124 INFO:tensorflow:global_step/sec: 14.2461 2021-11-27 22:12:36,681 [INFO] tensorflow: global_step/sec: 14.2461 INFO:tensorflow:global_step/sec: 14.9067 2021-11-27 22:12:36,815 [INFO] tensorflow: global_step/sec: 14.9067 INFO:tensorflow:global_step/sec: 15.1283 2021-11-27 22:12:36,948 [INFO] tensorflow: global_step/sec: 15.1283 INFO:tensorflow:global_step/sec: 14.5499 2021-11-27 22:12:37,085 [INFO] tensorflow: global_step/sec: 14.5499 INFO:tensorflow:global_step/sec: 15.0433 2021-11-27 22:12:37,218 [INFO] tensorflow: global_step/sec: 15.0433 INFO:tensorflow:global_step/sec: 14.5256 2021-11-27 22:12:37,356 [INFO] tensorflow: global_step/sec: 14.5256 INFO:tensorflow:global_step/sec: 14.9401 2021-11-27 22:12:37,490 [INFO] tensorflow: global_step/sec: 14.9401 INFO:tensorflow:global_step/sec: 15.3974 2021-11-27 22:12:37,620 [INFO] tensorflow: global_step/sec: 15.3974 INFO:tensorflow:global_step/sec: 15.0253 2021-11-27 22:12:37,753 [INFO] tensorflow: global_step/sec: 15.0253 INFO:tensorflow:global_step/sec: 14.207 2021-11-27 22:12:37,893 [INFO] tensorflow: global_step/sec: 14.207 2021-11-27 22:12:37,894 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 68/120: loss: 0.00086 learning rate: 0.00050 Time taken: 0:00:01.492450 ETA: 0:01:17.607400 INFO:tensorflow:global_step/sec: 15.0805 2021-11-27 22:12:38,026 [INFO] tensorflow: global_step/sec: 15.0805 2021-11-27 22:12:38,091 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.274 INFO:tensorflow:global_step/sec: 15.1857 2021-11-27 22:12:38,158 [INFO] tensorflow: global_step/sec: 15.1857 INFO:tensorflow:global_step/sec: 15.3878 2021-11-27 22:12:38,288 [INFO] tensorflow: global_step/sec: 15.3878 INFO:tensorflow:global_step/sec: 14.888 2021-11-27 22:12:38,422 [INFO] tensorflow: global_step/sec: 14.888 INFO:tensorflow:global_step/sec: 15.1366 2021-11-27 22:12:38,554 [INFO] tensorflow: global_step/sec: 15.1366 INFO:tensorflow:global_step/sec: 15.2477 2021-11-27 22:12:38,685 [INFO] tensorflow: global_step/sec: 15.2477 INFO:tensorflow:global_step/sec: 15.2033 2021-11-27 22:12:38,817 [INFO] tensorflow: global_step/sec: 15.2033 INFO:tensorflow:global_step/sec: 14.7444 2021-11-27 22:12:38,953 [INFO] tensorflow: global_step/sec: 14.7444 INFO:tensorflow:global_step/sec: 14.6964 2021-11-27 22:12:39,089 [INFO] tensorflow: global_step/sec: 14.6964 INFO:tensorflow:global_step/sec: 15.021 2021-11-27 22:12:39,222 [INFO] tensorflow: global_step/sec: 15.021 INFO:tensorflow:global_step/sec: 14.5311 2021-11-27 22:12:39,359 [INFO] tensorflow: global_step/sec: 14.5311 2021-11-27 22:12:39,360 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 69/120: loss: 0.00078 learning rate: 0.00050 Time taken: 0:00:01.466060 ETA: 0:01:14.769044 INFO:tensorflow:global_step/sec: 14.9926 2021-11-27 22:12:39,493 [INFO] tensorflow: global_step/sec: 14.9926 INFO:tensorflow:global_step/sec: 14.228 2021-11-27 22:12:39,633 [INFO] tensorflow: global_step/sec: 14.228 INFO:tensorflow:global_step/sec: 14.8496 2021-11-27 22:12:39,768 [INFO] tensorflow: global_step/sec: 14.8496 2021-11-27 22:12:39,768 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.638 INFO:tensorflow:global_step/sec: 14.7667 2021-11-27 22:12:39,903 [INFO] tensorflow: global_step/sec: 14.7667 INFO:tensorflow:global_step/sec: 14.8912 2021-11-27 22:12:40,038 [INFO] tensorflow: global_step/sec: 14.8912 INFO:tensorflow:global_step/sec: 14.6907 2021-11-27 22:12:40,174 [INFO] tensorflow: global_step/sec: 14.6907 INFO:tensorflow:global_step/sec: 15.0516 2021-11-27 22:12:40,307 [INFO] tensorflow: global_step/sec: 15.0516 INFO:tensorflow:global_step/sec: 15.2418 2021-11-27 22:12:40,438 [INFO] tensorflow: global_step/sec: 15.2418 INFO:tensorflow:global_step/sec: 14.1835 2021-11-27 22:12:40,579 [INFO] tensorflow: global_step/sec: 14.1835 INFO:tensorflow:global_step/sec: 14.4201 2021-11-27 22:12:40,718 [INFO] tensorflow: global_step/sec: 14.4201 INFO:tensorflow:Saving checkpoints for step-1540. 2021-11-27 22:12:40,786 [INFO] tensorflow: Saving checkpoints for step-1540. WARNING:tensorflow:Ignoring: /tmp/tmpl5e3bt52; No such file or directory 2021-11-27 22:12:40,875 [WARNING] tensorflow: Ignoring: /tmp/tmpl5e3bt52; No such file or directory 2021-11-27 22:12:43,090 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 1109/1109 [00:00<00:00, 24772.77it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 132/132 [00:00<00:00, 24423.14it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 358/358 [00:00<00:00, 25020.59it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 1027/1027 [00:00<00:00, 25286.32it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 372/372 [00:00<00:00, 24498.05it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 920/920 [00:00<00:00, 24068.96it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 2308/2308 [00:00<00:00, 35560.36it/s] Epoch 70/120 ========================= Validation cost: 0.000533 Mean average_precision (in %): 27.0035 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 53.7311 floor 0 palette 8.71212 pillar 54.5732 pushcart 0 rackframe 38.1974 rackshelf 49.1223 wall 38.6951 Median Inference Time: 0.007034 INFO:tensorflow:epoch = 70.0, learning_rate = 0.00049999997, loss = 0.0007588954, step = 1540 (9.764 sec) 2021-11-27 22:12:46,088 [INFO] tensorflow: epoch = 70.0, learning_rate = 0.00049999997, loss = 0.0007588954, step = 1540 (9.764 sec) INFO:tensorflow:global_step/sec: 0.372372 2021-11-27 22:12:46,089 [INFO] tensorflow: global_step/sec: 0.372372 2021-11-27 22:12:46,090 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 70/120: loss: 0.00076 learning rate: 0.00050 Time taken: 0:00:06.722126 ETA: 0:05:36.106277 INFO:tensorflow:global_step/sec: 13.6125 2021-11-27 22:12:46,236 [INFO] tensorflow: global_step/sec: 13.6125 INFO:tensorflow:global_step/sec: 14.2295 2021-11-27 22:12:46,376 [INFO] tensorflow: global_step/sec: 14.2295 INFO:tensorflow:global_step/sec: 13.8296 2021-11-27 22:12:46,521 [INFO] tensorflow: global_step/sec: 13.8296 INFO:tensorflow:global_step/sec: 14.6712 2021-11-27 22:12:46,657 [INFO] tensorflow: global_step/sec: 14.6712 2021-11-27 22:12:46,721 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 14.384 INFO:tensorflow:global_step/sec: 15.1416 2021-11-27 22:12:46,789 [INFO] tensorflow: global_step/sec: 15.1416 INFO:tensorflow:global_step/sec: 15.2101 2021-11-27 22:12:46,921 [INFO] tensorflow: global_step/sec: 15.2101 INFO:tensorflow:global_step/sec: 15.7213 2021-11-27 22:12:47,048 [INFO] tensorflow: global_step/sec: 15.7213 INFO:tensorflow:global_step/sec: 15.3027 2021-11-27 22:12:47,179 [INFO] tensorflow: global_step/sec: 15.3027 INFO:tensorflow:global_step/sec: 15.1458 2021-11-27 22:12:47,311 [INFO] tensorflow: global_step/sec: 15.1458 INFO:tensorflow:global_step/sec: 15.3902 2021-11-27 22:12:47,441 [INFO] tensorflow: global_step/sec: 15.3902 INFO:tensorflow:global_step/sec: 14.2352 2021-11-27 22:12:47,581 [INFO] tensorflow: global_step/sec: 14.2352 2021-11-27 22:12:47,582 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 71/120: loss: 0.00079 learning rate: 0.00050 Time taken: 0:00:01.495772 ETA: 0:01:13.292846 INFO:tensorflow:global_step/sec: 14.8002 2021-11-27 22:12:47,716 [INFO] tensorflow: global_step/sec: 14.8002 INFO:tensorflow:global_step/sec: 15.1268 2021-11-27 22:12:47,848 [INFO] tensorflow: global_step/sec: 15.1268 INFO:tensorflow:global_step/sec: 15.1706 2021-11-27 22:12:47,980 [INFO] tensorflow: global_step/sec: 15.1706 INFO:tensorflow:global_step/sec: 14.8205 2021-11-27 22:12:48,115 [INFO] tensorflow: global_step/sec: 14.8205 INFO:tensorflow:global_step/sec: 14.7806 2021-11-27 22:12:48,251 [INFO] tensorflow: global_step/sec: 14.7806 INFO:tensorflow:global_step/sec: 15.1353 2021-11-27 22:12:48,383 [INFO] tensorflow: global_step/sec: 15.1353 2021-11-27 22:12:48,383 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.158 INFO:tensorflow:global_step/sec: 14.6156 2021-11-27 22:12:48,520 [INFO] tensorflow: global_step/sec: 14.6156 INFO:tensorflow:global_step/sec: 14.6246 2021-11-27 22:12:48,656 [INFO] tensorflow: global_step/sec: 14.6246 INFO:tensorflow:global_step/sec: 14.8062 2021-11-27 22:12:48,791 [INFO] tensorflow: global_step/sec: 14.8062 INFO:tensorflow:global_step/sec: 15.1029 2021-11-27 22:12:48,924 [INFO] tensorflow: global_step/sec: 15.1029 INFO:tensorflow:global_step/sec: 13.8264 2021-11-27 22:12:49,068 [INFO] tensorflow: global_step/sec: 13.8264 2021-11-27 22:12:49,069 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 72/120: loss: 0.00075 learning rate: 0.00050 Time taken: 0:00:01.483009 ETA: 0:01:11.184437 INFO:tensorflow:global_step/sec: 15.0983 2021-11-27 22:12:49,201 [INFO] tensorflow: global_step/sec: 15.0983 INFO:tensorflow:global_step/sec: 14.7319 2021-11-27 22:12:49,337 [INFO] tensorflow: global_step/sec: 14.7319 INFO:tensorflow:global_step/sec: 14.1149 2021-11-27 22:12:49,478 [INFO] tensorflow: global_step/sec: 14.1149 INFO:tensorflow:global_step/sec: 14.9489 2021-11-27 22:12:49,612 [INFO] tensorflow: global_step/sec: 14.9489 INFO:tensorflow:global_step/sec: 15.3224 2021-11-27 22:12:49,743 [INFO] tensorflow: global_step/sec: 15.3224 INFO:tensorflow:global_step/sec: 15.118 2021-11-27 22:12:49,875 [INFO] tensorflow: global_step/sec: 15.118 INFO:tensorflow:global_step/sec: 15.4484 2021-11-27 22:12:50,004 [INFO] tensorflow: global_step/sec: 15.4484 2021-11-27 22:12:50,069 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.328 INFO:tensorflow:global_step/sec: 15.4375 2021-11-27 22:12:50,134 [INFO] tensorflow: global_step/sec: 15.4375 INFO:tensorflow:global_step/sec: 14.5934 2021-11-27 22:12:50,271 [INFO] tensorflow: global_step/sec: 14.5934 INFO:tensorflow:global_step/sec: 15.2868 2021-11-27 22:12:50,402 [INFO] tensorflow: global_step/sec: 15.2868 INFO:tensorflow:global_step/sec: 13.9608 2021-11-27 22:12:50,545 [INFO] tensorflow: global_step/sec: 13.9608 2021-11-27 22:12:50,546 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 73/120: loss: 0.00071 learning rate: 0.00050 Time taken: 0:00:01.473545 ETA: 0:01:09.256630 INFO:tensorflow:global_step/sec: 15.1236 2021-11-27 22:12:50,677 [INFO] tensorflow: global_step/sec: 15.1236 INFO:tensorflow:global_step/sec: 15.2885 2021-11-27 22:12:50,808 [INFO] tensorflow: global_step/sec: 15.2885 INFO:tensorflow:global_step/sec: 15.0971 2021-11-27 22:12:50,941 [INFO] tensorflow: global_step/sec: 15.0971 INFO:tensorflow:global_step/sec: 15.0934 2021-11-27 22:12:51,073 [INFO] tensorflow: global_step/sec: 15.0934 INFO:tensorflow:epoch = 73.45454545454545, learning_rate = 0.00049999997, loss = 0.0007004625, step = 1616 (5.115 sec) 2021-11-27 22:12:51,203 [INFO] tensorflow: epoch = 73.45454545454545, learning_rate = 0.00049999997, loss = 0.0007004625, step = 1616 (5.115 sec) INFO:tensorflow:global_step/sec: 15.3594 2021-11-27 22:12:51,203 [INFO] tensorflow: global_step/sec: 15.3594 INFO:tensorflow:global_step/sec: 15.0263 2021-11-27 22:12:51,336 [INFO] tensorflow: global_step/sec: 15.0263 INFO:tensorflow:global_step/sec: 15.0121 2021-11-27 22:12:51,470 [INFO] tensorflow: global_step/sec: 15.0121 INFO:tensorflow:global_step/sec: 15.2726 2021-11-27 22:12:51,601 [INFO] tensorflow: global_step/sec: 15.2726 INFO:tensorflow:global_step/sec: 15.1035 2021-11-27 22:12:51,733 [INFO] tensorflow: global_step/sec: 15.1035 2021-11-27 22:12:51,734 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.099 INFO:tensorflow:global_step/sec: 15.029 2021-11-27 22:12:51,866 [INFO] tensorflow: global_step/sec: 15.029 INFO:tensorflow:global_step/sec: 14.0965 2021-11-27 22:12:52,008 [INFO] tensorflow: global_step/sec: 14.0965 2021-11-27 22:12:52,009 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 74/120: loss: 0.00074 learning rate: 0.00050 Time taken: 0:00:01.464094 ETA: 0:01:07.348342 INFO:tensorflow:global_step/sec: 15.0669 2021-11-27 22:12:52,141 [INFO] tensorflow: global_step/sec: 15.0669 INFO:tensorflow:global_step/sec: 15.1088 2021-11-27 22:12:52,273 [INFO] tensorflow: global_step/sec: 15.1088 INFO:tensorflow:global_step/sec: 15.037 2021-11-27 22:12:52,406 [INFO] tensorflow: global_step/sec: 15.037 INFO:tensorflow:global_step/sec: 14.7934 2021-11-27 22:12:52,541 [INFO] tensorflow: global_step/sec: 14.7934 INFO:tensorflow:global_step/sec: 15.13 2021-11-27 22:12:52,674 [INFO] tensorflow: global_step/sec: 15.13 INFO:tensorflow:global_step/sec: 14.7019 2021-11-27 22:12:52,810 [INFO] tensorflow: global_step/sec: 14.7019 INFO:tensorflow:global_step/sec: 15.2613 2021-11-27 22:12:52,941 [INFO] tensorflow: global_step/sec: 15.2613 INFO:tensorflow:global_step/sec: 15.0271 2021-11-27 22:12:53,074 [INFO] tensorflow: global_step/sec: 15.0271 INFO:tensorflow:global_step/sec: 14.9261 2021-11-27 22:12:53,208 [INFO] tensorflow: global_step/sec: 14.9261 INFO:tensorflow:global_step/sec: 14.6805 2021-11-27 22:12:53,344 [INFO] tensorflow: global_step/sec: 14.6805 2021-11-27 22:12:53,414 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.513 INFO:tensorflow:global_step/sec: 14.3085 2021-11-27 22:12:53,484 [INFO] tensorflow: global_step/sec: 14.3085 2021-11-27 22:12:53,485 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 75/120: loss: 0.00078 learning rate: 0.00050 Time taken: 0:00:01.473139 ETA: 0:01:06.291268 INFO:tensorflow:global_step/sec: 14.863 2021-11-27 22:12:53,618 [INFO] tensorflow: global_step/sec: 14.863 INFO:tensorflow:global_step/sec: 14.9176 2021-11-27 22:12:53,752 [INFO] tensorflow: global_step/sec: 14.9176 INFO:tensorflow:global_step/sec: 14.5529 2021-11-27 22:12:53,890 [INFO] tensorflow: global_step/sec: 14.5529 INFO:tensorflow:global_step/sec: 14.3515 2021-11-27 22:12:54,029 [INFO] tensorflow: global_step/sec: 14.3515 INFO:tensorflow:global_step/sec: 15.4043 2021-11-27 22:12:54,159 [INFO] tensorflow: global_step/sec: 15.4043 INFO:tensorflow:global_step/sec: 15.8303 2021-11-27 22:12:54,285 [INFO] tensorflow: global_step/sec: 15.8303 INFO:tensorflow:global_step/sec: 14.8735 2021-11-27 22:12:54,420 [INFO] tensorflow: global_step/sec: 14.8735 INFO:tensorflow:global_step/sec: 14.9424 2021-11-27 22:12:54,554 [INFO] tensorflow: global_step/sec: 14.9424 INFO:tensorflow:global_step/sec: 14.9376 2021-11-27 22:12:54,688 [INFO] tensorflow: global_step/sec: 14.9376 INFO:tensorflow:global_step/sec: 15.5001 2021-11-27 22:12:54,817 [INFO] tensorflow: global_step/sec: 15.5001 INFO:tensorflow:global_step/sec: 14.1045 2021-11-27 22:12:54,958 [INFO] tensorflow: global_step/sec: 14.1045 2021-11-27 22:12:54,959 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 76/120: loss: 0.00081 learning rate: 0.00050 Time taken: 0:00:01.476994 ETA: 0:01:04.987717 INFO:tensorflow:global_step/sec: 15.2177 2021-11-27 22:12:55,090 [INFO] tensorflow: global_step/sec: 15.2177 2021-11-27 22:12:55,091 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.710 INFO:tensorflow:global_step/sec: 14.9719 2021-11-27 22:12:55,223 [INFO] tensorflow: global_step/sec: 14.9719 INFO:tensorflow:global_step/sec: 15.692 2021-11-27 22:12:55,351 [INFO] tensorflow: global_step/sec: 15.692 INFO:tensorflow:global_step/sec: 15.4475 2021-11-27 22:12:55,480 [INFO] tensorflow: global_step/sec: 15.4475 INFO:tensorflow:global_step/sec: 15.1329 2021-11-27 22:12:55,612 [INFO] tensorflow: global_step/sec: 15.1329 INFO:tensorflow:global_step/sec: 15.5349 2021-11-27 22:12:55,741 [INFO] tensorflow: global_step/sec: 15.5349 INFO:tensorflow:global_step/sec: 14.9617 2021-11-27 22:12:55,875 [INFO] tensorflow: global_step/sec: 14.9617 INFO:tensorflow:global_step/sec: 14.9667 2021-11-27 22:12:56,009 [INFO] tensorflow: global_step/sec: 14.9667 INFO:tensorflow:global_step/sec: 15.0135 2021-11-27 22:12:56,142 [INFO] tensorflow: global_step/sec: 15.0135 INFO:tensorflow:epoch = 76.9090909090909, learning_rate = 0.00049999997, loss = 0.00073854055, step = 1692 (5.075 sec) 2021-11-27 22:12:56,278 [INFO] tensorflow: epoch = 76.9090909090909, learning_rate = 0.00049999997, loss = 0.00073854055, step = 1692 (5.075 sec) INFO:tensorflow:global_step/sec: 14.5652 2021-11-27 22:12:56,279 [INFO] tensorflow: global_step/sec: 14.5652 INFO:tensorflow:global_step/sec: 13.5652 2021-11-27 22:12:56,426 [INFO] tensorflow: global_step/sec: 13.5652 2021-11-27 22:12:56,427 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 77/120: loss: 0.00073 learning rate: 0.00050 Time taken: 0:00:01.463050 ETA: 0:01:02.911166 INFO:tensorflow:global_step/sec: 14.4322 2021-11-27 22:12:56,565 [INFO] tensorflow: global_step/sec: 14.4322 INFO:tensorflow:global_step/sec: 14.93 2021-11-27 22:12:56,699 [INFO] tensorflow: global_step/sec: 14.93 2021-11-27 22:12:56,767 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.648 INFO:tensorflow:global_step/sec: 14.4709 2021-11-27 22:12:56,837 [INFO] tensorflow: global_step/sec: 14.4709 INFO:tensorflow:global_step/sec: 14.4396 2021-11-27 22:12:56,976 [INFO] tensorflow: global_step/sec: 14.4396 INFO:tensorflow:global_step/sec: 13.8835 2021-11-27 22:12:57,120 [INFO] tensorflow: global_step/sec: 13.8835 INFO:tensorflow:global_step/sec: 14.6914 2021-11-27 22:12:57,256 [INFO] tensorflow: global_step/sec: 14.6914 INFO:tensorflow:global_step/sec: 15.1329 2021-11-27 22:12:57,388 [INFO] tensorflow: global_step/sec: 15.1329 INFO:tensorflow:global_step/sec: 14.889 2021-11-27 22:12:57,522 [INFO] tensorflow: global_step/sec: 14.889 INFO:tensorflow:global_step/sec: 14.6504 2021-11-27 22:12:57,659 [INFO] tensorflow: global_step/sec: 14.6504 INFO:tensorflow:global_step/sec: 14.7089 2021-11-27 22:12:57,795 [INFO] tensorflow: global_step/sec: 14.7089 INFO:tensorflow:global_step/sec: 13.3885 2021-11-27 22:12:57,944 [INFO] tensorflow: global_step/sec: 13.3885 2021-11-27 22:12:57,946 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 78/120: loss: 0.00071 learning rate: 0.00050 Time taken: 0:00:01.512005 ETA: 0:01:03.504214 INFO:tensorflow:global_step/sec: 14.6969 2021-11-27 22:12:58,080 [INFO] tensorflow: global_step/sec: 14.6969 INFO:tensorflow:global_step/sec: 14.5369 2021-11-27 22:12:58,218 [INFO] tensorflow: global_step/sec: 14.5369 INFO:tensorflow:global_step/sec: 15.6171 2021-11-27 22:12:58,346 [INFO] tensorflow: global_step/sec: 15.6171 INFO:tensorflow:global_step/sec: 15.2686 2021-11-27 22:12:58,477 [INFO] tensorflow: global_step/sec: 15.2686 2021-11-27 22:12:58,477 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.488 INFO:tensorflow:global_step/sec: 15.3921 2021-11-27 22:12:58,607 [INFO] tensorflow: global_step/sec: 15.3921 INFO:tensorflow:global_step/sec: 14.4972 2021-11-27 22:12:58,745 [INFO] tensorflow: global_step/sec: 14.4972 INFO:tensorflow:global_step/sec: 15.0587 2021-11-27 22:12:58,878 [INFO] tensorflow: global_step/sec: 15.0587 INFO:tensorflow:global_step/sec: 15.1277 2021-11-27 22:12:59,010 [INFO] tensorflow: global_step/sec: 15.1277 INFO:tensorflow:global_step/sec: 14.8894 2021-11-27 22:12:59,144 [INFO] tensorflow: global_step/sec: 14.8894 INFO:tensorflow:global_step/sec: 14.5121 2021-11-27 22:12:59,282 [INFO] tensorflow: global_step/sec: 14.5121 INFO:tensorflow:global_step/sec: 13.2763 2021-11-27 22:12:59,433 [INFO] tensorflow: global_step/sec: 13.2763 2021-11-27 22:12:59,434 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 79/120: loss: 0.00065 learning rate: 0.00050 Time taken: 0:00:01.486251 ETA: 0:01:00.936286 INFO:tensorflow:global_step/sec: 14.3228 2021-11-27 22:12:59,572 [INFO] tensorflow: global_step/sec: 14.3228 INFO:tensorflow:global_step/sec: 14.1395 2021-11-27 22:12:59,714 [INFO] tensorflow: global_step/sec: 14.1395 INFO:tensorflow:global_step/sec: 14.7495 2021-11-27 22:12:59,849 [INFO] tensorflow: global_step/sec: 14.7495 INFO:tensorflow:global_step/sec: 15.0211 2021-11-27 22:12:59,982 [INFO] tensorflow: global_step/sec: 15.0211 INFO:tensorflow:global_step/sec: 15.1254 2021-11-27 22:13:00,115 [INFO] tensorflow: global_step/sec: 15.1254 2021-11-27 22:13:00,181 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.716 INFO:tensorflow:global_step/sec: 15.3276 2021-11-27 22:13:00,245 [INFO] tensorflow: global_step/sec: 15.3276 INFO:tensorflow:global_step/sec: 14.6185 2021-11-27 22:13:00,382 [INFO] tensorflow: global_step/sec: 14.6185 INFO:tensorflow:global_step/sec: 14.8032 2021-11-27 22:13:00,517 [INFO] tensorflow: global_step/sec: 14.8032 INFO:tensorflow:global_step/sec: 14.9164 2021-11-27 22:13:00,651 [INFO] tensorflow: global_step/sec: 14.9164 INFO:tensorflow:global_step/sec: 15.7042 2021-11-27 22:13:00,779 [INFO] tensorflow: global_step/sec: 15.7042 INFO:tensorflow:Saving checkpoints for step-1760. 2021-11-27 22:13:00,845 [INFO] tensorflow: Saving checkpoints for step-1760. WARNING:tensorflow:Ignoring: /tmp/tmpw88zljs7; No such file or directory 2021-11-27 22:13:00,934 [WARNING] tensorflow: Ignoring: /tmp/tmpw88zljs7; No such file or directory 2021-11-27 22:13:03,176 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 825/825 [00:00<00:00, 24141.18it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 51/51 [00:00<00:00, 22834.06it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 169/169 [00:00<00:00, 24357.00it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 891/891 [00:00<00:00, 25336.44it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 492/492 [00:00<00:00, 23677.60it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 839/839 [00:00<00:00, 23788.74it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 2452/2452 [00:00<00:00, 36299.84it/s] Epoch 80/120 ========================= Validation cost: 0.000479 Mean average_precision (in %): 28.1822 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 60.6922 floor 0 palette 10.7372 pillar 44.2346 pushcart 0 rackframe 46.2873 rackshelf 58.7035 wall 32.9852 Median Inference Time: 0.007864 INFO:tensorflow:epoch = 80.0, learning_rate = 0.00049999997, loss = 0.0006499792, step = 1760 (9.147 sec) 2021-11-27 22:13:05,426 [INFO] tensorflow: epoch = 80.0, learning_rate = 0.00049999997, loss = 0.0006499792, step = 1760 (9.147 sec) INFO:tensorflow:global_step/sec: 0.430287 2021-11-27 22:13:05,427 [INFO] tensorflow: global_step/sec: 0.430287 2021-11-27 22:13:05,428 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 80/120: loss: 0.00065 learning rate: 0.00050 Time taken: 0:00:05.998800 ETA: 0:03:59.952011 INFO:tensorflow:global_step/sec: 13.6292 2021-11-27 22:13:05,573 [INFO] tensorflow: global_step/sec: 13.6292 INFO:tensorflow:global_step/sec: 14.7563 2021-11-27 22:13:05,709 [INFO] tensorflow: global_step/sec: 14.7563 INFO:tensorflow:global_step/sec: 15.0554 2021-11-27 22:13:05,842 [INFO] tensorflow: global_step/sec: 15.0554 INFO:tensorflow:global_step/sec: 15.3417 2021-11-27 22:13:05,972 [INFO] tensorflow: global_step/sec: 15.3417 INFO:tensorflow:global_step/sec: 14.3697 2021-11-27 22:13:06,111 [INFO] tensorflow: global_step/sec: 14.3697 INFO:tensorflow:global_step/sec: 14.4241 2021-11-27 22:13:06,250 [INFO] tensorflow: global_step/sec: 14.4241 INFO:tensorflow:global_step/sec: 14.628 2021-11-27 22:13:06,387 [INFO] tensorflow: global_step/sec: 14.628 2021-11-27 22:13:06,387 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 16.113 INFO:tensorflow:global_step/sec: 15.359 2021-11-27 22:13:06,517 [INFO] tensorflow: global_step/sec: 15.359 INFO:tensorflow:global_step/sec: 15.3121 2021-11-27 22:13:06,648 [INFO] tensorflow: global_step/sec: 15.3121 INFO:tensorflow:global_step/sec: 15.4831 2021-11-27 22:13:06,777 [INFO] tensorflow: global_step/sec: 15.4831 INFO:tensorflow:global_step/sec: 14.493 2021-11-27 22:13:06,915 [INFO] tensorflow: global_step/sec: 14.493 2021-11-27 22:13:06,916 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 81/120: loss: 0.00074 learning rate: 0.00050 Time taken: 0:00:01.486891 ETA: 0:00:57.988750 INFO:tensorflow:global_step/sec: 14.831 2021-11-27 22:13:07,050 [INFO] tensorflow: global_step/sec: 14.831 INFO:tensorflow:global_step/sec: 15.5973 2021-11-27 22:13:07,178 [INFO] tensorflow: global_step/sec: 15.5973 INFO:tensorflow:global_step/sec: 14.683 2021-11-27 22:13:07,314 [INFO] tensorflow: global_step/sec: 14.683 INFO:tensorflow:global_step/sec: 15.1998 2021-11-27 22:13:07,446 [INFO] tensorflow: global_step/sec: 15.1998 INFO:tensorflow:global_step/sec: 14.3385 2021-11-27 22:13:07,585 [INFO] tensorflow: global_step/sec: 14.3385 INFO:tensorflow:global_step/sec: 15.29 2021-11-27 22:13:07,716 [INFO] tensorflow: global_step/sec: 15.29 INFO:tensorflow:global_step/sec: 15.4708 2021-11-27 22:13:07,845 [INFO] tensorflow: global_step/sec: 15.4708 INFO:tensorflow:global_step/sec: 14.6313 2021-11-27 22:13:07,982 [INFO] tensorflow: global_step/sec: 14.6313 2021-11-27 22:13:08,047 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 60.265 INFO:tensorflow:global_step/sec: 15.5324 2021-11-27 22:13:08,111 [INFO] tensorflow: global_step/sec: 15.5324 INFO:tensorflow:global_step/sec: 14.8359 2021-11-27 22:13:08,245 [INFO] tensorflow: global_step/sec: 14.8359 INFO:tensorflow:global_step/sec: 14.3576 2021-11-27 22:13:08,385 [INFO] tensorflow: global_step/sec: 14.3576 2021-11-27 22:13:08,386 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 82/120: loss: 0.00061 learning rate: 0.00050 Time taken: 0:00:01.465412 ETA: 0:00:55.685661 INFO:tensorflow:global_step/sec: 14.5825 2021-11-27 22:13:08,522 [INFO] tensorflow: global_step/sec: 14.5825 INFO:tensorflow:global_step/sec: 14.6026 2021-11-27 22:13:08,659 [INFO] tensorflow: global_step/sec: 14.6026 INFO:tensorflow:global_step/sec: 14.7815 2021-11-27 22:13:08,794 [INFO] tensorflow: global_step/sec: 14.7815 INFO:tensorflow:global_step/sec: 14.7293 2021-11-27 22:13:08,930 [INFO] tensorflow: global_step/sec: 14.7293 INFO:tensorflow:global_step/sec: 15.1709 2021-11-27 22:13:09,062 [INFO] tensorflow: global_step/sec: 15.1709 INFO:tensorflow:global_step/sec: 15.4105 2021-11-27 22:13:09,192 [INFO] tensorflow: global_step/sec: 15.4105 INFO:tensorflow:global_step/sec: 14.616 2021-11-27 22:13:09,328 [INFO] tensorflow: global_step/sec: 14.616 INFO:tensorflow:global_step/sec: 14.1376 2021-11-27 22:13:09,470 [INFO] tensorflow: global_step/sec: 14.1376 INFO:tensorflow:global_step/sec: 13.8033 2021-11-27 22:13:09,615 [INFO] tensorflow: global_step/sec: 13.8033 INFO:tensorflow:global_step/sec: 13.8202 2021-11-27 22:13:09,759 [INFO] tensorflow: global_step/sec: 13.8202 2021-11-27 22:13:09,760 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.383 INFO:tensorflow:global_step/sec: 13.5034 2021-11-27 22:13:09,908 [INFO] tensorflow: global_step/sec: 13.5034 2021-11-27 22:13:09,909 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 83/120: loss: 0.00073 learning rate: 0.00050 Time taken: 0:00:01.522144 ETA: 0:00:56.319331 INFO:tensorflow:global_step/sec: 14.5834 2021-11-27 22:13:10,045 [INFO] tensorflow: global_step/sec: 14.5834 INFO:tensorflow:global_step/sec: 14.8498 2021-11-27 22:13:10,179 [INFO] tensorflow: global_step/sec: 14.8498 INFO:tensorflow:global_step/sec: 14.8563 2021-11-27 22:13:10,314 [INFO] tensorflow: global_step/sec: 14.8563 INFO:tensorflow:global_step/sec: 14.479 2021-11-27 22:13:10,452 [INFO] tensorflow: global_step/sec: 14.479 INFO:tensorflow:epoch = 83.4090909090909, learning_rate = 0.00049999997, loss = 0.0007822754, step = 1835 (5.093 sec) 2021-11-27 22:13:10,518 [INFO] tensorflow: epoch = 83.4090909090909, learning_rate = 0.00049999997, loss = 0.0007822754, step = 1835 (5.093 sec) INFO:tensorflow:global_step/sec: 15.0943 2021-11-27 22:13:10,585 [INFO] tensorflow: global_step/sec: 15.0943 INFO:tensorflow:global_step/sec: 15.1703 2021-11-27 22:13:10,716 [INFO] tensorflow: global_step/sec: 15.1703 INFO:tensorflow:global_step/sec: 14.9898 2021-11-27 22:13:10,850 [INFO] tensorflow: global_step/sec: 14.9898 INFO:tensorflow:global_step/sec: 15.4098 2021-11-27 22:13:10,980 [INFO] tensorflow: global_step/sec: 15.4098 INFO:tensorflow:global_step/sec: 15.1817 2021-11-27 22:13:11,111 [INFO] tensorflow: global_step/sec: 15.1817 INFO:tensorflow:global_step/sec: 15.337 2021-11-27 22:13:11,242 [INFO] tensorflow: global_step/sec: 15.337 INFO:tensorflow:global_step/sec: 14.1729 2021-11-27 22:13:11,383 [INFO] tensorflow: global_step/sec: 14.1729 2021-11-27 22:13:11,384 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 84/120: loss: 0.00072 learning rate: 0.00050 Time taken: 0:00:01.473306 ETA: 0:00:53.039022 2021-11-27 22:13:11,449 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.239 INFO:tensorflow:global_step/sec: 15.1327 2021-11-27 22:13:11,515 [INFO] tensorflow: global_step/sec: 15.1327 INFO:tensorflow:global_step/sec: 14.8292 2021-11-27 22:13:11,650 [INFO] tensorflow: global_step/sec: 14.8292 INFO:tensorflow:global_step/sec: 14.8591 2021-11-27 22:13:11,785 [INFO] tensorflow: global_step/sec: 14.8591 INFO:tensorflow:global_step/sec: 15.2282 2021-11-27 22:13:11,916 [INFO] tensorflow: global_step/sec: 15.2282 INFO:tensorflow:global_step/sec: 15.2467 2021-11-27 22:13:12,047 [INFO] tensorflow: global_step/sec: 15.2467 INFO:tensorflow:global_step/sec: 14.8331 2021-11-27 22:13:12,182 [INFO] tensorflow: global_step/sec: 14.8331 INFO:tensorflow:global_step/sec: 15.0929 2021-11-27 22:13:12,314 [INFO] tensorflow: global_step/sec: 15.0929 INFO:tensorflow:global_step/sec: 14.6942 2021-11-27 22:13:12,451 [INFO] tensorflow: global_step/sec: 14.6942 INFO:tensorflow:global_step/sec: 14.8106 2021-11-27 22:13:12,586 [INFO] tensorflow: global_step/sec: 14.8106 INFO:tensorflow:global_step/sec: 15.3081 2021-11-27 22:13:12,716 [INFO] tensorflow: global_step/sec: 15.3081 INFO:tensorflow:global_step/sec: 14.281 2021-11-27 22:13:12,856 [INFO] tensorflow: global_step/sec: 14.281 2021-11-27 22:13:12,857 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 85/120: loss: 0.00067 learning rate: 0.00044 Time taken: 0:00:01.474650 ETA: 0:00:51.612738 INFO:tensorflow:global_step/sec: 15.2563 2021-11-27 22:13:12,987 [INFO] tensorflow: global_step/sec: 15.2563 INFO:tensorflow:global_step/sec: 14.6811 2021-11-27 22:13:13,124 [INFO] tensorflow: global_step/sec: 14.6811 2021-11-27 22:13:13,124 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.688 INFO:tensorflow:global_step/sec: 15.064 2021-11-27 22:13:13,256 [INFO] tensorflow: global_step/sec: 15.064 INFO:tensorflow:global_step/sec: 14.7387 2021-11-27 22:13:13,392 [INFO] tensorflow: global_step/sec: 14.7387 INFO:tensorflow:global_step/sec: 14.9827 2021-11-27 22:13:13,526 [INFO] tensorflow: global_step/sec: 14.9827 INFO:tensorflow:global_step/sec: 14.8412 2021-11-27 22:13:13,660 [INFO] tensorflow: global_step/sec: 14.8412 INFO:tensorflow:global_step/sec: 15.2277 2021-11-27 22:13:13,792 [INFO] tensorflow: global_step/sec: 15.2277 INFO:tensorflow:global_step/sec: 14.9006 2021-11-27 22:13:13,926 [INFO] tensorflow: global_step/sec: 14.9006 INFO:tensorflow:global_step/sec: 15.5387 2021-11-27 22:13:14,055 [INFO] tensorflow: global_step/sec: 15.5387 INFO:tensorflow:global_step/sec: 15.5275 2021-11-27 22:13:14,183 [INFO] tensorflow: global_step/sec: 15.5275 INFO:tensorflow:global_step/sec: 14.1983 2021-11-27 22:13:14,324 [INFO] tensorflow: global_step/sec: 14.1983 2021-11-27 22:13:14,325 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 86/120: loss: 0.00070 learning rate: 0.00039 Time taken: 0:00:01.463946 ETA: 0:00:49.774151 INFO:tensorflow:global_step/sec: 14.7477 2021-11-27 22:13:14,460 [INFO] tensorflow: global_step/sec: 14.7477 INFO:tensorflow:global_step/sec: 14.7541 2021-11-27 22:13:14,595 [INFO] tensorflow: global_step/sec: 14.7541 INFO:tensorflow:global_step/sec: 15.3032 2021-11-27 22:13:14,726 [INFO] tensorflow: global_step/sec: 15.3032 2021-11-27 22:13:14,802 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.611 INFO:tensorflow:global_step/sec: 13.8856 2021-11-27 22:13:14,870 [INFO] tensorflow: global_step/sec: 13.8856 INFO:tensorflow:global_step/sec: 15.2284 2021-11-27 22:13:15,001 [INFO] tensorflow: global_step/sec: 15.2284 INFO:tensorflow:global_step/sec: 14.9008 2021-11-27 22:13:15,136 [INFO] tensorflow: global_step/sec: 14.9008 INFO:tensorflow:global_step/sec: 15.0425 2021-11-27 22:13:15,269 [INFO] tensorflow: global_step/sec: 15.0425 INFO:tensorflow:global_step/sec: 14.4612 2021-11-27 22:13:15,407 [INFO] tensorflow: global_step/sec: 14.4612 INFO:tensorflow:global_step/sec: 14.4209 2021-11-27 22:13:15,546 [INFO] tensorflow: global_step/sec: 14.4209 INFO:tensorflow:epoch = 86.86363636363636, learning_rate = 0.0003466404, loss = 0.00072251324, step = 1911 (5.096 sec) 2021-11-27 22:13:15,614 [INFO] tensorflow: epoch = 86.86363636363636, learning_rate = 0.0003466404, loss = 0.00072251324, step = 1911 (5.096 sec) INFO:tensorflow:global_step/sec: 14.8664 2021-11-27 22:13:15,680 [INFO] tensorflow: global_step/sec: 14.8664 INFO:tensorflow:global_step/sec: 14.5591 2021-11-27 22:13:15,818 [INFO] tensorflow: global_step/sec: 14.5591 2021-11-27 22:13:15,818 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 87/120: loss: 0.00060 learning rate: 0.00034 Time taken: 0:00:01.495117 ETA: 0:00:49.338851 INFO:tensorflow:global_step/sec: 15.1702 2021-11-27 22:13:15,949 [INFO] tensorflow: global_step/sec: 15.1702 INFO:tensorflow:global_step/sec: 15.3082 2021-11-27 22:13:16,080 [INFO] tensorflow: global_step/sec: 15.3082 INFO:tensorflow:global_step/sec: 15.122 2021-11-27 22:13:16,212 [INFO] tensorflow: global_step/sec: 15.122 INFO:tensorflow:global_step/sec: 14.8722 2021-11-27 22:13:16,347 [INFO] tensorflow: global_step/sec: 14.8722 INFO:tensorflow:global_step/sec: 14.4974 2021-11-27 22:13:16,485 [INFO] tensorflow: global_step/sec: 14.4974 2021-11-27 22:13:16,485 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.415 INFO:tensorflow:global_step/sec: 15.5415 2021-11-27 22:13:16,613 [INFO] tensorflow: global_step/sec: 15.5415 INFO:tensorflow:global_step/sec: 14.7761 2021-11-27 22:13:16,749 [INFO] tensorflow: global_step/sec: 14.7761 INFO:tensorflow:global_step/sec: 14.9693 2021-11-27 22:13:16,882 [INFO] tensorflow: global_step/sec: 14.9693 INFO:tensorflow:global_step/sec: 14.4355 2021-11-27 22:13:17,021 [INFO] tensorflow: global_step/sec: 14.4355 INFO:tensorflow:global_step/sec: 13.9816 2021-11-27 22:13:17,164 [INFO] tensorflow: global_step/sec: 13.9816 INFO:tensorflow:global_step/sec: 13.7595 2021-11-27 22:13:17,309 [INFO] tensorflow: global_step/sec: 13.7595 2021-11-27 22:13:17,310 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 88/120: loss: 0.00058 learning rate: 0.00030 Time taken: 0:00:01.484386 ETA: 0:00:47.500343 INFO:tensorflow:global_step/sec: 14.8488 2021-11-27 22:13:17,444 [INFO] tensorflow: global_step/sec: 14.8488 INFO:tensorflow:global_step/sec: 14.5991 2021-11-27 22:13:17,581 [INFO] tensorflow: global_step/sec: 14.5991 INFO:tensorflow:global_step/sec: 14.7755 2021-11-27 22:13:17,716 [INFO] tensorflow: global_step/sec: 14.7755 INFO:tensorflow:global_step/sec: 13.9732 2021-11-27 22:13:17,859 [INFO] tensorflow: global_step/sec: 13.9732 INFO:tensorflow:global_step/sec: 14.8747 2021-11-27 22:13:17,994 [INFO] tensorflow: global_step/sec: 14.8747 INFO:tensorflow:global_step/sec: 13.8057 2021-11-27 22:13:18,139 [INFO] tensorflow: global_step/sec: 13.8057 2021-11-27 22:13:18,210 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.990 INFO:tensorflow:global_step/sec: 14.0308 2021-11-27 22:13:18,281 [INFO] tensorflow: global_step/sec: 14.0308 INFO:tensorflow:global_step/sec: 15.0172 2021-11-27 22:13:18,415 [INFO] tensorflow: global_step/sec: 15.0172 INFO:tensorflow:global_step/sec: 15.2718 2021-11-27 22:13:18,545 [INFO] tensorflow: global_step/sec: 15.2718 INFO:tensorflow:global_step/sec: 15.2321 2021-11-27 22:13:18,677 [INFO] tensorflow: global_step/sec: 15.2321 INFO:tensorflow:global_step/sec: 14.558 2021-11-27 22:13:18,814 [INFO] tensorflow: global_step/sec: 14.558 2021-11-27 22:13:18,815 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 89/120: loss: 0.00062 learning rate: 0.00026 Time taken: 0:00:01.507442 ETA: 0:00:46.730717 INFO:tensorflow:global_step/sec: 14.9583 2021-11-27 22:13:18,948 [INFO] tensorflow: global_step/sec: 14.9583 INFO:tensorflow:global_step/sec: 14.9255 2021-11-27 22:13:19,082 [INFO] tensorflow: global_step/sec: 14.9255 INFO:tensorflow:global_step/sec: 15.2949 2021-11-27 22:13:19,213 [INFO] tensorflow: global_step/sec: 15.2949 INFO:tensorflow:global_step/sec: 15.0618 2021-11-27 22:13:19,345 [INFO] tensorflow: global_step/sec: 15.0618 INFO:tensorflow:global_step/sec: 14.7123 2021-11-27 22:13:19,481 [INFO] tensorflow: global_step/sec: 14.7123 INFO:tensorflow:global_step/sec: 14.8202 2021-11-27 22:13:19,616 [INFO] tensorflow: global_step/sec: 14.8202 INFO:tensorflow:global_step/sec: 14.734 2021-11-27 22:13:19,752 [INFO] tensorflow: global_step/sec: 14.734 INFO:tensorflow:global_step/sec: 14.7792 2021-11-27 22:13:19,887 [INFO] tensorflow: global_step/sec: 14.7792 2021-11-27 22:13:19,888 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.611 INFO:tensorflow:global_step/sec: 15.0663 2021-11-27 22:13:20,020 [INFO] tensorflow: global_step/sec: 15.0663 INFO:tensorflow:global_step/sec: 14.6455 2021-11-27 22:13:20,157 [INFO] tensorflow: global_step/sec: 14.6455 INFO:tensorflow:Saving checkpoints for step-1980. 2021-11-27 22:13:20,224 [INFO] tensorflow: Saving checkpoints for step-1980. WARNING:tensorflow:Ignoring: /tmp/tmp24snkaxz; No such file or directory 2021-11-27 22:13:20,313 [WARNING] tensorflow: Ignoring: /tmp/tmp24snkaxz; No such file or directory 2021-11-27 22:13:22,554 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 1036/1036 [00:00<00:00, 24695.37it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 54/54 [00:00<00:00, 23373.83it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 196/196 [00:00<00:00, 24721.34it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 718/718 [00:00<00:00, 25645.81it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 241/241 [00:00<00:00, 24213.17it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 736/736 [00:00<00:00, 23490.53it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 1605/1605 [00:00<00:00, 36985.59it/s] Epoch 90/120 ========================= Validation cost: 0.000422 Mean average_precision (in %): 28.8910 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 74.7346 floor 0 palette 7.65957 pillar 49.2648 pushcart 0 rackframe 44.7523 rackshelf 48.4322 wall 35.1759 Median Inference Time: 0.007415 INFO:tensorflow:epoch = 90.0, learning_rate = 0.00023207937, loss = 0.00057127076, step = 1980 (9.215 sec) 2021-11-27 22:13:24,830 [INFO] tensorflow: epoch = 90.0, learning_rate = 0.00023207937, loss = 0.00057127076, step = 1980 (9.215 sec) INFO:tensorflow:global_step/sec: 0.42791 2021-11-27 22:13:24,831 [INFO] tensorflow: global_step/sec: 0.42791 2021-11-27 22:13:24,831 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 90/120: loss: 0.00057 learning rate: 0.00023 Time taken: 0:00:06.009696 ETA: 0:03:00.290895 INFO:tensorflow:global_step/sec: 14.9932 2021-11-27 22:13:24,964 [INFO] tensorflow: global_step/sec: 14.9932 INFO:tensorflow:global_step/sec: 15.0883 2021-11-27 22:13:25,097 [INFO] tensorflow: global_step/sec: 15.0883 INFO:tensorflow:global_step/sec: 14.7956 2021-11-27 22:13:25,232 [INFO] tensorflow: global_step/sec: 14.7956 INFO:tensorflow:global_step/sec: 15.2936 2021-11-27 22:13:25,362 [INFO] tensorflow: global_step/sec: 15.2936 INFO:tensorflow:global_step/sec: 15.1085 2021-11-27 22:13:25,495 [INFO] tensorflow: global_step/sec: 15.1085 INFO:tensorflow:global_step/sec: 15.2844 2021-11-27 22:13:25,626 [INFO] tensorflow: global_step/sec: 15.2844 INFO:tensorflow:global_step/sec: 15.1568 2021-11-27 22:13:25,758 [INFO] tensorflow: global_step/sec: 15.1568 INFO:tensorflow:global_step/sec: 14.877 2021-11-27 22:13:25,892 [INFO] tensorflow: global_step/sec: 14.877 INFO:tensorflow:global_step/sec: 15.1688 2021-11-27 22:13:26,024 [INFO] tensorflow: global_step/sec: 15.1688 2021-11-27 22:13:26,090 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 16.126 INFO:tensorflow:global_step/sec: 15.3013 2021-11-27 22:13:26,155 [INFO] tensorflow: global_step/sec: 15.3013 INFO:tensorflow:global_step/sec: 14.3635 2021-11-27 22:13:26,294 [INFO] tensorflow: global_step/sec: 14.3635 2021-11-27 22:13:26,295 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 91/120: loss: 0.00055 learning rate: 0.00020 Time taken: 0:00:01.468175 ETA: 0:00:42.577087 INFO:tensorflow:global_step/sec: 14.735 2021-11-27 22:13:26,430 [INFO] tensorflow: global_step/sec: 14.735 INFO:tensorflow:global_step/sec: 15.2105 2021-11-27 22:13:26,561 [INFO] tensorflow: global_step/sec: 15.2105 INFO:tensorflow:global_step/sec: 14.5592 2021-11-27 22:13:26,698 [INFO] tensorflow: global_step/sec: 14.5592 INFO:tensorflow:global_step/sec: 15.1098 2021-11-27 22:13:26,831 [INFO] tensorflow: global_step/sec: 15.1098 INFO:tensorflow:global_step/sec: 14.5534 2021-11-27 22:13:26,968 [INFO] tensorflow: global_step/sec: 14.5534 INFO:tensorflow:global_step/sec: 15.0356 2021-11-27 22:13:27,101 [INFO] tensorflow: global_step/sec: 15.0356 INFO:tensorflow:global_step/sec: 14.7363 2021-11-27 22:13:27,237 [INFO] tensorflow: global_step/sec: 14.7363 INFO:tensorflow:global_step/sec: 15.3127 2021-11-27 22:13:27,368 [INFO] tensorflow: global_step/sec: 15.3127 INFO:tensorflow:global_step/sec: 15.0626 2021-11-27 22:13:27,500 [INFO] tensorflow: global_step/sec: 15.0626 INFO:tensorflow:global_step/sec: 14.9401 2021-11-27 22:13:27,634 [INFO] tensorflow: global_step/sec: 14.9401 INFO:tensorflow:global_step/sec: 13.7332 2021-11-27 22:13:27,780 [INFO] tensorflow: global_step/sec: 13.7332 2021-11-27 22:13:27,781 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 92/120: loss: 0.00068 learning rate: 0.00018 Time taken: 0:00:01.481202 ETA: 0:00:41.473666 2021-11-27 22:13:27,781 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.136 INFO:tensorflow:global_step/sec: 14.8315 2021-11-27 22:13:27,915 [INFO] tensorflow: global_step/sec: 14.8315 INFO:tensorflow:global_step/sec: 15.0609 2021-11-27 22:13:28,047 [INFO] tensorflow: global_step/sec: 15.0609 INFO:tensorflow:global_step/sec: 14.6548 2021-11-27 22:13:28,184 [INFO] tensorflow: global_step/sec: 14.6548 INFO:tensorflow:global_step/sec: 15.0389 2021-11-27 22:13:28,317 [INFO] tensorflow: global_step/sec: 15.0389 INFO:tensorflow:global_step/sec: 14.84 2021-11-27 22:13:28,452 [INFO] tensorflow: global_step/sec: 14.84 INFO:tensorflow:global_step/sec: 14.8077 2021-11-27 22:13:28,587 [INFO] tensorflow: global_step/sec: 14.8077 INFO:tensorflow:global_step/sec: 14.7013 2021-11-27 22:13:28,723 [INFO] tensorflow: global_step/sec: 14.7013 INFO:tensorflow:global_step/sec: 13.8526 2021-11-27 22:13:28,867 [INFO] tensorflow: global_step/sec: 13.8526 INFO:tensorflow:global_step/sec: 14.5947 2021-11-27 22:13:29,004 [INFO] tensorflow: global_step/sec: 14.5947 INFO:tensorflow:global_step/sec: 15.115 2021-11-27 22:13:29,137 [INFO] tensorflow: global_step/sec: 15.115 INFO:tensorflow:global_step/sec: 14.7715 2021-11-27 22:13:29,272 [INFO] tensorflow: global_step/sec: 14.7715 2021-11-27 22:13:29,273 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 93/120: loss: 0.00057 learning rate: 0.00016 Time taken: 0:00:01.496615 ETA: 0:00:40.408597 INFO:tensorflow:global_step/sec: 15.0622 2021-11-27 22:13:29,405 [INFO] tensorflow: global_step/sec: 15.0622 2021-11-27 22:13:29,470 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.223 INFO:tensorflow:global_step/sec: 15.4088 2021-11-27 22:13:29,535 [INFO] tensorflow: global_step/sec: 15.4088 INFO:tensorflow:global_step/sec: 14.9831 2021-11-27 22:13:29,668 [INFO] tensorflow: global_step/sec: 14.9831 INFO:tensorflow:global_step/sec: 14.4544 2021-11-27 22:13:29,806 [INFO] tensorflow: global_step/sec: 14.4544 INFO:tensorflow:epoch = 93.45454545454545, learning_rate = 0.0001491824, loss = 0.000626393, step = 2056 (5.117 sec) 2021-11-27 22:13:29,946 [INFO] tensorflow: epoch = 93.45454545454545, learning_rate = 0.0001491824, loss = 0.000626393, step = 2056 (5.117 sec) INFO:tensorflow:global_step/sec: 14.2034 2021-11-27 22:13:29,947 [INFO] tensorflow: global_step/sec: 14.2034 INFO:tensorflow:global_step/sec: 14.5378 2021-11-27 22:13:30,085 [INFO] tensorflow: global_step/sec: 14.5378 INFO:tensorflow:global_step/sec: 15.1569 2021-11-27 22:13:30,217 [INFO] tensorflow: global_step/sec: 15.1569 INFO:tensorflow:global_step/sec: 14.9863 2021-11-27 22:13:30,350 [INFO] tensorflow: global_step/sec: 14.9863 INFO:tensorflow:global_step/sec: 14.8413 2021-11-27 22:13:30,485 [INFO] tensorflow: global_step/sec: 14.8413 INFO:tensorflow:global_step/sec: 14.9437 2021-11-27 22:13:30,619 [INFO] tensorflow: global_step/sec: 14.9437 INFO:tensorflow:global_step/sec: 13.8728 2021-11-27 22:13:30,763 [INFO] tensorflow: global_step/sec: 13.8728 2021-11-27 22:13:30,764 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 94/120: loss: 0.00062 learning rate: 0.00014 Time taken: 0:00:01.484202 ETA: 0:00:38.589250 INFO:tensorflow:global_step/sec: 14.9684 2021-11-27 22:13:30,897 [INFO] tensorflow: global_step/sec: 14.9684 INFO:tensorflow:global_step/sec: 14.8754 2021-11-27 22:13:31,031 [INFO] tensorflow: global_step/sec: 14.8754 INFO:tensorflow:global_step/sec: 14.8074 2021-11-27 22:13:31,166 [INFO] tensorflow: global_step/sec: 14.8074 2021-11-27 22:13:31,167 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.931 INFO:tensorflow:global_step/sec: 14.8315 2021-11-27 22:13:31,301 [INFO] tensorflow: global_step/sec: 14.8315 INFO:tensorflow:global_step/sec: 15.0223 2021-11-27 22:13:31,434 [INFO] tensorflow: global_step/sec: 15.0223 INFO:tensorflow:global_step/sec: 14.7531 2021-11-27 22:13:31,570 [INFO] tensorflow: global_step/sec: 14.7531 INFO:tensorflow:global_step/sec: 15.318 2021-11-27 22:13:31,700 [INFO] tensorflow: global_step/sec: 15.318 INFO:tensorflow:global_step/sec: 15.0131 2021-11-27 22:13:31,833 [INFO] tensorflow: global_step/sec: 15.0131 INFO:tensorflow:global_step/sec: 15.0069 2021-11-27 22:13:31,967 [INFO] tensorflow: global_step/sec: 15.0069 INFO:tensorflow:global_step/sec: 14.8463 2021-11-27 22:13:32,101 [INFO] tensorflow: global_step/sec: 14.8463 INFO:tensorflow:global_step/sec: 14.4051 2021-11-27 22:13:32,240 [INFO] tensorflow: global_step/sec: 14.4051 2021-11-27 22:13:32,241 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 95/120: loss: 0.00062 learning rate: 0.00012 Time taken: 0:00:01.478175 ETA: 0:00:36.954379 INFO:tensorflow:global_step/sec: 14.7962 2021-11-27 22:13:32,375 [INFO] tensorflow: global_step/sec: 14.7962 INFO:tensorflow:global_step/sec: 15.0096 2021-11-27 22:13:32,509 [INFO] tensorflow: global_step/sec: 15.0096 INFO:tensorflow:global_step/sec: 14.8786 2021-11-27 22:13:32,643 [INFO] tensorflow: global_step/sec: 14.8786 INFO:tensorflow:global_step/sec: 15.0628 2021-11-27 22:13:32,776 [INFO] tensorflow: global_step/sec: 15.0628 2021-11-27 22:13:32,840 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.771 INFO:tensorflow:global_step/sec: 15.1816 2021-11-27 22:13:32,908 [INFO] tensorflow: global_step/sec: 15.1816 INFO:tensorflow:global_step/sec: 14.8557 2021-11-27 22:13:33,042 [INFO] tensorflow: global_step/sec: 14.8557 INFO:tensorflow:global_step/sec: 15.4076 2021-11-27 22:13:33,172 [INFO] tensorflow: global_step/sec: 15.4076 INFO:tensorflow:global_step/sec: 15.1708 2021-11-27 22:13:33,304 [INFO] tensorflow: global_step/sec: 15.1708 INFO:tensorflow:global_step/sec: 14.6008 2021-11-27 22:13:33,441 [INFO] tensorflow: global_step/sec: 14.6008 INFO:tensorflow:global_step/sec: 15.1131 2021-11-27 22:13:33,573 [INFO] tensorflow: global_step/sec: 15.1131 INFO:tensorflow:global_step/sec: 14.3264 2021-11-27 22:13:33,713 [INFO] tensorflow: global_step/sec: 14.3264 2021-11-27 22:13:33,714 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 96/120: loss: 0.00058 learning rate: 0.00011 Time taken: 0:00:01.468922 ETA: 0:00:35.254131 INFO:tensorflow:global_step/sec: 15.2513 2021-11-27 22:13:33,844 [INFO] tensorflow: global_step/sec: 15.2513 INFO:tensorflow:global_step/sec: 15.003 2021-11-27 22:13:33,977 [INFO] tensorflow: global_step/sec: 15.003 INFO:tensorflow:global_step/sec: 15.0827 2021-11-27 22:13:34,110 [INFO] tensorflow: global_step/sec: 15.0827 INFO:tensorflow:global_step/sec: 15.1125 2021-11-27 22:13:34,242 [INFO] tensorflow: global_step/sec: 15.1125 INFO:tensorflow:global_step/sec: 13.9267 2021-11-27 22:13:34,386 [INFO] tensorflow: global_step/sec: 13.9267 INFO:tensorflow:global_step/sec: 14.2696 2021-11-27 22:13:34,526 [INFO] tensorflow: global_step/sec: 14.2696 2021-11-27 22:13:34,527 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.309 INFO:tensorflow:global_step/sec: 13.3772 2021-11-27 22:13:34,675 [INFO] tensorflow: global_step/sec: 13.3772 INFO:tensorflow:global_step/sec: 14.9418 2021-11-27 22:13:34,809 [INFO] tensorflow: global_step/sec: 14.9418 INFO:tensorflow:global_step/sec: 14.7551 2021-11-27 22:13:34,945 [INFO] tensorflow: global_step/sec: 14.7551 INFO:tensorflow:epoch = 96.9090909090909, learning_rate = 9.589558e-05, loss = 0.0005523006, step = 2132 (5.134 sec) 2021-11-27 22:13:35,080 [INFO] tensorflow: epoch = 96.9090909090909, learning_rate = 9.589558e-05, loss = 0.0005523006, step = 2132 (5.134 sec) INFO:tensorflow:global_step/sec: 14.711 2021-11-27 22:13:35,081 [INFO] tensorflow: global_step/sec: 14.711 INFO:tensorflow:global_step/sec: 12.8561 2021-11-27 22:13:35,236 [INFO] tensorflow: global_step/sec: 12.8561 2021-11-27 22:13:35,237 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 97/120: loss: 0.00057 learning rate: 0.00009 Time taken: 0:00:01.510840 ETA: 0:00:34.749319 INFO:tensorflow:global_step/sec: 13.9675 2021-11-27 22:13:35,380 [INFO] tensorflow: global_step/sec: 13.9675 INFO:tensorflow:global_step/sec: 14.9383 2021-11-27 22:13:35,513 [INFO] tensorflow: global_step/sec: 14.9383 INFO:tensorflow:global_step/sec: 15.0593 2021-11-27 22:13:35,646 [INFO] tensorflow: global_step/sec: 15.0593 INFO:tensorflow:global_step/sec: 14.9271 2021-11-27 22:13:35,780 [INFO] tensorflow: global_step/sec: 14.9271 INFO:tensorflow:global_step/sec: 15.5292 2021-11-27 22:13:35,909 [INFO] tensorflow: global_step/sec: 15.5292 INFO:tensorflow:global_step/sec: 15.0128 2021-11-27 22:13:36,042 [INFO] tensorflow: global_step/sec: 15.0128 INFO:tensorflow:global_step/sec: 15.0751 2021-11-27 22:13:36,175 [INFO] tensorflow: global_step/sec: 15.0751 2021-11-27 22:13:36,240 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.370 INFO:tensorflow:global_step/sec: 15.2464 2021-11-27 22:13:36,306 [INFO] tensorflow: global_step/sec: 15.2464 INFO:tensorflow:global_step/sec: 14.931 2021-11-27 22:13:36,440 [INFO] tensorflow: global_step/sec: 14.931 INFO:tensorflow:global_step/sec: 15.0601 2021-11-27 22:13:36,573 [INFO] tensorflow: global_step/sec: 15.0601 INFO:tensorflow:global_step/sec: 14.4101 2021-11-27 22:13:36,712 [INFO] tensorflow: global_step/sec: 14.4101 2021-11-27 22:13:36,713 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 98/120: loss: 0.00051 learning rate: 0.00008 Time taken: 0:00:01.484409 ETA: 0:00:32.657000 INFO:tensorflow:global_step/sec: 15.0223 2021-11-27 22:13:36,845 [INFO] tensorflow: global_step/sec: 15.0223 INFO:tensorflow:global_step/sec: 15.3027 2021-11-27 22:13:36,976 [INFO] tensorflow: global_step/sec: 15.3027 INFO:tensorflow:global_step/sec: 15.1061 2021-11-27 22:13:37,108 [INFO] tensorflow: global_step/sec: 15.1061 INFO:tensorflow:global_step/sec: 15.2104 2021-11-27 22:13:37,239 [INFO] tensorflow: global_step/sec: 15.2104 INFO:tensorflow:global_step/sec: 14.9271 2021-11-27 22:13:37,373 [INFO] tensorflow: global_step/sec: 14.9271 INFO:tensorflow:global_step/sec: 14.4789 2021-11-27 22:13:37,512 [INFO] tensorflow: global_step/sec: 14.4789 INFO:tensorflow:global_step/sec: 14.8067 2021-11-27 22:13:37,647 [INFO] tensorflow: global_step/sec: 14.8067 INFO:tensorflow:global_step/sec: 14.9415 2021-11-27 22:13:37,780 [INFO] tensorflow: global_step/sec: 14.9415 INFO:tensorflow:global_step/sec: 14.6001 2021-11-27 22:13:37,917 [INFO] tensorflow: global_step/sec: 14.6001 2021-11-27 22:13:37,918 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.608 INFO:tensorflow:global_step/sec: 15.2626 2021-11-27 22:13:38,048 [INFO] tensorflow: global_step/sec: 15.2626 INFO:tensorflow:global_step/sec: 14.2748 2021-11-27 22:13:38,189 [INFO] tensorflow: global_step/sec: 14.2748 2021-11-27 22:13:38,189 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 99/120: loss: 0.00053 learning rate: 0.00007 Time taken: 0:00:01.477549 ETA: 0:00:31.028531 INFO:tensorflow:global_step/sec: 14.8238 2021-11-27 22:13:38,323 [INFO] tensorflow: global_step/sec: 14.8238 INFO:tensorflow:global_step/sec: 14.8193 2021-11-27 22:13:38,458 [INFO] tensorflow: global_step/sec: 14.8193 INFO:tensorflow:global_step/sec: 15.6166 2021-11-27 22:13:38,587 [INFO] tensorflow: global_step/sec: 15.6166 INFO:tensorflow:global_step/sec: 15.198 2021-11-27 22:13:38,718 [INFO] tensorflow: global_step/sec: 15.198 INFO:tensorflow:global_step/sec: 14.6753 2021-11-27 22:13:38,854 [INFO] tensorflow: global_step/sec: 14.6753 INFO:tensorflow:global_step/sec: 14.7144 2021-11-27 22:13:38,990 [INFO] tensorflow: global_step/sec: 14.7144 INFO:tensorflow:global_step/sec: 15.1402 2021-11-27 22:13:39,122 [INFO] tensorflow: global_step/sec: 15.1402 INFO:tensorflow:global_step/sec: 15.1915 2021-11-27 22:13:39,254 [INFO] tensorflow: global_step/sec: 15.1915 INFO:tensorflow:global_step/sec: 15.2127 2021-11-27 22:13:39,386 [INFO] tensorflow: global_step/sec: 15.2127 INFO:tensorflow:global_step/sec: 14.866 2021-11-27 22:13:39,520 [INFO] tensorflow: global_step/sec: 14.866 INFO:tensorflow:Saving checkpoints for step-2200. 2021-11-27 22:13:39,584 [INFO] tensorflow: Saving checkpoints for step-2200. WARNING:tensorflow:Ignoring: /tmp/tmpsujycxfe; No such file or directory 2021-11-27 22:13:39,675 [WARNING] tensorflow: Ignoring: /tmp/tmpsujycxfe; No such file or directory 2021-11-27 22:13:41,958 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 803/803 [00:00<00:00, 24276.16it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 55/55 [00:00<00:00, 23198.58it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 183/183 [00:00<00:00, 24072.69it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 602/602 [00:00<00:00, 25071.95it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 257/257 [00:00<00:00, 23842.34it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 716/716 [00:00<00:00, 23360.05it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 1187/1187 [00:00<00:00, 32942.54it/s] Epoch 100/120 ========================= Validation cost: 0.000361 Mean average_precision (in %): 30.8107 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 80.0994 floor 0 palette 6.77966 pillar 54.2219 pushcart 0 rackframe 46.9401 rackshelf 49.1903 wall 40.0651 Median Inference Time: 0.006997 2021-11-27 22:13:43,963 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 16.545 INFO:tensorflow:epoch = 100.0, learning_rate = 6.457747e-05, loss = 0.00055886863, step = 2200 (8.954 sec) 2021-11-27 22:13:44,034 [INFO] tensorflow: epoch = 100.0, learning_rate = 6.457747e-05, loss = 0.00055886863, step = 2200 (8.954 sec) INFO:tensorflow:global_step/sec: 0.442994 2021-11-27 22:13:44,035 [INFO] tensorflow: global_step/sec: 0.442994 2021-11-27 22:13:44,036 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 100/120: loss: 0.00056 learning rate: 0.00006 Time taken: 0:00:05.839059 ETA: 0:01:56.781173 INFO:tensorflow:global_step/sec: 14.5727 2021-11-27 22:13:44,172 [INFO] tensorflow: global_step/sec: 14.5727 INFO:tensorflow:global_step/sec: 14.8189 2021-11-27 22:13:44,307 [INFO] tensorflow: global_step/sec: 14.8189 INFO:tensorflow:global_step/sec: 14.8315 2021-11-27 22:13:44,442 [INFO] tensorflow: global_step/sec: 14.8315 INFO:tensorflow:global_step/sec: 14.9728 2021-11-27 22:13:44,575 [INFO] tensorflow: global_step/sec: 14.9728 INFO:tensorflow:global_step/sec: 14.7101 2021-11-27 22:13:44,711 [INFO] tensorflow: global_step/sec: 14.7101 INFO:tensorflow:global_step/sec: 15.037 2021-11-27 22:13:44,844 [INFO] tensorflow: global_step/sec: 15.037 INFO:tensorflow:global_step/sec: 15.341 2021-11-27 22:13:44,975 [INFO] tensorflow: global_step/sec: 15.341 INFO:tensorflow:global_step/sec: 15.1629 2021-11-27 22:13:45,107 [INFO] tensorflow: global_step/sec: 15.1629 INFO:tensorflow:global_step/sec: 15.0081 2021-11-27 22:13:45,240 [INFO] tensorflow: global_step/sec: 15.0081 INFO:tensorflow:global_step/sec: 14.6894 2021-11-27 22:13:45,376 [INFO] tensorflow: global_step/sec: 14.6894 INFO:tensorflow:global_step/sec: 14.1061 2021-11-27 22:13:45,518 [INFO] tensorflow: global_step/sec: 14.1061 2021-11-27 22:13:45,519 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 101/120: loss: 0.00058 learning rate: 0.00006 Time taken: 0:00:01.487553 ETA: 0:00:28.263500 INFO:tensorflow:global_step/sec: 15.2236 2021-11-27 22:13:45,649 [INFO] tensorflow: global_step/sec: 15.2236 2021-11-27 22:13:45,650 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.314 INFO:tensorflow:global_step/sec: 14.2657 2021-11-27 22:13:45,789 [INFO] tensorflow: global_step/sec: 14.2657 INFO:tensorflow:global_step/sec: 14.6146 2021-11-27 22:13:45,926 [INFO] tensorflow: global_step/sec: 14.6146 INFO:tensorflow:global_step/sec: 15.0145 2021-11-27 22:13:46,059 [INFO] tensorflow: global_step/sec: 15.0145 INFO:tensorflow:global_step/sec: 14.7514 2021-11-27 22:13:46,195 [INFO] tensorflow: global_step/sec: 14.7514 INFO:tensorflow:global_step/sec: 14.9557 2021-11-27 22:13:46,329 [INFO] tensorflow: global_step/sec: 14.9557 INFO:tensorflow:global_step/sec: 14.6666 2021-11-27 22:13:46,465 [INFO] tensorflow: global_step/sec: 14.6666 INFO:tensorflow:global_step/sec: 15.27 2021-11-27 22:13:46,596 [INFO] tensorflow: global_step/sec: 15.27 INFO:tensorflow:global_step/sec: 14.7994 2021-11-27 22:13:46,731 [INFO] tensorflow: global_step/sec: 14.7994 INFO:tensorflow:global_step/sec: 14.7466 2021-11-27 22:13:46,867 [INFO] tensorflow: global_step/sec: 14.7466 INFO:tensorflow:global_step/sec: 13.3923 2021-11-27 22:13:47,016 [INFO] tensorflow: global_step/sec: 13.3923 2021-11-27 22:13:47,017 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 102/120: loss: 0.00057 learning rate: 0.00005 Time taken: 0:00:01.490161 ETA: 0:00:26.822906 INFO:tensorflow:global_step/sec: 14.4915 2021-11-27 22:13:47,154 [INFO] tensorflow: global_step/sec: 14.4915 INFO:tensorflow:global_step/sec: 14.3181 2021-11-27 22:13:47,294 [INFO] tensorflow: global_step/sec: 14.3181 2021-11-27 22:13:47,363 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.375 INFO:tensorflow:global_step/sec: 14.3946 2021-11-27 22:13:47,433 [INFO] tensorflow: global_step/sec: 14.3946 INFO:tensorflow:global_step/sec: 14.6103 2021-11-27 22:13:47,570 [INFO] tensorflow: global_step/sec: 14.6103 INFO:tensorflow:global_step/sec: 15.0284 2021-11-27 22:13:47,703 [INFO] tensorflow: global_step/sec: 15.0284 INFO:tensorflow:global_step/sec: 15.2751 2021-11-27 22:13:47,834 [INFO] tensorflow: global_step/sec: 15.2751 INFO:tensorflow:global_step/sec: 14.5911 2021-11-27 22:13:47,971 [INFO] tensorflow: global_step/sec: 14.5911 INFO:tensorflow:global_step/sec: 14.0522 2021-11-27 22:13:48,113 [INFO] tensorflow: global_step/sec: 14.0522 INFO:tensorflow:global_step/sec: 14.4364 2021-11-27 22:13:48,252 [INFO] tensorflow: global_step/sec: 14.4364 INFO:tensorflow:global_step/sec: 14.569 2021-11-27 22:13:48,389 [INFO] tensorflow: global_step/sec: 14.569 INFO:tensorflow:global_step/sec: 14.3818 2021-11-27 22:13:48,528 [INFO] tensorflow: global_step/sec: 14.3818 2021-11-27 22:13:48,529 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 103/120: loss: 0.00059 learning rate: 0.00004 Time taken: 0:00:01.513487 ETA: 0:00:25.729281 INFO:tensorflow:global_step/sec: 14.4868 2021-11-27 22:13:48,666 [INFO] tensorflow: global_step/sec: 14.4868 INFO:tensorflow:global_step/sec: 14.7924 2021-11-27 22:13:48,801 [INFO] tensorflow: global_step/sec: 14.7924 INFO:tensorflow:global_step/sec: 14.829 2021-11-27 22:13:48,936 [INFO] tensorflow: global_step/sec: 14.829 INFO:tensorflow:global_step/sec: 15.2678 2021-11-27 22:13:49,067 [INFO] tensorflow: global_step/sec: 15.2678 2021-11-27 22:13:49,068 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.675 INFO:tensorflow:epoch = 103.4090909090909, learning_rate = 4.175296e-05, loss = 0.0005593177, step = 2275 (5.102 sec) 2021-11-27 22:13:49,136 [INFO] tensorflow: epoch = 103.4090909090909, learning_rate = 4.175296e-05, loss = 0.0005593177, step = 2275 (5.102 sec) INFO:tensorflow:global_step/sec: 14.4317 2021-11-27 22:13:49,206 [INFO] tensorflow: global_step/sec: 14.4317 INFO:tensorflow:global_step/sec: 14.6899 2021-11-27 22:13:49,342 [INFO] tensorflow: global_step/sec: 14.6899 INFO:tensorflow:global_step/sec: 14.9752 2021-11-27 22:13:49,475 [INFO] tensorflow: global_step/sec: 14.9752 INFO:tensorflow:global_step/sec: 14.6214 2021-11-27 22:13:49,612 [INFO] tensorflow: global_step/sec: 14.6214 INFO:tensorflow:global_step/sec: 15.0527 2021-11-27 22:13:49,745 [INFO] tensorflow: global_step/sec: 15.0527 INFO:tensorflow:global_step/sec: 15.0547 2021-11-27 22:13:49,878 [INFO] tensorflow: global_step/sec: 15.0547 INFO:tensorflow:global_step/sec: 14.3406 2021-11-27 22:13:50,017 [INFO] tensorflow: global_step/sec: 14.3406 2021-11-27 22:13:50,018 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 104/120: loss: 0.00057 learning rate: 0.00004 Time taken: 0:00:01.488014 ETA: 0:00:23.808220 INFO:tensorflow:global_step/sec: 14.797 2021-11-27 22:13:50,153 [INFO] tensorflow: global_step/sec: 14.797 INFO:tensorflow:global_step/sec: 14.9948 2021-11-27 22:13:50,286 [INFO] tensorflow: global_step/sec: 14.9948 INFO:tensorflow:global_step/sec: 14.7074 2021-11-27 22:13:50,422 [INFO] tensorflow: global_step/sec: 14.7074 INFO:tensorflow:global_step/sec: 14.7617 2021-11-27 22:13:50,557 [INFO] tensorflow: global_step/sec: 14.7617 INFO:tensorflow:global_step/sec: 14.8354 2021-11-27 22:13:50,692 [INFO] tensorflow: global_step/sec: 14.8354 2021-11-27 22:13:50,759 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.137 INFO:tensorflow:global_step/sec: 15.1909 2021-11-27 22:13:50,824 [INFO] tensorflow: global_step/sec: 15.1909 INFO:tensorflow:global_step/sec: 15.036 2021-11-27 22:13:50,957 [INFO] tensorflow: global_step/sec: 15.036 INFO:tensorflow:global_step/sec: 14.9644 2021-11-27 22:13:51,091 [INFO] tensorflow: global_step/sec: 14.9644 INFO:tensorflow:global_step/sec: 14.9499 2021-11-27 22:13:51,224 [INFO] tensorflow: global_step/sec: 14.9499 INFO:tensorflow:global_step/sec: 15.184 2021-11-27 22:13:51,356 [INFO] tensorflow: global_step/sec: 15.184 INFO:tensorflow:global_step/sec: 14.759 2021-11-27 22:13:51,492 [INFO] tensorflow: global_step/sec: 14.759 2021-11-27 22:13:51,493 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 105/120: loss: 0.00054 learning rate: 0.00003 Time taken: 0:00:01.475093 ETA: 0:00:22.126400 INFO:tensorflow:global_step/sec: 14.9596 2021-11-27 22:13:51,625 [INFO] tensorflow: global_step/sec: 14.9596 INFO:tensorflow:global_step/sec: 15.1018 2021-11-27 22:13:51,758 [INFO] tensorflow: global_step/sec: 15.1018 INFO:tensorflow:global_step/sec: 15.1254 2021-11-27 22:13:51,890 [INFO] tensorflow: global_step/sec: 15.1254 INFO:tensorflow:global_step/sec: 14.7954 2021-11-27 22:13:52,025 [INFO] tensorflow: global_step/sec: 14.7954 INFO:tensorflow:global_step/sec: 15.0259 2021-11-27 22:13:52,158 [INFO] tensorflow: global_step/sec: 15.0259 INFO:tensorflow:global_step/sec: 14.978 2021-11-27 22:13:52,292 [INFO] tensorflow: global_step/sec: 14.978 INFO:tensorflow:global_step/sec: 14.4577 2021-11-27 22:13:52,430 [INFO] tensorflow: global_step/sec: 14.4577 2021-11-27 22:13:52,431 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.832 INFO:tensorflow:global_step/sec: 15.4703 2021-11-27 22:13:52,559 [INFO] tensorflow: global_step/sec: 15.4703 INFO:tensorflow:global_step/sec: 14.93 2021-11-27 22:13:52,693 [INFO] tensorflow: global_step/sec: 14.93 INFO:tensorflow:global_step/sec: 14.72 2021-11-27 22:13:52,829 [INFO] tensorflow: global_step/sec: 14.72 INFO:tensorflow:global_step/sec: 14.0773 2021-11-27 22:13:52,971 [INFO] tensorflow: global_step/sec: 14.0773 2021-11-27 22:13:52,972 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 106/120: loss: 0.00052 learning rate: 0.00003 Time taken: 0:00:01.476597 ETA: 0:00:20.672352 INFO:tensorflow:global_step/sec: 15.3114 2021-11-27 22:13:53,102 [INFO] tensorflow: global_step/sec: 15.3114 INFO:tensorflow:global_step/sec: 15.1175 2021-11-27 22:13:53,234 [INFO] tensorflow: global_step/sec: 15.1175 INFO:tensorflow:global_step/sec: 15.5868 2021-11-27 22:13:53,363 [INFO] tensorflow: global_step/sec: 15.5868 INFO:tensorflow:global_step/sec: 15.1488 2021-11-27 22:13:53,495 [INFO] tensorflow: global_step/sec: 15.1488 INFO:tensorflow:global_step/sec: 15.0376 2021-11-27 22:13:53,628 [INFO] tensorflow: global_step/sec: 15.0376 INFO:tensorflow:global_step/sec: 14.8196 2021-11-27 22:13:53,762 [INFO] tensorflow: global_step/sec: 14.8196 INFO:tensorflow:global_step/sec: 15.1396 2021-11-27 22:13:53,895 [INFO] tensorflow: global_step/sec: 15.1396 INFO:tensorflow:global_step/sec: 14.8561 2021-11-27 22:13:54,029 [INFO] tensorflow: global_step/sec: 14.8561 2021-11-27 22:13:54,098 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.997 INFO:tensorflow:global_step/sec: 14.7577 2021-11-27 22:13:54,165 [INFO] tensorflow: global_step/sec: 14.7577 INFO:tensorflow:epoch = 106.86363636363636, learning_rate = 2.6839094e-05, loss = 0.0005783711, step = 2351 (5.097 sec) 2021-11-27 22:13:54,233 [INFO] tensorflow: epoch = 106.86363636363636, learning_rate = 2.6839094e-05, loss = 0.0005783711, step = 2351 (5.097 sec) INFO:tensorflow:global_step/sec: 14.5509 2021-11-27 22:13:54,302 [INFO] tensorflow: global_step/sec: 14.5509 INFO:tensorflow:global_step/sec: 13.7995 2021-11-27 22:13:54,447 [INFO] tensorflow: global_step/sec: 13.7995 2021-11-27 22:13:54,448 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 107/120: loss: 0.00055 learning rate: 0.00003 Time taken: 0:00:01.473645 ETA: 0:00:19.157388 INFO:tensorflow:global_step/sec: 14.205 2021-11-27 22:13:54,588 [INFO] tensorflow: global_step/sec: 14.205 INFO:tensorflow:global_step/sec: 15.021 2021-11-27 22:13:54,721 [INFO] tensorflow: global_step/sec: 15.021 INFO:tensorflow:global_step/sec: 15.1786 2021-11-27 22:13:54,853 [INFO] tensorflow: global_step/sec: 15.1786 INFO:tensorflow:global_step/sec: 15.4445 2021-11-27 22:13:54,982 [INFO] tensorflow: global_step/sec: 15.4445 INFO:tensorflow:global_step/sec: 14.3361 2021-11-27 22:13:55,122 [INFO] tensorflow: global_step/sec: 14.3361 INFO:tensorflow:global_step/sec: 15.227 2021-11-27 22:13:55,253 [INFO] tensorflow: global_step/sec: 15.227 INFO:tensorflow:global_step/sec: 15.1612 2021-11-27 22:13:55,385 [INFO] tensorflow: global_step/sec: 15.1612 INFO:tensorflow:global_step/sec: 14.7772 2021-11-27 22:13:55,520 [INFO] tensorflow: global_step/sec: 14.7772 INFO:tensorflow:global_step/sec: 14.7789 2021-11-27 22:13:55,656 [INFO] tensorflow: global_step/sec: 14.7789 INFO:tensorflow:global_step/sec: 15.0687 2021-11-27 22:13:55,788 [INFO] tensorflow: global_step/sec: 15.0687 2021-11-27 22:13:55,789 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.138 INFO:tensorflow:global_step/sec: 14.2253 2021-11-27 22:13:55,929 [INFO] tensorflow: global_step/sec: 14.2253 2021-11-27 22:13:55,930 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 108/120: loss: 0.00061 learning rate: 0.00002 Time taken: 0:00:01.481451 ETA: 0:00:17.777407 INFO:tensorflow:global_step/sec: 15.1751 2021-11-27 22:13:56,061 [INFO] tensorflow: global_step/sec: 15.1751 INFO:tensorflow:global_step/sec: 15.0851 2021-11-27 22:13:56,193 [INFO] tensorflow: global_step/sec: 15.0851 INFO:tensorflow:global_step/sec: 14.9349 2021-11-27 22:13:56,327 [INFO] tensorflow: global_step/sec: 14.9349 INFO:tensorflow:global_step/sec: 14.8667 2021-11-27 22:13:56,462 [INFO] tensorflow: global_step/sec: 14.8667 INFO:tensorflow:global_step/sec: 14.6712 2021-11-27 22:13:56,598 [INFO] tensorflow: global_step/sec: 14.6712 INFO:tensorflow:global_step/sec: 15.0774 2021-11-27 22:13:56,731 [INFO] tensorflow: global_step/sec: 15.0774 INFO:tensorflow:global_step/sec: 14.7904 2021-11-27 22:13:56,866 [INFO] tensorflow: global_step/sec: 14.7904 INFO:tensorflow:global_step/sec: 14.8893 2021-11-27 22:13:57,000 [INFO] tensorflow: global_step/sec: 14.8893 INFO:tensorflow:global_step/sec: 14.6063 2021-11-27 22:13:57,137 [INFO] tensorflow: global_step/sec: 14.6063 INFO:tensorflow:global_step/sec: 14.5439 2021-11-27 22:13:57,275 [INFO] tensorflow: global_step/sec: 14.5439 INFO:tensorflow:global_step/sec: 13.9451 2021-11-27 22:13:57,418 [INFO] tensorflow: global_step/sec: 13.9451 2021-11-27 22:13:57,419 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 109/120: loss: 0.00052 learning rate: 0.00002 Time taken: 0:00:01.486024 ETA: 0:00:16.346268 2021-11-27 22:13:57,481 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 59.117 INFO:tensorflow:global_step/sec: 15.4105 2021-11-27 22:13:57,548 [INFO] tensorflow: global_step/sec: 15.4105 INFO:tensorflow:global_step/sec: 14.9786 2021-11-27 22:13:57,682 [INFO] tensorflow: global_step/sec: 14.9786 INFO:tensorflow:global_step/sec: 14.7983 2021-11-27 22:13:57,817 [INFO] tensorflow: global_step/sec: 14.7983 INFO:tensorflow:global_step/sec: 14.8149 2021-11-27 22:13:57,952 [INFO] tensorflow: global_step/sec: 14.8149 INFO:tensorflow:global_step/sec: 14.5381 2021-11-27 22:13:58,089 [INFO] tensorflow: global_step/sec: 14.5381 INFO:tensorflow:global_step/sec: 14.6208 2021-11-27 22:13:58,226 [INFO] tensorflow: global_step/sec: 14.6208 INFO:tensorflow:global_step/sec: 14.9362 2021-11-27 22:13:58,360 [INFO] tensorflow: global_step/sec: 14.9362 INFO:tensorflow:global_step/sec: 15.4475 2021-11-27 22:13:58,489 [INFO] tensorflow: global_step/sec: 15.4475 INFO:tensorflow:global_step/sec: 15.3136 2021-11-27 22:13:58,620 [INFO] tensorflow: global_step/sec: 15.3136 INFO:tensorflow:global_step/sec: 15.0841 2021-11-27 22:13:58,753 [INFO] tensorflow: global_step/sec: 15.0841 INFO:tensorflow:Saving checkpoints for step-2420. 2021-11-27 22:13:58,819 [INFO] tensorflow: Saving checkpoints for step-2420. WARNING:tensorflow:Ignoring: /tmp/tmp085v6unk; No such file or directory 2021-11-27 22:13:58,906 [WARNING] tensorflow: Ignoring: /tmp/tmp085v6unk; No such file or directory 2021-11-27 22:14:01,162 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 811/811 [00:00<00:00, 23914.88it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 57/57 [00:00<00:00, 23921.89it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 177/177 [00:00<00:00, 24374.28it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 572/572 [00:00<00:00, 25186.52it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 286/286 [00:00<00:00, 23310.29it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 719/719 [00:00<00:00, 23982.13it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 1021/1021 [00:00<00:00, 33398.72it/s] Epoch 110/120 ========================= Validation cost: 0.000356 Mean average_precision (in %): 32.1409 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 83.3622 floor 0 palette 9.60187 pillar 57.2921 pushcart 0 rackframe 46.9219 rackshelf 51.9863 wall 40.1041 Median Inference Time: 0.007966 INFO:tensorflow:epoch = 110.0, learning_rate = 1.7969083e-05, loss = 0.0005546734, step = 2420 (8.912 sec) 2021-11-27 22:14:03,145 [INFO] tensorflow: epoch = 110.0, learning_rate = 1.7969083e-05, loss = 0.0005546734, step = 2420 (8.912 sec) INFO:tensorflow:global_step/sec: 0.455199 2021-11-27 22:14:03,146 [INFO] tensorflow: global_step/sec: 0.455199 2021-11-27 22:14:03,147 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 110/120: loss: 0.00055 learning rate: 0.00002 Time taken: 0:00:05.721983 ETA: 0:00:57.219834 INFO:tensorflow:global_step/sec: 13.6625 2021-11-27 22:14:03,293 [INFO] tensorflow: global_step/sec: 13.6625 INFO:tensorflow:global_step/sec: 14.7438 2021-11-27 22:14:03,428 [INFO] tensorflow: global_step/sec: 14.7438 2021-11-27 22:14:03,429 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 16.813 INFO:tensorflow:global_step/sec: 13.9278 2021-11-27 22:14:03,572 [INFO] tensorflow: global_step/sec: 13.9278 INFO:tensorflow:global_step/sec: 14.1084 2021-11-27 22:14:03,714 [INFO] tensorflow: global_step/sec: 14.1084 INFO:tensorflow:global_step/sec: 14.4681 2021-11-27 22:14:03,852 [INFO] tensorflow: global_step/sec: 14.4681 INFO:tensorflow:global_step/sec: 14.7191 2021-11-27 22:14:03,988 [INFO] tensorflow: global_step/sec: 14.7191 INFO:tensorflow:global_step/sec: 14.1071 2021-11-27 22:14:04,130 [INFO] tensorflow: global_step/sec: 14.1071 INFO:tensorflow:global_step/sec: 14.9028 2021-11-27 22:14:04,264 [INFO] tensorflow: global_step/sec: 14.9028 INFO:tensorflow:global_step/sec: 14.7907 2021-11-27 22:14:04,399 [INFO] tensorflow: global_step/sec: 14.7907 INFO:tensorflow:global_step/sec: 14.7381 2021-11-27 22:14:04,535 [INFO] tensorflow: global_step/sec: 14.7381 INFO:tensorflow:global_step/sec: 14.0034 2021-11-27 22:14:04,678 [INFO] tensorflow: global_step/sec: 14.0034 2021-11-27 22:14:04,678 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 111/120: loss: 0.00055 learning rate: 0.00002 Time taken: 0:00:01.532775 ETA: 0:00:13.794974 INFO:tensorflow:global_step/sec: 14.7861 2021-11-27 22:14:04,813 [INFO] tensorflow: global_step/sec: 14.7861 INFO:tensorflow:global_step/sec: 13.8382 2021-11-27 22:14:04,957 [INFO] tensorflow: global_step/sec: 13.8382 INFO:tensorflow:global_step/sec: 14.5552 2021-11-27 22:14:05,095 [INFO] tensorflow: global_step/sec: 14.5552 2021-11-27 22:14:05,163 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.669 INFO:tensorflow:global_step/sec: 14.5795 2021-11-27 22:14:05,232 [INFO] tensorflow: global_step/sec: 14.5795 INFO:tensorflow:global_step/sec: 14.9513 2021-11-27 22:14:05,366 [INFO] tensorflow: global_step/sec: 14.9513 INFO:tensorflow:global_step/sec: 15.0493 2021-11-27 22:14:05,499 [INFO] tensorflow: global_step/sec: 15.0493 INFO:tensorflow:global_step/sec: 14.5385 2021-11-27 22:14:05,636 [INFO] tensorflow: global_step/sec: 14.5385 INFO:tensorflow:global_step/sec: 14.8733 2021-11-27 22:14:05,771 [INFO] tensorflow: global_step/sec: 14.8733 INFO:tensorflow:global_step/sec: 14.433 2021-11-27 22:14:05,909 [INFO] tensorflow: global_step/sec: 14.433 INFO:tensorflow:global_step/sec: 15.3317 2021-11-27 22:14:06,040 [INFO] tensorflow: global_step/sec: 15.3317 INFO:tensorflow:global_step/sec: 13.509 2021-11-27 22:14:06,188 [INFO] tensorflow: global_step/sec: 13.509 2021-11-27 22:14:06,188 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 112/120: loss: 0.00057 learning rate: 0.00001 Time taken: 0:00:01.506736 ETA: 0:00:12.053888 INFO:tensorflow:global_step/sec: 14.458 2021-11-27 22:14:06,326 [INFO] tensorflow: global_step/sec: 14.458 INFO:tensorflow:global_step/sec: 14.5047 2021-11-27 22:14:06,464 [INFO] tensorflow: global_step/sec: 14.5047 INFO:tensorflow:global_step/sec: 14.5484 2021-11-27 22:14:06,601 [INFO] tensorflow: global_step/sec: 14.5484 INFO:tensorflow:global_step/sec: 14.8116 2021-11-27 22:14:06,736 [INFO] tensorflow: global_step/sec: 14.8116 INFO:tensorflow:global_step/sec: 14.9014 2021-11-27 22:14:06,871 [INFO] tensorflow: global_step/sec: 14.9014 2021-11-27 22:14:06,871 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.560 INFO:tensorflow:global_step/sec: 14.3655 2021-11-27 22:14:07,010 [INFO] tensorflow: global_step/sec: 14.3655 INFO:tensorflow:global_step/sec: 14.6463 2021-11-27 22:14:07,146 [INFO] tensorflow: global_step/sec: 14.6463 INFO:tensorflow:global_step/sec: 14.5217 2021-11-27 22:14:07,284 [INFO] tensorflow: global_step/sec: 14.5217 INFO:tensorflow:global_step/sec: 15.0949 2021-11-27 22:14:07,417 [INFO] tensorflow: global_step/sec: 15.0949 INFO:tensorflow:global_step/sec: 14.7148 2021-11-27 22:14:07,553 [INFO] tensorflow: global_step/sec: 14.7148 INFO:tensorflow:global_step/sec: 13.6502 2021-11-27 22:14:07,699 [INFO] tensorflow: global_step/sec: 13.6502 2021-11-27 22:14:07,700 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 113/120: loss: 0.00049 learning rate: 0.00001 Time taken: 0:00:01.511716 ETA: 0:00:10.582013 INFO:tensorflow:global_step/sec: 13.9831 2021-11-27 22:14:07,842 [INFO] tensorflow: global_step/sec: 13.9831 INFO:tensorflow:global_step/sec: 14.1898 2021-11-27 22:14:07,983 [INFO] tensorflow: global_step/sec: 14.1898 INFO:tensorflow:global_step/sec: 14.6837 2021-11-27 22:14:08,119 [INFO] tensorflow: global_step/sec: 14.6837 INFO:tensorflow:epoch = 113.36363636363636, learning_rate = 1.168576e-05, loss = 0.0005457344, step = 2494 (5.107 sec) 2021-11-27 22:14:08,252 [INFO] tensorflow: epoch = 113.36363636363636, learning_rate = 1.168576e-05, loss = 0.0005457344, step = 2494 (5.107 sec) INFO:tensorflow:global_step/sec: 14.9502 2021-11-27 22:14:08,253 [INFO] tensorflow: global_step/sec: 14.9502 INFO:tensorflow:global_step/sec: 14.4158 2021-11-27 22:14:08,392 [INFO] tensorflow: global_step/sec: 14.4158 INFO:tensorflow:global_step/sec: 14.4871 2021-11-27 22:14:08,530 [INFO] tensorflow: global_step/sec: 14.4871 2021-11-27 22:14:08,596 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 57.990 INFO:tensorflow:global_step/sec: 14.9496 2021-11-27 22:14:08,664 [INFO] tensorflow: global_step/sec: 14.9496 INFO:tensorflow:global_step/sec: 14.7773 2021-11-27 22:14:08,799 [INFO] tensorflow: global_step/sec: 14.7773 INFO:tensorflow:global_step/sec: 14.8251 2021-11-27 22:14:08,934 [INFO] tensorflow: global_step/sec: 14.8251 INFO:tensorflow:global_step/sec: 14.9363 2021-11-27 22:14:09,068 [INFO] tensorflow: global_step/sec: 14.9363 INFO:tensorflow:global_step/sec: 14.0095 2021-11-27 22:14:09,211 [INFO] tensorflow: global_step/sec: 14.0095 2021-11-27 22:14:09,212 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 114/120: loss: 0.00051 learning rate: 0.00001 Time taken: 0:00:01.507674 ETA: 0:00:09.046042 INFO:tensorflow:global_step/sec: 14.265 2021-11-27 22:14:09,351 [INFO] tensorflow: global_step/sec: 14.265 INFO:tensorflow:global_step/sec: 14.7811 2021-11-27 22:14:09,486 [INFO] tensorflow: global_step/sec: 14.7811 INFO:tensorflow:global_step/sec: 14.5124 2021-11-27 22:14:09,624 [INFO] tensorflow: global_step/sec: 14.5124 INFO:tensorflow:global_step/sec: 15.0106 2021-11-27 22:14:09,757 [INFO] tensorflow: global_step/sec: 15.0106 INFO:tensorflow:global_step/sec: 14.5523 2021-11-27 22:14:09,895 [INFO] tensorflow: global_step/sec: 14.5523 INFO:tensorflow:global_step/sec: 14.6874 2021-11-27 22:14:10,031 [INFO] tensorflow: global_step/sec: 14.6874 INFO:tensorflow:global_step/sec: 14.5284 2021-11-27 22:14:10,168 [INFO] tensorflow: global_step/sec: 14.5284 INFO:tensorflow:global_step/sec: 14.6142 2021-11-27 22:14:10,305 [INFO] tensorflow: global_step/sec: 14.6142 2021-11-27 22:14:10,306 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.506 INFO:tensorflow:global_step/sec: 14.4073 2021-11-27 22:14:10,444 [INFO] tensorflow: global_step/sec: 14.4073 INFO:tensorflow:global_step/sec: 14.6873 2021-11-27 22:14:10,580 [INFO] tensorflow: global_step/sec: 14.6873 INFO:tensorflow:global_step/sec: 13.3242 2021-11-27 22:14:10,730 [INFO] tensorflow: global_step/sec: 13.3242 2021-11-27 22:14:10,731 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 115/120: loss: 0.00054 learning rate: 0.00001 Time taken: 0:00:01.519587 ETA: 0:00:07.597936 INFO:tensorflow:global_step/sec: 14.6239 2021-11-27 22:14:10,867 [INFO] tensorflow: global_step/sec: 14.6239 INFO:tensorflow:global_step/sec: 14.5794 2021-11-27 22:14:11,004 [INFO] tensorflow: global_step/sec: 14.5794 INFO:tensorflow:global_step/sec: 14.8667 2021-11-27 22:14:11,139 [INFO] tensorflow: global_step/sec: 14.8667 INFO:tensorflow:global_step/sec: 14.6045 2021-11-27 22:14:11,276 [INFO] tensorflow: global_step/sec: 14.6045 INFO:tensorflow:global_step/sec: 14.2711 2021-11-27 22:14:11,416 [INFO] tensorflow: global_step/sec: 14.2711 INFO:tensorflow:global_step/sec: 14.5006 2021-11-27 22:14:11,554 [INFO] tensorflow: global_step/sec: 14.5006 INFO:tensorflow:global_step/sec: 15.0917 2021-11-27 22:14:11,686 [INFO] tensorflow: global_step/sec: 15.0917 INFO:tensorflow:global_step/sec: 14.9849 2021-11-27 22:14:11,820 [INFO] tensorflow: global_step/sec: 14.9849 INFO:tensorflow:global_step/sec: 15.0553 2021-11-27 22:14:11,953 [INFO] tensorflow: global_step/sec: 15.0553 2021-11-27 22:14:12,021 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.301 INFO:tensorflow:global_step/sec: 14.6977 2021-11-27 22:14:12,089 [INFO] tensorflow: global_step/sec: 14.6977 INFO:tensorflow:global_step/sec: 13.9754 2021-11-27 22:14:12,232 [INFO] tensorflow: global_step/sec: 13.9754 2021-11-27 22:14:12,233 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 116/120: loss: 0.00057 learning rate: 0.00001 Time taken: 0:00:01.501678 ETA: 0:00:06.006714 INFO:tensorflow:global_step/sec: 15.1511 2021-11-27 22:14:12,364 [INFO] tensorflow: global_step/sec: 15.1511 INFO:tensorflow:global_step/sec: 14.4551 2021-11-27 22:14:12,502 [INFO] tensorflow: global_step/sec: 14.4551 INFO:tensorflow:global_step/sec: 14.612 2021-11-27 22:14:12,639 [INFO] tensorflow: global_step/sec: 14.612 INFO:tensorflow:global_step/sec: 14.7892 2021-11-27 22:14:12,774 [INFO] tensorflow: global_step/sec: 14.7892 INFO:tensorflow:global_step/sec: 14.5904 2021-11-27 22:14:12,911 [INFO] tensorflow: global_step/sec: 14.5904 INFO:tensorflow:global_step/sec: 14.6879 2021-11-27 22:14:13,048 [INFO] tensorflow: global_step/sec: 14.6879 INFO:tensorflow:global_step/sec: 14.8979 2021-11-27 22:14:13,182 [INFO] tensorflow: global_step/sec: 14.8979 INFO:tensorflow:global_step/sec: 15.0688 2021-11-27 22:14:13,314 [INFO] tensorflow: global_step/sec: 15.0688 INFO:tensorflow:epoch = 116.77272727272728, learning_rate = 7.5555e-06, loss = 0.00049362035, step = 2569 (5.129 sec) 2021-11-27 22:14:13,382 [INFO] tensorflow: epoch = 116.77272727272728, learning_rate = 7.5555e-06, loss = 0.00049362035, step = 2569 (5.129 sec) INFO:tensorflow:global_step/sec: 14.7136 2021-11-27 22:14:13,450 [INFO] tensorflow: global_step/sec: 14.7136 INFO:tensorflow:global_step/sec: 14.9746 2021-11-27 22:14:13,584 [INFO] tensorflow: global_step/sec: 14.9746 INFO:tensorflow:global_step/sec: 13.7404 2021-11-27 22:14:13,730 [INFO] tensorflow: global_step/sec: 13.7404 2021-11-27 22:14:13,730 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 117/120: loss: 0.00058 learning rate: 0.00001 Time taken: 0:00:01.496253 ETA: 0:00:04.488758 2021-11-27 22:14:13,731 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.507 INFO:tensorflow:global_step/sec: 14.8639 2021-11-27 22:14:13,864 [INFO] tensorflow: global_step/sec: 14.8639 INFO:tensorflow:global_step/sec: 14.7895 2021-11-27 22:14:13,999 [INFO] tensorflow: global_step/sec: 14.7895 INFO:tensorflow:global_step/sec: 14.3918 2021-11-27 22:14:14,138 [INFO] tensorflow: global_step/sec: 14.3918 INFO:tensorflow:global_step/sec: 14.2683 2021-11-27 22:14:14,278 [INFO] tensorflow: global_step/sec: 14.2683 INFO:tensorflow:global_step/sec: 14.4947 2021-11-27 22:14:14,416 [INFO] tensorflow: global_step/sec: 14.4947 INFO:tensorflow:global_step/sec: 14.8349 2021-11-27 22:14:14,551 [INFO] tensorflow: global_step/sec: 14.8349 INFO:tensorflow:global_step/sec: 14.7231 2021-11-27 22:14:14,687 [INFO] tensorflow: global_step/sec: 14.7231 INFO:tensorflow:global_step/sec: 14.0777 2021-11-27 22:14:14,829 [INFO] tensorflow: global_step/sec: 14.0777 INFO:tensorflow:global_step/sec: 14.6964 2021-11-27 22:14:14,965 [INFO] tensorflow: global_step/sec: 14.6964 INFO:tensorflow:global_step/sec: 15.074 2021-11-27 22:14:15,098 [INFO] tensorflow: global_step/sec: 15.074 INFO:tensorflow:global_step/sec: 13.9061 2021-11-27 22:14:15,242 [INFO] tensorflow: global_step/sec: 13.9061 2021-11-27 22:14:15,243 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 118/120: loss: 0.00056 learning rate: 0.00001 Time taken: 0:00:01.511011 ETA: 0:00:03.022022 INFO:tensorflow:global_step/sec: 14.5515 2021-11-27 22:14:15,379 [INFO] tensorflow: global_step/sec: 14.5515 2021-11-27 22:14:15,448 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.233 INFO:tensorflow:global_step/sec: 14.5891 2021-11-27 22:14:15,516 [INFO] tensorflow: global_step/sec: 14.5891 INFO:tensorflow:global_step/sec: 14.9013 2021-11-27 22:14:15,651 [INFO] tensorflow: global_step/sec: 14.9013 INFO:tensorflow:global_step/sec: 15.0269 2021-11-27 22:14:15,784 [INFO] tensorflow: global_step/sec: 15.0269 INFO:tensorflow:global_step/sec: 14.5289 2021-11-27 22:14:15,921 [INFO] tensorflow: global_step/sec: 14.5289 INFO:tensorflow:global_step/sec: 14.851 2021-11-27 22:14:16,056 [INFO] tensorflow: global_step/sec: 14.851 INFO:tensorflow:global_step/sec: 14.6678 2021-11-27 22:14:16,192 [INFO] tensorflow: global_step/sec: 14.6678 INFO:tensorflow:global_step/sec: 14.872 2021-11-27 22:14:16,327 [INFO] tensorflow: global_step/sec: 14.872 INFO:tensorflow:global_step/sec: 14.5707 2021-11-27 22:14:16,464 [INFO] tensorflow: global_step/sec: 14.5707 INFO:tensorflow:global_step/sec: 14.3698 2021-11-27 22:14:16,603 [INFO] tensorflow: global_step/sec: 14.3698 INFO:tensorflow:global_step/sec: 14.2 2021-11-27 22:14:16,744 [INFO] tensorflow: global_step/sec: 14.2 2021-11-27 22:14:16,745 [INFO] iva.detectnet_v2.tfhooks.task_progress_monitor_hook: Epoch 119/120: loss: 0.00056 learning rate: 0.00001 Time taken: 0:00:01.503073 ETA: 0:00:01.503073 INFO:tensorflow:global_step/sec: 14.925 2021-11-27 22:14:16,878 [INFO] tensorflow: global_step/sec: 14.925 INFO:tensorflow:global_step/sec: 14.7784 2021-11-27 22:14:17,013 [INFO] tensorflow: global_step/sec: 14.7784 INFO:tensorflow:global_step/sec: 14.4469 2021-11-27 22:14:17,152 [INFO] tensorflow: global_step/sec: 14.4469 2021-11-27 22:14:17,152 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.685 INFO:tensorflow:global_step/sec: 14.4737 2021-11-27 22:14:17,290 [INFO] tensorflow: global_step/sec: 14.4737 INFO:tensorflow:global_step/sec: 14.8276 2021-11-27 22:14:17,425 [INFO] tensorflow: global_step/sec: 14.8276 INFO:tensorflow:global_step/sec: 14.8145 2021-11-27 22:14:17,560 [INFO] tensorflow: global_step/sec: 14.8145 INFO:tensorflow:global_step/sec: 14.9416 2021-11-27 22:14:17,694 [INFO] tensorflow: global_step/sec: 14.9416 INFO:tensorflow:global_step/sec: 14.4597 2021-11-27 22:14:17,832 [INFO] tensorflow: global_step/sec: 14.4597 INFO:tensorflow:global_step/sec: 14.7073 2021-11-27 22:14:17,968 [INFO] tensorflow: global_step/sec: 14.7073 INFO:tensorflow:global_step/sec: 14.5652 2021-11-27 22:14:18,105 [INFO] tensorflow: global_step/sec: 14.5652 INFO:tensorflow:Saving checkpoints for step-2640. 2021-11-27 22:14:18,174 [INFO] tensorflow: Saving checkpoints for step-2640. WARNING:tensorflow:Ignoring: /tmp/tmpst265022; No such file or directory 2021-11-27 22:14:18,265 [WARNING] tensorflow: Ignoring: /tmp/tmpst265022; No such file or directory 2021-11-27 22:14:20,584 [INFO] iva.detectnet_v2.evaluation.evaluation: step 0 / 3, 0.00s/step Matching predictions to ground truth, class 1/9.: 100%|█| 671/671 [00:00<00:00, 24039.72it/s] Matching predictions to ground truth, class 3/9.: 100%|█| 33/33 [00:00<00:00, 22572.09it/s] Matching predictions to ground truth, class 4/9.: 100%|█| 134/134 [00:00<00:00, 24012.51it/s] Matching predictions to ground truth, class 6/9.: 100%|█| 532/532 [00:00<00:00, 23845.53it/s] Matching predictions to ground truth, class 7/9.: 100%|█| 198/198 [00:00<00:00, 24022.22it/s] Matching predictions to ground truth, class 8/9.: 100%|█| 702/702 [00:00<00:00, 23627.23it/s] Matching predictions to ground truth, class 9/9.: 100%|█| 954/954 [00:00<00:00, 30982.08it/s] Epoch 120/120 ========================= Validation cost: 0.000278 Mean average_precision (in %): 30.6785 class name average precision (in %) ------------ -------------------------- cardbox 0 ceiling 80.6844 floor 0 palette 10.2041 pillar 53.995 pushcart 0 rackframe 43.0036 rackshelf 48.4257 wall 39.7941 Median Inference Time: 0.007785 WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:95: The name tf.reset_default_graph is deprecated. Please use tf.compat.v1.reset_default_graph instead. 2021-11-27 22:14:22,764 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:95: The name tf.reset_default_graph is deprecated. Please use tf.compat.v1.reset_default_graph instead. WARNING:tensorflow:From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:98: The name tf.placeholder_with_default is deprecated. Please use tf.compat.v1.placeholder_with_default instead. 2021-11-27 22:14:22,764 [WARNING] tensorflow: From /usr/local/lib/python3.6/dist-packages/keras/backend/tensorflow_backend.py:98: The name tf.placeholder_with_default is deprecated. Please use tf.compat.v1.placeholder_with_default instead. 2021-11-27 22:14:22,766 [INFO] modulus.hooks.sample_counter_hook: Train Samples / sec: 58.685 Time taken to run __main__:main: 0:04:24.418081. 2021-11-27 17:14:24,569 [INFO] tlt.components.docker_handler.docker_handler: Stopping container.
pantelis-classes/omniverse-ai/Wikipages/Editing Synthetic Data Generation (Python API).md
# Synthetic Data in Omniverse from Isaac Sim Omniverse comes with synthetic data generation samples in Python. These can be found in (home/.local/share/ov/pkg/isaac_sim-2021.2.0/python_samples) ## Offline Dataset Generation This example will demonstrate how to generate synthetic dataset offline which can be used for training deep neural networks using default values. From the package root folder (home/.local/share/ov/pkg/isaac_sim-2021.2.0/) run this command to generate synthetic data: ./python.sh standalone_examples/replicator/offline_generation.py These are the arguments we can use: 1. --scenario: Specify the USD stage to load from omniverse server for dataset generation. 1. --num_frames: Number of frames to record. 1. --max_queue_size: Maximum size of queue to store and process synthetic data. If value of this field is less than or equal to zero, the queue size is infinite. 1. --data_dir: Location where data will be output. Default is ./output 1. --writer_mode: Specify output format - npy or kitti. Default is npy. When KittiWriter is used with the --writer_mode kitti argument, two more arguments become available. 6. --classes: Which classes to write labels for. Defaults to all classes. 7. --train_size: Number of frames for training set. Defaults to 8. queue size is infinite. With arguments, the above command looks like: ./python.sh standalone_examples/replicator/offline_generation.py --scenario omniverse://<server-name>/Isaac/Samples/Synthetic_Data/Stage/warehouse_with_sensors.usd --num_frames 10 --max_queue_size 500 All output data is stored within (home/.local/share/ov/pkg/isaac_sim-2021.1.1/output) ## Offline Training with TLT To leverage TLT, we need to have a dataset in the Kitti format. NVIDIA Transfer Learning Toolkit (TLT) is a Python-based AI toolkit for taking purpose-built pretrained AI models and customizing them with your own data. ### Offline Kitti Dataset Generation for this we add the argument --writer_mode kitti and specify the classes like in this example (not specifying an argument makes it use the default): ./python.sh standalone_examples/replicator/offline_generation.py --writer_mode kitti --classes ceiling floor --num_frames 500 --train_size 100 ![image](https://user-images.githubusercontent.com/589439/143666365-9cbab570-213f-403b-bdc9-d891025fabac.png) ![image](https://user-images.githubusercontent.com/589439/143666538-47885861-2340-4fca-9507-8a1a66d82fe9.png) ![image](https://user-images.githubusercontent.com/589439/143666560-4a7dd70c-abde-4af8-a1c7-16eab5d99bf3.png) ![omniverse data gen](https://user-images.githubusercontent.com/589439/143667012-183800ff-f197-44a7-9677-d19940a06179.gif) The python scripts can be extensively modified to generate more customized datasets (code deep dive to come). - The output of the synthetic data generation can be found in: `~/.local/share/ov/pkg/isaac_sim-2021.2.0/output` ![image](https://user-images.githubusercontent.com/589439/143666727-f7a06dbc-aba6-410f-8bd5-0aa24ecf38d3.png) - The dataset is divided into two folders; A Training and Test Dataset. The training dataset contains **images** and **labels** of the warehouse. ![image](https://user-images.githubusercontent.com/589439/143666820-b12aafdd-f1e1-4c46-889c-34af1c9ca929.png) ![image](https://user-images.githubusercontent.com/589439/143666829-813f9715-3a2d-49f1-9124-5a690681accc.png) ![image](https://user-images.githubusercontent.com/589439/143666852-90d659de-01a0-4685-bf36-42868e1c77d9.png) ![image](https://user-images.githubusercontent.com/589439/143666866-5896317b-1255-4e67-abe7-5f3ff03be288.png) - The test dataset contains only **images**. ![image](https://user-images.githubusercontent.com/589439/143666874-a453b635-63e6-44e0-94c1-7127e1c7f729.png) ![omniversepicgen](https://user-images.githubusercontent.com/589439/143667064-d0136cd5-9b3e-4b5d-987f-c013ff08d401.gif)
pantelis-classes/omniverse-ai/Wikipages/Isaac Sim SDK Omniverse Installation.md
## Prerequisites Ubuntu 18.04 LTS required Nvidia drivers 470 or higher ### Installing Nvidia Drivers on Ubuntu 18.04 LTS sudo apt-add-repository -r ppa:graphics-drivers/ppa ![image](https://user-images.githubusercontent.com/589439/143662835-6d5624b2-b78d-4ff2-acc3-efadc64d58a2.png) sudo apt update ![image](https://user-images.githubusercontent.com/589439/143662852-f99e89cc-1c28-4039-8c25-95c470de171f.png) sudo apt remove nvidia* ![image](https://user-images.githubusercontent.com/589439/143662863-5dbc78c5-c175-495e-bd36-5b214557774c.png) ![image](https://user-images.githubusercontent.com/589439/143662877-cd6abe58-973f-4da1-ac1c-9fe5d28a5853.png) sudo apt autoremove ![image](https://user-images.githubusercontent.com/589439/143662895-53e3155b-e8bf-498b-9bb3-4cbe39e1354a.png) ![image](https://user-images.githubusercontent.com/589439/143662915-70024577-3531-46da-8f6e-ea2d8d230e8a.png) sudo ubuntu-drivers autoinstall ![image](https://user-images.githubusercontent.com/589439/143662959-6b21b9f4-5462-4b9d-9a29-083fad49eafe.png) sudo apt install nvidia-driver-470 ![image](https://user-images.githubusercontent.com/589439/143662965-5e05ee0d-a48f-4161-a086-ab03bf6854bf.png) - Restart your PC. - Run nvidia-smi to make sure you are on the latest nvidia drivers for Isaac. nvidia-smi ![image](https://user-images.githubusercontent.com/589439/143663079-a9503fd4-75f1-4bb0-bfd8-ada3bd9fa2ec.png) ## Omniverse and Isaac Sim installation (executable) ### 1. Create nvidia developer account. This is required to access some of the downloads as well as obtaining API keys for Nvidia NGC - Go to this <a href="https://developer.nvidia.com/developer-program">link</a> and create an account. ![image](https://user-images.githubusercontent.com/589439/143655734-92f93f94-723b-4a03-aee3-9004ebdfa931.png) - Fill out your NVIDIA profile. ![image](https://user-images.githubusercontent.com/589439/143655803-423dddd8-398e-49e0-839f-d96a5e655441.png) ### 2. Go to this <a href="https://www.nvidia.com/en-us/omniverse/">omniverse link</a> and download Omniverse and install. ![image](https://user-images.githubusercontent.com/589439/143158851-a4f7a00b-4f25-40e0-ae2e-2fba3edef08e.png) - Fill out the form. ![image](https://user-images.githubusercontent.com/589439/143158880-17506781-abc2-4188-aca3-4546dcb475f9.png) - Click the download link for Linux. ![image](https://user-images.githubusercontent.com/589439/143158912-97fb24ad-8b49-432e-a3d7-4badb0977714.png) - Download and save the AppImage file to your ~/Downloads folder. ![image](https://user-images.githubusercontent.com/589439/143158967-afad1831-822f-4440-9a4b-9248c909007d.png) - Run these commands to execute the AppImage. cd ~/Downloads ls chmod +x omniverse-launcher-linux.AppImage ./omniverse-launcher-linux.AppImage ![image](https://user-images.githubusercontent.com/589439/143656306-85f1aefd-a6a8-4f07-a2e9-b7153ff175ce.png) ### 3. Login to Omniverse to install Isaac Sim 2021. - Login with your NVIDIA credentials. ![image](https://user-images.githubusercontent.com/589439/143160948-90380e23-e8cc-42b3-8933-4d88c5c9bc90.png) - Accept the terms of agreement. ![image](https://user-images.githubusercontent.com/589439/143161008-59913f3c-cfde-4c9f-93d4-609dc0346469.png) - Click continue. (default paths) ![image](https://user-images.githubusercontent.com/589439/143161046-21afc550-6bf7-450c-b023-3296de59d7b4.png) - Install cache. ![image](https://user-images.githubusercontent.com/589439/143161192-9936a489-e81d-4ccc-a2e0-caf120ce92c4.png) ### 4. Installing Isaac through Omniverse. - Click the Exchange tab in Omniverse. ![image](https://user-images.githubusercontent.com/589439/143165080-9daa5e96-99c0-4e60-9a40-ff4f77944311.png) - Search for Isaac and Click Isaac Sim. ![image](https://user-images.githubusercontent.com/589439/143165387-659a75bf-ba62-49e4-9bab-320b0da9eeb1.png) - Click install. ![image](https://user-images.githubusercontent.com/589439/143165778-75f9cbea-b93b-4c0a-9661-269ec0e643f5.png) ### 5. Go to the nucleus tab and create a nucleus local server to run the Omniverse Isaac Sim Samples. - Create your local nucleus account by clicking the Nucleus tab in Omniverse. - Click Add Local Nucleus Service. ![image](https://user-images.githubusercontent.com/589439/143163402-c38ef3e5-64a8-437f-8a4c-7f978b37e40b.png) - Click Next. (Default Path) ![image](https://user-images.githubusercontent.com/589439/143163446-5fa6c2bc-6437-4239-bcd7-5be8f9159de7.png) - Create Administrator Account. - Go to this <a href="https://developer.nvidia.com/nvidia-isaac-sim-assets-20211">link</a> and download the Isaac Sim Assets. ![image](https://user-images.githubusercontent.com/589439/143163494-95fba91c-12b3-4228-ae21-39ce639d66b4.png) - Unzip the by going to your downloads folder and right clicking isaac-sim-assets-2021.1.1.zip and choosing "extract here". ![image](https://user-images.githubusercontent.com/589439/143657912-d33c71f8-1965-4ca2-b06c-3d0790ffd1e4.png) - Log into the Nucleus Service with the credentials you created. ![image](https://user-images.githubusercontent.com/589439/143163725-d7b1a5ae-2391-4da0-9a70-f58ce063eb38.png) - Create an Isaac Folder. (Right click localhost) ![image](https://user-images.githubusercontent.com/589439/143164075-7cfacb0b-a2e2-4e29-a63f-85316f585a5e.png) ![image](https://user-images.githubusercontent.com/589439/143164125-851ba73c-0cc8-4555-b5d8-769d54625d8d.png) ![image](https://user-images.githubusercontent.com/589439/143657335-7499d95b-d4e0-44bd-88f9-87f4d73a9de9.png) - Drag and drop the the files in the isaac-sim-assets-2021.1.1. folder into the Isaac folder in Omniverse. (NOT THE .ZIP; THE FILES IN THE FOLDER THAT WAS CREATED WHEN YOU EXTRACTED IT). ![image](https://user-images.githubusercontent.com/589439/143666284-5ff41514-5c89-4cc7-afa0-b17ed9003b61.png) - Click upload. ![image](https://user-images.githubusercontent.com/589439/143657451-f9792fd1-e085-4850-a5b5-1ccbe9d4d4e5.png) ![image](https://user-images.githubusercontent.com/589439/143666323-eb172e58-d0cb-4228-af31-f9f7daf43d19.png) ### 6. Now launch Isaac Sim from the Library Omniverse tab within Omniverse. - Click Launch in the Library Tab of Omniverse. ![image](https://user-images.githubusercontent.com/589439/143657605-6b09b104-698d-4eba-b5f7-e027eee033eb.png) - Click Start with the default settings with "Issac Sim" selected. ![image](https://user-images.githubusercontent.com/589439/143657653-c3d31131-1da7-4919-b7dd-8a9555c4aba6.png) - Once Isaac Sim has finished loading, login to localhost with the browser window that opened. ![image](https://user-images.githubusercontent.com/589439/143658289-5d6ed582-e15f-4ca7-b3dd-b7cd1d37a2fb.png) ![image](https://user-images.githubusercontent.com/589439/143658399-7538b399-a050-4468-842f-32cfe782bf80.png) From here we can launch the Isaac Sim application. Currently there is no way to generate KITTI formated output synthetic data (which is required for Nvidia's transfer learning) from the domain randomizer within the application itself. For this we need to use Omniverse's built in python environment. ## Python API Installation 1. Using the Linux command line interface (terminal), go to the packages root folder (home/.local/share/ov/pkg/isaac_sim-2021.2.0/). cd ~/.local/share/ov/pkg/isaac_sim-2021.2.0/ ls ![image](https://user-images.githubusercontent.com/589439/143659975-91da9c57-e9c0-4c41-a208-c02010656a83.png) 2. Run the following command to get all the required dependencies: ./python.sh -m pip install -r requirements.txt ![image](https://user-images.githubusercontent.com/589439/143660049-8e2288b8-14c4-4503-a4d4-56fb45574849.png)
pantelis-classes/omniverse-ai/Wikipages/TAO (NVIDIA Train, Adapt, and Optimize).md
All instructions stem from this <a href="https://docs.nvidia.com/tao/tao-toolkit/text/tao_toolkit_quick_start_guide.html">Nvidia Doc</a>. # Requirements ### Hardware Requirements (Recommended) 32 GB system RAM 32 GB of GPU RAM 8 core CPU 1 NVIDIA GPU 100 GB of SSD space ### Hardware Requirements (REQUIRED) - TAO Toolkit is supported on **A100**, **V100** and **RTX 30x0 GPUs**. # Login to the NGC docker registry. Login to the NGC docker registry: Use the command docker login nvcr.io and enter the following credentials: a. Username: "$oauthtoken" b. Password: "YOUR_NGC_API_KEY" - Where YOUR_NGC_API_KEY corresponds to the key you generated from step 3. ![image](https://user-images.githubusercontent.com/589439/143663405-5323b62f-74a8-409f-80a8-c2c6ad961497.png) # Installing TAO Toolkit - TAO Toolkit is a Python pip package that is hosted on the NVIDIA PyIndex. The package uses the docker restAPI under the hood to interact with the NGC Docker registry to pull and instantiate the underlying docker containers. You must have an NGC account and an API key associated with your account. See the Installation Prerequisites section for details on creating an NGC account and obtaining an API key. ## 1. Create a new virtualenv using virtualenvwrapper - Click this <a href="https://python-guide-cn.readthedocs.io/en/latest/dev/virtualenvs.html"> link</a> to understand how virtual enviroments in python work. - Make sure you have virtualenv installed by checking it's version. (Instructions are in this <a href="https://github.com/pantelis-classes/omniverse-ai/wiki/NVIDIA-Transfer-Learning-Toolkit-(TLT)-Installation#1-create-new-python-virtual-environment">page</a> of the) virtualenv --version ![image](https://user-images.githubusercontent.com/589439/143723668-73111ae8-0ac5-4729-b89b-481d29b25d16.png) ## 2. Define the environment variable called VIRTUALENVWRAPPER_PYTHON. - Run this command to see where your python is located. which python3 ![image](https://user-images.githubusercontent.com/589439/143723824-968874c9-5f8e-44cc-a535-d0d336a72b78.png) - Define the environment variable of your Python location. export VIRTUALENVWRAPPER_PYTHON=/usr/bin/python3 ![image](https://user-images.githubusercontent.com/589439/143723906-baf552bc-e9d1-435b-8d43-553f6f0a6707.png) - Run this command to make sure the enviroment variable was created. (There should be red output with the variable name.) env | grep 'VIRTUALENVWRAPPER_PYTHON' ![image](https://user-images.githubusercontent.com/589439/143723930-c9c8658f-339d-4693-894a-daf70dea28ae.png) - Run this command. source `which virtualenvwrapper.sh` - Run this command to create a virtualenv named "TAO". mkvirtualenv TAO -p $VIRTUALENVWRAPPER_PYTHON ![image](https://user-images.githubusercontent.com/589439/143724459-afaf363f-dd92-494b-9707-5400f409d05a.png) - You should now see a (TAO) prepending your username in the CLI. ![image](https://user-images.githubusercontent.com/589439/143724476-77609fc2-e5a7-4773-94d9-799f2b78be6f.png) ## Intructions on how to activate/deactive the vitualenv. - When you are done with you session, you may deactivate your virtualenv using the deactivate command: deactivate ![image](https://user-images.githubusercontent.com/589439/143724159-ae6c0578-14e4-463b-8287-ef4147ff0f34.png) - You may re-instantiate this created virtualenv env using the workon command. workon TAO ![image](https://user-images.githubusercontent.com/589439/143724492-3036d310-3569-4820-9087-daca2bf9869f.png) ## 3. Download Jupyter Notebook. - TAO Toolkit provides samples notebooks to walk through and prescrible TAO workflow. These samples are hosted on NGC as a resource and can be downloaded from NGC by executing the command mentioned below. - Run these commands to set up your notebook. workon TAO ![image](https://user-images.githubusercontent.com/589439/143725152-cbbd609d-6d94-452c-8a48-a2bcf66dc4ab.png) - Copy the command belown and keep pressing enter until you are in ~/cv_samples_v1.2.0. wget --content-disposition https://api.ngc.nvidia.com/v2/resources/nvidia/tao/cv_samples/versions/v1.2.0/zip -O cv_samples_v1.2.0.zip unzip -u cv_samples_v1.2.0.zip -d ./cv_samples_v1.2.0 && rm -rf cv_samples_v1.2.0.zip && cd ./cv_samples_v1.2.0 ![image](https://user-images.githubusercontent.com/589439/143725176-02cc805c-4a98-4afe-9d49-ff17b48e171c.png) ![image](https://user-images.githubusercontent.com/589439/143725173-3c7d7cf0-c3b7-487a-9ed9-818aa5615e84.png) ![image](https://user-images.githubusercontent.com/589439/143725183-3d1caa61-125e-43fe-be67-683429c272ab.png) ## 4. Start Jupyter Notebook - Once the notebook samples are downloaded, you may start the notebook using the below commands: jupyter notebook --ip 0.0.0.0 --port 8888 --allow-root ![image](https://user-images.githubusercontent.com/589439/143725216-d67fe159-5f1f-47b1-8dbe-5c14a4e6a7aa.png) - Open an internet browser on localhost and navigate to the following URL: http://0.0.0.0:8888 ![image](https://user-images.githubusercontent.com/589439/143725228-4696d70e-ec0b-485c-985b-3bffb83be6ac.png) - Navigate to ./detectnet_v2/detectnet_v2.ipynb ![image](https://user-images.githubusercontent.com/589439/143725266-806cf049-c46f-4e22-9940-ac4e9d952117.png) ![image](https://user-images.githubusercontent.com/589439/143725290-0778740c-3b39-45b4-8d83-a254f545844c.png) ![image](https://user-images.githubusercontent.com/589439/143725306-14110acd-9a61-460a-be5d-df45a55c5b65.png)
pantelis-classes/omniverse-ai/Wikipages/_Sidebar.md
# Isaac Sim in Omniverse * [Home][home] * [Isaac-Sim-SDK-Omniverse-Installation][Omniverse] * [Synthetic-Data-Generation][SDG] * [NVIDIA Transfer Learning Toolkit (TLT) Installation][TLT] * [NVIDIA TAO][TAO] * [detectnet_v2 Installation][detectnet_v2] * [Jupyter Notebook][Jupyter-Notebook] [home]: https://github.com/pantelis-classes/omniverse-ai/wiki [Omniverse]: https://github.com/pantelis-classes/omniverse-ai/wiki/Isaac-Sim-SDK-Omniverse-Installation [SDG]: https://github.com/pantelis-classes/omniverse-ai/wiki/Synthetic-Data-Generation-(Python-API) [TLT]: https://github.com/pantelis-classes/omniverse-ai/wiki/NVIDIA-Transfer-Learning-Toolkit-(TLT)-Installation [NTLTSD]: https://github.com/pantelis-classes/omniverse-ai/wiki/Using-NVIDIA-TLT-with-Synthetic-Data [TAO]: https://github.com/pantelis-classes/omniverse-ai/wiki/TAO-(NVIDIA-Train,-Adapt,-and-Optimize) [detectnet_v2]: https://github.com/pantelis-classes/omniverse-ai/wiki/detectnet_v2-Installation [Jupyter-Notebook]: https://github.com/pantelis-classes/omniverse-ai/wiki/Jupyter-Notebook
pantelis-classes/omniverse-ai/Wikipages/home.md
# Learning in Simulated Worlds in Omniverse. ## Wiki Navigation * [Home][home] * [Isaac-Sim-SDK-Omniverse-Installation][Omniverse] * [Synthetic-Data-Generation][SDG] * [NVIDIA Transfer Learning Toolkit (TLT) Installation][TLT] * [NVIDIA TAO][TAO] * [detectnet_v2 Installation][detectnet_v2] * [Jupyter Notebook][Jupyter-Notebook] [home]: https://github.com/pantelis-classes/omniverse-ai/wiki [Omniverse]: https://github.com/pantelis-classes/omniverse-ai/wiki/Isaac-Sim-SDK-Omniverse-Installation [SDG]: https://github.com/pantelis-classes/omniverse-ai/wiki/Synthetic-Data-Generation-(Python-API) [TLT]: https://github.com/pantelis-classes/omniverse-ai/wiki/NVIDIA-Transfer-Learning-Toolkit-(TLT)-Installation [NTLTSD]: https://github.com/pantelis-classes/omniverse-ai/wiki/Using-NVIDIA-TLT-with-Synthetic-Data [TAO]: https://github.com/pantelis-classes/omniverse-ai/wiki/TAO-(NVIDIA-Train,-Adapt,-and-Optimize) [detectnet_v2]: https://github.com/pantelis-classes/omniverse-ai/wiki/detectnet_v2-Installation [Jupyter-Notebook]: https://github.com/pantelis-classes/omniverse-ai/wiki/Jupyter-Notebook <hr /> ## Reports <a href="https://docs.google.com/document/d/1jVXxrNgtOosZw_vAORzomSnmy45G3qK_mmk2B4oJtPg/edit?usp=sharing">Domain Randomization Paper</a><br> This report provides an indepth understanding on how Domain Randomization helps perception machine learning tasks such as object detection and/or segmentation. <a href="https://docs.google.com/document/d/1WAzdqlWE0RUns41-0P951mnsqMR7I2XV/edit?usp=sharing&ouid=112712585131518554614&rtpof=true&sd=true">Final Report</a><br> This final report contains an indepth explanation on the hardware/software used, the methods used to collect the data, an explanation on the data collected, trained and pruned, and the overall conclusions made from the trained and pruned datasets.
pantelis-classes/omniverse-ai/Wikipages/NVIDIA Transfer Learning Toolkit (TLT) Installation.md
# Installing the Pre-requisites ## 1. Install docker-ce: ### * Set up repository: Update apt package index and install packages. sudo apt-get update ![image](https://user-images.githubusercontent.com/589439/143660967-37eb6626-62c0-4afa-af3a-c43a3c172e85.png) sudo apt-get install \ ca-certificates \ curl \ gnupg \ lsb-release - The following image has these dependencies already installed. ![image](https://user-images.githubusercontent.com/589439/143660985-4ae4366b-8d28-4514-b1df-bd7fe03e581d.png) Add Docker's official GPG key: curl -fsSL https://download.docker.com/linux/ubuntu/gpg | sudo gpg --dearmor -o /usr/share/keyrings/docker-archive-keyring.gpg ![image](https://user-images.githubusercontent.com/589439/143661077-2d0ce142-be2f-4ab6-ad99-a685fa709182.png) ### * Install Docker Engine: Update the apt package index, and install the latest version of Docker Engine. sudo apt-get update ![image](https://user-images.githubusercontent.com/589439/143661094-a2b86161-c37f-42fd-9110-34523343f65a.png) sudo apt-get install docker-ce docker-ce-cli containerd.io ![image](https://user-images.githubusercontent.com/589439/143661447-8fa25b3b-1c79-470d-b962-88c21bd56f63.png) Verify that Docker Engine is installed correctly by running the hello-world image. sudo docker run hello-world ![image](https://user-images.githubusercontent.com/589439/143661433-d67e18ac-c098-4665-b7ba-127e397b0df6.png) ### * Manage Docker as a non-root user: Create the docker group. sudo groupadd docker ![image](https://user-images.githubusercontent.com/589439/143661491-c43c3f94-90d7-47d4-8bd4-dee974f67838.png) Add your user to the docker group. sudo usermod -aG docker $USER ![image](https://user-images.githubusercontent.com/589439/143661478-cff5282c-e864-4821-a084-7f1f8360b4bc.png) Log out and log back in so that your group membership is re-evaluated. ![image](https://user-images.githubusercontent.com/589439/143661541-098c52b5-0c54-46c9-9d14-fd0250f27a1e.png) Verify that you can run docker commands without sudo. docker run hello-world ![image](https://user-images.githubusercontent.com/589439/143661708-6baceb75-a047-4f75-8b51-9496e6908d15.png) - If you get the WARNING error in the above image, run these two commands. Otherwise Skip to #2. sudo chown "$USER":"$USER" /home/"$USER"/.docker -R sudo chmod g+rwx "/home/$USER/.docker" -R - Run docker run hello-world to double check it works now. docker run hello-world ![image](https://user-images.githubusercontent.com/589439/143661749-52f2103f-19c5-47bb-85b3-0b5069957b87.png) ## 2. Install NVIDIA Container Toolkit: Setup the stable repository and the GPG key: distribution=$(. /etc/os-release;echo $ID$VERSION_ID) \ && curl -s -L https://nvidia.github.io/nvidia-docker/gpgkey | sudo apt-key add - \ && curl -s -L https://nvidia.github.io/nvidia-docker/$distribution/nvidia-docker.list | sudo tee /etc/apt/sources.list.d/nvidia-docker.list ![image](https://user-images.githubusercontent.com/589439/143662010-9b31cc9d-bbbe-4aa7-af69-ade75e18ccc6.png) Install the nvidia-docker2 package (and dependencies) after updating the package listing: sudo apt-get update sudo apt-get install -y nvidia-docker2 ![image](https://user-images.githubusercontent.com/589439/143662034-8e020c83-780b-40d0-a17b-ad0cdfd4210f.png) Restart the Docker daemon to complete the installation after setting the default runtime: sudo systemctl restart docker ![image](https://user-images.githubusercontent.com/589439/143662068-dfcad334-8466-4c9a-9cd0-e08a23f31b66.png) At this point, a working setup can be tested by running a base CUDA container: sudo docker run --rm --gpus all nvidia/cuda:11.0-base nvidia-smi - This should result in a console output shown below: ![image](https://user-images.githubusercontent.com/589439/143663183-0bdb6ee0-84be-4788-bdc7-0ab23e9e5d41.png) ## 3. Get an NVIDIA NGC account and API key: - Go to <a href="https://ngc.nvidia.com/signin">NGC</a> and click the Transfer Learning Toolkit container in the Catalog tab. This message is displayed: “Sign in to access the PULL feature of this repository”. ![image](https://user-images.githubusercontent.com/589439/143662546-8e8053f4-9aa9-40bb-bb8c-432d652db64b.png) - Enter your Email address and click Next, or click Create an Account. - Choose your organization when prompted for Organization/Team. - Click Sign In. - Once redirected to this <a href="https://catalog.ngc.nvidia.com/">page</a> with your account made, click the top right corner to click your profile and click "Setup" ![image](https://user-images.githubusercontent.com/589439/143662652-a6595488-44e6-494e-8e11-17056209a3fd.png) - Click Get API Key. ![image](https://user-images.githubusercontent.com/589439/143662747-cda7d160-6f1f-41dc-815f-65bf13ba7bc7.png) - Click Generate API Key. ![image](https://user-images.githubusercontent.com/589439/143662782-9bebeb67-26ec-4980-9624-1a91f0d1a6cc.png) - Your API key and username will be shown under the DOCKER tm section. Copy the text with your username and API password and save it in a file somewhere. ![image](https://user-images.githubusercontent.com/589439/143663255-907bff87-ae02-4c4d-8400-ef6a914c3aae.png) ![image](https://user-images.githubusercontent.com/589439/143663347-4ec70e43-da4d-4b97-bd26-b336586bc9d7.png) ## 4. Login to the NGC docker registry: Use the command docker login nvcr.io and enter the following credentials: a. Username: "$oauthtoken" b. Password: "YOUR_NGC_API_KEY" - Where YOUR_NGC_API_KEY corresponds to the key you generated from step 3. ![image](https://user-images.githubusercontent.com/589439/143663405-5323b62f-74a8-409f-80a8-c2c6ad961497.png) # Installing TLT The Transfer Learning Toolkit (TLT) is a Python pip package that is hosted on the NVIDIA PyIndex. The package uses the docker restAPI under the hood to interact with the NGC Docker registry to pull and instantiate the underlying docker containers. ## 1. Create new Python virtual environment. ### Python virtualenv setup using virtualenvwrapper Install via pip: pip3 install virtualenv ![image](https://user-images.githubusercontent.com/589439/143667101-35f5e890-f96d-4a24-8f85-4db1ff95ab8f.png) pip3 install virtualenvwrapper ![image](https://user-images.githubusercontent.com/589439/143667117-cef7ead6-5ca1-4f93-b759-4caa9c8dca76.png)
pantelis-classes/omniverse-ai/Wikipages/_Footer.md
## Authors ### <a href="https://github.com/dfsanchez999">Diego Sanchez</a> | <a href="https://harp.njit.edu/~jga26/">Jibran Absarulislam</a> | <a href="https://github.com/markkcruz">Mark Cruz</a> | <a href="https://github.com/sppatel2112">Sapan Patel</a> ## Supervisor ### <a href="https://pantelis.github.io/">Dr. Pantelis Monogioudis</a> ## Credits ### <a href="https://developer.nvidia.com/nvidia-omniverse-platform">NVIDIA Omniverse</a>
pantelis-classes/omniverse-ai/Wikipages/detectnet_v2 Installation.md
# Installing running detectnet_v2 in a jupyter notebook ## Setup File Structures. - Run these commands to create the correct file structure. cd ~ mkdir tao mv cv_samples_v1.2.0/ tao cd tao/cv_samples_v1.2.0/ rm -r detectnet_v2 ![image](https://user-images.githubusercontent.com/589439/143797815-904b6033-f5db-43ac-a736-d653d4d19cfe.png) ![image](https://user-images.githubusercontent.com/589439/143797903-cd33e342-e45d-44ca-a8ac-6efb6d2cd18f.png) - Download the detectnet_v2.zip from this <a href="https://github.com/pantelis-classes/omniverse-ai/raw/main/detectnet_v2.zip">link</a>. ![image](https://user-images.githubusercontent.com/589439/143727479-6828fc05-4672-4c60-8a21-f1fe6e97d0ea.png) - Run this command to move the .zip from your downloads folder to your detectnet_v2 folder. mv ~/Downloads/detectnet_v2.zip ~/tao/cv_samples_v1.2.0/ ![image](https://user-images.githubusercontent.com/589439/143798005-a702ed00-5971-4ece-b60a-d05e14fa09b9.png) - Run this command to unzip the folder. unzip ~/tao/cv_samples_v1.2.0/detectnet_v2.zip -d detectnet_v2 ![image](https://user-images.githubusercontent.com/589439/143798404-ae066e4a-d573-4144-a1ec-b5410db9efb7.png) ![image](https://user-images.githubusercontent.com/589439/143798434-9d14756d-2bdb-4f68-88cb-0e5610562034.png) - Run this command to copy your dataset to the TAO folder. (You generated this dataset in this <a href="https://github.com/pantelis-classes/omniverse-ai/wiki/Synthetic-Data-Generation-(Python-API)#offline-training-with-tlt">wiki page</a>.) cp -r ~/.local/share/ov/pkg/isaac_sim-2021.2.0/output/testing/ ~/tao/cv_samples_v1.2.0/detectnet_v2/workspace/tao-experiment/data/ cp -r ~/.local/share/ov/pkg/isaac_sim-2021.2.0/output/training/ ~/tao/cv_samples_v1.2.0/detectnet_v2/workspace/tao-experiment/data/ ![image](https://user-images.githubusercontent.com/589439/143798514-be064b8e-18e9-4f21-97b2-ef72820190a8.png) ![image](https://user-images.githubusercontent.com/589439/143798539-d7555c9c-87c3-4037-819a-ee32aca9fa44.png) - Navigate to Home -> cv_samples_v1.2.0 -> detectnet_v2 - Open the detectnet_v2.ipynb file. ![image](https://user-images.githubusercontent.com/589439/143729232-16e479b2-527e-4b0f-94b0-e43bd08cfba8.png) - Scroll down to section "0. Set up env variables and map drives" (Ctrl + F) ![image](https://user-images.githubusercontent.com/589439/143729413-dffdd2dc-d0cb-40aa-8b0f-fd567b2a527c.png) - Replace "diego" with your username. (TIP: whoami in BASH) ![image](https://user-images.githubusercontent.com/589439/143729441-e43fde75-76ed-489d-acef-56fea5ddf539.png) ![image](https://user-images.githubusercontent.com/589439/143729521-c7b0fc38-baf0-4701-9032-dba324497f5e.png)
pantelis-classes/omniverse-ai/Wikipages/Jupyter Notebook.md
# Object Detection using TAO DetectNet_v2 - Transfer learning is the process of transferring learned features from one application to another. It is a commonly used training technique where you use a model trained on one task and re-train to use it on a different task. - Train Adapt Optimize (TAO) Toolkit is a simple and easy-to-use Python based AI toolkit for taking purpose-built AI models and customizing them with users' own data. ## How to use the notebook. - Please refer to the actual jupyter notebook to have more in-depth explanations of the code. - Each Cell will run some lines of code. Start from the top of the notebook and run each cell by click the play button or using **shift + enter**. ![image](https://user-images.githubusercontent.com/589439/143809035-2ae69802-7929-47a6-a445-12b571cacd14.png) - Some of the cells may take a long time to complete. Please do not skip cells and wait for the output to finish. ## 0. Set up env variables and map drives ![image](https://user-images.githubusercontent.com/589439/143808844-e4244060-5842-41e2-868d-7a75c57a3c21.png) ![image](https://user-images.githubusercontent.com/589439/143809423-cea91ff5-916f-4c03-b7c3-e4eb625756a4.png) - We set up the env variables by linking paths, setting number of GPUs, and choosing an encoding style. ## 1. Install the TAO launcher - This step should have been already completed in the previous wiki pages. Please refer to this <a href="https://github.com/pantelis-classes/omniverse-ai/wiki/TAO-(NVIDIA-Train,-Adapt,-and-Optimize)#login-to-the-ngc-docker-registry">link</a>. ![image](https://user-images.githubusercontent.com/589439/143809877-6e766d73-ff1c-405f-bd6f-600a58736b25.png) ## 2. Prepare dataset and pre-trained model ![image](https://user-images.githubusercontent.com/589439/143809929-1e119a3b-0239-4144-bece-a1d9aa7d51bf.png) ![image](https://user-images.githubusercontent.com/589439/143809965-7997fd22-e172-4360-af13-8c0d65b83f4e.png) ![image](https://user-images.githubusercontent.com/589439/143809992-3a41471a-dd02-4a3e-acea-96b7a7c3a674.png) ![image](https://user-images.githubusercontent.com/589439/143810068-5f175928-4e4d-4820-8b14-067a31b35cd6.png) ![image](https://user-images.githubusercontent.com/589439/143810077-6bfb77d3-4643-4129-a8c4-0b4fbf196b43.png) ![image](https://user-images.githubusercontent.com/589439/143810093-f8508bb1-5728-4010-b87b-21f4aed74e73.png) ![image](https://user-images.githubusercontent.com/589439/143810115-c88787cb-3cae-433a-93c8-712a25db0c78.png) ## 3. Provide training specification ![image](https://user-images.githubusercontent.com/589439/143810872-231209ca-eb71-4bd2-930d-3527fbaaace0.png) ## 4. Run TAO training ![image](https://user-images.githubusercontent.com/589439/143810896-a9875ab8-b9ab-4ced-ad49-c47ea321a052.png) ## 5. Evaluate the trained model ![image](https://user-images.githubusercontent.com/589439/143811275-488e15be-15bd-4341-8392-834cd68bbcad.png) ## 6. Prune the trained model ![image](https://user-images.githubusercontent.com/589439/143810915-c9428405-1f00-462d-8a80-2d1467c95e7b.png) ## 7. Retrain the pruned model ![image](https://user-images.githubusercontent.com/589439/143810942-972f34b4-b7a4-4532-9e8d-6f6bcc01ac9f.png) ![image](https://user-images.githubusercontent.com/589439/143810970-69367200-b71e-481f-b813-3d447e154bb3.png) ## 8. Evaluate the retrained model ![image](https://user-images.githubusercontent.com/589439/143811255-0b946589-2679-4747-b514-3b91ac2259cd.png) ## 9. Visualize inferences ![image](https://user-images.githubusercontent.com/589439/143811032-4adc40ef-fa0e-4596-88b5-2a24610cdaf3.png) ![image](https://user-images.githubusercontent.com/589439/143811081-edaa58f5-d3e6-40c6-9dab-f19e547d090e.png)
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/CODE_OF_CONDUCT.md
## Code of Conduct This project has adopted the [Amazon Open Source Code of Conduct](https://aws.github.io/code-of-conduct). For more information see the [Code of Conduct FAQ](https://aws.github.io/code-of-conduct-faq) or contact [email protected] with any additional questions or comments.
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/package.json
{ "name": "omni-app", "version": "0.1.0", "bin": { "omni-app": "bin/omni-app.js" }, "scripts": { "build": "tsc", "watch": "tsc -w", "test": "jest", "cdk": "cdk" }, "devDependencies": { "@types/jest": "^26.0.10", "@types/node": "10.17.27", "aws-cdk": "2.20.0", "jest": "^26.4.2", "ts-jest": "^26.2.0", "ts-node": "^9.0.0", "typescript": "~3.9.7" }, "dependencies": { "@aws-cdk/aws-lambda-python-alpha": "2.88.0-alpha.0", "aws-cdk-lib": "2.88.0", "cdk-nag": "^2.14.13", "constructs": "^10.0.0", "dotenv": "^16.0.3", "envalid": "^7.2.1", "source-map-support": "^0.5.16" } }
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/package-lock.json
{ "name": "omni-app", "version": "0.1.0", "lockfileVersion": 3, "requires": true, "packages": { "": { "name": "omni-app", "version": "0.1.0", "dependencies": { "@aws-cdk/aws-lambda-python-alpha": "2.88.0-alpha.0", "aws-cdk-lib": "2.88.0", "cdk-nag": "^2.14.13", "constructs": "^10.0.0", "dotenv": "^16.0.3", "envalid": "^7.2.1", "source-map-support": "^0.5.16" }, "bin": { "omni-app": "bin/omni-app.js" }, "devDependencies": { "@types/jest": "^26.0.10", "@types/node": "10.17.27", "aws-cdk": "2.20.0", "jest": "^26.4.2", "ts-jest": "^26.2.0", "ts-node": "^9.0.0", "typescript": "~3.9.7" } }, "node_modules/@ampproject/remapping": { "version": "2.2.1", "resolved": "https://registry.npmjs.org/@ampproject/remapping/-/remapping-2.2.1.tgz", "integrity": "sha512-lFMjJTrFL3j7L9yBxwYfCq2k6qqwHyzuUl/XBnif78PWTJYyL/dfowQHWE3sp6U6ZzqWiiIZnpTMO96zhkjwtg==", "dev": true, "dependencies": { "@jridgewell/gen-mapping": "^0.3.0", "@jridgewell/trace-mapping": "^0.3.9" }, "engines": { "node": ">=6.0.0" } }, "node_modules/@aws-cdk/asset-awscli-v1": { "version": "2.2.200", "resolved": "https://registry.npmjs.org/@aws-cdk/asset-awscli-v1/-/asset-awscli-v1-2.2.200.tgz", "integrity": "sha512-Kf5J8DfJK4wZFWT2Myca0lhwke7LwHcHBo+4TvWOGJrFVVKVuuiLCkzPPRBQQVDj0Vtn2NBokZAz8pfMpAqAKg==" }, "node_modules/@aws-cdk/asset-kubectl-v20": { "version": "2.1.2", "resolved": "https://registry.npmjs.org/@aws-cdk/asset-kubectl-v20/-/asset-kubectl-v20-2.1.2.tgz", "integrity": "sha512-3M2tELJOxQv0apCIiuKQ4pAbncz9GuLwnKFqxifWfe77wuMxyTRPmxssYHs42ePqzap1LT6GDcPygGs+hHstLg==" }, "node_modules/@aws-cdk/asset-node-proxy-agent-v5": { "version": "2.0.166", "resolved": "https://registry.npmjs.org/@aws-cdk/asset-node-proxy-agent-v5/-/asset-node-proxy-agent-v5-2.0.166.tgz", "integrity": "sha512-j0xnccpUQHXJKPgCwQcGGNu4lRiC1PptYfdxBIH1L4dRK91iBxtSQHESRQX+yB47oGLaF/WfNN/aF3WXwlhikg==" }, "node_modules/@aws-cdk/aws-lambda-python-alpha": { "version": "2.88.0-alpha.0", "resolved": "https://registry.npmjs.org/@aws-cdk/aws-lambda-python-alpha/-/aws-lambda-python-alpha-2.88.0-alpha.0.tgz", "integrity": "sha512-CdSLWAeHLx9uRqAt9OhaWmlsc1wrDEMIDtRWCHVwPW1oVzEjiQ1yUH3sRxZtL0O9rRXpZbJrtUdOM+3SZld64w==", "engines": { "node": ">= 14.15.0" }, "peerDependencies": { "aws-cdk-lib": "2.88.0", "constructs": "^10.0.0" } }, "node_modules/@babel/code-frame": { "version": "7.22.13", "resolved": "https://registry.npmjs.org/@babel/code-frame/-/code-frame-7.22.13.tgz", "integrity": "sha512-XktuhWlJ5g+3TJXc5upd9Ks1HutSArik6jf2eAjYFyIOf4ej3RN+184cZbzDvbPnuTJIUhPKKJE3cIsYTiAT3w==", "dev": true, "dependencies": { "@babel/highlight": "^7.22.13", "chalk": "^2.4.2" }, "engines": { "node": ">=6.9.0" } }, "node_modules/@babel/code-frame/node_modules/ansi-styles": { "version": "3.2.1", "resolved": "https://registry.npmjs.org/ansi-styles/-/ansi-styles-3.2.1.tgz", "integrity": "sha512-VT0ZI6kZRdTh8YyJw3SMbYm/u+NqfsAxEpWO0Pf9sq8/e94WxxOpPKx9FR1FlyCtOVDNOQ+8ntlqFxiRc+r5qA==", "dev": true, "dependencies": { "color-convert": "^1.9.0" }, "engines": { "node": ">=4" } }, "node_modules/@babel/code-frame/node_modules/chalk": { "version": "2.4.2", "resolved": "https://registry.npmjs.org/chalk/-/chalk-2.4.2.tgz", "integrity": "sha512-Mti+f9lpJNcwF4tWV8/OrTTtF1gZi+f8FqlyAdouralcFWFQWF2+NgCHShjkCb+IFBLq9buZwE1xckQU4peSuQ==", "dev": true, "dependencies": { "ansi-styles": "^3.2.1", "escape-string-regexp": "^1.0.5", "supports-color": "^5.3.0" }, "engines": { "node": ">=4" } }, "node_modules/@babel/code-frame/node_modules/color-convert": { "version": "1.9.3", "resolved": "https://registry.npmjs.org/color-convert/-/color-convert-1.9.3.tgz", "integrity": "sha512-QfAUtd+vFdAtFQcC8CCyYt1fYWxSqAiK2cSD6zDB8N3cpsEBAvRxp9zOGg6G/SHHJYAT88/az/IuDGALsNVbGg==", "dev": true, "dependencies": { "color-name": "1.1.3" } }, "node_modules/@babel/code-frame/node_modules/color-name": { "version": "1.1.3", "resolved": "https://registry.npmjs.org/color-name/-/color-name-1.1.3.tgz", "integrity": "sha512-72fSenhMw2HZMTVHeCA9KCmpEIbzWiQsjN+BHcBbS9vr1mtt+vJjPdksIBNUmKAW8TFUDPJK5SUU3QhE9NEXDw==", "dev": true }, "node_modules/@babel/code-frame/node_modules/escape-string-regexp": { "version": "1.0.5", "resolved": "https://registry.npmjs.org/escape-string-regexp/-/escape-string-regexp-1.0.5.tgz", "integrity": "sha512-vbRorB5FUQWvla16U8R/qgaFIya2qGzwDrNmCZuYKrbdSUMG6I1ZCGQRefkRVhuOkIGVne7BQ35DSfo1qvJqFg==", "dev": true, "engines": { "node": ">=0.8.0" } }, "node_modules/@babel/code-frame/node_modules/has-flag": { "version": "3.0.0", "resolved": "https://registry.npmjs.org/has-flag/-/has-flag-3.0.0.tgz", "integrity": "sha512-sKJf1+ceQBr4SMkvQnBDNDtf4TXpVhVGateu0t918bl30FnbE2m4vNLX+VWe/dpjlb+HugGYzW7uQXH98HPEYw==", "dev": true, "engines": { "node": ">=4" } }, "node_modules/@babel/code-frame/node_modules/supports-color": { "version": "5.5.0", "resolved": "https://registry.npmjs.org/supports-color/-/supports-color-5.5.0.tgz", "integrity": "sha512-QjVjwdXIt408MIiAqCX4oUKsgU2EqAGzs2Ppkm4aQYbjm+ZEWEcW4SfFNTr4uMNZma0ey4f5lgLrkB0aX0QMow==", "dev": true, "dependencies": { "has-flag": "^3.0.0" }, "engines": { "node": ">=4" } }, "node_modules/@babel/compat-data": { "version": "7.22.9", "resolved": "https://registry.npmjs.org/@babel/compat-data/-/compat-data-7.22.9.tgz", "integrity": "sha512-5UamI7xkUcJ3i9qVDS+KFDEK8/7oJ55/sJMB1Ge7IEapr7KfdfV/HErR+koZwOfd+SgtFKOKRhRakdg++DcJpQ==", "dev": true, "engines": { "node": ">=6.9.0" } }, "node_modules/@babel/core": { "version": "7.22.10", "resolved": "https://registry.npmjs.org/@babel/core/-/core-7.22.10.tgz", "integrity": "sha512-fTmqbbUBAwCcre6zPzNngvsI0aNrPZe77AeqvDxWM9Nm+04RrJ3CAmGHA9f7lJQY6ZMhRztNemy4uslDxTX4Qw==", "dev": true, "dependencies": { "@ampproject/remapping": "^2.2.0", "@babel/code-frame": "^7.22.10", "@babel/generator": "^7.22.10", "@babel/helper-compilation-targets": "^7.22.10", "@babel/helper-module-transforms": "^7.22.9", "@babel/helpers": "^7.22.10", "@babel/parser": "^7.22.10", "@babel/template": "^7.22.5", "@babel/traverse": "^7.22.10", "@babel/types": "^7.22.10", "convert-source-map": "^1.7.0", "debug": "^4.1.0", "gensync": "^1.0.0-beta.2", "json5": "^2.2.2", "semver": "^6.3.1" }, "engines": { "node": ">=6.9.0" }, "funding": { "type": "opencollective", "url": "https://opencollective.com/babel" } }, "node_modules/@babel/generator": { "version": "7.23.0", "resolved": "https://registry.npmjs.org/@babel/generator/-/generator-7.23.0.tgz", "integrity": "sha512-lN85QRR+5IbYrMWM6Y4pE/noaQtg4pNiqeNGX60eqOfo6gtEj6uw/JagelB8vVztSd7R6M5n1+PQkDbHbBRU4g==", "dev": true, "dependencies": { "@babel/types": "^7.23.0", "@jridgewell/gen-mapping": "^0.3.2", "@jridgewell/trace-mapping": "^0.3.17", "jsesc": "^2.5.1" }, "engines": { "node": ">=6.9.0" } }, "node_modules/@babel/helper-compilation-targets": { "version": "7.22.10", "resolved": "https://registry.npmjs.org/@babel/helper-compilation-targets/-/helper-compilation-targets-7.22.10.tgz", "integrity": "sha512-JMSwHD4J7SLod0idLq5PKgI+6g/hLD/iuWBq08ZX49xE14VpVEojJ5rHWptpirV2j020MvypRLAXAO50igCJ5Q==", "dev": true, "dependencies": { "@babel/compat-data": "^7.22.9", "@babel/helper-validator-option": "^7.22.5", "browserslist": "^4.21.9", "lru-cache": "^5.1.1", "semver": "^6.3.1" }, "engines": { "node": ">=6.9.0" } }, "node_modules/@babel/helper-environment-visitor": { "version": "7.22.20", "resolved": "https://registry.npmjs.org/@babel/helper-environment-visitor/-/helper-environment-visitor-7.22.20.tgz", "integrity": "sha512-zfedSIzFhat/gFhWfHtgWvlec0nqB9YEIVrpuwjruLlXfUSnA8cJB0miHKwqDnQ7d32aKo2xt88/xZptwxbfhA==", "dev": true, "engines": { "node": ">=6.9.0" } }, "node_modules/@babel/helper-function-name": { "version": "7.23.0", "resolved": "https://registry.npmjs.org/@babel/helper-function-name/-/helper-function-name-7.23.0.tgz", "integrity": "sha512-OErEqsrxjZTJciZ4Oo+eoZqeW9UIiOcuYKRJA4ZAgV9myA+pOXhhmpfNCKjEH/auVfEYVFJ6y1Tc4r0eIApqiw==", "dev": true, "dependencies": { "@babel/template": "^7.22.15", "@babel/types": "^7.23.0" }, "engines": { "node": ">=6.9.0" } }, "node_modules/@babel/helper-hoist-variables": { "version": "7.22.5", "resolved": "https://registry.npmjs.org/@babel/helper-hoist-variables/-/helper-hoist-variables-7.22.5.tgz", "integrity": "sha512-wGjk9QZVzvknA6yKIUURb8zY3grXCcOZt+/7Wcy8O2uctxhplmUPkOdlgoNhmdVee2c92JXbf1xpMtVNbfoxRw==", "dev": true, "dependencies": { "@babel/types": "^7.22.5" }, "engines": { "node": ">=6.9.0" } }, "node_modules/@babel/helper-module-imports": { "version": "7.22.5", "resolved": "https://registry.npmjs.org/@babel/helper-module-imports/-/helper-module-imports-7.22.5.tgz", "integrity": "sha512-8Dl6+HD/cKifutF5qGd/8ZJi84QeAKh+CEe1sBzz8UayBBGg1dAIJrdHOcOM5b2MpzWL2yuotJTtGjETq0qjXg==", "dev": true, "dependencies": { "@babel/types": "^7.22.5" }, "engines": { "node": ">=6.9.0" } }, "node_modules/@babel/helper-module-transforms": { "version": "7.22.9", "resolved": "https://registry.npmjs.org/@babel/helper-module-transforms/-/helper-module-transforms-7.22.9.tgz", "integrity": "sha512-t+WA2Xn5K+rTeGtC8jCsdAH52bjggG5TKRuRrAGNM/mjIbO4GxvlLMFOEz9wXY5I2XQ60PMFsAG2WIcG82dQMQ==", "dev": true, "dependencies": { "@babel/helper-environment-visitor": "^7.22.5", "@babel/helper-module-imports": "^7.22.5", "@babel/helper-simple-access": "^7.22.5", "@babel/helper-split-export-declaration": "^7.22.6", "@babel/helper-validator-identifier": "^7.22.5" }, "engines": { "node": ">=6.9.0" }, "peerDependencies": { "@babel/core": "^7.0.0" } }, "node_modules/@babel/helper-plugin-utils": { "version": "7.22.5", "resolved": "https://registry.npmjs.org/@babel/helper-plugin-utils/-/helper-plugin-utils-7.22.5.tgz", "integrity": "sha512-uLls06UVKgFG9QD4OeFYLEGteMIAa5kpTPcFL28yuCIIzsf6ZyKZMllKVOCZFhiZ5ptnwX4mtKdWCBE/uT4amg==", "dev": true, "engines": { "node": ">=6.9.0" } }, "node_modules/@babel/helper-simple-access": { "version": "7.22.5", "resolved": "https://registry.npmjs.org/@babel/helper-simple-access/-/helper-simple-access-7.22.5.tgz", "integrity": "sha512-n0H99E/K+Bika3++WNL17POvo4rKWZ7lZEp1Q+fStVbUi8nxPQEBOlTmCOxW/0JsS56SKKQ+ojAe2pHKJHN35w==", "dev": true, "dependencies": { "@babel/types": "^7.22.5" }, "engines": { "node": ">=6.9.0" } }, "node_modules/@babel/helper-split-export-declaration": { "version": "7.22.6", "resolved": "https://registry.npmjs.org/@babel/helper-split-export-declaration/-/helper-split-export-declaration-7.22.6.tgz", "integrity": "sha512-AsUnxuLhRYsisFiaJwvp1QF+I3KjD5FOxut14q/GzovUe6orHLesW2C7d754kRm53h5gqrz6sFl6sxc4BVtE/g==", "dev": true, "dependencies": { "@babel/types": "^7.22.5" }, "engines": { "node": ">=6.9.0" } }, "node_modules/@babel/helper-string-parser": { "version": "7.22.5", "resolved": "https://registry.npmjs.org/@babel/helper-string-parser/-/helper-string-parser-7.22.5.tgz", "integrity": "sha512-mM4COjgZox8U+JcXQwPijIZLElkgEpO5rsERVDJTc2qfCDfERyob6k5WegS14SX18IIjv+XD+GrqNumY5JRCDw==", "dev": true, "engines": { "node": ">=6.9.0" } }, "node_modules/@babel/helper-validator-identifier": { "version": "7.22.20", "resolved": "https://registry.npmjs.org/@babel/helper-validator-identifier/-/helper-validator-identifier-7.22.20.tgz", "integrity": "sha512-Y4OZ+ytlatR8AI+8KZfKuL5urKp7qey08ha31L8b3BwewJAoJamTzyvxPR/5D+KkdJCGPq/+8TukHBlY10FX9A==", "dev": true, "engines": { "node": ">=6.9.0" } }, "node_modules/@babel/helper-validator-option": { "version": "7.22.5", "resolved": "https://registry.npmjs.org/@babel/helper-validator-option/-/helper-validator-option-7.22.5.tgz", "integrity": "sha512-R3oB6xlIVKUnxNUxbmgq7pKjxpru24zlimpE8WK47fACIlM0II/Hm1RS8IaOI7NgCr6LNS+jl5l75m20npAziw==", "dev": true, "engines": { "node": ">=6.9.0" } }, "node_modules/@babel/helpers": { "version": "7.22.10", "resolved": "https://registry.npmjs.org/@babel/helpers/-/helpers-7.22.10.tgz", "integrity": "sha512-a41J4NW8HyZa1I1vAndrraTlPZ/eZoga2ZgS7fEr0tZJGVU4xqdE80CEm0CcNjha5EZ8fTBYLKHF0kqDUuAwQw==", "dev": true, "dependencies": { "@babel/template": "^7.22.5", "@babel/traverse": "^7.22.10", "@babel/types": "^7.22.10" }, "engines": { "node": ">=6.9.0" } }, "node_modules/@babel/highlight": { "version": "7.22.20", "resolved": "https://registry.npmjs.org/@babel/highlight/-/highlight-7.22.20.tgz", "integrity": "sha512-dkdMCN3py0+ksCgYmGG8jKeGA/8Tk+gJwSYYlFGxG5lmhfKNoAy004YpLxpS1W2J8m/EK2Ew+yOs9pVRwO89mg==", "dev": true, "dependencies": { "@babel/helper-validator-identifier": "^7.22.20", "chalk": "^2.4.2", "js-tokens": "^4.0.0" }, "engines": { "node": ">=6.9.0" } }, "node_modules/@babel/highlight/node_modules/ansi-styles": { "version": "3.2.1", "resolved": "https://registry.npmjs.org/ansi-styles/-/ansi-styles-3.2.1.tgz", "integrity": "sha512-VT0ZI6kZRdTh8YyJw3SMbYm/u+NqfsAxEpWO0Pf9sq8/e94WxxOpPKx9FR1FlyCtOVDNOQ+8ntlqFxiRc+r5qA==", "dev": true, "dependencies": { "color-convert": "^1.9.0" }, "engines": { "node": ">=4" } }, "node_modules/@babel/highlight/node_modules/chalk": { "version": "2.4.2", "resolved": "https://registry.npmjs.org/chalk/-/chalk-2.4.2.tgz", "integrity": "sha512-Mti+f9lpJNcwF4tWV8/OrTTtF1gZi+f8FqlyAdouralcFWFQWF2+NgCHShjkCb+IFBLq9buZwE1xckQU4peSuQ==", "dev": true, "dependencies": { "ansi-styles": "^3.2.1", "escape-string-regexp": "^1.0.5", "supports-color": "^5.3.0" }, "engines": { "node": ">=4" } }, "node_modules/@babel/highlight/node_modules/color-convert": { "version": "1.9.3", "resolved": "https://registry.npmjs.org/color-convert/-/color-convert-1.9.3.tgz", "integrity": "sha512-QfAUtd+vFdAtFQcC8CCyYt1fYWxSqAiK2cSD6zDB8N3cpsEBAvRxp9zOGg6G/SHHJYAT88/az/IuDGALsNVbGg==", "dev": true, "dependencies": { "color-name": "1.1.3" } }, "node_modules/@babel/highlight/node_modules/color-name": { "version": "1.1.3", "resolved": "https://registry.npmjs.org/color-name/-/color-name-1.1.3.tgz", "integrity": "sha512-72fSenhMw2HZMTVHeCA9KCmpEIbzWiQsjN+BHcBbS9vr1mtt+vJjPdksIBNUmKAW8TFUDPJK5SUU3QhE9NEXDw==", "dev": true }, "node_modules/@babel/highlight/node_modules/escape-string-regexp": { "version": "1.0.5", "resolved": "https://registry.npmjs.org/escape-string-regexp/-/escape-string-regexp-1.0.5.tgz", "integrity": "sha512-vbRorB5FUQWvla16U8R/qgaFIya2qGzwDrNmCZuYKrbdSUMG6I1ZCGQRefkRVhuOkIGVne7BQ35DSfo1qvJqFg==", "dev": true, "engines": { "node": ">=0.8.0" } }, "node_modules/@babel/highlight/node_modules/has-flag": { "version": "3.0.0", "resolved": "https://registry.npmjs.org/has-flag/-/has-flag-3.0.0.tgz", "integrity": "sha512-sKJf1+ceQBr4SMkvQnBDNDtf4TXpVhVGateu0t918bl30FnbE2m4vNLX+VWe/dpjlb+HugGYzW7uQXH98HPEYw==", "dev": true, "engines": { "node": ">=4" } }, "node_modules/@babel/highlight/node_modules/supports-color": { "version": "5.5.0", "resolved": "https://registry.npmjs.org/supports-color/-/supports-color-5.5.0.tgz", "integrity": "sha512-QjVjwdXIt408MIiAqCX4oUKsgU2EqAGzs2Ppkm4aQYbjm+ZEWEcW4SfFNTr4uMNZma0ey4f5lgLrkB0aX0QMow==", "dev": true, "dependencies": { "has-flag": "^3.0.0" }, "engines": { "node": ">=4" } }, "node_modules/@babel/parser": { "version": "7.23.0", "resolved": "https://registry.npmjs.org/@babel/parser/-/parser-7.23.0.tgz", "integrity": "sha512-vvPKKdMemU85V9WE/l5wZEmImpCtLqbnTvqDS2U1fJ96KrxoW7KrXhNsNCblQlg8Ck4b85yxdTyelsMUgFUXiw==", "dev": true, "bin": { "parser": "bin/babel-parser.js" }, "engines": { "node": ">=6.0.0" } }, "node_modules/@babel/plugin-syntax-async-generators": { "version": "7.8.4", "resolved": "https://registry.npmjs.org/@babel/plugin-syntax-async-generators/-/plugin-syntax-async-generators-7.8.4.tgz", "integrity": "sha512-tycmZxkGfZaxhMRbXlPXuVFpdWlXpir2W4AMhSJgRKzk/eDlIXOhb2LHWoLpDF7TEHylV5zNhykX6KAgHJmTNw==", "dev": true, "dependencies": { "@babel/helper-plugin-utils": "^7.8.0" }, "peerDependencies": { "@babel/core": "^7.0.0-0" } }, "node_modules/@babel/plugin-syntax-bigint": { "version": "7.8.3", "resolved": "https://registry.npmjs.org/@babel/plugin-syntax-bigint/-/plugin-syntax-bigint-7.8.3.tgz", "integrity": "sha512-wnTnFlG+YxQm3vDxpGE57Pj0srRU4sHE/mDkt1qv2YJJSeUAec2ma4WLUnUPeKjyrfntVwe/N6dCXpU+zL3Npg==", "dev": true, "dependencies": { "@babel/helper-plugin-utils": "^7.8.0" }, "peerDependencies": { "@babel/core": "^7.0.0-0" } }, "node_modules/@babel/plugin-syntax-class-properties": { "version": "7.12.13", "resolved": "https://registry.npmjs.org/@babel/plugin-syntax-class-properties/-/plugin-syntax-class-properties-7.12.13.tgz", "integrity": "sha512-fm4idjKla0YahUNgFNLCB0qySdsoPiZP3iQE3rky0mBUtMZ23yDJ9SJdg6dXTSDnulOVqiF3Hgr9nbXvXTQZYA==", "dev": true, "dependencies": { "@babel/helper-plugin-utils": "^7.12.13" }, "peerDependencies": { "@babel/core": "^7.0.0-0" } }, "node_modules/@babel/plugin-syntax-import-meta": { "version": "7.10.4", "resolved": "https://registry.npmjs.org/@babel/plugin-syntax-import-meta/-/plugin-syntax-import-meta-7.10.4.tgz", "integrity": "sha512-Yqfm+XDx0+Prh3VSeEQCPU81yC+JWZ2pDPFSS4ZdpfZhp4MkFMaDC1UqseovEKwSUpnIL7+vK+Clp7bfh0iD7g==", "dev": true, "dependencies": { "@babel/helper-plugin-utils": "^7.10.4" }, "peerDependencies": { "@babel/core": "^7.0.0-0" } }, "node_modules/@babel/plugin-syntax-json-strings": { "version": "7.8.3", "resolved": "https://registry.npmjs.org/@babel/plugin-syntax-json-strings/-/plugin-syntax-json-strings-7.8.3.tgz", "integrity": "sha512-lY6kdGpWHvjoe2vk4WrAapEuBR69EMxZl+RoGRhrFGNYVK8mOPAW8VfbT/ZgrFbXlDNiiaxQnAtgVCZ6jv30EA==", "dev": true, "dependencies": { "@babel/helper-plugin-utils": "^7.8.0" }, "peerDependencies": { "@babel/core": "^7.0.0-0" } }, "node_modules/@babel/plugin-syntax-logical-assignment-operators": { "version": "7.10.4", "resolved": "https://registry.npmjs.org/@babel/plugin-syntax-logical-assignment-operators/-/plugin-syntax-logical-assignment-operators-7.10.4.tgz", "integrity": "sha512-d8waShlpFDinQ5MtvGU9xDAOzKH47+FFoney2baFIoMr952hKOLp1HR7VszoZvOsV/4+RRszNY7D17ba0te0ig==", "dev": true, "dependencies": { "@babel/helper-plugin-utils": "^7.10.4" }, "peerDependencies": { "@babel/core": "^7.0.0-0" } }, "node_modules/@babel/plugin-syntax-nullish-coalescing-operator": { "version": "7.8.3", "resolved": "https://registry.npmjs.org/@babel/plugin-syntax-nullish-coalescing-operator/-/plugin-syntax-nullish-coalescing-operator-7.8.3.tgz", "integrity": "sha512-aSff4zPII1u2QD7y+F8oDsz19ew4IGEJg9SVW+bqwpwtfFleiQDMdzA/R+UlWDzfnHFCxxleFT0PMIrR36XLNQ==", "dev": true, "dependencies": { "@babel/helper-plugin-utils": "^7.8.0" }, "peerDependencies": { "@babel/core": "^7.0.0-0" } }, "node_modules/@babel/plugin-syntax-numeric-separator": { "version": "7.10.4", "resolved": "https://registry.npmjs.org/@babel/plugin-syntax-numeric-separator/-/plugin-syntax-numeric-separator-7.10.4.tgz", "integrity": "sha512-9H6YdfkcK/uOnY/K7/aA2xpzaAgkQn37yzWUMRK7OaPOqOpGS1+n0H5hxT9AUw9EsSjPW8SVyMJwYRtWs3X3ug==", "dev": true, "dependencies": { "@babel/helper-plugin-utils": "^7.10.4" }, "peerDependencies": { "@babel/core": "^7.0.0-0" } }, "node_modules/@babel/plugin-syntax-object-rest-spread": { "version": "7.8.3", "resolved": "https://registry.npmjs.org/@babel/plugin-syntax-object-rest-spread/-/plugin-syntax-object-rest-spread-7.8.3.tgz", "integrity": "sha512-XoqMijGZb9y3y2XskN+P1wUGiVwWZ5JmoDRwx5+3GmEplNyVM2s2Dg8ILFQm8rWM48orGy5YpI5Bl8U1y7ydlA==", "dev": true, "dependencies": { "@babel/helper-plugin-utils": "^7.8.0" }, "peerDependencies": { "@babel/core": "^7.0.0-0" } }, "node_modules/@babel/plugin-syntax-optional-catch-binding": { "version": "7.8.3", "resolved": "https://registry.npmjs.org/@babel/plugin-syntax-optional-catch-binding/-/plugin-syntax-optional-catch-binding-7.8.3.tgz", "integrity": "sha512-6VPD0Pc1lpTqw0aKoeRTMiB+kWhAoT24PA+ksWSBrFtl5SIRVpZlwN3NNPQjehA2E/91FV3RjLWoVTglWcSV3Q==", "dev": true, "dependencies": { "@babel/helper-plugin-utils": "^7.8.0" }, "peerDependencies": { "@babel/core": "^7.0.0-0" } }, "node_modules/@babel/plugin-syntax-optional-chaining": { "version": "7.8.3", "resolved": "https://registry.npmjs.org/@babel/plugin-syntax-optional-chaining/-/plugin-syntax-optional-chaining-7.8.3.tgz", "integrity": "sha512-KoK9ErH1MBlCPxV0VANkXW2/dw4vlbGDrFgz8bmUsBGYkFRcbRwMh6cIJubdPrkxRwuGdtCk0v/wPTKbQgBjkg==", "dev": true, "dependencies": { "@babel/helper-plugin-utils": "^7.8.0" }, "peerDependencies": { "@babel/core": "^7.0.0-0" } }, "node_modules/@babel/plugin-syntax-top-level-await": { "version": "7.14.5", "resolved": "https://registry.npmjs.org/@babel/plugin-syntax-top-level-await/-/plugin-syntax-top-level-await-7.14.5.tgz", "integrity": "sha512-hx++upLv5U1rgYfwe1xBQUhRmU41NEvpUvrp8jkrSCdvGSnM5/qdRMtylJ6PG5OFkBaHkbTAKTnd3/YyESRHFw==", "dev": true, "dependencies": { "@babel/helper-plugin-utils": "^7.14.5" }, "engines": { "node": ">=6.9.0" }, "peerDependencies": { "@babel/core": "^7.0.0-0" } }, "node_modules/@babel/template": { "version": "7.22.15", "resolved": "https://registry.npmjs.org/@babel/template/-/template-7.22.15.tgz", "integrity": "sha512-QPErUVm4uyJa60rkI73qneDacvdvzxshT3kksGqlGWYdOTIUOwJ7RDUL8sGqslY1uXWSL6xMFKEXDS3ox2uF0w==", "dev": true, "dependencies": { "@babel/code-frame": "^7.22.13", "@babel/parser": "^7.22.15", "@babel/types": "^7.22.15" }, "engines": { "node": ">=6.9.0" } }, "node_modules/@babel/traverse": { "version": "7.23.2", "resolved": "https://registry.npmjs.org/@babel/traverse/-/traverse-7.23.2.tgz", "integrity": "sha512-azpe59SQ48qG6nu2CzcMLbxUudtN+dOM9kDbUqGq3HXUJRlo7i8fvPoxQUzYgLZ4cMVmuZgm8vvBpNeRhd6XSw==", "dev": true, "dependencies": { "@babel/code-frame": "^7.22.13", "@babel/generator": "^7.23.0", "@babel/helper-environment-visitor": "^7.22.20", "@babel/helper-function-name": "^7.23.0", "@babel/helper-hoist-variables": "^7.22.5", "@babel/helper-split-export-declaration": "^7.22.6", "@babel/parser": "^7.23.0", "@babel/types": "^7.23.0", "debug": "^4.1.0", "globals": "^11.1.0" }, "engines": { "node": ">=6.9.0" } }, "node_modules/@babel/types": { "version": "7.23.0", "resolved": "https://registry.npmjs.org/@babel/types/-/types-7.23.0.tgz", "integrity": "sha512-0oIyUfKoI3mSqMvsxBdclDwxXKXAUA8v/apZbc+iSyARYou1o8ZGDxbUYyLFoW2arqS2jDGqJuZvv1d/io1axg==", "dev": true, "dependencies": { "@babel/helper-string-parser": "^7.22.5", "@babel/helper-validator-identifier": "^7.22.20", "to-fast-properties": "^2.0.0" }, "engines": { "node": ">=6.9.0" } }, "node_modules/@bcoe/v8-coverage": { "version": "0.2.3", "resolved": "https://registry.npmjs.org/@bcoe/v8-coverage/-/v8-coverage-0.2.3.tgz", "integrity": "sha512-0hYQ8SB4Db5zvZB4axdMHGwEaQjkZzFjQiN9LVYvIFB2nSUHW9tYpxWriPrWDASIxiaXax83REcLxuSdnGPZtw==", "dev": true }, "node_modules/@cnakazawa/watch": { "version": "1.0.4", "resolved": "https://registry.npmjs.org/@cnakazawa/watch/-/watch-1.0.4.tgz", "integrity": "sha512-v9kIhKwjeZThiWrLmj0y17CWoyddASLj9O2yvbZkbvw/N3rWOYy9zkV66ursAoVr0mV15bL8g0c4QZUE6cdDoQ==", "dev": true, "dependencies": { "exec-sh": "^0.3.2", "minimist": "^1.2.0" }, "bin": { "watch": "cli.js" }, "engines": { "node": ">=0.1.95" } }, "node_modules/@istanbuljs/load-nyc-config": { "version": "1.1.0", "resolved": "https://registry.npmjs.org/@istanbuljs/load-nyc-config/-/load-nyc-config-1.1.0.tgz", "integrity": "sha512-VjeHSlIzpv/NyD3N0YuHfXOPDIixcA1q2ZV98wsMqcYlPmv2n3Yb2lYP9XMElnaFVXg5A7YLTeLu6V84uQDjmQ==", "dev": true, "dependencies": { "camelcase": "^5.3.1", "find-up": "^4.1.0", "get-package-type": "^0.1.0", "js-yaml": "^3.13.1", "resolve-from": "^5.0.0" }, "engines": { "node": ">=8" } }, "node_modules/@istanbuljs/schema": { "version": "0.1.3", "resolved": "https://registry.npmjs.org/@istanbuljs/schema/-/schema-0.1.3.tgz", "integrity": "sha512-ZXRY4jNvVgSVQ8DL3LTcakaAtXwTVUxE81hslsyD2AtoXW/wVob10HkOJ1X/pAlcI7D+2YoZKg5do8G/w6RYgA==", "dev": true, "engines": { "node": ">=8" } }, "node_modules/@jest/console": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/@jest/console/-/console-26.6.2.tgz", "integrity": "sha512-IY1R2i2aLsLr7Id3S6p2BA82GNWryt4oSvEXLAKc+L2zdi89dSkE8xC1C+0kpATG4JhBJREnQOH7/zmccM2B0g==", "dev": true, "dependencies": { "@jest/types": "^26.6.2", "@types/node": "*", "chalk": "^4.0.0", "jest-message-util": "^26.6.2", "jest-util": "^26.6.2", "slash": "^3.0.0" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/@jest/core": { "version": "26.6.3", "resolved": "https://registry.npmjs.org/@jest/core/-/core-26.6.3.tgz", "integrity": "sha512-xvV1kKbhfUqFVuZ8Cyo+JPpipAHHAV3kcDBftiduK8EICXmTFddryy3P7NfZt8Pv37rA9nEJBKCCkglCPt/Xjw==", "dev": true, "dependencies": { "@jest/console": "^26.6.2", "@jest/reporters": "^26.6.2", "@jest/test-result": "^26.6.2", "@jest/transform": "^26.6.2", "@jest/types": "^26.6.2", "@types/node": "*", "ansi-escapes": "^4.2.1", "chalk": "^4.0.0", "exit": "^0.1.2", "graceful-fs": "^4.2.4", "jest-changed-files": "^26.6.2", "jest-config": "^26.6.3", "jest-haste-map": "^26.6.2", "jest-message-util": "^26.6.2", "jest-regex-util": "^26.0.0", "jest-resolve": "^26.6.2", "jest-resolve-dependencies": "^26.6.3", "jest-runner": "^26.6.3", "jest-runtime": "^26.6.3", "jest-snapshot": "^26.6.2", "jest-util": "^26.6.2", "jest-validate": "^26.6.2", "jest-watcher": "^26.6.2", "micromatch": "^4.0.2", "p-each-series": "^2.1.0", "rimraf": "^3.0.0", "slash": "^3.0.0", "strip-ansi": "^6.0.0" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/@jest/environment": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/@jest/environment/-/environment-26.6.2.tgz", "integrity": "sha512-nFy+fHl28zUrRsCeMB61VDThV1pVTtlEokBRgqPrcT1JNq4yRNIyTHfyht6PqtUvY9IsuLGTrbG8kPXjSZIZwA==", "dev": true, "dependencies": { "@jest/fake-timers": "^26.6.2", "@jest/types": "^26.6.2", "@types/node": "*", "jest-mock": "^26.6.2" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/@jest/fake-timers": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/@jest/fake-timers/-/fake-timers-26.6.2.tgz", "integrity": "sha512-14Uleatt7jdzefLPYM3KLcnUl1ZNikaKq34enpb5XG9i81JpppDb5muZvonvKyrl7ftEHkKS5L5/eB/kxJ+bvA==", "dev": true, "dependencies": { "@jest/types": "^26.6.2", "@sinonjs/fake-timers": "^6.0.1", "@types/node": "*", "jest-message-util": "^26.6.2", "jest-mock": "^26.6.2", "jest-util": "^26.6.2" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/@jest/globals": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/@jest/globals/-/globals-26.6.2.tgz", "integrity": "sha512-85Ltnm7HlB/KesBUuALwQ68YTU72w9H2xW9FjZ1eL1U3lhtefjjl5c2MiUbpXt/i6LaPRvoOFJ22yCBSfQ0JIA==", "dev": true, "dependencies": { "@jest/environment": "^26.6.2", "@jest/types": "^26.6.2", "expect": "^26.6.2" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/@jest/reporters": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/@jest/reporters/-/reporters-26.6.2.tgz", "integrity": "sha512-h2bW53APG4HvkOnVMo8q3QXa6pcaNt1HkwVsOPMBV6LD/q9oSpxNSYZQYkAnjdMjrJ86UuYeLo+aEZClV6opnw==", "dev": true, "dependencies": { "@bcoe/v8-coverage": "^0.2.3", "@jest/console": "^26.6.2", "@jest/test-result": "^26.6.2", "@jest/transform": "^26.6.2", "@jest/types": "^26.6.2", "chalk": "^4.0.0", "collect-v8-coverage": "^1.0.0", "exit": "^0.1.2", "glob": "^7.1.2", "graceful-fs": "^4.2.4", "istanbul-lib-coverage": "^3.0.0", "istanbul-lib-instrument": "^4.0.3", "istanbul-lib-report": "^3.0.0", "istanbul-lib-source-maps": "^4.0.0", "istanbul-reports": "^3.0.2", "jest-haste-map": "^26.6.2", "jest-resolve": "^26.6.2", "jest-util": "^26.6.2", "jest-worker": "^26.6.2", "slash": "^3.0.0", "source-map": "^0.6.0", "string-length": "^4.0.1", "terminal-link": "^2.0.0", "v8-to-istanbul": "^7.0.0" }, "engines": { "node": ">= 10.14.2" }, "optionalDependencies": { "node-notifier": "^8.0.0" } }, "node_modules/@jest/source-map": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/@jest/source-map/-/source-map-26.6.2.tgz", "integrity": "sha512-YwYcCwAnNmOVsZ8mr3GfnzdXDAl4LaenZP5z+G0c8bzC9/dugL8zRmxZzdoTl4IaS3CryS1uWnROLPFmb6lVvA==", "dev": true, "dependencies": { "callsites": "^3.0.0", "graceful-fs": "^4.2.4", "source-map": "^0.6.0" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/@jest/test-result": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/@jest/test-result/-/test-result-26.6.2.tgz", "integrity": "sha512-5O7H5c/7YlojphYNrK02LlDIV2GNPYisKwHm2QTKjNZeEzezCbwYs9swJySv2UfPMyZ0VdsmMv7jIlD/IKYQpQ==", "dev": true, "dependencies": { "@jest/console": "^26.6.2", "@jest/types": "^26.6.2", "@types/istanbul-lib-coverage": "^2.0.0", "collect-v8-coverage": "^1.0.0" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/@jest/test-sequencer": { "version": "26.6.3", "resolved": "https://registry.npmjs.org/@jest/test-sequencer/-/test-sequencer-26.6.3.tgz", "integrity": "sha512-YHlVIjP5nfEyjlrSr8t/YdNfU/1XEt7c5b4OxcXCjyRhjzLYu/rO69/WHPuYcbCWkz8kAeZVZp2N2+IOLLEPGw==", "dev": true, "dependencies": { "@jest/test-result": "^26.6.2", "graceful-fs": "^4.2.4", "jest-haste-map": "^26.6.2", "jest-runner": "^26.6.3", "jest-runtime": "^26.6.3" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/@jest/transform": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/@jest/transform/-/transform-26.6.2.tgz", "integrity": "sha512-E9JjhUgNzvuQ+vVAL21vlyfy12gP0GhazGgJC4h6qUt1jSdUXGWJ1wfu/X7Sd8etSgxV4ovT1pb9v5D6QW4XgA==", "dev": true, "dependencies": { "@babel/core": "^7.1.0", "@jest/types": "^26.6.2", "babel-plugin-istanbul": "^6.0.0", "chalk": "^4.0.0", "convert-source-map": "^1.4.0", "fast-json-stable-stringify": "^2.0.0", "graceful-fs": "^4.2.4", "jest-haste-map": "^26.6.2", "jest-regex-util": "^26.0.0", "jest-util": "^26.6.2", "micromatch": "^4.0.2", "pirates": "^4.0.1", "slash": "^3.0.0", "source-map": "^0.6.1", "write-file-atomic": "^3.0.0" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/@jest/types": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/@jest/types/-/types-26.6.2.tgz", "integrity": "sha512-fC6QCp7Sc5sX6g8Tvbmj4XUTbyrik0akgRy03yjXbQaBWWNWGE7SGtJk98m0N8nzegD/7SggrUlivxo5ax4KWQ==", "dev": true, "dependencies": { "@types/istanbul-lib-coverage": "^2.0.0", "@types/istanbul-reports": "^3.0.0", "@types/node": "*", "@types/yargs": "^15.0.0", "chalk": "^4.0.0" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/@jridgewell/gen-mapping": { "version": "0.3.3", "resolved": "https://registry.npmjs.org/@jridgewell/gen-mapping/-/gen-mapping-0.3.3.tgz", "integrity": "sha512-HLhSWOLRi875zjjMG/r+Nv0oCW8umGb0BgEhyX3dDX3egwZtB8PqLnjz3yedt8R5StBrzcg4aBpnh8UA9D1BoQ==", "dev": true, "dependencies": { "@jridgewell/set-array": "^1.0.1", "@jridgewell/sourcemap-codec": "^1.4.10", "@jridgewell/trace-mapping": "^0.3.9" }, "engines": { "node": ">=6.0.0" } }, "node_modules/@jridgewell/resolve-uri": { "version": "3.1.1", "resolved": "https://registry.npmjs.org/@jridgewell/resolve-uri/-/resolve-uri-3.1.1.tgz", "integrity": "sha512-dSYZh7HhCDtCKm4QakX0xFpsRDqjjtZf/kjI/v3T3Nwt5r8/qz/M19F9ySyOqU94SXBmeG9ttTul+YnR4LOxFA==", "dev": true, "engines": { "node": ">=6.0.0" } }, "node_modules/@jridgewell/set-array": { "version": "1.1.2", "resolved": "https://registry.npmjs.org/@jridgewell/set-array/-/set-array-1.1.2.tgz", "integrity": "sha512-xnkseuNADM0gt2bs+BvhO0p78Mk762YnZdsuzFV018NoG1Sj1SCQvpSqa7XUaTam5vAGasABV9qXASMKnFMwMw==", "dev": true, "engines": { "node": ">=6.0.0" } }, "node_modules/@jridgewell/sourcemap-codec": { "version": "1.4.15", "resolved": "https://registry.npmjs.org/@jridgewell/sourcemap-codec/-/sourcemap-codec-1.4.15.tgz", "integrity": "sha512-eF2rxCRulEKXHTRiDrDy6erMYWqNw4LPdQ8UQA4huuxaQsVeRPFl2oM8oDGxMFhJUWZf9McpLtJasDDZb/Bpeg==", "dev": true }, "node_modules/@jridgewell/trace-mapping": { "version": "0.3.19", "resolved": "https://registry.npmjs.org/@jridgewell/trace-mapping/-/trace-mapping-0.3.19.tgz", "integrity": "sha512-kf37QtfW+Hwx/buWGMPcR60iF9ziHa6r/CZJIHbmcm4+0qrXiVdxegAH0F6yddEVQ7zdkjcGCgCzUu+BcbhQxw==", "dev": true, "dependencies": { "@jridgewell/resolve-uri": "^3.1.0", "@jridgewell/sourcemap-codec": "^1.4.14" } }, "node_modules/@sinonjs/commons": { "version": "1.8.6", "resolved": "https://registry.npmjs.org/@sinonjs/commons/-/commons-1.8.6.tgz", "integrity": "sha512-Ky+XkAkqPZSm3NLBeUng77EBQl3cmeJhITaGHdYH8kjVB+aun3S4XBRti2zt17mtt0mIUDiNxYeoJm6drVvBJQ==", "dev": true, "dependencies": { "type-detect": "4.0.8" } }, "node_modules/@sinonjs/fake-timers": { "version": "6.0.1", "resolved": "https://registry.npmjs.org/@sinonjs/fake-timers/-/fake-timers-6.0.1.tgz", "integrity": "sha512-MZPUxrmFubI36XS1DI3qmI0YdN1gks62JtFZvxR67ljjSNCeK6U08Zx4msEWOXuofgqUt6zPHSi1H9fbjR/NRA==", "dev": true, "dependencies": { "@sinonjs/commons": "^1.7.0" } }, "node_modules/@tootallnate/once": { "version": "1.1.2", "resolved": "https://registry.npmjs.org/@tootallnate/once/-/once-1.1.2.tgz", "integrity": "sha512-RbzJvlNzmRq5c3O09UipeuXno4tA1FE6ikOjxZK0tuxVv3412l64l5t1W5pj4+rJq9vpkm/kwiR07aZXnsKPxw==", "dev": true, "engines": { "node": ">= 6" } }, "node_modules/@types/babel__core": { "version": "7.20.1", "resolved": "https://registry.npmjs.org/@types/babel__core/-/babel__core-7.20.1.tgz", "integrity": "sha512-aACu/U/omhdk15O4Nfb+fHgH/z3QsfQzpnvRZhYhThms83ZnAOZz7zZAWO7mn2yyNQaA4xTO8GLK3uqFU4bYYw==", "dev": true, "dependencies": { "@babel/parser": "^7.20.7", "@babel/types": "^7.20.7", "@types/babel__generator": "*", "@types/babel__template": "*", "@types/babel__traverse": "*" } }, "node_modules/@types/babel__generator": { "version": "7.6.4", "resolved": "https://registry.npmjs.org/@types/babel__generator/-/babel__generator-7.6.4.tgz", "integrity": "sha512-tFkciB9j2K755yrTALxD44McOrk+gfpIpvC3sxHjRawj6PfnQxrse4Clq5y/Rq+G3mrBurMax/lG8Qn2t9mSsg==", "dev": true, "dependencies": { "@babel/types": "^7.0.0" } }, "node_modules/@types/babel__template": { "version": "7.4.1", "resolved": "https://registry.npmjs.org/@types/babel__template/-/babel__template-7.4.1.tgz", "integrity": "sha512-azBFKemX6kMg5Io+/rdGT0dkGreboUVR0Cdm3fz9QJWpaQGJRQXl7C+6hOTCZcMll7KFyEQpgbYI2lHdsS4U7g==", "dev": true, "dependencies": { "@babel/parser": "^7.1.0", "@babel/types": "^7.0.0" } }, "node_modules/@types/babel__traverse": { "version": "7.20.1", "resolved": "https://registry.npmjs.org/@types/babel__traverse/-/babel__traverse-7.20.1.tgz", "integrity": "sha512-MitHFXnhtgwsGZWtT68URpOvLN4EREih1u3QtQiN4VdAxWKRVvGCSvw/Qth0M0Qq3pJpnGOu5JaM/ydK7OGbqg==", "dev": true, "dependencies": { "@babel/types": "^7.20.7" } }, "node_modules/@types/graceful-fs": { "version": "4.1.6", "resolved": "https://registry.npmjs.org/@types/graceful-fs/-/graceful-fs-4.1.6.tgz", "integrity": "sha512-Sig0SNORX9fdW+bQuTEovKj3uHcUL6LQKbCrrqb1X7J6/ReAbhCXRAhc+SMejhLELFj2QcyuxmUooZ4bt5ReSw==", "dev": true, "dependencies": { "@types/node": "*" } }, "node_modules/@types/istanbul-lib-coverage": { "version": "2.0.4", "resolved": "https://registry.npmjs.org/@types/istanbul-lib-coverage/-/istanbul-lib-coverage-2.0.4.tgz", "integrity": "sha512-z/QT1XN4K4KYuslS23k62yDIDLwLFkzxOuMplDtObz0+y7VqJCaO2o+SPwHCvLFZh7xazvvoor2tA/hPz9ee7g==", "dev": true }, "node_modules/@types/istanbul-lib-report": { "version": "3.0.0", "resolved": "https://registry.npmjs.org/@types/istanbul-lib-report/-/istanbul-lib-report-3.0.0.tgz", "integrity": "sha512-plGgXAPfVKFoYfa9NpYDAkseG+g6Jr294RqeqcqDixSbU34MZVJRi/P+7Y8GDpzkEwLaGZZOpKIEmeVZNtKsrg==", "dev": true, "dependencies": { "@types/istanbul-lib-coverage": "*" } }, "node_modules/@types/istanbul-reports": { "version": "3.0.1", "resolved": "https://registry.npmjs.org/@types/istanbul-reports/-/istanbul-reports-3.0.1.tgz", "integrity": "sha512-c3mAZEuK0lvBp8tmuL74XRKn1+y2dcwOUpH7x4WrF6gk1GIgiluDRgMYQtw2OFcBvAJWlt6ASU3tSqxp0Uu0Aw==", "dev": true, "dependencies": { "@types/istanbul-lib-report": "*" } }, "node_modules/@types/jest": { "version": "26.0.24", "resolved": "https://registry.npmjs.org/@types/jest/-/jest-26.0.24.tgz", "integrity": "sha512-E/X5Vib8BWqZNRlDxj9vYXhsDwPYbPINqKF9BsnSoon4RQ0D9moEuLD8txgyypFLH7J4+Lho9Nr/c8H0Fi+17w==", "dev": true, "dependencies": { "jest-diff": "^26.0.0", "pretty-format": "^26.0.0" } }, "node_modules/@types/node": { "version": "10.17.27", "resolved": "https://registry.npmjs.org/@types/node/-/node-10.17.27.tgz", "integrity": "sha512-J0oqm9ZfAXaPdwNXMMgAhylw5fhmXkToJd06vuDUSAgEDZ/n/69/69UmyBZbc+zT34UnShuDSBqvim3SPnozJg==", "dev": true }, "node_modules/@types/normalize-package-data": { "version": "2.4.1", "resolved": "https://registry.npmjs.org/@types/normalize-package-data/-/normalize-package-data-2.4.1.tgz", "integrity": "sha512-Gj7cI7z+98M282Tqmp2K5EIsoouUEzbBJhQQzDE3jSIRk6r9gsz0oUokqIUR4u1R3dMHo0pDHM7sNOHyhulypw==", "dev": true }, "node_modules/@types/prettier": { "version": "2.7.3", "resolved": "https://registry.npmjs.org/@types/prettier/-/prettier-2.7.3.tgz", "integrity": "sha512-+68kP9yzs4LMp7VNh8gdzMSPZFL44MLGqiHWvttYJe+6qnuVr4Ek9wSBQoveqY/r+LwjCcU29kNVkidwim+kYA==", "dev": true }, "node_modules/@types/stack-utils": { "version": "2.0.1", "resolved": "https://registry.npmjs.org/@types/stack-utils/-/stack-utils-2.0.1.tgz", "integrity": "sha512-Hl219/BT5fLAaz6NDkSuhzasy49dwQS/DSdu4MdggFB8zcXv7vflBI3xp7FEmkmdDkBUI2bPUNeMttp2knYdxw==", "dev": true }, "node_modules/@types/yargs": { "version": "15.0.15", "resolved": "https://registry.npmjs.org/@types/yargs/-/yargs-15.0.15.tgz", "integrity": "sha512-IziEYMU9XoVj8hWg7k+UJrXALkGFjWJhn5QFEv9q4p+v40oZhSuC135M38st8XPjICL7Ey4TV64ferBGUoJhBg==", "dev": true, "dependencies": { "@types/yargs-parser": "*" } }, "node_modules/@types/yargs-parser": { "version": "21.0.0", "resolved": "https://registry.npmjs.org/@types/yargs-parser/-/yargs-parser-21.0.0.tgz", "integrity": "sha512-iO9ZQHkZxHn4mSakYV0vFHAVDyEOIJQrV2uZ06HxEPcx+mt8swXoZHIbaaJ2crJYFfErySgktuTZ3BeLz+XmFA==", "dev": true }, "node_modules/abab": { "version": "2.0.6", "resolved": "https://registry.npmjs.org/abab/-/abab-2.0.6.tgz", "integrity": "sha512-j2afSsaIENvHZN2B8GOpF566vZ5WVk5opAiMTvWgaQT8DkbOqsTfvNAvHoRGU2zzP8cPoqys+xHTRDWW8L+/BA==", "dev": true }, "node_modules/acorn": { "version": "8.10.0", "resolved": "https://registry.npmjs.org/acorn/-/acorn-8.10.0.tgz", "integrity": "sha512-F0SAmZ8iUtS//m8DmCTA0jlh6TDKkHQyK6xc6V4KDTyZKA9dnvX9/3sRTVQrWm79glUAZbnmmNcdYwUIHWVybw==", "dev": true, "bin": { "acorn": "bin/acorn" }, "engines": { "node": ">=0.4.0" } }, "node_modules/acorn-globals": { "version": "6.0.0", "resolved": "https://registry.npmjs.org/acorn-globals/-/acorn-globals-6.0.0.tgz", "integrity": "sha512-ZQl7LOWaF5ePqqcX4hLuv/bLXYQNfNWw2c0/yX/TsPRKamzHcTGQnlCjHT3TsmkOUVEPS3crCxiPfdzE/Trlhg==", "dev": true, "dependencies": { "acorn": "^7.1.1", "acorn-walk": "^7.1.1" } }, "node_modules/acorn-globals/node_modules/acorn": { "version": "7.4.1", "resolved": "https://registry.npmjs.org/acorn/-/acorn-7.4.1.tgz", "integrity": "sha512-nQyp0o1/mNdbTO1PO6kHkwSrmgZ0MT/jCCpNiwbUjGoRN4dlBhqJtoQuCnEOKzgTVwg0ZWiCoQy6SxMebQVh8A==", "dev": true, "bin": { "acorn": "bin/acorn" }, "engines": { "node": ">=0.4.0" } }, "node_modules/acorn-walk": { "version": "7.2.0", "resolved": "https://registry.npmjs.org/acorn-walk/-/acorn-walk-7.2.0.tgz", "integrity": "sha512-OPdCF6GsMIP+Az+aWfAAOEt2/+iVDKE7oy6lJ098aoe59oAmK76qV6Gw60SbZ8jHuG2wH058GF4pLFbYamYrVA==", "dev": true, "engines": { "node": ">=0.4.0" } }, "node_modules/agent-base": { "version": "6.0.2", "resolved": "https://registry.npmjs.org/agent-base/-/agent-base-6.0.2.tgz", "integrity": "sha512-RZNwNclF7+MS/8bDg70amg32dyeZGZxiDuQmZxKLAlQjr3jGyLx+4Kkk58UO7D2QdgFIQCovuSuZESne6RG6XQ==", "dev": true, "dependencies": { "debug": "4" }, "engines": { "node": ">= 6.0.0" } }, "node_modules/ansi-escapes": { "version": "4.3.2", "resolved": "https://registry.npmjs.org/ansi-escapes/-/ansi-escapes-4.3.2.tgz", "integrity": "sha512-gKXj5ALrKWQLsYG9jlTRmR/xKluxHV+Z9QEwNIgCfM1/uwPMCuzVVnh5mwTd+OuBZcwSIMbqssNWRm1lE51QaQ==", "dev": true, "dependencies": { "type-fest": "^0.21.3" }, "engines": { "node": ">=8" }, "funding": { "url": "https://github.com/sponsors/sindresorhus" } }, "node_modules/ansi-regex": { "version": "5.0.1", "resolved": "https://registry.npmjs.org/ansi-regex/-/ansi-regex-5.0.1.tgz", "integrity": "sha512-quJQXlTSUGL2LH9SUXo8VwsY4soanhgo6LNSm84E1LBcE8s3O0wpdiRzyR9z/ZZJMlMWv37qOOb9pdJlMUEKFQ==", "dev": true, "engines": { "node": ">=8" } }, "node_modules/ansi-styles": { "version": "4.3.0", "resolved": "https://registry.npmjs.org/ansi-styles/-/ansi-styles-4.3.0.tgz", "integrity": "sha512-zbB9rCJAT1rbjiVDb2hqKFHNYLxgtk8NURxZ3IZwD3F6NtxbXZQCnnSi1Lkx+IDohdPlFp222wVALIheZJQSEg==", "dev": true, "dependencies": { "color-convert": "^2.0.1" }, "engines": { "node": ">=8" }, "funding": { "url": "https://github.com/chalk/ansi-styles?sponsor=1" } }, "node_modules/anymatch": { "version": "3.1.3", "resolved": "https://registry.npmjs.org/anymatch/-/anymatch-3.1.3.tgz", "integrity": "sha512-KMReFUr0B4t+D+OBkjR3KYqvocp2XaSzO55UcB6mgQMd3KbcE+mWTyvVV7D/zsdEbNnV6acZUutkiHQXvTr1Rw==", "dev": true, "dependencies": { "normalize-path": "^3.0.0", "picomatch": "^2.0.4" }, "engines": { "node": ">= 8" } }, "node_modules/arg": { "version": "4.1.3", "resolved": "https://registry.npmjs.org/arg/-/arg-4.1.3.tgz", "integrity": "sha512-58S9QDqG0Xx27YwPSt9fJxivjYl432YCwfDMfZ+71RAqUrZef7LrKQZ3LHLOwCS4FLNBplP533Zx895SeOCHvA==", "dev": true }, "node_modules/argparse": { "version": "1.0.10", "resolved": "https://registry.npmjs.org/argparse/-/argparse-1.0.10.tgz", "integrity": "sha512-o5Roy6tNG4SL/FOkCAN6RzjiakZS25RLYFrcMttJqbdd8BWrnA+fGz57iN5Pb06pvBGvl5gQ0B48dJlslXvoTg==", "dev": true, "dependencies": { "sprintf-js": "~1.0.2" } }, "node_modules/arr-diff": { "version": "4.0.0", "resolved": "https://registry.npmjs.org/arr-diff/-/arr-diff-4.0.0.tgz", "integrity": "sha512-YVIQ82gZPGBebQV/a8dar4AitzCQs0jjXwMPZllpXMaGjXPYVUawSxQrRsjhjupyVxEvbHgUmIhKVlND+j02kA==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/arr-flatten": { "version": "1.1.0", "resolved": "https://registry.npmjs.org/arr-flatten/-/arr-flatten-1.1.0.tgz", "integrity": "sha512-L3hKV5R/p5o81R7O02IGnwpDmkp6E982XhtbuwSe3O4qOtMMMtodicASA1Cny2U+aCXcNpml+m4dPsvsJ3jatg==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/arr-union": { "version": "3.1.0", "resolved": "https://registry.npmjs.org/arr-union/-/arr-union-3.1.0.tgz", "integrity": "sha512-sKpyeERZ02v1FeCZT8lrfJq5u6goHCtpTAzPwJYe7c8SPFOboNjNg1vz2L4VTn9T4PQxEx13TbXLmYUcS6Ug7Q==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/array-unique": { "version": "0.3.2", "resolved": "https://registry.npmjs.org/array-unique/-/array-unique-0.3.2.tgz", "integrity": "sha512-SleRWjh9JUud2wH1hPs9rZBZ33H6T9HOiL0uwGnGx9FpE6wKGyfWugmbkEOIs6qWrZhg0LWeLziLrEwQJhs5mQ==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/assign-symbols": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/assign-symbols/-/assign-symbols-1.0.0.tgz", "integrity": "sha512-Q+JC7Whu8HhmTdBph/Tq59IoRtoy6KAm5zzPv00WdujX82lbAL8K7WVjne7vdCsAmbF4AYaDOPyO3k0kl8qIrw==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/asynckit": { "version": "0.4.0", "resolved": "https://registry.npmjs.org/asynckit/-/asynckit-0.4.0.tgz", "integrity": "sha512-Oei9OH4tRh0YqU3GxhX79dM/mwVgvbZJaSNaRk+bshkj0S5cfHcgYakreBjrHwatXKbz+IoIdYLxrKim2MjW0Q==", "dev": true }, "node_modules/atob": { "version": "2.1.2", "resolved": "https://registry.npmjs.org/atob/-/atob-2.1.2.tgz", "integrity": "sha512-Wm6ukoaOGJi/73p/cl2GvLjTI5JM1k/O14isD73YML8StrH/7/lRFgmg8nICZgD3bZZvjwCGxtMOD3wWNAu8cg==", "dev": true, "bin": { "atob": "bin/atob.js" }, "engines": { "node": ">= 4.5.0" } }, "node_modules/aws-cdk": { "version": "2.20.0", "resolved": "https://registry.npmjs.org/aws-cdk/-/aws-cdk-2.20.0.tgz", "integrity": "sha512-rs9LTpvrlbsMcenZ3t7TuLDGbHhbnDocrE63Xb2PT++VptR/A8svllK8k1W7hPl77L9QS75GNK5gh+ShkEzsnw==", "dev": true, "bin": { "cdk": "bin/cdk" }, "engines": { "node": ">= 14.15.0" }, "optionalDependencies": { "fsevents": "2.3.2" } }, "node_modules/aws-cdk-lib": { "version": "2.88.0", "resolved": "https://registry.npmjs.org/aws-cdk-lib/-/aws-cdk-lib-2.88.0.tgz", "integrity": "sha512-bmhokh30HVeqlotWaoEmK7mKB9SJbJwpbsiVgmYe3JcMu8DposHQqaIPI7LnC+dg015tZaxUsExxOYBEw+vntQ==", "bundleDependencies": [ "@balena/dockerignore", "case", "fs-extra", "ignore", "jsonschema", "minimatch", "punycode", "semver", "table", "yaml" ], "dependencies": { "@aws-cdk/asset-awscli-v1": "^2.2.200", "@aws-cdk/asset-kubectl-v20": "^2.1.2", "@aws-cdk/asset-node-proxy-agent-v5": "^2.0.165", "@balena/dockerignore": "^1.0.2", "case": "1.6.3", "fs-extra": "^11.1.1", "ignore": "^5.2.4", "jsonschema": "^1.4.1", "minimatch": "^3.1.2", "punycode": "^2.3.0", "semver": "^7.5.4", "table": "^6.8.1", "yaml": "1.10.2" }, "engines": { "node": ">= 14.15.0" }, "peerDependencies": { "constructs": "^10.0.0" } }, "node_modules/aws-cdk-lib/node_modules/@balena/dockerignore": { "version": "1.0.2", "inBundle": true, "license": "Apache-2.0" }, "node_modules/aws-cdk-lib/node_modules/ajv": { "version": "8.12.0", "inBundle": true, "license": "MIT", "dependencies": { "fast-deep-equal": "^3.1.1", "json-schema-traverse": "^1.0.0", "require-from-string": "^2.0.2", "uri-js": "^4.2.2" }, "funding": { "type": "github", "url": "https://github.com/sponsors/epoberezkin" } }, "node_modules/aws-cdk-lib/node_modules/ansi-regex": { "version": "5.0.1", "inBundle": true, "license": "MIT", "engines": { "node": ">=8" } }, "node_modules/aws-cdk-lib/node_modules/ansi-styles": { "version": "4.3.0", "inBundle": true, "license": "MIT", "dependencies": { "color-convert": "^2.0.1" }, "engines": { "node": ">=8" }, "funding": { "url": "https://github.com/chalk/ansi-styles?sponsor=1" } }, "node_modules/aws-cdk-lib/node_modules/astral-regex": { "version": "2.0.0", "inBundle": true, "license": "MIT", "engines": { "node": ">=8" } }, "node_modules/aws-cdk-lib/node_modules/balanced-match": { "version": "1.0.2", "inBundle": true, "license": "MIT" }, "node_modules/aws-cdk-lib/node_modules/brace-expansion": { "version": "1.1.11", "inBundle": true, "license": "MIT", "dependencies": { "balanced-match": "^1.0.0", "concat-map": "0.0.1" } }, "node_modules/aws-cdk-lib/node_modules/case": { "version": "1.6.3", "inBundle": true, "license": "(MIT OR GPL-3.0-or-later)", "engines": { "node": ">= 0.8.0" } }, "node_modules/aws-cdk-lib/node_modules/color-convert": { "version": "2.0.1", "inBundle": true, "license": "MIT", "dependencies": { "color-name": "~1.1.4" }, "engines": { "node": ">=7.0.0" } }, "node_modules/aws-cdk-lib/node_modules/color-name": { "version": "1.1.4", "inBundle": true, "license": "MIT" }, "node_modules/aws-cdk-lib/node_modules/concat-map": { "version": "0.0.1", "inBundle": true, "license": "MIT" }, "node_modules/aws-cdk-lib/node_modules/emoji-regex": { "version": "8.0.0", "inBundle": true, "license": "MIT" }, "node_modules/aws-cdk-lib/node_modules/fast-deep-equal": { "version": "3.1.3", "inBundle": true, "license": "MIT" }, "node_modules/aws-cdk-lib/node_modules/fs-extra": { "version": "11.1.1", "inBundle": true, "license": "MIT", "dependencies": { "graceful-fs": "^4.2.0", "jsonfile": "^6.0.1", "universalify": "^2.0.0" }, "engines": { "node": ">=14.14" } }, "node_modules/aws-cdk-lib/node_modules/graceful-fs": { "version": "4.2.11", "inBundle": true, "license": "ISC" }, "node_modules/aws-cdk-lib/node_modules/ignore": { "version": "5.2.4", "inBundle": true, "license": "MIT", "engines": { "node": ">= 4" } }, "node_modules/aws-cdk-lib/node_modules/is-fullwidth-code-point": { "version": "3.0.0", "inBundle": true, "license": "MIT", "engines": { "node": ">=8" } }, "node_modules/aws-cdk-lib/node_modules/json-schema-traverse": { "version": "1.0.0", "inBundle": true, "license": "MIT" }, "node_modules/aws-cdk-lib/node_modules/jsonfile": { "version": "6.1.0", "inBundle": true, "license": "MIT", "dependencies": { "universalify": "^2.0.0" }, "optionalDependencies": { "graceful-fs": "^4.1.6" } }, "node_modules/aws-cdk-lib/node_modules/jsonschema": { "version": "1.4.1", "inBundle": true, "license": "MIT", "engines": { "node": "*" } }, "node_modules/aws-cdk-lib/node_modules/lodash.truncate": { "version": "4.4.2", "inBundle": true, "license": "MIT" }, "node_modules/aws-cdk-lib/node_modules/lru-cache": { "version": "6.0.0", "inBundle": true, "license": "ISC", "dependencies": { "yallist": "^4.0.0" }, "engines": { "node": ">=10" } }, "node_modules/aws-cdk-lib/node_modules/minimatch": { "version": "3.1.2", "inBundle": true, "license": "ISC", "dependencies": { "brace-expansion": "^1.1.7" }, "engines": { "node": "*" } }, "node_modules/aws-cdk-lib/node_modules/punycode": { "version": "2.3.0", "inBundle": true, "license": "MIT", "engines": { "node": ">=6" } }, "node_modules/aws-cdk-lib/node_modules/require-from-string": { "version": "2.0.2", "inBundle": true, "license": "MIT", "engines": { "node": ">=0.10.0" } }, "node_modules/aws-cdk-lib/node_modules/semver": { "version": "7.5.4", "inBundle": true, "license": "ISC", "dependencies": { "lru-cache": "^6.0.0" }, "bin": { "semver": "bin/semver.js" }, "engines": { "node": ">=10" } }, "node_modules/aws-cdk-lib/node_modules/slice-ansi": { "version": "4.0.0", "inBundle": true, "license": "MIT", "dependencies": { "ansi-styles": "^4.0.0", "astral-regex": "^2.0.0", "is-fullwidth-code-point": "^3.0.0" }, "engines": { "node": ">=10" }, "funding": { "url": "https://github.com/chalk/slice-ansi?sponsor=1" } }, "node_modules/aws-cdk-lib/node_modules/string-width": { "version": "4.2.3", "inBundle": true, "license": "MIT", "dependencies": { "emoji-regex": "^8.0.0", "is-fullwidth-code-point": "^3.0.0", "strip-ansi": "^6.0.1" }, "engines": { "node": ">=8" } }, "node_modules/aws-cdk-lib/node_modules/strip-ansi": { "version": "6.0.1", "inBundle": true, "license": "MIT", "dependencies": { "ansi-regex": "^5.0.1" }, "engines": { "node": ">=8" } }, "node_modules/aws-cdk-lib/node_modules/table": { "version": "6.8.1", "inBundle": true, "license": "BSD-3-Clause", "dependencies": { "ajv": "^8.0.1", "lodash.truncate": "^4.4.2", "slice-ansi": "^4.0.0", "string-width": "^4.2.3", "strip-ansi": "^6.0.1" }, "engines": { "node": ">=10.0.0" } }, "node_modules/aws-cdk-lib/node_modules/universalify": { "version": "2.0.0", "inBundle": true, "license": "MIT", "engines": { "node": ">= 10.0.0" } }, "node_modules/aws-cdk-lib/node_modules/uri-js": { "version": "4.4.1", "inBundle": true, "license": "BSD-2-Clause", "dependencies": { "punycode": "^2.1.0" } }, "node_modules/aws-cdk-lib/node_modules/yallist": { "version": "4.0.0", "inBundle": true, "license": "ISC" }, "node_modules/aws-cdk-lib/node_modules/yaml": { "version": "1.10.2", "inBundle": true, "license": "ISC", "engines": { "node": ">= 6" } }, "node_modules/babel-jest": { "version": "26.6.3", "resolved": "https://registry.npmjs.org/babel-jest/-/babel-jest-26.6.3.tgz", "integrity": "sha512-pl4Q+GAVOHwvjrck6jKjvmGhnO3jHX/xuB9d27f+EJZ/6k+6nMuPjorrYp7s++bKKdANwzElBWnLWaObvTnaZA==", "dev": true, "dependencies": { "@jest/transform": "^26.6.2", "@jest/types": "^26.6.2", "@types/babel__core": "^7.1.7", "babel-plugin-istanbul": "^6.0.0", "babel-preset-jest": "^26.6.2", "chalk": "^4.0.0", "graceful-fs": "^4.2.4", "slash": "^3.0.0" }, "engines": { "node": ">= 10.14.2" }, "peerDependencies": { "@babel/core": "^7.0.0" } }, "node_modules/babel-plugin-istanbul": { "version": "6.1.1", "resolved": "https://registry.npmjs.org/babel-plugin-istanbul/-/babel-plugin-istanbul-6.1.1.tgz", "integrity": "sha512-Y1IQok9821cC9onCx5otgFfRm7Lm+I+wwxOx738M/WLPZ9Q42m4IG5W0FNX8WLL2gYMZo3JkuXIH2DOpWM+qwA==", "dev": true, "dependencies": { "@babel/helper-plugin-utils": "^7.0.0", "@istanbuljs/load-nyc-config": "^1.0.0", "@istanbuljs/schema": "^0.1.2", "istanbul-lib-instrument": "^5.0.4", "test-exclude": "^6.0.0" }, "engines": { "node": ">=8" } }, "node_modules/babel-plugin-istanbul/node_modules/istanbul-lib-instrument": { "version": "5.2.1", "resolved": "https://registry.npmjs.org/istanbul-lib-instrument/-/istanbul-lib-instrument-5.2.1.tgz", "integrity": "sha512-pzqtp31nLv/XFOzXGuvhCb8qhjmTVo5vjVk19XE4CRlSWz0KoeJ3bw9XsA7nOp9YBf4qHjwBxkDzKcME/J29Yg==", "dev": true, "dependencies": { "@babel/core": "^7.12.3", "@babel/parser": "^7.14.7", "@istanbuljs/schema": "^0.1.2", "istanbul-lib-coverage": "^3.2.0", "semver": "^6.3.0" }, "engines": { "node": ">=8" } }, "node_modules/babel-plugin-jest-hoist": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/babel-plugin-jest-hoist/-/babel-plugin-jest-hoist-26.6.2.tgz", "integrity": "sha512-PO9t0697lNTmcEHH69mdtYiOIkkOlj9fySqfO3K1eCcdISevLAE0xY59VLLUj0SoiPiTX/JU2CYFpILydUa5Lw==", "dev": true, "dependencies": { "@babel/template": "^7.3.3", "@babel/types": "^7.3.3", "@types/babel__core": "^7.0.0", "@types/babel__traverse": "^7.0.6" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/babel-preset-current-node-syntax": { "version": "1.0.1", "resolved": "https://registry.npmjs.org/babel-preset-current-node-syntax/-/babel-preset-current-node-syntax-1.0.1.tgz", "integrity": "sha512-M7LQ0bxarkxQoN+vz5aJPsLBn77n8QgTFmo8WK0/44auK2xlCXrYcUxHFxgU7qW5Yzw/CjmLRK2uJzaCd7LvqQ==", "dev": true, "dependencies": { "@babel/plugin-syntax-async-generators": "^7.8.4", "@babel/plugin-syntax-bigint": "^7.8.3", "@babel/plugin-syntax-class-properties": "^7.8.3", "@babel/plugin-syntax-import-meta": "^7.8.3", "@babel/plugin-syntax-json-strings": "^7.8.3", "@babel/plugin-syntax-logical-assignment-operators": "^7.8.3", "@babel/plugin-syntax-nullish-coalescing-operator": "^7.8.3", "@babel/plugin-syntax-numeric-separator": "^7.8.3", "@babel/plugin-syntax-object-rest-spread": "^7.8.3", "@babel/plugin-syntax-optional-catch-binding": "^7.8.3", "@babel/plugin-syntax-optional-chaining": "^7.8.3", "@babel/plugin-syntax-top-level-await": "^7.8.3" }, "peerDependencies": { "@babel/core": "^7.0.0" } }, "node_modules/babel-preset-jest": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/babel-preset-jest/-/babel-preset-jest-26.6.2.tgz", "integrity": "sha512-YvdtlVm9t3k777c5NPQIv6cxFFFapys25HiUmuSgHwIZhfifweR5c5Sf5nwE3MAbfu327CYSvps8Yx6ANLyleQ==", "dev": true, "dependencies": { "babel-plugin-jest-hoist": "^26.6.2", "babel-preset-current-node-syntax": "^1.0.0" }, "engines": { "node": ">= 10.14.2" }, "peerDependencies": { "@babel/core": "^7.0.0" } }, "node_modules/balanced-match": { "version": "1.0.2", "resolved": "https://registry.npmjs.org/balanced-match/-/balanced-match-1.0.2.tgz", "integrity": "sha512-3oSeUO0TMV67hN1AmbXsK4yaqU7tjiHlbxRDZOpH0KW9+CeX4bRAaX0Anxt0tx2MrpRpWwQaPwIlISEJhYU5Pw==", "dev": true }, "node_modules/base": { "version": "0.11.2", "resolved": "https://registry.npmjs.org/base/-/base-0.11.2.tgz", "integrity": "sha512-5T6P4xPgpp0YDFvSWwEZ4NoE3aM4QBQXDzmVbraCkFj8zHM+mba8SyqB5DbZWyR7mYHo6Y7BdQo3MoA4m0TeQg==", "dev": true, "dependencies": { "cache-base": "^1.0.1", "class-utils": "^0.3.5", "component-emitter": "^1.2.1", "define-property": "^1.0.0", "isobject": "^3.0.1", "mixin-deep": "^1.2.0", "pascalcase": "^0.1.1" }, "engines": { "node": ">=0.10.0" } }, "node_modules/base/node_modules/define-property": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/define-property/-/define-property-1.0.0.tgz", "integrity": "sha512-cZTYKFWspt9jZsMscWo8sc/5lbPC9Q0N5nBLgb+Yd915iL3udB1uFgS3B8YCx66UVHq018DAVFoee7x+gxggeA==", "dev": true, "dependencies": { "is-descriptor": "^1.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/brace-expansion": { "version": "1.1.11", "resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-1.1.11.tgz", "integrity": "sha512-iCuPHDFgrHX7H2vEI/5xpz07zSHB00TpugqhmYtVmMO6518mCuRMoOYFldEBl0g187ufozdaHgWKcYFb61qGiA==", "dev": true, "dependencies": { "balanced-match": "^1.0.0", "concat-map": "0.0.1" } }, "node_modules/braces": { "version": "3.0.2", "resolved": "https://registry.npmjs.org/braces/-/braces-3.0.2.tgz", "integrity": "sha512-b8um+L1RzM3WDSzvhm6gIz1yfTbBt6YTlcEKAvsmqCZZFw46z626lVj9j1yEPW33H5H+lBQpZMP1k8l+78Ha0A==", "dev": true, "dependencies": { "fill-range": "^7.0.1" }, "engines": { "node": ">=8" } }, "node_modules/browser-process-hrtime": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/browser-process-hrtime/-/browser-process-hrtime-1.0.0.tgz", "integrity": "sha512-9o5UecI3GhkpM6DrXr69PblIuWxPKk9Y0jHBRhdocZ2y7YECBFCsHm79Pr3OyR2AvjhDkabFJaDJMYRazHgsow==", "dev": true }, "node_modules/browserslist": { "version": "4.21.10", "resolved": "https://registry.npmjs.org/browserslist/-/browserslist-4.21.10.tgz", "integrity": "sha512-bipEBdZfVH5/pwrvqc+Ub0kUPVfGUhlKxbvfD+z1BDnPEO/X98ruXGA1WP5ASpAFKan7Qr6j736IacbZQuAlKQ==", "dev": true, "funding": [ { "type": "opencollective", "url": "https://opencollective.com/browserslist" }, { "type": "tidelift", "url": "https://tidelift.com/funding/github/npm/browserslist" }, { "type": "github", "url": "https://github.com/sponsors/ai" } ], "dependencies": { "caniuse-lite": "^1.0.30001517", "electron-to-chromium": "^1.4.477", "node-releases": "^2.0.13", "update-browserslist-db": "^1.0.11" }, "bin": { "browserslist": "cli.js" }, "engines": { "node": "^6 || ^7 || ^8 || ^9 || ^10 || ^11 || ^12 || >=13.7" } }, "node_modules/bs-logger": { "version": "0.2.6", "resolved": "https://registry.npmjs.org/bs-logger/-/bs-logger-0.2.6.tgz", "integrity": "sha512-pd8DCoxmbgc7hyPKOvxtqNcjYoOsABPQdcCUjGp3d42VR2CX1ORhk2A87oqqu5R1kk+76nsxZupkmyd+MVtCog==", "dev": true, "dependencies": { "fast-json-stable-stringify": "2.x" }, "engines": { "node": ">= 6" } }, "node_modules/bser": { "version": "2.1.1", "resolved": "https://registry.npmjs.org/bser/-/bser-2.1.1.tgz", "integrity": "sha512-gQxTNE/GAfIIrmHLUE3oJyp5FO6HRBfhjnw4/wMmA63ZGDJnWBmgY/lyQBpnDUkGmAhbSe39tx2d/iTOAfglwQ==", "dev": true, "dependencies": { "node-int64": "^0.4.0" } }, "node_modules/buffer-from": { "version": "1.1.2", "resolved": "https://registry.npmjs.org/buffer-from/-/buffer-from-1.1.2.tgz", "integrity": "sha512-E+XQCRwSbaaiChtv6k6Dwgc+bx+Bs6vuKJHHl5kox/BaKbhiXzqQOwK4cO22yElGp2OCmjwVhT3HmxgyPGnJfQ==" }, "node_modules/cache-base": { "version": "1.0.1", "resolved": "https://registry.npmjs.org/cache-base/-/cache-base-1.0.1.tgz", "integrity": "sha512-AKcdTnFSWATd5/GCPRxr2ChwIJ85CeyrEyjRHlKxQ56d4XJMGym0uAiKn0xbLOGOl3+yRpOTi484dVCEc5AUzQ==", "dev": true, "dependencies": { "collection-visit": "^1.0.0", "component-emitter": "^1.2.1", "get-value": "^2.0.6", "has-value": "^1.0.0", "isobject": "^3.0.1", "set-value": "^2.0.0", "to-object-path": "^0.3.0", "union-value": "^1.0.0", "unset-value": "^1.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/callsites": { "version": "3.1.0", "resolved": "https://registry.npmjs.org/callsites/-/callsites-3.1.0.tgz", "integrity": "sha512-P8BjAsXvZS+VIDUI11hHCQEv74YT67YUi5JJFNWIqL235sBmjX4+qx9Muvls5ivyNENctx46xQLQ3aTuE7ssaQ==", "dev": true, "engines": { "node": ">=6" } }, "node_modules/camelcase": { "version": "5.3.1", "resolved": "https://registry.npmjs.org/camelcase/-/camelcase-5.3.1.tgz", "integrity": "sha512-L28STB170nwWS63UjtlEOE3dldQApaJXZkOI1uMFfzf3rRuPegHaHesyee+YxQ+W6SvRDQV6UrdOdRiR153wJg==", "dev": true, "engines": { "node": ">=6" } }, "node_modules/caniuse-lite": { "version": "1.0.30001519", "resolved": "https://registry.npmjs.org/caniuse-lite/-/caniuse-lite-1.0.30001519.tgz", "integrity": "sha512-0QHgqR+Jv4bxHMp8kZ1Kn8CH55OikjKJ6JmKkZYP1F3D7w+lnFXF70nG5eNfsZS89jadi5Ywy5UCSKLAglIRkg==", "dev": true, "funding": [ { "type": "opencollective", "url": "https://opencollective.com/browserslist" }, { "type": "tidelift", "url": "https://tidelift.com/funding/github/npm/caniuse-lite" }, { "type": "github", "url": "https://github.com/sponsors/ai" } ] }, "node_modules/capture-exit": { "version": "2.0.0", "resolved": "https://registry.npmjs.org/capture-exit/-/capture-exit-2.0.0.tgz", "integrity": "sha512-PiT/hQmTonHhl/HFGN+Lx3JJUznrVYJ3+AQsnthneZbvW7x+f08Tk7yLJTLEOUvBTbduLeeBkxEaYXUOUrRq6g==", "dev": true, "dependencies": { "rsvp": "^4.8.4" }, "engines": { "node": "6.* || 8.* || >= 10.*" } }, "node_modules/cdk-nag": { "version": "2.27.94", "resolved": "https://registry.npmjs.org/cdk-nag/-/cdk-nag-2.27.94.tgz", "integrity": "sha512-yKginlYCzbjYMQo1tV6IPyK9p7du84pgL0+WgTIkA0DgM0vqlZMCWh69vKJHpMraIx43xz75Tezyq9Pnd5tuzw==", "peerDependencies": { "aws-cdk-lib": "^2.78.0", "constructs": "^10.0.5" } }, "node_modules/chalk": { "version": "4.1.2", "resolved": "https://registry.npmjs.org/chalk/-/chalk-4.1.2.tgz", "integrity": "sha512-oKnbhFyRIXpUuez8iBMmyEa4nbj4IOQyuhc/wy9kY7/WVPcwIO9VA668Pu8RkO7+0G76SLROeyw9CpQ061i4mA==", "dev": true, "dependencies": { "ansi-styles": "^4.1.0", "supports-color": "^7.1.0" }, "engines": { "node": ">=10" }, "funding": { "url": "https://github.com/chalk/chalk?sponsor=1" } }, "node_modules/char-regex": { "version": "1.0.2", "resolved": "https://registry.npmjs.org/char-regex/-/char-regex-1.0.2.tgz", "integrity": "sha512-kWWXztvZ5SBQV+eRgKFeh8q5sLuZY2+8WUIzlxWVTg+oGwY14qylx1KbKzHd8P6ZYkAg0xyIDU9JMHhyJMZ1jw==", "dev": true, "engines": { "node": ">=10" } }, "node_modules/ci-info": { "version": "2.0.0", "resolved": "https://registry.npmjs.org/ci-info/-/ci-info-2.0.0.tgz", "integrity": "sha512-5tK7EtrZ0N+OLFMthtqOj4fI2Jeb88C4CAZPu25LDVUgXJ0A3Js4PMGqrn0JU1W0Mh1/Z8wZzYPxqUrXeBboCQ==", "dev": true }, "node_modules/cjs-module-lexer": { "version": "0.6.0", "resolved": "https://registry.npmjs.org/cjs-module-lexer/-/cjs-module-lexer-0.6.0.tgz", "integrity": "sha512-uc2Vix1frTfnuzxxu1Hp4ktSvM3QaI4oXl4ZUqL1wjTu/BGki9TrCWoqLTg/drR1KwAEarXuRFCG2Svr1GxPFw==", "dev": true }, "node_modules/class-utils": { "version": "0.3.6", "resolved": "https://registry.npmjs.org/class-utils/-/class-utils-0.3.6.tgz", "integrity": "sha512-qOhPa/Fj7s6TY8H8esGu5QNpMMQxz79h+urzrNYN6mn+9BnxlDGf5QZ+XeCDsxSjPqsSR56XOZOJmpeurnLMeg==", "dev": true, "dependencies": { "arr-union": "^3.1.0", "define-property": "^0.2.5", "isobject": "^3.0.0", "static-extend": "^0.1.1" }, "engines": { "node": ">=0.10.0" } }, "node_modules/class-utils/node_modules/define-property": { "version": "0.2.5", "resolved": "https://registry.npmjs.org/define-property/-/define-property-0.2.5.tgz", "integrity": "sha512-Rr7ADjQZenceVOAKop6ALkkRAmH1A4Gx9hV/7ZujPUN2rkATqFO0JZLZInbAjpZYoJ1gUx8MRMQVkYemcbMSTA==", "dev": true, "dependencies": { "is-descriptor": "^0.1.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/class-utils/node_modules/is-accessor-descriptor": { "version": "0.1.6", "resolved": "https://registry.npmjs.org/is-accessor-descriptor/-/is-accessor-descriptor-0.1.6.tgz", "integrity": "sha512-e1BM1qnDbMRG3ll2U9dSK0UMHuWOs3pY3AtcFsmvwPtKL3MML/Q86i+GilLfvqEs4GW+ExB91tQ3Ig9noDIZ+A==", "dev": true, "dependencies": { "kind-of": "^3.0.2" }, "engines": { "node": ">=0.10.0" } }, "node_modules/class-utils/node_modules/is-accessor-descriptor/node_modules/kind-of": { "version": "3.2.2", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-3.2.2.tgz", "integrity": "sha512-NOW9QQXMoZGg/oqnVNoNTTIFEIid1627WCffUBJEdMxYApq7mNE7CpzucIPc+ZQg25Phej7IJSmX3hO+oblOtQ==", "dev": true, "dependencies": { "is-buffer": "^1.1.5" }, "engines": { "node": ">=0.10.0" } }, "node_modules/class-utils/node_modules/is-data-descriptor": { "version": "0.1.4", "resolved": "https://registry.npmjs.org/is-data-descriptor/-/is-data-descriptor-0.1.4.tgz", "integrity": "sha512-+w9D5ulSoBNlmw9OHn3U2v51SyoCd0he+bB3xMl62oijhrspxowjU+AIcDY0N3iEJbUEkB15IlMASQsxYigvXg==", "dev": true, "dependencies": { "kind-of": "^3.0.2" }, "engines": { "node": ">=0.10.0" } }, "node_modules/class-utils/node_modules/is-data-descriptor/node_modules/kind-of": { "version": "3.2.2", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-3.2.2.tgz", "integrity": "sha512-NOW9QQXMoZGg/oqnVNoNTTIFEIid1627WCffUBJEdMxYApq7mNE7CpzucIPc+ZQg25Phej7IJSmX3hO+oblOtQ==", "dev": true, "dependencies": { "is-buffer": "^1.1.5" }, "engines": { "node": ">=0.10.0" } }, "node_modules/class-utils/node_modules/is-descriptor": { "version": "0.1.6", "resolved": "https://registry.npmjs.org/is-descriptor/-/is-descriptor-0.1.6.tgz", "integrity": "sha512-avDYr0SB3DwO9zsMov0gKCESFYqCnE4hq/4z3TdUlukEy5t9C0YRq7HLrsN52NAcqXKaepeCD0n+B0arnVG3Hg==", "dev": true, "dependencies": { "is-accessor-descriptor": "^0.1.6", "is-data-descriptor": "^0.1.4", "kind-of": "^5.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/class-utils/node_modules/kind-of": { "version": "5.1.0", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-5.1.0.tgz", "integrity": "sha512-NGEErnH6F2vUuXDh+OlbcKW7/wOcfdRHaZ7VWtqCztfHri/++YKmP51OdWeGPuqCOba6kk2OTe5d02VmTB80Pw==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/cliui": { "version": "6.0.0", "resolved": "https://registry.npmjs.org/cliui/-/cliui-6.0.0.tgz", "integrity": "sha512-t6wbgtoCXvAzst7QgXxJYqPt0usEfbgQdftEPbLL/cvv6HPE5VgvqCuAIDR0NgU52ds6rFwqrgakNLrHEjCbrQ==", "dev": true, "dependencies": { "string-width": "^4.2.0", "strip-ansi": "^6.0.0", "wrap-ansi": "^6.2.0" } }, "node_modules/co": { "version": "4.6.0", "resolved": "https://registry.npmjs.org/co/-/co-4.6.0.tgz", "integrity": "sha512-QVb0dM5HvG+uaxitm8wONl7jltx8dqhfU33DcqtOZcLSVIKSDDLDi7+0LbAKiyI8hD9u42m2YxXSkMGWThaecQ==", "dev": true, "engines": { "iojs": ">= 1.0.0", "node": ">= 0.12.0" } }, "node_modules/collect-v8-coverage": { "version": "1.0.2", "resolved": "https://registry.npmjs.org/collect-v8-coverage/-/collect-v8-coverage-1.0.2.tgz", "integrity": "sha512-lHl4d5/ONEbLlJvaJNtsF/Lz+WvB07u2ycqTYbdrq7UypDXailES4valYb2eWiJFxZlVmpGekfqoxQhzyFdT4Q==", "dev": true }, "node_modules/collection-visit": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/collection-visit/-/collection-visit-1.0.0.tgz", "integrity": "sha512-lNkKvzEeMBBjUGHZ+q6z9pSJla0KWAQPvtzhEV9+iGyQYG+pBpl7xKDhxoNSOZH2hhv0v5k0y2yAM4o4SjoSkw==", "dev": true, "dependencies": { "map-visit": "^1.0.0", "object-visit": "^1.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/color-convert": { "version": "2.0.1", "resolved": "https://registry.npmjs.org/color-convert/-/color-convert-2.0.1.tgz", "integrity": "sha512-RRECPsj7iu/xb5oKYcsFHSppFNnsj/52OVTRKb4zP5onXwVF3zVmmToNcOfGC+CRDpfK/U584fMg38ZHCaElKQ==", "dev": true, "dependencies": { "color-name": "~1.1.4" }, "engines": { "node": ">=7.0.0" } }, "node_modules/color-name": { "version": "1.1.4", "resolved": "https://registry.npmjs.org/color-name/-/color-name-1.1.4.tgz", "integrity": "sha512-dOy+3AuW3a2wNbZHIuMZpTcgjGuLU/uBL/ubcZF9OXbDo8ff4O8yVp5Bf0efS8uEoYo5q4Fx7dY9OgQGXgAsQA==", "dev": true }, "node_modules/combined-stream": { "version": "1.0.8", "resolved": "https://registry.npmjs.org/combined-stream/-/combined-stream-1.0.8.tgz", "integrity": "sha512-FQN4MRfuJeHf7cBbBMJFXhKSDq+2kAArBlmRBvcvFE5BB1HZKXtSFASDhdlz9zOYwxh8lDdnvmMOe/+5cdoEdg==", "dev": true, "dependencies": { "delayed-stream": "~1.0.0" }, "engines": { "node": ">= 0.8" } }, "node_modules/component-emitter": { "version": "1.3.0", "resolved": "https://registry.npmjs.org/component-emitter/-/component-emitter-1.3.0.tgz", "integrity": "sha512-Rd3se6QB+sO1TwqZjscQrurpEPIfO0/yYnSin6Q/rD3mOutHvUrCAhJub3r90uNb+SESBuE0QYoB90YdfatsRg==", "dev": true }, "node_modules/concat-map": { "version": "0.0.1", "resolved": "https://registry.npmjs.org/concat-map/-/concat-map-0.0.1.tgz", "integrity": "sha512-/Srv4dswyQNBfohGpz9o6Yb3Gz3SrUDqBH5rTuhGR7ahtlbYKnVxw2bCFMRljaA7EXHaXZ8wsHdodFvbkhKmqg==", "dev": true }, "node_modules/constructs": { "version": "10.2.69", "resolved": "https://registry.npmjs.org/constructs/-/constructs-10.2.69.tgz", "integrity": "sha512-0AiM/uQe5Uk6JVe/62oolmSN2MjbFQkOlYrM3fFGZLKuT+g7xlAI10EebFhyCcZwI2JAcWuWCmmCAyCothxjuw==", "engines": { "node": ">= 16.14.0" } }, "node_modules/convert-source-map": { "version": "1.9.0", "resolved": "https://registry.npmjs.org/convert-source-map/-/convert-source-map-1.9.0.tgz", "integrity": "sha512-ASFBup0Mz1uyiIjANan1jzLQami9z1PoYSZCiiYW2FczPbenXc45FZdBZLzOT+r6+iciuEModtmCti+hjaAk0A==", "dev": true }, "node_modules/copy-descriptor": { "version": "0.1.1", "resolved": "https://registry.npmjs.org/copy-descriptor/-/copy-descriptor-0.1.1.tgz", "integrity": "sha512-XgZ0pFcakEUlbwQEVNg3+QAis1FyTL3Qel9FYy8pSkQqoG3PNoT0bOCQtOXcOkur21r2Eq2kI+IE+gsmAEVlYw==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/create-require": { "version": "1.1.1", "resolved": "https://registry.npmjs.org/create-require/-/create-require-1.1.1.tgz", "integrity": "sha512-dcKFX3jn0MpIaXjisoRvexIJVEKzaq7z2rZKxf+MSr9TkdmHmsU4m2lcLojrj/FHl8mk5VxMmYA+ftRkP/3oKQ==", "dev": true }, "node_modules/cross-spawn": { "version": "7.0.3", "resolved": "https://registry.npmjs.org/cross-spawn/-/cross-spawn-7.0.3.tgz", "integrity": "sha512-iRDPJKUPVEND7dHPO8rkbOnPpyDygcDFtWjpeWNCgy8WP2rXcxXL8TskReQl6OrB2G7+UJrags1q15Fudc7G6w==", "dev": true, "dependencies": { "path-key": "^3.1.0", "shebang-command": "^2.0.0", "which": "^2.0.1" }, "engines": { "node": ">= 8" } }, "node_modules/cssom": { "version": "0.4.4", "resolved": "https://registry.npmjs.org/cssom/-/cssom-0.4.4.tgz", "integrity": "sha512-p3pvU7r1MyyqbTk+WbNJIgJjG2VmTIaB10rI93LzVPrmDJKkzKYMtxxyAvQXR/NS6otuzveI7+7BBq3SjBS2mw==", "dev": true }, "node_modules/cssstyle": { "version": "2.3.0", "resolved": "https://registry.npmjs.org/cssstyle/-/cssstyle-2.3.0.tgz", "integrity": "sha512-AZL67abkUzIuvcHqk7c09cezpGNcxUxU4Ioi/05xHk4DQeTkWmGYftIE6ctU6AEt+Gn4n1lDStOtj7FKycP71A==", "dev": true, "dependencies": { "cssom": "~0.3.6" }, "engines": { "node": ">=8" } }, "node_modules/cssstyle/node_modules/cssom": { "version": "0.3.8", "resolved": "https://registry.npmjs.org/cssom/-/cssom-0.3.8.tgz", "integrity": "sha512-b0tGHbfegbhPJpxpiBPU2sCkigAqtM9O121le6bbOlgyV+NyGyCmVfJ6QW9eRjz8CpNfWEOYBIMIGRYkLwsIYg==", "dev": true }, "node_modules/data-urls": { "version": "2.0.0", "resolved": "https://registry.npmjs.org/data-urls/-/data-urls-2.0.0.tgz", "integrity": "sha512-X5eWTSXO/BJmpdIKCRuKUgSCgAN0OwliVK3yPKbwIWU1Tdw5BRajxlzMidvh+gwko9AfQ9zIj52pzF91Q3YAvQ==", "dev": true, "dependencies": { "abab": "^2.0.3", "whatwg-mimetype": "^2.3.0", "whatwg-url": "^8.0.0" }, "engines": { "node": ">=10" } }, "node_modules/debug": { "version": "4.3.4", "resolved": "https://registry.npmjs.org/debug/-/debug-4.3.4.tgz", "integrity": "sha512-PRWFHuSU3eDtQJPvnNY7Jcket1j0t5OuOsFzPPzsekD52Zl8qUfFIPEiswXqIvHWGVHOgX+7G/vCNNhehwxfkQ==", "dev": true, "dependencies": { "ms": "2.1.2" }, "engines": { "node": ">=6.0" }, "peerDependenciesMeta": { "supports-color": { "optional": true } } }, "node_modules/decamelize": { "version": "1.2.0", "resolved": "https://registry.npmjs.org/decamelize/-/decamelize-1.2.0.tgz", "integrity": "sha512-z2S+W9X73hAUUki+N+9Za2lBlun89zigOyGrsax+KUQ6wKW4ZoWpEYBkGhQjwAjjDCkWxhY0VKEhk8wzY7F5cA==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/decimal.js": { "version": "10.4.3", "resolved": "https://registry.npmjs.org/decimal.js/-/decimal.js-10.4.3.tgz", "integrity": "sha512-VBBaLc1MgL5XpzgIP7ny5Z6Nx3UrRkIViUkPUdtl9aya5amy3De1gsUUSB1g3+3sExYNjCAsAznmukyxCb1GRA==", "dev": true }, "node_modules/decode-uri-component": { "version": "0.2.2", "resolved": "https://registry.npmjs.org/decode-uri-component/-/decode-uri-component-0.2.2.tgz", "integrity": "sha512-FqUYQ+8o158GyGTrMFJms9qh3CqTKvAqgqsTnkLI8sKu0028orqBhxNMFkFen0zGyg6epACD32pjVk58ngIErQ==", "dev": true, "engines": { "node": ">=0.10" } }, "node_modules/deepmerge": { "version": "4.3.1", "resolved": "https://registry.npmjs.org/deepmerge/-/deepmerge-4.3.1.tgz", "integrity": "sha512-3sUqbMEc77XqpdNO7FRyRog+eW3ph+GYCbj+rK+uYyRMuwsVy0rMiVtPn+QJlKFvWP/1PYpapqYn0Me2knFn+A==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/define-property": { "version": "2.0.2", "resolved": "https://registry.npmjs.org/define-property/-/define-property-2.0.2.tgz", "integrity": "sha512-jwK2UV4cnPpbcG7+VRARKTZPUWowwXA8bzH5NP6ud0oeAxyYPuGZUAC7hMugpCdz4BeSZl2Dl9k66CHJ/46ZYQ==", "dev": true, "dependencies": { "is-descriptor": "^1.0.2", "isobject": "^3.0.1" }, "engines": { "node": ">=0.10.0" } }, "node_modules/delayed-stream": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/delayed-stream/-/delayed-stream-1.0.0.tgz", "integrity": "sha512-ZySD7Nf91aLB0RxL4KGrKHBXl7Eds1DAmEdcoVawXnLD7SDhpNgtuII2aAkg7a7QS41jxPSZ17p4VdGnMHk3MQ==", "dev": true, "engines": { "node": ">=0.4.0" } }, "node_modules/detect-newline": { "version": "3.1.0", "resolved": "https://registry.npmjs.org/detect-newline/-/detect-newline-3.1.0.tgz", "integrity": "sha512-TLz+x/vEXm/Y7P7wn1EJFNLxYpUD4TgMosxY6fAVJUnJMbupHBOncxyWUG9OpTaH9EBD7uFI5LfEgmMOc54DsA==", "dev": true, "engines": { "node": ">=8" } }, "node_modules/diff": { "version": "4.0.2", "resolved": "https://registry.npmjs.org/diff/-/diff-4.0.2.tgz", "integrity": "sha512-58lmxKSA4BNyLz+HHMUzlOEpg09FV+ev6ZMe3vJihgdxzgcwZ8VoEEPmALCZG9LmqfVoNMMKpttIYTVG6uDY7A==", "dev": true, "engines": { "node": ">=0.3.1" } }, "node_modules/diff-sequences": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/diff-sequences/-/diff-sequences-26.6.2.tgz", "integrity": "sha512-Mv/TDa3nZ9sbc5soK+OoA74BsS3mL37yixCvUAQkiuA4Wz6YtwP/K47n2rv2ovzHZvoiQeA5FTQOschKkEwB0Q==", "dev": true, "engines": { "node": ">= 10.14.2" } }, "node_modules/domexception": { "version": "2.0.1", "resolved": "https://registry.npmjs.org/domexception/-/domexception-2.0.1.tgz", "integrity": "sha512-yxJ2mFy/sibVQlu5qHjOkf9J3K6zgmCxgJ94u2EdvDOV09H+32LtRswEcUsmUWN72pVLOEnTSRaIVVzVQgS0dg==", "dev": true, "dependencies": { "webidl-conversions": "^5.0.0" }, "engines": { "node": ">=8" } }, "node_modules/domexception/node_modules/webidl-conversions": { "version": "5.0.0", "resolved": "https://registry.npmjs.org/webidl-conversions/-/webidl-conversions-5.0.0.tgz", "integrity": "sha512-VlZwKPCkYKxQgeSbH5EyngOmRp7Ww7I9rQLERETtf5ofd9pGeswWiOtogpEO850jziPRarreGxn5QIiTqpb2wA==", "dev": true, "engines": { "node": ">=8" } }, "node_modules/dotenv": { "version": "16.3.1", "resolved": "https://registry.npmjs.org/dotenv/-/dotenv-16.3.1.tgz", "integrity": "sha512-IPzF4w4/Rd94bA9imS68tZBaYyBWSCE47V1RGuMrB94iyTOIEwRmVL2x/4An+6mETpLrKJ5hQkB8W4kFAadeIQ==", "engines": { "node": ">=12" }, "funding": { "url": "https://github.com/motdotla/dotenv?sponsor=1" } }, "node_modules/electron-to-chromium": { "version": "1.4.487", "resolved": "https://registry.npmjs.org/electron-to-chromium/-/electron-to-chromium-1.4.487.tgz", "integrity": "sha512-XbCRs/34l31np/p33m+5tdBrdXu9jJkZxSbNxj5I0H1KtV2ZMSB+i/HYqDiRzHaFx2T5EdytjoBRe8QRJE2vQg==", "dev": true }, "node_modules/emittery": { "version": "0.7.2", "resolved": "https://registry.npmjs.org/emittery/-/emittery-0.7.2.tgz", "integrity": "sha512-A8OG5SR/ij3SsJdWDJdkkSYUjQdCUx6APQXem0SaEePBSRg4eymGYwBkKo1Y6DU+af/Jn2dBQqDBvjnr9Vi8nQ==", "dev": true, "engines": { "node": ">=10" }, "funding": { "url": "https://github.com/sindresorhus/emittery?sponsor=1" } }, "node_modules/emoji-regex": { "version": "8.0.0", "resolved": "https://registry.npmjs.org/emoji-regex/-/emoji-regex-8.0.0.tgz", "integrity": "sha512-MSjYzcWNOA0ewAHpz0MxpYFvwg6yjy1NG3xteoqz644VCo/RPgnr1/GGt+ic3iJTzQ8Eu3TdM14SawnVUmGE6A==", "dev": true }, "node_modules/end-of-stream": { "version": "1.4.4", "resolved": "https://registry.npmjs.org/end-of-stream/-/end-of-stream-1.4.4.tgz", "integrity": "sha512-+uw1inIHVPQoaVuHzRyXd21icM+cnt4CzD5rW+NC1wjOUSTOs+Te7FOv7AhN7vS9x/oIyhLP5PR1H+phQAHu5Q==", "dev": true, "dependencies": { "once": "^1.4.0" } }, "node_modules/envalid": { "version": "7.3.1", "resolved": "https://registry.npmjs.org/envalid/-/envalid-7.3.1.tgz", "integrity": "sha512-KL1YRwn8WcoF/Ty7t+yLLtZol01xr9ZJMTjzoGRM8NaSU+nQQjSWOQKKJhJP2P57bpdakJ9jbxqQX4fGTOicZg==", "dependencies": { "tslib": "2.3.1" }, "engines": { "node": ">=8.12" } }, "node_modules/error-ex": { "version": "1.3.2", "resolved": "https://registry.npmjs.org/error-ex/-/error-ex-1.3.2.tgz", "integrity": "sha512-7dFHNmqeFSEt2ZBsCriorKnn3Z2pj+fd9kmI6QoWw4//DL+icEBfc0U7qJCisqrTsKTjw4fNFy2pW9OqStD84g==", "dev": true, "dependencies": { "is-arrayish": "^0.2.1" } }, "node_modules/escalade": { "version": "3.1.1", "resolved": "https://registry.npmjs.org/escalade/-/escalade-3.1.1.tgz", "integrity": "sha512-k0er2gUkLf8O0zKJiAhmkTnJlTvINGv7ygDNPbeIsX/TJjGJZHuh9B2UxbsaEkmlEo9MfhrSzmhIlhRlI2GXnw==", "dev": true, "engines": { "node": ">=6" } }, "node_modules/escape-string-regexp": { "version": "2.0.0", "resolved": "https://registry.npmjs.org/escape-string-regexp/-/escape-string-regexp-2.0.0.tgz", "integrity": "sha512-UpzcLCXolUWcNu5HtVMHYdXJjArjsF9C0aNnquZYY4uW/Vu0miy5YoWvbV345HauVvcAUnpRuhMMcqTcGOY2+w==", "dev": true, "engines": { "node": ">=8" } }, "node_modules/escodegen": { "version": "2.1.0", "resolved": "https://registry.npmjs.org/escodegen/-/escodegen-2.1.0.tgz", "integrity": "sha512-2NlIDTwUWJN0mRPQOdtQBzbUHvdGY2P1VXSyU83Q3xKxM7WHX2Ql8dKq782Q9TgQUNOLEzEYu9bzLNj1q88I5w==", "dev": true, "dependencies": { "esprima": "^4.0.1", "estraverse": "^5.2.0", "esutils": "^2.0.2" }, "bin": { "escodegen": "bin/escodegen.js", "esgenerate": "bin/esgenerate.js" }, "engines": { "node": ">=6.0" }, "optionalDependencies": { "source-map": "~0.6.1" } }, "node_modules/esprima": { "version": "4.0.1", "resolved": "https://registry.npmjs.org/esprima/-/esprima-4.0.1.tgz", "integrity": "sha512-eGuFFw7Upda+g4p+QHvnW0RyTX/SVeJBDM/gCtMARO0cLuT2HcEKnTPvhjV6aGeqrCB/sbNop0Kszm0jsaWU4A==", "dev": true, "bin": { "esparse": "bin/esparse.js", "esvalidate": "bin/esvalidate.js" }, "engines": { "node": ">=4" } }, "node_modules/estraverse": { "version": "5.3.0", "resolved": "https://registry.npmjs.org/estraverse/-/estraverse-5.3.0.tgz", "integrity": "sha512-MMdARuVEQziNTeJD8DgMqmhwR11BRQ/cBP+pLtYdSTnf3MIO8fFeiINEbX36ZdNlfU/7A9f3gUw49B3oQsvwBA==", "dev": true, "engines": { "node": ">=4.0" } }, "node_modules/esutils": { "version": "2.0.3", "resolved": "https://registry.npmjs.org/esutils/-/esutils-2.0.3.tgz", "integrity": "sha512-kVscqXk4OCp68SZ0dkgEKVi6/8ij300KBWTJq32P/dYeWTSwK41WyTxalN1eRmA5Z9UU/LX9D7FWSmV9SAYx6g==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/exec-sh": { "version": "0.3.6", "resolved": "https://registry.npmjs.org/exec-sh/-/exec-sh-0.3.6.tgz", "integrity": "sha512-nQn+hI3yp+oD0huYhKwvYI32+JFeq+XkNcD1GAo3Y/MjxsfVGmrrzrnzjWiNY6f+pUCP440fThsFh5gZrRAU/w==", "dev": true }, "node_modules/execa": { "version": "4.1.0", "resolved": "https://registry.npmjs.org/execa/-/execa-4.1.0.tgz", "integrity": "sha512-j5W0//W7f8UxAn8hXVnwG8tLwdiUy4FJLcSupCg6maBYZDpyBvTApK7KyuI4bKj8KOh1r2YH+6ucuYtJv1bTZA==", "dev": true, "dependencies": { "cross-spawn": "^7.0.0", "get-stream": "^5.0.0", "human-signals": "^1.1.1", "is-stream": "^2.0.0", "merge-stream": "^2.0.0", "npm-run-path": "^4.0.0", "onetime": "^5.1.0", "signal-exit": "^3.0.2", "strip-final-newline": "^2.0.0" }, "engines": { "node": ">=10" }, "funding": { "url": "https://github.com/sindresorhus/execa?sponsor=1" } }, "node_modules/exit": { "version": "0.1.2", "resolved": "https://registry.npmjs.org/exit/-/exit-0.1.2.tgz", "integrity": "sha512-Zk/eNKV2zbjpKzrsQ+n1G6poVbErQxJ0LBOJXaKZ1EViLzH+hrLu9cdXI4zw9dBQJslwBEpbQ2P1oS7nDxs6jQ==", "dev": true, "engines": { "node": ">= 0.8.0" } }, "node_modules/expand-brackets": { "version": "2.1.4", "resolved": "https://registry.npmjs.org/expand-brackets/-/expand-brackets-2.1.4.tgz", "integrity": "sha512-w/ozOKR9Obk3qoWeY/WDi6MFta9AoMR+zud60mdnbniMcBxRuFJyDt2LdX/14A1UABeqk+Uk+LDfUpvoGKppZA==", "dev": true, "dependencies": { "debug": "^2.3.3", "define-property": "^0.2.5", "extend-shallow": "^2.0.1", "posix-character-classes": "^0.1.0", "regex-not": "^1.0.0", "snapdragon": "^0.8.1", "to-regex": "^3.0.1" }, "engines": { "node": ">=0.10.0" } }, "node_modules/expand-brackets/node_modules/debug": { "version": "2.6.9", "resolved": "https://registry.npmjs.org/debug/-/debug-2.6.9.tgz", "integrity": "sha512-bC7ElrdJaJnPbAP+1EotYvqZsb3ecl5wi6Bfi6BJTUcNowp6cvspg0jXznRTKDjm/E7AdgFBVeAPVMNcKGsHMA==", "dev": true, "dependencies": { "ms": "2.0.0" } }, "node_modules/expand-brackets/node_modules/define-property": { "version": "0.2.5", "resolved": "https://registry.npmjs.org/define-property/-/define-property-0.2.5.tgz", "integrity": "sha512-Rr7ADjQZenceVOAKop6ALkkRAmH1A4Gx9hV/7ZujPUN2rkATqFO0JZLZInbAjpZYoJ1gUx8MRMQVkYemcbMSTA==", "dev": true, "dependencies": { "is-descriptor": "^0.1.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/expand-brackets/node_modules/extend-shallow": { "version": "2.0.1", "resolved": "https://registry.npmjs.org/extend-shallow/-/extend-shallow-2.0.1.tgz", "integrity": "sha512-zCnTtlxNoAiDc3gqY2aYAWFx7XWWiasuF2K8Me5WbN8otHKTUKBwjPtNpRs/rbUZm7KxWAaNj7P1a/p52GbVug==", "dev": true, "dependencies": { "is-extendable": "^0.1.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/expand-brackets/node_modules/is-accessor-descriptor": { "version": "0.1.6", "resolved": "https://registry.npmjs.org/is-accessor-descriptor/-/is-accessor-descriptor-0.1.6.tgz", "integrity": "sha512-e1BM1qnDbMRG3ll2U9dSK0UMHuWOs3pY3AtcFsmvwPtKL3MML/Q86i+GilLfvqEs4GW+ExB91tQ3Ig9noDIZ+A==", "dev": true, "dependencies": { "kind-of": "^3.0.2" }, "engines": { "node": ">=0.10.0" } }, "node_modules/expand-brackets/node_modules/is-accessor-descriptor/node_modules/kind-of": { "version": "3.2.2", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-3.2.2.tgz", "integrity": "sha512-NOW9QQXMoZGg/oqnVNoNTTIFEIid1627WCffUBJEdMxYApq7mNE7CpzucIPc+ZQg25Phej7IJSmX3hO+oblOtQ==", "dev": true, "dependencies": { "is-buffer": "^1.1.5" }, "engines": { "node": ">=0.10.0" } }, "node_modules/expand-brackets/node_modules/is-data-descriptor": { "version": "0.1.4", "resolved": "https://registry.npmjs.org/is-data-descriptor/-/is-data-descriptor-0.1.4.tgz", "integrity": "sha512-+w9D5ulSoBNlmw9OHn3U2v51SyoCd0he+bB3xMl62oijhrspxowjU+AIcDY0N3iEJbUEkB15IlMASQsxYigvXg==", "dev": true, "dependencies": { "kind-of": "^3.0.2" }, "engines": { "node": ">=0.10.0" } }, "node_modules/expand-brackets/node_modules/is-data-descriptor/node_modules/kind-of": { "version": "3.2.2", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-3.2.2.tgz", "integrity": "sha512-NOW9QQXMoZGg/oqnVNoNTTIFEIid1627WCffUBJEdMxYApq7mNE7CpzucIPc+ZQg25Phej7IJSmX3hO+oblOtQ==", "dev": true, "dependencies": { "is-buffer": "^1.1.5" }, "engines": { "node": ">=0.10.0" } }, "node_modules/expand-brackets/node_modules/is-descriptor": { "version": "0.1.6", "resolved": "https://registry.npmjs.org/is-descriptor/-/is-descriptor-0.1.6.tgz", "integrity": "sha512-avDYr0SB3DwO9zsMov0gKCESFYqCnE4hq/4z3TdUlukEy5t9C0YRq7HLrsN52NAcqXKaepeCD0n+B0arnVG3Hg==", "dev": true, "dependencies": { "is-accessor-descriptor": "^0.1.6", "is-data-descriptor": "^0.1.4", "kind-of": "^5.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/expand-brackets/node_modules/is-extendable": { "version": "0.1.1", "resolved": "https://registry.npmjs.org/is-extendable/-/is-extendable-0.1.1.tgz", "integrity": "sha512-5BMULNob1vgFX6EjQw5izWDxrecWK9AM72rugNr0TFldMOi0fj6Jk+zeKIt0xGj4cEfQIJth4w3OKWOJ4f+AFw==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/expand-brackets/node_modules/kind-of": { "version": "5.1.0", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-5.1.0.tgz", "integrity": "sha512-NGEErnH6F2vUuXDh+OlbcKW7/wOcfdRHaZ7VWtqCztfHri/++YKmP51OdWeGPuqCOba6kk2OTe5d02VmTB80Pw==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/expand-brackets/node_modules/ms": { "version": "2.0.0", "resolved": "https://registry.npmjs.org/ms/-/ms-2.0.0.tgz", "integrity": "sha512-Tpp60P6IUJDTuOq/5Z8cdskzJujfwqfOTkrwIwj7IRISpnkJnT6SyJ4PCPnGMoFjC9ddhal5KVIYtAt97ix05A==", "dev": true }, "node_modules/expect": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/expect/-/expect-26.6.2.tgz", "integrity": "sha512-9/hlOBkQl2l/PLHJx6JjoDF6xPKcJEsUlWKb23rKE7KzeDqUZKXKNMW27KIue5JMdBV9HgmoJPcc8HtO85t9IA==", "dev": true, "dependencies": { "@jest/types": "^26.6.2", "ansi-styles": "^4.0.0", "jest-get-type": "^26.3.0", "jest-matcher-utils": "^26.6.2", "jest-message-util": "^26.6.2", "jest-regex-util": "^26.0.0" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/extend-shallow": { "version": "3.0.2", "resolved": "https://registry.npmjs.org/extend-shallow/-/extend-shallow-3.0.2.tgz", "integrity": "sha512-BwY5b5Ql4+qZoefgMj2NUmx+tehVTH/Kf4k1ZEtOHNFcm2wSxMRo992l6X3TIgni2eZVTZ85xMOjF31fwZAj6Q==", "dev": true, "dependencies": { "assign-symbols": "^1.0.0", "is-extendable": "^1.0.1" }, "engines": { "node": ">=0.10.0" } }, "node_modules/extglob": { "version": "2.0.4", "resolved": "https://registry.npmjs.org/extglob/-/extglob-2.0.4.tgz", "integrity": "sha512-Nmb6QXkELsuBr24CJSkilo6UHHgbekK5UiZgfE6UHD3Eb27YC6oD+bhcT+tJ6cl8dmsgdQxnWlcry8ksBIBLpw==", "dev": true, "dependencies": { "array-unique": "^0.3.2", "define-property": "^1.0.0", "expand-brackets": "^2.1.4", "extend-shallow": "^2.0.1", "fragment-cache": "^0.2.1", "regex-not": "^1.0.0", "snapdragon": "^0.8.1", "to-regex": "^3.0.1" }, "engines": { "node": ">=0.10.0" } }, "node_modules/extglob/node_modules/define-property": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/define-property/-/define-property-1.0.0.tgz", "integrity": "sha512-cZTYKFWspt9jZsMscWo8sc/5lbPC9Q0N5nBLgb+Yd915iL3udB1uFgS3B8YCx66UVHq018DAVFoee7x+gxggeA==", "dev": true, "dependencies": { "is-descriptor": "^1.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/extglob/node_modules/extend-shallow": { "version": "2.0.1", "resolved": "https://registry.npmjs.org/extend-shallow/-/extend-shallow-2.0.1.tgz", "integrity": "sha512-zCnTtlxNoAiDc3gqY2aYAWFx7XWWiasuF2K8Me5WbN8otHKTUKBwjPtNpRs/rbUZm7KxWAaNj7P1a/p52GbVug==", "dev": true, "dependencies": { "is-extendable": "^0.1.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/extglob/node_modules/is-extendable": { "version": "0.1.1", "resolved": "https://registry.npmjs.org/is-extendable/-/is-extendable-0.1.1.tgz", "integrity": "sha512-5BMULNob1vgFX6EjQw5izWDxrecWK9AM72rugNr0TFldMOi0fj6Jk+zeKIt0xGj4cEfQIJth4w3OKWOJ4f+AFw==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/fast-json-stable-stringify": { "version": "2.1.0", "resolved": "https://registry.npmjs.org/fast-json-stable-stringify/-/fast-json-stable-stringify-2.1.0.tgz", "integrity": "sha512-lhd/wF+Lk98HZoTCtlVraHtfh5XYijIjalXck7saUtuanSDyLMxnHhSXEDJqHxD7msR8D0uCmqlkwjCV8xvwHw==", "dev": true }, "node_modules/fb-watchman": { "version": "2.0.2", "resolved": "https://registry.npmjs.org/fb-watchman/-/fb-watchman-2.0.2.tgz", "integrity": "sha512-p5161BqbuCaSnB8jIbzQHOlpgsPmK5rJVDfDKO91Axs5NC1uu3HRQm6wt9cd9/+GtQQIO53JdGXXoyDpTAsgYA==", "dev": true, "dependencies": { "bser": "2.1.1" } }, "node_modules/fill-range": { "version": "7.0.1", "resolved": "https://registry.npmjs.org/fill-range/-/fill-range-7.0.1.tgz", "integrity": "sha512-qOo9F+dMUmC2Lcb4BbVvnKJxTPjCm+RRpe4gDuGrzkL7mEVl/djYSu2OdQ2Pa302N4oqkSg9ir6jaLWJ2USVpQ==", "dev": true, "dependencies": { "to-regex-range": "^5.0.1" }, "engines": { "node": ">=8" } }, "node_modules/find-up": { "version": "4.1.0", "resolved": "https://registry.npmjs.org/find-up/-/find-up-4.1.0.tgz", "integrity": "sha512-PpOwAdQ/YlXQ2vj8a3h8IipDuYRi3wceVQQGYWxNINccq40Anw7BlsEXCMbt1Zt+OLA6Fq9suIpIWD0OsnISlw==", "dev": true, "dependencies": { "locate-path": "^5.0.0", "path-exists": "^4.0.0" }, "engines": { "node": ">=8" } }, "node_modules/for-in": { "version": "1.0.2", "resolved": "https://registry.npmjs.org/for-in/-/for-in-1.0.2.tgz", "integrity": "sha512-7EwmXrOjyL+ChxMhmG5lnW9MPt1aIeZEwKhQzoBUdTV0N3zuwWDZYVJatDvZ2OyzPUvdIAZDsCetk3coyMfcnQ==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/form-data": { "version": "3.0.1", "resolved": "https://registry.npmjs.org/form-data/-/form-data-3.0.1.tgz", "integrity": "sha512-RHkBKtLWUVwd7SqRIvCZMEvAMoGUp0XU+seQiZejj0COz3RI3hWP4sCv3gZWWLjJTd7rGwcsF5eKZGii0r/hbg==", "dev": true, "dependencies": { "asynckit": "^0.4.0", "combined-stream": "^1.0.8", "mime-types": "^2.1.12" }, "engines": { "node": ">= 6" } }, "node_modules/fragment-cache": { "version": "0.2.1", "resolved": "https://registry.npmjs.org/fragment-cache/-/fragment-cache-0.2.1.tgz", "integrity": "sha512-GMBAbW9antB8iZRHLoGw0b3HANt57diZYFO/HL1JGIC1MjKrdmhxvrJbupnVvpys0zsz7yBApXdQyfepKly2kA==", "dev": true, "dependencies": { "map-cache": "^0.2.2" }, "engines": { "node": ">=0.10.0" } }, "node_modules/fs.realpath": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/fs.realpath/-/fs.realpath-1.0.0.tgz", "integrity": "sha512-OO0pH2lK6a0hZnAdau5ItzHPI6pUlvI7jMVnxUQRtw4owF2wk8lOSabtGDCTP4Ggrg2MbGnWO9X8K1t4+fGMDw==", "dev": true }, "node_modules/fsevents": { "version": "2.3.2", "resolved": "https://registry.npmjs.org/fsevents/-/fsevents-2.3.2.tgz", "integrity": "sha512-xiqMQR4xAeHTuB9uWm+fFRcIOgKBMiOBP+eXiyT7jsgVCq1bkVygt00oASowB7EdtpOHaaPgKt812P9ab+DDKA==", "dev": true, "hasInstallScript": true, "optional": true, "os": [ "darwin" ], "engines": { "node": "^8.16.0 || ^10.6.0 || >=11.0.0" } }, "node_modules/function-bind": { "version": "1.1.1", "resolved": "https://registry.npmjs.org/function-bind/-/function-bind-1.1.1.tgz", "integrity": "sha512-yIovAzMX49sF8Yl58fSCWJ5svSLuaibPxXQJFLmBObTuCr0Mf1KiPopGM9NiFjiYBCbfaa2Fh6breQ6ANVTI0A==", "dev": true }, "node_modules/gensync": { "version": "1.0.0-beta.2", "resolved": "https://registry.npmjs.org/gensync/-/gensync-1.0.0-beta.2.tgz", "integrity": "sha512-3hN7NaskYvMDLQY55gnW3NQ+mesEAepTqlg+VEbj7zzqEMBVNhzcGYYeqFo/TlYz6eQiFcp1HcsCZO+nGgS8zg==", "dev": true, "engines": { "node": ">=6.9.0" } }, "node_modules/get-caller-file": { "version": "2.0.5", "resolved": "https://registry.npmjs.org/get-caller-file/-/get-caller-file-2.0.5.tgz", "integrity": "sha512-DyFP3BM/3YHTQOCUL/w0OZHR0lpKeGrxotcHWcqNEdnltqFwXVfhEBQ94eIo34AfQpo0rGki4cyIiftY06h2Fg==", "dev": true, "engines": { "node": "6.* || 8.* || >= 10.*" } }, "node_modules/get-package-type": { "version": "0.1.0", "resolved": "https://registry.npmjs.org/get-package-type/-/get-package-type-0.1.0.tgz", "integrity": "sha512-pjzuKtY64GYfWizNAJ0fr9VqttZkNiK2iS430LtIHzjBEr6bX8Am2zm4sW4Ro5wjWW5cAlRL1qAMTcXbjNAO2Q==", "dev": true, "engines": { "node": ">=8.0.0" } }, "node_modules/get-stream": { "version": "5.2.0", "resolved": "https://registry.npmjs.org/get-stream/-/get-stream-5.2.0.tgz", "integrity": "sha512-nBF+F1rAZVCu/p7rjzgA+Yb4lfYXrpl7a6VmJrU8wF9I1CKvP/QwPNZHnOlwbTkY6dvtFIzFMSyQXbLoTQPRpA==", "dev": true, "dependencies": { "pump": "^3.0.0" }, "engines": { "node": ">=8" }, "funding": { "url": "https://github.com/sponsors/sindresorhus" } }, "node_modules/get-value": { "version": "2.0.6", "resolved": "https://registry.npmjs.org/get-value/-/get-value-2.0.6.tgz", "integrity": "sha512-Ln0UQDlxH1BapMu3GPtf7CuYNwRZf2gwCuPqbyG6pB8WfmFpzqcy4xtAaAMUhnNqjMKTiCPZG2oMT3YSx8U2NA==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/glob": { "version": "7.2.3", "resolved": "https://registry.npmjs.org/glob/-/glob-7.2.3.tgz", "integrity": "sha512-nFR0zLpU2YCaRxwoCJvL6UvCH2JFyFVIvwTLsIf21AuHlMskA1hhTdk+LlYJtOlYt9v6dvszD2BGRqBL+iQK9Q==", "dev": true, "dependencies": { "fs.realpath": "^1.0.0", "inflight": "^1.0.4", "inherits": "2", "minimatch": "^3.1.1", "once": "^1.3.0", "path-is-absolute": "^1.0.0" }, "engines": { "node": "*" }, "funding": { "url": "https://github.com/sponsors/isaacs" } }, "node_modules/globals": { "version": "11.12.0", "resolved": "https://registry.npmjs.org/globals/-/globals-11.12.0.tgz", "integrity": "sha512-WOBp/EEGUiIsJSp7wcv/y6MO+lV9UoncWqxuFfm8eBwzWNgyfBd6Gz+IeKQ9jCmyhoH99g15M3T+QaVHFjizVA==", "dev": true, "engines": { "node": ">=4" } }, "node_modules/graceful-fs": { "version": "4.2.11", "resolved": "https://registry.npmjs.org/graceful-fs/-/graceful-fs-4.2.11.tgz", "integrity": "sha512-RbJ5/jmFcNNCcDV5o9eTnBLJ/HszWV0P73bc+Ff4nS/rJj+YaS6IGyiOL0VoBYX+l1Wrl3k63h/KrH+nhJ0XvQ==", "dev": true }, "node_modules/growly": { "version": "1.3.0", "resolved": "https://registry.npmjs.org/growly/-/growly-1.3.0.tgz", "integrity": "sha512-+xGQY0YyAWCnqy7Cd++hc2JqMYzlm0dG30Jd0beaA64sROr8C4nt8Yc9V5Ro3avlSUDTN0ulqP/VBKi1/lLygw==", "dev": true, "optional": true }, "node_modules/has": { "version": "1.0.3", "resolved": "https://registry.npmjs.org/has/-/has-1.0.3.tgz", "integrity": "sha512-f2dvO0VU6Oej7RkWJGrehjbzMAjFp5/VKPp5tTpWIV4JHHZK1/BxbFRtf/siA2SWTe09caDmVtYYzWEIbBS4zw==", "dev": true, "dependencies": { "function-bind": "^1.1.1" }, "engines": { "node": ">= 0.4.0" } }, "node_modules/has-flag": { "version": "4.0.0", "resolved": "https://registry.npmjs.org/has-flag/-/has-flag-4.0.0.tgz", "integrity": "sha512-EykJT/Q1KjTWctppgIAgfSO0tKVuZUjhgMr17kqTumMl6Afv3EISleU7qZUzoXDFTAHTDC4NOoG/ZxU3EvlMPQ==", "dev": true, "engines": { "node": ">=8" } }, "node_modules/has-value": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/has-value/-/has-value-1.0.0.tgz", "integrity": "sha512-IBXk4GTsLYdQ7Rvt+GRBrFSVEkmuOUy4re0Xjd9kJSUQpnTrWR4/y9RpfexN9vkAPMFuQoeWKwqzPozRTlasGw==", "dev": true, "dependencies": { "get-value": "^2.0.6", "has-values": "^1.0.0", "isobject": "^3.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/has-values": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/has-values/-/has-values-1.0.0.tgz", "integrity": "sha512-ODYZC64uqzmtfGMEAX/FvZiRyWLpAC3vYnNunURUnkGVTS+mI0smVsWaPydRBsE3g+ok7h960jChO8mFcWlHaQ==", "dev": true, "dependencies": { "is-number": "^3.0.0", "kind-of": "^4.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/has-values/node_modules/is-number": { "version": "3.0.0", "resolved": "https://registry.npmjs.org/is-number/-/is-number-3.0.0.tgz", "integrity": "sha512-4cboCqIpliH+mAvFNegjZQ4kgKc3ZUhQVr3HvWbSh5q3WH2v82ct+T2Y1hdU5Gdtorx/cLifQjqCbL7bpznLTg==", "dev": true, "dependencies": { "kind-of": "^3.0.2" }, "engines": { "node": ">=0.10.0" } }, "node_modules/has-values/node_modules/is-number/node_modules/kind-of": { "version": "3.2.2", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-3.2.2.tgz", "integrity": "sha512-NOW9QQXMoZGg/oqnVNoNTTIFEIid1627WCffUBJEdMxYApq7mNE7CpzucIPc+ZQg25Phej7IJSmX3hO+oblOtQ==", "dev": true, "dependencies": { "is-buffer": "^1.1.5" }, "engines": { "node": ">=0.10.0" } }, "node_modules/has-values/node_modules/kind-of": { "version": "4.0.0", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-4.0.0.tgz", "integrity": "sha512-24XsCxmEbRwEDbz/qz3stgin8TTzZ1ESR56OMCN0ujYg+vRutNSiOj9bHH9u85DKgXguraugV5sFuvbD4FW/hw==", "dev": true, "dependencies": { "is-buffer": "^1.1.5" }, "engines": { "node": ">=0.10.0" } }, "node_modules/hosted-git-info": { "version": "2.8.9", "resolved": "https://registry.npmjs.org/hosted-git-info/-/hosted-git-info-2.8.9.tgz", "integrity": "sha512-mxIDAb9Lsm6DoOJ7xH+5+X4y1LU/4Hi50L9C5sIswK3JzULS4bwk1FvjdBgvYR4bzT4tuUQiC15FE2f5HbLvYw==", "dev": true }, "node_modules/html-encoding-sniffer": { "version": "2.0.1", "resolved": "https://registry.npmjs.org/html-encoding-sniffer/-/html-encoding-sniffer-2.0.1.tgz", "integrity": "sha512-D5JbOMBIR/TVZkubHT+OyT2705QvogUW4IBn6nHd756OwieSF9aDYFj4dv6HHEVGYbHaLETa3WggZYWWMyy3ZQ==", "dev": true, "dependencies": { "whatwg-encoding": "^1.0.5" }, "engines": { "node": ">=10" } }, "node_modules/html-escaper": { "version": "2.0.2", "resolved": "https://registry.npmjs.org/html-escaper/-/html-escaper-2.0.2.tgz", "integrity": "sha512-H2iMtd0I4Mt5eYiapRdIDjp+XzelXQ0tFE4JS7YFwFevXXMmOp9myNrUvCg0D6ws8iqkRPBfKHgbwig1SmlLfg==", "dev": true }, "node_modules/http-proxy-agent": { "version": "4.0.1", "resolved": "https://registry.npmjs.org/http-proxy-agent/-/http-proxy-agent-4.0.1.tgz", "integrity": "sha512-k0zdNgqWTGA6aeIRVpvfVob4fL52dTfaehylg0Y4UvSySvOq/Y+BOyPrgpUrA7HylqvU8vIZGsRuXmspskV0Tg==", "dev": true, "dependencies": { "@tootallnate/once": "1", "agent-base": "6", "debug": "4" }, "engines": { "node": ">= 6" } }, "node_modules/https-proxy-agent": { "version": "5.0.1", "resolved": "https://registry.npmjs.org/https-proxy-agent/-/https-proxy-agent-5.0.1.tgz", "integrity": "sha512-dFcAjpTQFgoLMzC2VwU+C/CbS7uRL0lWmxDITmqm7C+7F0Odmj6s9l6alZc6AELXhrnggM2CeWSXHGOdX2YtwA==", "dev": true, "dependencies": { "agent-base": "6", "debug": "4" }, "engines": { "node": ">= 6" } }, "node_modules/human-signals": { "version": "1.1.1", "resolved": "https://registry.npmjs.org/human-signals/-/human-signals-1.1.1.tgz", "integrity": "sha512-SEQu7vl8KjNL2eoGBLF3+wAjpsNfA9XMlXAYj/3EdaNfAlxKthD1xjEQfGOUhllCGGJVNY34bRr6lPINhNjyZw==", "dev": true, "engines": { "node": ">=8.12.0" } }, "node_modules/iconv-lite": { "version": "0.4.24", "resolved": "https://registry.npmjs.org/iconv-lite/-/iconv-lite-0.4.24.tgz", "integrity": "sha512-v3MXnZAcvnywkTUEZomIActle7RXXeedOR31wwl7VlyoXO4Qi9arvSenNQWne1TcRwhCL1HwLI21bEqdpj8/rA==", "dev": true, "dependencies": { "safer-buffer": ">= 2.1.2 < 3" }, "engines": { "node": ">=0.10.0" } }, "node_modules/import-local": { "version": "3.1.0", "resolved": "https://registry.npmjs.org/import-local/-/import-local-3.1.0.tgz", "integrity": "sha512-ASB07uLtnDs1o6EHjKpX34BKYDSqnFerfTOJL2HvMqF70LnxpjkzDB8J44oT9pu4AMPkQwf8jl6szgvNd2tRIg==", "dev": true, "dependencies": { "pkg-dir": "^4.2.0", "resolve-cwd": "^3.0.0" }, "bin": { "import-local-fixture": "fixtures/cli.js" }, "engines": { "node": ">=8" }, "funding": { "url": "https://github.com/sponsors/sindresorhus" } }, "node_modules/imurmurhash": { "version": "0.1.4", "resolved": "https://registry.npmjs.org/imurmurhash/-/imurmurhash-0.1.4.tgz", "integrity": "sha512-JmXMZ6wuvDmLiHEml9ykzqO6lwFbof0GG4IkcGaENdCRDDmMVnny7s5HsIgHCbaq0w2MyPhDqkhTUgS2LU2PHA==", "dev": true, "engines": { "node": ">=0.8.19" } }, "node_modules/inflight": { "version": "1.0.6", "resolved": "https://registry.npmjs.org/inflight/-/inflight-1.0.6.tgz", "integrity": "sha512-k92I/b08q4wvFscXCLvqfsHCrjrF7yiXsQuIVvVE7N82W3+aqpzuUdBbfhWcy/FZR3/4IgflMgKLOsvPDrGCJA==", "dev": true, "dependencies": { "once": "^1.3.0", "wrappy": "1" } }, "node_modules/inherits": { "version": "2.0.4", "resolved": "https://registry.npmjs.org/inherits/-/inherits-2.0.4.tgz", "integrity": "sha512-k/vGaX4/Yla3WzyMCvTQOXYeIHvqOKtnqBduzTHpzpQZzAskKMhZ2K+EnBiSM9zGSoIFeMpXKxa4dYeZIQqewQ==", "dev": true }, "node_modules/is-accessor-descriptor": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/is-accessor-descriptor/-/is-accessor-descriptor-1.0.0.tgz", "integrity": "sha512-m5hnHTkcVsPfqx3AKlyttIPb7J+XykHvJP2B9bZDjlhLIoEq4XoK64Vg7boZlVWYK6LUY94dYPEE7Lh0ZkZKcQ==", "dev": true, "dependencies": { "kind-of": "^6.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/is-arrayish": { "version": "0.2.1", "resolved": "https://registry.npmjs.org/is-arrayish/-/is-arrayish-0.2.1.tgz", "integrity": "sha512-zz06S8t0ozoDXMG+ube26zeCTNXcKIPJZJi8hBrF4idCLms4CG9QtK7qBl1boi5ODzFpjswb5JPmHCbMpjaYzg==", "dev": true }, "node_modules/is-buffer": { "version": "1.1.6", "resolved": "https://registry.npmjs.org/is-buffer/-/is-buffer-1.1.6.tgz", "integrity": "sha512-NcdALwpXkTm5Zvvbk7owOUSvVvBKDgKP5/ewfXEznmQFfs4ZRmanOeKBTjRVjka3QFoN6XJ+9F3USqfHqTaU5w==", "dev": true }, "node_modules/is-ci": { "version": "2.0.0", "resolved": "https://registry.npmjs.org/is-ci/-/is-ci-2.0.0.tgz", "integrity": "sha512-YfJT7rkpQB0updsdHLGWrvhBJfcfzNNawYDNIyQXJz0IViGf75O8EBPKSdvw2rF+LGCsX4FZ8tcr3b19LcZq4w==", "dev": true, "dependencies": { "ci-info": "^2.0.0" }, "bin": { "is-ci": "bin.js" } }, "node_modules/is-core-module": { "version": "2.13.0", "resolved": "https://registry.npmjs.org/is-core-module/-/is-core-module-2.13.0.tgz", "integrity": "sha512-Z7dk6Qo8pOCp3l4tsX2C5ZVas4V+UxwQodwZhLopL91TX8UyyHEXafPcyoeeWuLrwzHcr3igO78wNLwHJHsMCQ==", "dev": true, "dependencies": { "has": "^1.0.3" }, "funding": { "url": "https://github.com/sponsors/ljharb" } }, "node_modules/is-data-descriptor": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/is-data-descriptor/-/is-data-descriptor-1.0.0.tgz", "integrity": "sha512-jbRXy1FmtAoCjQkVmIVYwuuqDFUbaOeDjmed1tOGPrsMhtJA4rD9tkgA0F1qJ3gRFRXcHYVkdeaP50Q5rE/jLQ==", "dev": true, "dependencies": { "kind-of": "^6.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/is-descriptor": { "version": "1.0.2", "resolved": "https://registry.npmjs.org/is-descriptor/-/is-descriptor-1.0.2.tgz", "integrity": "sha512-2eis5WqQGV7peooDyLmNEPUrps9+SXX5c9pL3xEB+4e9HnGuDa7mB7kHxHw4CbqS9k1T2hOH3miL8n8WtiYVtg==", "dev": true, "dependencies": { "is-accessor-descriptor": "^1.0.0", "is-data-descriptor": "^1.0.0", "kind-of": "^6.0.2" }, "engines": { "node": ">=0.10.0" } }, "node_modules/is-docker": { "version": "2.2.1", "resolved": "https://registry.npmjs.org/is-docker/-/is-docker-2.2.1.tgz", "integrity": "sha512-F+i2BKsFrH66iaUFc0woD8sLy8getkwTwtOBjvs56Cx4CgJDeKQeqfz8wAYiSb8JOprWhHH5p77PbmYCvvUuXQ==", "dev": true, "optional": true, "bin": { "is-docker": "cli.js" }, "engines": { "node": ">=8" }, "funding": { "url": "https://github.com/sponsors/sindresorhus" } }, "node_modules/is-extendable": { "version": "1.0.1", "resolved": "https://registry.npmjs.org/is-extendable/-/is-extendable-1.0.1.tgz", "integrity": "sha512-arnXMxT1hhoKo9k1LZdmlNyJdDDfy2v0fXjFlmok4+i8ul/6WlbVge9bhM74OpNPQPMGUToDtz+KXa1PneJxOA==", "dev": true, "dependencies": { "is-plain-object": "^2.0.4" }, "engines": { "node": ">=0.10.0" } }, "node_modules/is-fullwidth-code-point": { "version": "3.0.0", "resolved": "https://registry.npmjs.org/is-fullwidth-code-point/-/is-fullwidth-code-point-3.0.0.tgz", "integrity": "sha512-zymm5+u+sCsSWyD9qNaejV3DFvhCKclKdizYaJUuHA83RLjb7nSuGnddCHGv0hk+KY7BMAlsWeK4Ueg6EV6XQg==", "dev": true, "engines": { "node": ">=8" } }, "node_modules/is-generator-fn": { "version": "2.1.0", "resolved": "https://registry.npmjs.org/is-generator-fn/-/is-generator-fn-2.1.0.tgz", "integrity": "sha512-cTIB4yPYL/Grw0EaSzASzg6bBy9gqCofvWN8okThAYIxKJZC+udlRAmGbM0XLeniEJSs8uEgHPGuHSe1XsOLSQ==", "dev": true, "engines": { "node": ">=6" } }, "node_modules/is-number": { "version": "7.0.0", "resolved": "https://registry.npmjs.org/is-number/-/is-number-7.0.0.tgz", "integrity": "sha512-41Cifkg6e8TylSpdtTpeLVMqvSBEVzTttHvERD741+pnZ8ANv0004MRL43QKPDlK9cGvNp6NZWZUBlbGXYxxng==", "dev": true, "engines": { "node": ">=0.12.0" } }, "node_modules/is-plain-object": { "version": "2.0.4", "resolved": "https://registry.npmjs.org/is-plain-object/-/is-plain-object-2.0.4.tgz", "integrity": "sha512-h5PpgXkWitc38BBMYawTYMWJHFZJVnBquFE57xFpjB8pJFiF6gZ+bU+WyI/yqXiFR5mdLsgYNaPe8uao6Uv9Og==", "dev": true, "dependencies": { "isobject": "^3.0.1" }, "engines": { "node": ">=0.10.0" } }, "node_modules/is-potential-custom-element-name": { "version": "1.0.1", "resolved": "https://registry.npmjs.org/is-potential-custom-element-name/-/is-potential-custom-element-name-1.0.1.tgz", "integrity": "sha512-bCYeRA2rVibKZd+s2625gGnGF/t7DSqDs4dP7CrLA1m7jKWz6pps0LpYLJN8Q64HtmPKJ1hrN3nzPNKFEKOUiQ==", "dev": true }, "node_modules/is-stream": { "version": "2.0.1", "resolved": "https://registry.npmjs.org/is-stream/-/is-stream-2.0.1.tgz", "integrity": "sha512-hFoiJiTl63nn+kstHGBtewWSKnQLpyb155KHheA1l39uvtO9nWIop1p3udqPcUd/xbF1VLMO4n7OI6p7RbngDg==", "dev": true, "engines": { "node": ">=8" }, "funding": { "url": "https://github.com/sponsors/sindresorhus" } }, "node_modules/is-typedarray": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/is-typedarray/-/is-typedarray-1.0.0.tgz", "integrity": "sha512-cyA56iCMHAh5CdzjJIa4aohJyeO1YbwLi3Jc35MmRU6poroFjIGZzUzupGiRPOjgHg9TLu43xbpwXk523fMxKA==", "dev": true }, "node_modules/is-windows": { "version": "1.0.2", "resolved": "https://registry.npmjs.org/is-windows/-/is-windows-1.0.2.tgz", "integrity": "sha512-eXK1UInq2bPmjyX6e3VHIzMLobc4J94i4AWn+Hpq3OU5KkrRC96OAcR3PRJ/pGu6m8TRnBHP9dkXQVsT/COVIA==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/is-wsl": { "version": "2.2.0", "resolved": "https://registry.npmjs.org/is-wsl/-/is-wsl-2.2.0.tgz", "integrity": "sha512-fKzAra0rGJUUBwGBgNkHZuToZcn+TtXHpeCgmkMJMMYx1sQDYaCSyjJBSCa2nH1DGm7s3n1oBnohoVTBaN7Lww==", "dev": true, "optional": true, "dependencies": { "is-docker": "^2.0.0" }, "engines": { "node": ">=8" } }, "node_modules/isarray": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/isarray/-/isarray-1.0.0.tgz", "integrity": "sha512-VLghIWNM6ELQzo7zwmcg0NmTVyWKYjvIeM83yjp0wRDTmUnrM678fQbcKBo6n2CJEF0szoG//ytg+TKla89ALQ==", "dev": true }, "node_modules/isexe": { "version": "2.0.0", "resolved": "https://registry.npmjs.org/isexe/-/isexe-2.0.0.tgz", "integrity": "sha512-RHxMLp9lnKHGHRng9QFhRCMbYAcVpn69smSGcq3f36xjgVVWThj4qqLbTLlq7Ssj8B+fIQ1EuCEGI2lKsyQeIw==", "dev": true }, "node_modules/isobject": { "version": "3.0.1", "resolved": "https://registry.npmjs.org/isobject/-/isobject-3.0.1.tgz", "integrity": "sha512-WhB9zCku7EGTj/HQQRz5aUQEUeoQZH2bWcltRErOpymJ4boYE6wL9Tbr23krRPSZ+C5zqNSrSw+Cc7sZZ4b7vg==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/istanbul-lib-coverage": { "version": "3.2.0", "resolved": "https://registry.npmjs.org/istanbul-lib-coverage/-/istanbul-lib-coverage-3.2.0.tgz", "integrity": "sha512-eOeJ5BHCmHYvQK7xt9GkdHuzuCGS1Y6g9Gvnx3Ym33fz/HpLRYxiS0wHNr+m/MBC8B647Xt608vCDEvhl9c6Mw==", "dev": true, "engines": { "node": ">=8" } }, "node_modules/istanbul-lib-instrument": { "version": "4.0.3", "resolved": "https://registry.npmjs.org/istanbul-lib-instrument/-/istanbul-lib-instrument-4.0.3.tgz", "integrity": "sha512-BXgQl9kf4WTCPCCpmFGoJkz/+uhvm7h7PFKUYxh7qarQd3ER33vHG//qaE8eN25l07YqZPpHXU9I09l/RD5aGQ==", "dev": true, "dependencies": { "@babel/core": "^7.7.5", "@istanbuljs/schema": "^0.1.2", "istanbul-lib-coverage": "^3.0.0", "semver": "^6.3.0" }, "engines": { "node": ">=8" } }, "node_modules/istanbul-lib-report": { "version": "3.0.1", "resolved": "https://registry.npmjs.org/istanbul-lib-report/-/istanbul-lib-report-3.0.1.tgz", "integrity": "sha512-GCfE1mtsHGOELCU8e/Z7YWzpmybrx/+dSTfLrvY8qRmaY6zXTKWn6WQIjaAFw069icm6GVMNkgu0NzI4iPZUNw==", "dev": true, "dependencies": { "istanbul-lib-coverage": "^3.0.0", "make-dir": "^4.0.0", "supports-color": "^7.1.0" }, "engines": { "node": ">=10" } }, "node_modules/istanbul-lib-source-maps": { "version": "4.0.1", "resolved": "https://registry.npmjs.org/istanbul-lib-source-maps/-/istanbul-lib-source-maps-4.0.1.tgz", "integrity": "sha512-n3s8EwkdFIJCG3BPKBYvskgXGoy88ARzvegkitk60NxRdwltLOTaH7CUiMRXvwYorl0Q712iEjcWB+fK/MrWVw==", "dev": true, "dependencies": { "debug": "^4.1.1", "istanbul-lib-coverage": "^3.0.0", "source-map": "^0.6.1" }, "engines": { "node": ">=10" } }, "node_modules/istanbul-reports": { "version": "3.1.6", "resolved": "https://registry.npmjs.org/istanbul-reports/-/istanbul-reports-3.1.6.tgz", "integrity": "sha512-TLgnMkKg3iTDsQ9PbPTdpfAK2DzjF9mqUG7RMgcQl8oFjad8ob4laGxv5XV5U9MAfx8D6tSJiUyuAwzLicaxlg==", "dev": true, "dependencies": { "html-escaper": "^2.0.0", "istanbul-lib-report": "^3.0.0" }, "engines": { "node": ">=8" } }, "node_modules/jest": { "version": "26.6.3", "resolved": "https://registry.npmjs.org/jest/-/jest-26.6.3.tgz", "integrity": "sha512-lGS5PXGAzR4RF7V5+XObhqz2KZIDUA1yD0DG6pBVmy10eh0ZIXQImRuzocsI/N2XZ1GrLFwTS27In2i2jlpq1Q==", "dev": true, "dependencies": { "@jest/core": "^26.6.3", "import-local": "^3.0.2", "jest-cli": "^26.6.3" }, "bin": { "jest": "bin/jest.js" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-changed-files": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/jest-changed-files/-/jest-changed-files-26.6.2.tgz", "integrity": "sha512-fDS7szLcY9sCtIip8Fjry9oGf3I2ht/QT21bAHm5Dmf0mD4X3ReNUf17y+bO6fR8WgbIZTlbyG1ak/53cbRzKQ==", "dev": true, "dependencies": { "@jest/types": "^26.6.2", "execa": "^4.0.0", "throat": "^5.0.0" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-cli": { "version": "26.6.3", "resolved": "https://registry.npmjs.org/jest-cli/-/jest-cli-26.6.3.tgz", "integrity": "sha512-GF9noBSa9t08pSyl3CY4frMrqp+aQXFGFkf5hEPbh/pIUFYWMK6ZLTfbmadxJVcJrdRoChlWQsA2VkJcDFK8hg==", "dev": true, "dependencies": { "@jest/core": "^26.6.3", "@jest/test-result": "^26.6.2", "@jest/types": "^26.6.2", "chalk": "^4.0.0", "exit": "^0.1.2", "graceful-fs": "^4.2.4", "import-local": "^3.0.2", "is-ci": "^2.0.0", "jest-config": "^26.6.3", "jest-util": "^26.6.2", "jest-validate": "^26.6.2", "prompts": "^2.0.1", "yargs": "^15.4.1" }, "bin": { "jest": "bin/jest.js" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-config": { "version": "26.6.3", "resolved": "https://registry.npmjs.org/jest-config/-/jest-config-26.6.3.tgz", "integrity": "sha512-t5qdIj/bCj2j7NFVHb2nFB4aUdfucDn3JRKgrZnplb8nieAirAzRSHP8uDEd+qV6ygzg9Pz4YG7UTJf94LPSyg==", "dev": true, "dependencies": { "@babel/core": "^7.1.0", "@jest/test-sequencer": "^26.6.3", "@jest/types": "^26.6.2", "babel-jest": "^26.6.3", "chalk": "^4.0.0", "deepmerge": "^4.2.2", "glob": "^7.1.1", "graceful-fs": "^4.2.4", "jest-environment-jsdom": "^26.6.2", "jest-environment-node": "^26.6.2", "jest-get-type": "^26.3.0", "jest-jasmine2": "^26.6.3", "jest-regex-util": "^26.0.0", "jest-resolve": "^26.6.2", "jest-util": "^26.6.2", "jest-validate": "^26.6.2", "micromatch": "^4.0.2", "pretty-format": "^26.6.2" }, "engines": { "node": ">= 10.14.2" }, "peerDependencies": { "ts-node": ">=9.0.0" }, "peerDependenciesMeta": { "ts-node": { "optional": true } } }, "node_modules/jest-diff": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/jest-diff/-/jest-diff-26.6.2.tgz", "integrity": "sha512-6m+9Z3Gv9wN0WFVasqjCL/06+EFCMTqDEUl/b87HYK2rAPTyfz4ZIuSlPhY51PIQRWx5TaxeF1qmXKe9gfN3sA==", "dev": true, "dependencies": { "chalk": "^4.0.0", "diff-sequences": "^26.6.2", "jest-get-type": "^26.3.0", "pretty-format": "^26.6.2" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-docblock": { "version": "26.0.0", "resolved": "https://registry.npmjs.org/jest-docblock/-/jest-docblock-26.0.0.tgz", "integrity": "sha512-RDZ4Iz3QbtRWycd8bUEPxQsTlYazfYn/h5R65Fc6gOfwozFhoImx+affzky/FFBuqISPTqjXomoIGJVKBWoo0w==", "dev": true, "dependencies": { "detect-newline": "^3.0.0" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-each": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/jest-each/-/jest-each-26.6.2.tgz", "integrity": "sha512-Mer/f0KaATbjl8MCJ+0GEpNdqmnVmDYqCTJYTvoo7rqmRiDllmp2AYN+06F93nXcY3ur9ShIjS+CO/uD+BbH4A==", "dev": true, "dependencies": { "@jest/types": "^26.6.2", "chalk": "^4.0.0", "jest-get-type": "^26.3.0", "jest-util": "^26.6.2", "pretty-format": "^26.6.2" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-environment-jsdom": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/jest-environment-jsdom/-/jest-environment-jsdom-26.6.2.tgz", "integrity": "sha512-jgPqCruTlt3Kwqg5/WVFyHIOJHsiAvhcp2qiR2QQstuG9yWox5+iHpU3ZrcBxW14T4fe5Z68jAfLRh7joCSP2Q==", "dev": true, "dependencies": { "@jest/environment": "^26.6.2", "@jest/fake-timers": "^26.6.2", "@jest/types": "^26.6.2", "@types/node": "*", "jest-mock": "^26.6.2", "jest-util": "^26.6.2", "jsdom": "^16.4.0" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-environment-node": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/jest-environment-node/-/jest-environment-node-26.6.2.tgz", "integrity": "sha512-zhtMio3Exty18dy8ee8eJ9kjnRyZC1N4C1Nt/VShN1apyXc8rWGtJ9lI7vqiWcyyXS4BVSEn9lxAM2D+07/Tag==", "dev": true, "dependencies": { "@jest/environment": "^26.6.2", "@jest/fake-timers": "^26.6.2", "@jest/types": "^26.6.2", "@types/node": "*", "jest-mock": "^26.6.2", "jest-util": "^26.6.2" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-get-type": { "version": "26.3.0", "resolved": "https://registry.npmjs.org/jest-get-type/-/jest-get-type-26.3.0.tgz", "integrity": "sha512-TpfaviN1R2pQWkIihlfEanwOXK0zcxrKEE4MlU6Tn7keoXdN6/3gK/xl0yEh8DOunn5pOVGKf8hB4R9gVh04ig==", "dev": true, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-haste-map": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/jest-haste-map/-/jest-haste-map-26.6.2.tgz", "integrity": "sha512-easWIJXIw71B2RdR8kgqpjQrbMRWQBgiBwXYEhtGUTaX+doCjBheluShdDMeR8IMfJiTqH4+zfhtg29apJf/8w==", "dev": true, "dependencies": { "@jest/types": "^26.6.2", "@types/graceful-fs": "^4.1.2", "@types/node": "*", "anymatch": "^3.0.3", "fb-watchman": "^2.0.0", "graceful-fs": "^4.2.4", "jest-regex-util": "^26.0.0", "jest-serializer": "^26.6.2", "jest-util": "^26.6.2", "jest-worker": "^26.6.2", "micromatch": "^4.0.2", "sane": "^4.0.3", "walker": "^1.0.7" }, "engines": { "node": ">= 10.14.2" }, "optionalDependencies": { "fsevents": "^2.1.2" } }, "node_modules/jest-jasmine2": { "version": "26.6.3", "resolved": "https://registry.npmjs.org/jest-jasmine2/-/jest-jasmine2-26.6.3.tgz", "integrity": "sha512-kPKUrQtc8aYwBV7CqBg5pu+tmYXlvFlSFYn18ev4gPFtrRzB15N2gW/Roew3187q2w2eHuu0MU9TJz6w0/nPEg==", "dev": true, "dependencies": { "@babel/traverse": "^7.1.0", "@jest/environment": "^26.6.2", "@jest/source-map": "^26.6.2", "@jest/test-result": "^26.6.2", "@jest/types": "^26.6.2", "@types/node": "*", "chalk": "^4.0.0", "co": "^4.6.0", "expect": "^26.6.2", "is-generator-fn": "^2.0.0", "jest-each": "^26.6.2", "jest-matcher-utils": "^26.6.2", "jest-message-util": "^26.6.2", "jest-runtime": "^26.6.3", "jest-snapshot": "^26.6.2", "jest-util": "^26.6.2", "pretty-format": "^26.6.2", "throat": "^5.0.0" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-leak-detector": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/jest-leak-detector/-/jest-leak-detector-26.6.2.tgz", "integrity": "sha512-i4xlXpsVSMeKvg2cEKdfhh0H39qlJlP5Ex1yQxwF9ubahboQYMgTtz5oML35AVA3B4Eu+YsmwaiKVev9KCvLxg==", "dev": true, "dependencies": { "jest-get-type": "^26.3.0", "pretty-format": "^26.6.2" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-matcher-utils": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/jest-matcher-utils/-/jest-matcher-utils-26.6.2.tgz", "integrity": "sha512-llnc8vQgYcNqDrqRDXWwMr9i7rS5XFiCwvh6DTP7Jqa2mqpcCBBlpCbn+trkG0KNhPu/h8rzyBkriOtBstvWhw==", "dev": true, "dependencies": { "chalk": "^4.0.0", "jest-diff": "^26.6.2", "jest-get-type": "^26.3.0", "pretty-format": "^26.6.2" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-message-util": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/jest-message-util/-/jest-message-util-26.6.2.tgz", "integrity": "sha512-rGiLePzQ3AzwUshu2+Rn+UMFk0pHN58sOG+IaJbk5Jxuqo3NYO1U2/MIR4S1sKgsoYSXSzdtSa0TgrmtUwEbmA==", "dev": true, "dependencies": { "@babel/code-frame": "^7.0.0", "@jest/types": "^26.6.2", "@types/stack-utils": "^2.0.0", "chalk": "^4.0.0", "graceful-fs": "^4.2.4", "micromatch": "^4.0.2", "pretty-format": "^26.6.2", "slash": "^3.0.0", "stack-utils": "^2.0.2" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-mock": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/jest-mock/-/jest-mock-26.6.2.tgz", "integrity": "sha512-YyFjePHHp1LzpzYcmgqkJ0nm0gg/lJx2aZFzFy1S6eUqNjXsOqTK10zNRff2dNfssgokjkG65OlWNcIlgd3zew==", "dev": true, "dependencies": { "@jest/types": "^26.6.2", "@types/node": "*" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-pnp-resolver": { "version": "1.2.3", "resolved": "https://registry.npmjs.org/jest-pnp-resolver/-/jest-pnp-resolver-1.2.3.tgz", "integrity": "sha512-+3NpwQEnRoIBtx4fyhblQDPgJI0H1IEIkX7ShLUjPGA7TtUTvI1oiKi3SR4oBR0hQhQR80l4WAe5RrXBwWMA8w==", "dev": true, "engines": { "node": ">=6" }, "peerDependencies": { "jest-resolve": "*" }, "peerDependenciesMeta": { "jest-resolve": { "optional": true } } }, "node_modules/jest-regex-util": { "version": "26.0.0", "resolved": "https://registry.npmjs.org/jest-regex-util/-/jest-regex-util-26.0.0.tgz", "integrity": "sha512-Gv3ZIs/nA48/Zvjrl34bf+oD76JHiGDUxNOVgUjh3j890sblXryjY4rss71fPtD/njchl6PSE2hIhvyWa1eT0A==", "dev": true, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-resolve": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/jest-resolve/-/jest-resolve-26.6.2.tgz", "integrity": "sha512-sOxsZOq25mT1wRsfHcbtkInS+Ek7Q8jCHUB0ZUTP0tc/c41QHriU/NunqMfCUWsL4H3MHpvQD4QR9kSYhS7UvQ==", "dev": true, "dependencies": { "@jest/types": "^26.6.2", "chalk": "^4.0.0", "graceful-fs": "^4.2.4", "jest-pnp-resolver": "^1.2.2", "jest-util": "^26.6.2", "read-pkg-up": "^7.0.1", "resolve": "^1.18.1", "slash": "^3.0.0" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-resolve-dependencies": { "version": "26.6.3", "resolved": "https://registry.npmjs.org/jest-resolve-dependencies/-/jest-resolve-dependencies-26.6.3.tgz", "integrity": "sha512-pVwUjJkxbhe4RY8QEWzN3vns2kqyuldKpxlxJlzEYfKSvY6/bMvxoFrYYzUO1Gx28yKWN37qyV7rIoIp2h8fTg==", "dev": true, "dependencies": { "@jest/types": "^26.6.2", "jest-regex-util": "^26.0.0", "jest-snapshot": "^26.6.2" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-runner": { "version": "26.6.3", "resolved": "https://registry.npmjs.org/jest-runner/-/jest-runner-26.6.3.tgz", "integrity": "sha512-atgKpRHnaA2OvByG/HpGA4g6CSPS/1LK0jK3gATJAoptC1ojltpmVlYC3TYgdmGp+GLuhzpH30Gvs36szSL2JQ==", "dev": true, "dependencies": { "@jest/console": "^26.6.2", "@jest/environment": "^26.6.2", "@jest/test-result": "^26.6.2", "@jest/types": "^26.6.2", "@types/node": "*", "chalk": "^4.0.0", "emittery": "^0.7.1", "exit": "^0.1.2", "graceful-fs": "^4.2.4", "jest-config": "^26.6.3", "jest-docblock": "^26.0.0", "jest-haste-map": "^26.6.2", "jest-leak-detector": "^26.6.2", "jest-message-util": "^26.6.2", "jest-resolve": "^26.6.2", "jest-runtime": "^26.6.3", "jest-util": "^26.6.2", "jest-worker": "^26.6.2", "source-map-support": "^0.5.6", "throat": "^5.0.0" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-runtime": { "version": "26.6.3", "resolved": "https://registry.npmjs.org/jest-runtime/-/jest-runtime-26.6.3.tgz", "integrity": "sha512-lrzyR3N8sacTAMeonbqpnSka1dHNux2uk0qqDXVkMv2c/A3wYnvQ4EXuI013Y6+gSKSCxdaczvf4HF0mVXHRdw==", "dev": true, "dependencies": { "@jest/console": "^26.6.2", "@jest/environment": "^26.6.2", "@jest/fake-timers": "^26.6.2", "@jest/globals": "^26.6.2", "@jest/source-map": "^26.6.2", "@jest/test-result": "^26.6.2", "@jest/transform": "^26.6.2", "@jest/types": "^26.6.2", "@types/yargs": "^15.0.0", "chalk": "^4.0.0", "cjs-module-lexer": "^0.6.0", "collect-v8-coverage": "^1.0.0", "exit": "^0.1.2", "glob": "^7.1.3", "graceful-fs": "^4.2.4", "jest-config": "^26.6.3", "jest-haste-map": "^26.6.2", "jest-message-util": "^26.6.2", "jest-mock": "^26.6.2", "jest-regex-util": "^26.0.0", "jest-resolve": "^26.6.2", "jest-snapshot": "^26.6.2", "jest-util": "^26.6.2", "jest-validate": "^26.6.2", "slash": "^3.0.0", "strip-bom": "^4.0.0", "yargs": "^15.4.1" }, "bin": { "jest-runtime": "bin/jest-runtime.js" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-serializer": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/jest-serializer/-/jest-serializer-26.6.2.tgz", "integrity": "sha512-S5wqyz0DXnNJPd/xfIzZ5Xnp1HrJWBczg8mMfMpN78OJ5eDxXyf+Ygld9wX1DnUWbIbhM1YDY95NjR4CBXkb2g==", "dev": true, "dependencies": { "@types/node": "*", "graceful-fs": "^4.2.4" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-snapshot": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/jest-snapshot/-/jest-snapshot-26.6.2.tgz", "integrity": "sha512-OLhxz05EzUtsAmOMzuupt1lHYXCNib0ECyuZ/PZOx9TrZcC8vL0x+DUG3TL+GLX3yHG45e6YGjIm0XwDc3q3og==", "dev": true, "dependencies": { "@babel/types": "^7.0.0", "@jest/types": "^26.6.2", "@types/babel__traverse": "^7.0.4", "@types/prettier": "^2.0.0", "chalk": "^4.0.0", "expect": "^26.6.2", "graceful-fs": "^4.2.4", "jest-diff": "^26.6.2", "jest-get-type": "^26.3.0", "jest-haste-map": "^26.6.2", "jest-matcher-utils": "^26.6.2", "jest-message-util": "^26.6.2", "jest-resolve": "^26.6.2", "natural-compare": "^1.4.0", "pretty-format": "^26.6.2", "semver": "^7.3.2" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-snapshot/node_modules/lru-cache": { "version": "6.0.0", "resolved": "https://registry.npmjs.org/lru-cache/-/lru-cache-6.0.0.tgz", "integrity": "sha512-Jo6dJ04CmSjuznwJSS3pUeWmd/H0ffTlkXXgwZi+eq1UCmqQwCh+eLsYOYCwY991i2Fah4h1BEMCx4qThGbsiA==", "dev": true, "dependencies": { "yallist": "^4.0.0" }, "engines": { "node": ">=10" } }, "node_modules/jest-snapshot/node_modules/semver": { "version": "7.5.4", "resolved": "https://registry.npmjs.org/semver/-/semver-7.5.4.tgz", "integrity": "sha512-1bCSESV6Pv+i21Hvpxp3Dx+pSD8lIPt8uVjRrxAUt/nbswYc+tK6Y2btiULjd4+fnq15PX+nqQDC7Oft7WkwcA==", "dev": true, "dependencies": { "lru-cache": "^6.0.0" }, "bin": { "semver": "bin/semver.js" }, "engines": { "node": ">=10" } }, "node_modules/jest-snapshot/node_modules/yallist": { "version": "4.0.0", "resolved": "https://registry.npmjs.org/yallist/-/yallist-4.0.0.tgz", "integrity": "sha512-3wdGidZyq5PB084XLES5TpOSRA3wjXAlIWMhum2kRcv/41Sn2emQ0dycQW4uZXLejwKvg6EsvbdlVL+FYEct7A==", "dev": true }, "node_modules/jest-util": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/jest-util/-/jest-util-26.6.2.tgz", "integrity": "sha512-MDW0fKfsn0OI7MS7Euz6h8HNDXVQ0gaM9uW6RjfDmd1DAFcaxX9OqIakHIqhbnmF08Cf2DLDG+ulq8YQQ0Lp0Q==", "dev": true, "dependencies": { "@jest/types": "^26.6.2", "@types/node": "*", "chalk": "^4.0.0", "graceful-fs": "^4.2.4", "is-ci": "^2.0.0", "micromatch": "^4.0.2" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-validate": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/jest-validate/-/jest-validate-26.6.2.tgz", "integrity": "sha512-NEYZ9Aeyj0i5rQqbq+tpIOom0YS1u2MVu6+euBsvpgIme+FOfRmoC4R5p0JiAUpaFvFy24xgrpMknarR/93XjQ==", "dev": true, "dependencies": { "@jest/types": "^26.6.2", "camelcase": "^6.0.0", "chalk": "^4.0.0", "jest-get-type": "^26.3.0", "leven": "^3.1.0", "pretty-format": "^26.6.2" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-validate/node_modules/camelcase": { "version": "6.3.0", "resolved": "https://registry.npmjs.org/camelcase/-/camelcase-6.3.0.tgz", "integrity": "sha512-Gmy6FhYlCY7uOElZUSbxo2UCDH8owEk996gkbrpsgGtrJLM3J7jGxl9Ic7Qwwj4ivOE5AWZWRMecDdF7hqGjFA==", "dev": true, "engines": { "node": ">=10" }, "funding": { "url": "https://github.com/sponsors/sindresorhus" } }, "node_modules/jest-watcher": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/jest-watcher/-/jest-watcher-26.6.2.tgz", "integrity": "sha512-WKJob0P/Em2csiVthsI68p6aGKTIcsfjH9Gsx1f0A3Italz43e3ho0geSAVsmj09RWOELP1AZ/DXyJgOgDKxXQ==", "dev": true, "dependencies": { "@jest/test-result": "^26.6.2", "@jest/types": "^26.6.2", "@types/node": "*", "ansi-escapes": "^4.2.1", "chalk": "^4.0.0", "jest-util": "^26.6.2", "string-length": "^4.0.1" }, "engines": { "node": ">= 10.14.2" } }, "node_modules/jest-worker": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/jest-worker/-/jest-worker-26.6.2.tgz", "integrity": "sha512-KWYVV1c4i+jbMpaBC+U++4Va0cp8OisU185o73T1vo99hqi7w8tSJfUXYswwqqrjzwxa6KpRK54WhPvwf5w6PQ==", "dev": true, "dependencies": { "@types/node": "*", "merge-stream": "^2.0.0", "supports-color": "^7.0.0" }, "engines": { "node": ">= 10.13.0" } }, "node_modules/js-tokens": { "version": "4.0.0", "resolved": "https://registry.npmjs.org/js-tokens/-/js-tokens-4.0.0.tgz", "integrity": "sha512-RdJUflcE3cUzKiMqQgsCu06FPu9UdIJO0beYbPhHN4k6apgJtifcoCtT9bcxOpYBtpD2kCM6Sbzg4CausW/PKQ==", "dev": true }, "node_modules/js-yaml": { "version": "3.14.1", "resolved": "https://registry.npmjs.org/js-yaml/-/js-yaml-3.14.1.tgz", "integrity": "sha512-okMH7OXXJ7YrN9Ok3/SXrnu4iX9yOk+25nqX4imS2npuvTYDmo/QEZoqwZkYaIDk3jVvBOTOIEgEhaLOynBS9g==", "dev": true, "dependencies": { "argparse": "^1.0.7", "esprima": "^4.0.0" }, "bin": { "js-yaml": "bin/js-yaml.js" } }, "node_modules/jsdom": { "version": "16.7.0", "resolved": "https://registry.npmjs.org/jsdom/-/jsdom-16.7.0.tgz", "integrity": "sha512-u9Smc2G1USStM+s/x1ru5Sxrl6mPYCbByG1U/hUmqaVsm4tbNyS7CicOSRyuGQYZhTu0h84qkZZQ/I+dzizSVw==", "dev": true, "dependencies": { "abab": "^2.0.5", "acorn": "^8.2.4", "acorn-globals": "^6.0.0", "cssom": "^0.4.4", "cssstyle": "^2.3.0", "data-urls": "^2.0.0", "decimal.js": "^10.2.1", "domexception": "^2.0.1", "escodegen": "^2.0.0", "form-data": "^3.0.0", "html-encoding-sniffer": "^2.0.1", "http-proxy-agent": "^4.0.1", "https-proxy-agent": "^5.0.0", "is-potential-custom-element-name": "^1.0.1", "nwsapi": "^2.2.0", "parse5": "6.0.1", "saxes": "^5.0.1", "symbol-tree": "^3.2.4", "tough-cookie": "^4.0.0", "w3c-hr-time": "^1.0.2", "w3c-xmlserializer": "^2.0.0", "webidl-conversions": "^6.1.0", "whatwg-encoding": "^1.0.5", "whatwg-mimetype": "^2.3.0", "whatwg-url": "^8.5.0", "ws": "^7.4.6", "xml-name-validator": "^3.0.0" }, "engines": { "node": ">=10" }, "peerDependencies": { "canvas": "^2.5.0" }, "peerDependenciesMeta": { "canvas": { "optional": true } } }, "node_modules/jsesc": { "version": "2.5.2", "resolved": "https://registry.npmjs.org/jsesc/-/jsesc-2.5.2.tgz", "integrity": "sha512-OYu7XEzjkCQ3C5Ps3QIZsQfNpqoJyZZA99wd9aWd05NCtC5pWOkShK2mkL6HXQR6/Cy2lbNdPlZBpuQHXE63gA==", "dev": true, "bin": { "jsesc": "bin/jsesc" }, "engines": { "node": ">=4" } }, "node_modules/json-parse-even-better-errors": { "version": "2.3.1", "resolved": "https://registry.npmjs.org/json-parse-even-better-errors/-/json-parse-even-better-errors-2.3.1.tgz", "integrity": "sha512-xyFwyhro/JEof6Ghe2iz2NcXoj2sloNsWr/XsERDK/oiPCfaNhl5ONfp+jQdAZRQQ0IJWNzH9zIZF7li91kh2w==", "dev": true }, "node_modules/json5": { "version": "2.2.3", "resolved": "https://registry.npmjs.org/json5/-/json5-2.2.3.tgz", "integrity": "sha512-XmOWe7eyHYH14cLdVPoyg+GOH3rYX++KpzrylJwSW98t3Nk+U8XOl8FWKOgwtzdb8lXGf6zYwDUzeHMWfxasyg==", "dev": true, "bin": { "json5": "lib/cli.js" }, "engines": { "node": ">=6" } }, "node_modules/kind-of": { "version": "6.0.3", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-6.0.3.tgz", "integrity": "sha512-dcS1ul+9tmeD95T+x28/ehLgd9mENa3LsvDTtzm3vyBEO7RPptvAD+t44WVXaUjTBRcrpFeFlC8WCruUR456hw==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/kleur": { "version": "3.0.3", "resolved": "https://registry.npmjs.org/kleur/-/kleur-3.0.3.tgz", "integrity": "sha512-eTIzlVOSUR+JxdDFepEYcBMtZ9Qqdef+rnzWdRZuMbOywu5tO2w2N7rqjoANZ5k9vywhL6Br1VRjUIgTQx4E8w==", "dev": true, "engines": { "node": ">=6" } }, "node_modules/leven": { "version": "3.1.0", "resolved": "https://registry.npmjs.org/leven/-/leven-3.1.0.tgz", "integrity": "sha512-qsda+H8jTaUaN/x5vzW2rzc+8Rw4TAQ/4KjB46IwK5VH+IlVeeeje/EoZRpiXvIqjFgK84QffqPztGI3VBLG1A==", "dev": true, "engines": { "node": ">=6" } }, "node_modules/lines-and-columns": { "version": "1.2.4", "resolved": "https://registry.npmjs.org/lines-and-columns/-/lines-and-columns-1.2.4.tgz", "integrity": "sha512-7ylylesZQ/PV29jhEDl3Ufjo6ZX7gCqJr5F7PKrqc93v7fzSymt1BpwEU8nAUXs8qzzvqhbjhK5QZg6Mt/HkBg==", "dev": true }, "node_modules/locate-path": { "version": "5.0.0", "resolved": "https://registry.npmjs.org/locate-path/-/locate-path-5.0.0.tgz", "integrity": "sha512-t7hw9pI+WvuwNJXwk5zVHpyhIqzg2qTlklJOf0mVxGSbe3Fp2VieZcduNYjaLDoy6p9uGpQEGWG87WpMKlNq8g==", "dev": true, "dependencies": { "p-locate": "^4.1.0" }, "engines": { "node": ">=8" } }, "node_modules/lodash": { "version": "4.17.21", "resolved": "https://registry.npmjs.org/lodash/-/lodash-4.17.21.tgz", "integrity": "sha512-v2kDEe57lecTulaDIuNTPy3Ry4gLGJ6Z1O3vE1krgXZNrsQ+LFTGHVxVjcXPs17LhbZVGedAJv8XZ1tvj5FvSg==", "dev": true }, "node_modules/lru-cache": { "version": "5.1.1", "resolved": "https://registry.npmjs.org/lru-cache/-/lru-cache-5.1.1.tgz", "integrity": "sha512-KpNARQA3Iwv+jTA0utUVVbrh+Jlrr1Fv0e56GGzAFOXN7dk/FviaDW8LHmK52DlcH4WP2n6gI8vN1aesBFgo9w==", "dev": true, "dependencies": { "yallist": "^3.0.2" } }, "node_modules/make-dir": { "version": "4.0.0", "resolved": "https://registry.npmjs.org/make-dir/-/make-dir-4.0.0.tgz", "integrity": "sha512-hXdUTZYIVOt1Ex//jAQi+wTZZpUpwBj/0QsOzqegb3rGMMeJiSEu5xLHnYfBrRV4RH2+OCSOO95Is/7x1WJ4bw==", "dev": true, "dependencies": { "semver": "^7.5.3" }, "engines": { "node": ">=10" }, "funding": { "url": "https://github.com/sponsors/sindresorhus" } }, "node_modules/make-dir/node_modules/lru-cache": { "version": "6.0.0", "resolved": "https://registry.npmjs.org/lru-cache/-/lru-cache-6.0.0.tgz", "integrity": "sha512-Jo6dJ04CmSjuznwJSS3pUeWmd/H0ffTlkXXgwZi+eq1UCmqQwCh+eLsYOYCwY991i2Fah4h1BEMCx4qThGbsiA==", "dev": true, "dependencies": { "yallist": "^4.0.0" }, "engines": { "node": ">=10" } }, "node_modules/make-dir/node_modules/semver": { "version": "7.5.4", "resolved": "https://registry.npmjs.org/semver/-/semver-7.5.4.tgz", "integrity": "sha512-1bCSESV6Pv+i21Hvpxp3Dx+pSD8lIPt8uVjRrxAUt/nbswYc+tK6Y2btiULjd4+fnq15PX+nqQDC7Oft7WkwcA==", "dev": true, "dependencies": { "lru-cache": "^6.0.0" }, "bin": { "semver": "bin/semver.js" }, "engines": { "node": ">=10" } }, "node_modules/make-dir/node_modules/yallist": { "version": "4.0.0", "resolved": "https://registry.npmjs.org/yallist/-/yallist-4.0.0.tgz", "integrity": "sha512-3wdGidZyq5PB084XLES5TpOSRA3wjXAlIWMhum2kRcv/41Sn2emQ0dycQW4uZXLejwKvg6EsvbdlVL+FYEct7A==", "dev": true }, "node_modules/make-error": { "version": "1.3.6", "resolved": "https://registry.npmjs.org/make-error/-/make-error-1.3.6.tgz", "integrity": "sha512-s8UhlNe7vPKomQhC1qFelMokr/Sc3AgNbso3n74mVPA5LTZwkB9NlXf4XPamLxJE8h0gh73rM94xvwRT2CVInw==", "dev": true }, "node_modules/makeerror": { "version": "1.0.12", "resolved": "https://registry.npmjs.org/makeerror/-/makeerror-1.0.12.tgz", "integrity": "sha512-JmqCvUhmt43madlpFzG4BQzG2Z3m6tvQDNKdClZnO3VbIudJYmxsT0FNJMeiB2+JTSlTQTSbU8QdesVmwJcmLg==", "dev": true, "dependencies": { "tmpl": "1.0.5" } }, "node_modules/map-cache": { "version": "0.2.2", "resolved": "https://registry.npmjs.org/map-cache/-/map-cache-0.2.2.tgz", "integrity": "sha512-8y/eV9QQZCiyn1SprXSrCmqJN0yNRATe+PO8ztwqrvrbdRLA3eYJF0yaR0YayLWkMbsQSKWS9N2gPcGEc4UsZg==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/map-visit": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/map-visit/-/map-visit-1.0.0.tgz", "integrity": "sha512-4y7uGv8bd2WdM9vpQsiQNo41Ln1NvhvDRuVt0k2JZQ+ezN2uaQes7lZeZ+QQUHOLQAtDaBJ+7wCbi+ab/KFs+w==", "dev": true, "dependencies": { "object-visit": "^1.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/merge-stream": { "version": "2.0.0", "resolved": "https://registry.npmjs.org/merge-stream/-/merge-stream-2.0.0.tgz", "integrity": "sha512-abv/qOcuPfk3URPfDzmZU1LKmuw8kT+0nIHvKrKgFrwifol/doWcdA4ZqsWQ8ENrFKkd67Mfpo/LovbIUsbt3w==", "dev": true }, "node_modules/micromatch": { "version": "4.0.5", "resolved": "https://registry.npmjs.org/micromatch/-/micromatch-4.0.5.tgz", "integrity": "sha512-DMy+ERcEW2q8Z2Po+WNXuw3c5YaUSFjAO5GsJqfEl7UjvtIuFKO6ZrKvcItdy98dwFI2N1tg3zNIdKaQT+aNdA==", "dev": true, "dependencies": { "braces": "^3.0.2", "picomatch": "^2.3.1" }, "engines": { "node": ">=8.6" } }, "node_modules/mime-db": { "version": "1.52.0", "resolved": "https://registry.npmjs.org/mime-db/-/mime-db-1.52.0.tgz", "integrity": "sha512-sPU4uV7dYlvtWJxwwxHD0PuihVNiE7TyAbQ5SWxDCB9mUYvOgroQOwYQQOKPJ8CIbE+1ETVlOoK1UC2nU3gYvg==", "dev": true, "engines": { "node": ">= 0.6" } }, "node_modules/mime-types": { "version": "2.1.35", "resolved": "https://registry.npmjs.org/mime-types/-/mime-types-2.1.35.tgz", "integrity": "sha512-ZDY+bPm5zTTF+YpCrAU9nK0UgICYPT0QtT1NZWFv4s++TNkcgVaT0g6+4R2uI4MjQjzysHB1zxuWL50hzaeXiw==", "dev": true, "dependencies": { "mime-db": "1.52.0" }, "engines": { "node": ">= 0.6" } }, "node_modules/mimic-fn": { "version": "2.1.0", "resolved": "https://registry.npmjs.org/mimic-fn/-/mimic-fn-2.1.0.tgz", "integrity": "sha512-OqbOk5oEQeAZ8WXWydlu9HJjz9WVdEIvamMCcXmuqUYjTknH/sqsWvhQ3vgwKFRR1HpjvNBKQ37nbJgYzGqGcg==", "dev": true, "engines": { "node": ">=6" } }, "node_modules/minimatch": { "version": "3.1.2", "resolved": "https://registry.npmjs.org/minimatch/-/minimatch-3.1.2.tgz", "integrity": "sha512-J7p63hRiAjw1NDEww1W7i37+ByIrOWO5XQQAzZ3VOcL0PNybwpfmV/N05zFAzwQ9USyEcX6t3UO+K5aqBQOIHw==", "dev": true, "dependencies": { "brace-expansion": "^1.1.7" }, "engines": { "node": "*" } }, "node_modules/minimist": { "version": "1.2.8", "resolved": "https://registry.npmjs.org/minimist/-/minimist-1.2.8.tgz", "integrity": "sha512-2yyAR8qBkN3YuheJanUpWC5U3bb5osDywNB8RzDVlDwDHbocAJveqqj1u8+SVD7jkWT4yvsHCpWqqWqAxb0zCA==", "dev": true, "funding": { "url": "https://github.com/sponsors/ljharb" } }, "node_modules/mixin-deep": { "version": "1.3.2", "resolved": "https://registry.npmjs.org/mixin-deep/-/mixin-deep-1.3.2.tgz", "integrity": "sha512-WRoDn//mXBiJ1H40rqa3vH0toePwSsGb45iInWlTySa+Uu4k3tYUSxa2v1KqAiLtvlrSzaExqS1gtk96A9zvEA==", "dev": true, "dependencies": { "for-in": "^1.0.2", "is-extendable": "^1.0.1" }, "engines": { "node": ">=0.10.0" } }, "node_modules/mkdirp": { "version": "1.0.4", "resolved": "https://registry.npmjs.org/mkdirp/-/mkdirp-1.0.4.tgz", "integrity": "sha512-vVqVZQyf3WLx2Shd0qJ9xuvqgAyKPLAiqITEtqW0oIUjzo3PePDd6fW9iFz30ef7Ysp/oiWqbhszeGWW2T6Gzw==", "dev": true, "bin": { "mkdirp": "bin/cmd.js" }, "engines": { "node": ">=10" } }, "node_modules/ms": { "version": "2.1.2", "resolved": "https://registry.npmjs.org/ms/-/ms-2.1.2.tgz", "integrity": "sha512-sGkPx+VjMtmA6MX27oA4FBFELFCZZ4S4XqeGOXCv68tT+jb3vk/RyaKWP0PTKyWtmLSM0b+adUTEvbs1PEaH2w==", "dev": true }, "node_modules/nanomatch": { "version": "1.2.13", "resolved": "https://registry.npmjs.org/nanomatch/-/nanomatch-1.2.13.tgz", "integrity": "sha512-fpoe2T0RbHwBTBUOftAfBPaDEi06ufaUai0mE6Yn1kacc3SnTErfb/h+X94VXzI64rKFHYImXSvdwGGCmwOqCA==", "dev": true, "dependencies": { "arr-diff": "^4.0.0", "array-unique": "^0.3.2", "define-property": "^2.0.2", "extend-shallow": "^3.0.2", "fragment-cache": "^0.2.1", "is-windows": "^1.0.2", "kind-of": "^6.0.2", "object.pick": "^1.3.0", "regex-not": "^1.0.0", "snapdragon": "^0.8.1", "to-regex": "^3.0.1" }, "engines": { "node": ">=0.10.0" } }, "node_modules/natural-compare": { "version": "1.4.0", "resolved": "https://registry.npmjs.org/natural-compare/-/natural-compare-1.4.0.tgz", "integrity": "sha512-OWND8ei3VtNC9h7V60qff3SVobHr996CTwgxubgyQYEpg290h9J0buyECNNJexkFm5sOajh5G116RYA1c8ZMSw==", "dev": true }, "node_modules/nice-try": { "version": "1.0.5", "resolved": "https://registry.npmjs.org/nice-try/-/nice-try-1.0.5.tgz", "integrity": "sha512-1nh45deeb5olNY7eX82BkPO7SSxR5SSYJiPTrTdFUVYwAl8CKMA5N9PjTYkHiRjisVcxcQ1HXdLhx2qxxJzLNQ==", "dev": true }, "node_modules/node-int64": { "version": "0.4.0", "resolved": "https://registry.npmjs.org/node-int64/-/node-int64-0.4.0.tgz", "integrity": "sha512-O5lz91xSOeoXP6DulyHfllpq+Eg00MWitZIbtPfoSEvqIHdl5gfcY6hYzDWnj0qD5tz52PI08u9qUvSVeUBeHw==", "dev": true }, "node_modules/node-notifier": { "version": "8.0.2", "resolved": "https://registry.npmjs.org/node-notifier/-/node-notifier-8.0.2.tgz", "integrity": "sha512-oJP/9NAdd9+x2Q+rfphB2RJCHjod70RcRLjosiPMMu5gjIfwVnOUGq2nbTjTUbmy0DJ/tFIVT30+Qe3nzl4TJg==", "dev": true, "optional": true, "dependencies": { "growly": "^1.3.0", "is-wsl": "^2.2.0", "semver": "^7.3.2", "shellwords": "^0.1.1", "uuid": "^8.3.0", "which": "^2.0.2" } }, "node_modules/node-notifier/node_modules/lru-cache": { "version": "6.0.0", "resolved": "https://registry.npmjs.org/lru-cache/-/lru-cache-6.0.0.tgz", "integrity": "sha512-Jo6dJ04CmSjuznwJSS3pUeWmd/H0ffTlkXXgwZi+eq1UCmqQwCh+eLsYOYCwY991i2Fah4h1BEMCx4qThGbsiA==", "dev": true, "optional": true, "dependencies": { "yallist": "^4.0.0" }, "engines": { "node": ">=10" } }, "node_modules/node-notifier/node_modules/semver": { "version": "7.5.4", "resolved": "https://registry.npmjs.org/semver/-/semver-7.5.4.tgz", "integrity": "sha512-1bCSESV6Pv+i21Hvpxp3Dx+pSD8lIPt8uVjRrxAUt/nbswYc+tK6Y2btiULjd4+fnq15PX+nqQDC7Oft7WkwcA==", "dev": true, "optional": true, "dependencies": { "lru-cache": "^6.0.0" }, "bin": { "semver": "bin/semver.js" }, "engines": { "node": ">=10" } }, "node_modules/node-notifier/node_modules/yallist": { "version": "4.0.0", "resolved": "https://registry.npmjs.org/yallist/-/yallist-4.0.0.tgz", "integrity": "sha512-3wdGidZyq5PB084XLES5TpOSRA3wjXAlIWMhum2kRcv/41Sn2emQ0dycQW4uZXLejwKvg6EsvbdlVL+FYEct7A==", "dev": true, "optional": true }, "node_modules/node-releases": { "version": "2.0.13", "resolved": "https://registry.npmjs.org/node-releases/-/node-releases-2.0.13.tgz", "integrity": "sha512-uYr7J37ae/ORWdZeQ1xxMJe3NtdmqMC/JZK+geofDrkLUApKRHPd18/TxtBOJ4A0/+uUIliorNrfYV6s1b02eQ==", "dev": true }, "node_modules/normalize-package-data": { "version": "2.5.0", "resolved": "https://registry.npmjs.org/normalize-package-data/-/normalize-package-data-2.5.0.tgz", "integrity": "sha512-/5CMN3T0R4XTj4DcGaexo+roZSdSFW/0AOOTROrjxzCG1wrWXEsGbRKevjlIL+ZDE4sZlJr5ED4YW0yqmkK+eA==", "dev": true, "dependencies": { "hosted-git-info": "^2.1.4", "resolve": "^1.10.0", "semver": "2 || 3 || 4 || 5", "validate-npm-package-license": "^3.0.1" } }, "node_modules/normalize-package-data/node_modules/semver": { "version": "5.7.2", "resolved": "https://registry.npmjs.org/semver/-/semver-5.7.2.tgz", "integrity": "sha512-cBznnQ9KjJqU67B52RMC65CMarK2600WFnbkcaiwWq3xy/5haFJlshgnpjovMVJ+Hff49d8GEn0b87C5pDQ10g==", "dev": true, "bin": { "semver": "bin/semver" } }, "node_modules/normalize-path": { "version": "3.0.0", "resolved": "https://registry.npmjs.org/normalize-path/-/normalize-path-3.0.0.tgz", "integrity": "sha512-6eZs5Ls3WtCisHWp9S2GUy8dqkpGi4BVSz3GaqiE6ezub0512ESztXUwUB6C6IKbQkY2Pnb/mD4WYojCRwcwLA==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/npm-run-path": { "version": "4.0.1", "resolved": "https://registry.npmjs.org/npm-run-path/-/npm-run-path-4.0.1.tgz", "integrity": "sha512-S48WzZW777zhNIrn7gxOlISNAqi9ZC/uQFnRdbeIHhZhCA6UqpkOT8T1G7BvfdgP4Er8gF4sUbaS0i7QvIfCWw==", "dev": true, "dependencies": { "path-key": "^3.0.0" }, "engines": { "node": ">=8" } }, "node_modules/nwsapi": { "version": "2.2.7", "resolved": "https://registry.npmjs.org/nwsapi/-/nwsapi-2.2.7.tgz", "integrity": "sha512-ub5E4+FBPKwAZx0UwIQOjYWGHTEq5sPqHQNRN8Z9e4A7u3Tj1weLJsL59yH9vmvqEtBHaOmT6cYQKIZOxp35FQ==", "dev": true }, "node_modules/object-copy": { "version": "0.1.0", "resolved": "https://registry.npmjs.org/object-copy/-/object-copy-0.1.0.tgz", "integrity": "sha512-79LYn6VAb63zgtmAteVOWo9Vdj71ZVBy3Pbse+VqxDpEP83XuujMrGqHIwAXJ5I/aM0zU7dIyIAhifVTPrNItQ==", "dev": true, "dependencies": { "copy-descriptor": "^0.1.0", "define-property": "^0.2.5", "kind-of": "^3.0.3" }, "engines": { "node": ">=0.10.0" } }, "node_modules/object-copy/node_modules/define-property": { "version": "0.2.5", "resolved": "https://registry.npmjs.org/define-property/-/define-property-0.2.5.tgz", "integrity": "sha512-Rr7ADjQZenceVOAKop6ALkkRAmH1A4Gx9hV/7ZujPUN2rkATqFO0JZLZInbAjpZYoJ1gUx8MRMQVkYemcbMSTA==", "dev": true, "dependencies": { "is-descriptor": "^0.1.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/object-copy/node_modules/is-accessor-descriptor": { "version": "0.1.6", "resolved": "https://registry.npmjs.org/is-accessor-descriptor/-/is-accessor-descriptor-0.1.6.tgz", "integrity": "sha512-e1BM1qnDbMRG3ll2U9dSK0UMHuWOs3pY3AtcFsmvwPtKL3MML/Q86i+GilLfvqEs4GW+ExB91tQ3Ig9noDIZ+A==", "dev": true, "dependencies": { "kind-of": "^3.0.2" }, "engines": { "node": ">=0.10.0" } }, "node_modules/object-copy/node_modules/is-data-descriptor": { "version": "0.1.4", "resolved": "https://registry.npmjs.org/is-data-descriptor/-/is-data-descriptor-0.1.4.tgz", "integrity": "sha512-+w9D5ulSoBNlmw9OHn3U2v51SyoCd0he+bB3xMl62oijhrspxowjU+AIcDY0N3iEJbUEkB15IlMASQsxYigvXg==", "dev": true, "dependencies": { "kind-of": "^3.0.2" }, "engines": { "node": ">=0.10.0" } }, "node_modules/object-copy/node_modules/is-descriptor": { "version": "0.1.6", "resolved": "https://registry.npmjs.org/is-descriptor/-/is-descriptor-0.1.6.tgz", "integrity": "sha512-avDYr0SB3DwO9zsMov0gKCESFYqCnE4hq/4z3TdUlukEy5t9C0YRq7HLrsN52NAcqXKaepeCD0n+B0arnVG3Hg==", "dev": true, "dependencies": { "is-accessor-descriptor": "^0.1.6", "is-data-descriptor": "^0.1.4", "kind-of": "^5.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/object-copy/node_modules/is-descriptor/node_modules/kind-of": { "version": "5.1.0", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-5.1.0.tgz", "integrity": "sha512-NGEErnH6F2vUuXDh+OlbcKW7/wOcfdRHaZ7VWtqCztfHri/++YKmP51OdWeGPuqCOba6kk2OTe5d02VmTB80Pw==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/object-copy/node_modules/kind-of": { "version": "3.2.2", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-3.2.2.tgz", "integrity": "sha512-NOW9QQXMoZGg/oqnVNoNTTIFEIid1627WCffUBJEdMxYApq7mNE7CpzucIPc+ZQg25Phej7IJSmX3hO+oblOtQ==", "dev": true, "dependencies": { "is-buffer": "^1.1.5" }, "engines": { "node": ">=0.10.0" } }, "node_modules/object-visit": { "version": "1.0.1", "resolved": "https://registry.npmjs.org/object-visit/-/object-visit-1.0.1.tgz", "integrity": "sha512-GBaMwwAVK9qbQN3Scdo0OyvgPW7l3lnaVMj84uTOZlswkX0KpF6fyDBJhtTthf7pymztoN36/KEr1DyhF96zEA==", "dev": true, "dependencies": { "isobject": "^3.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/object.pick": { "version": "1.3.0", "resolved": "https://registry.npmjs.org/object.pick/-/object.pick-1.3.0.tgz", "integrity": "sha512-tqa/UMy/CCoYmj+H5qc07qvSL9dqcs/WZENZ1JbtWBlATP+iVOe778gE6MSijnyCnORzDuX6hU+LA4SZ09YjFQ==", "dev": true, "dependencies": { "isobject": "^3.0.1" }, "engines": { "node": ">=0.10.0" } }, "node_modules/once": { "version": "1.4.0", "resolved": "https://registry.npmjs.org/once/-/once-1.4.0.tgz", "integrity": "sha512-lNaJgI+2Q5URQBkccEKHTQOPaXdUxnZZElQTZY0MFUAuaEqe1E+Nyvgdz/aIyNi6Z9MzO5dv1H8n58/GELp3+w==", "dev": true, "dependencies": { "wrappy": "1" } }, "node_modules/onetime": { "version": "5.1.2", "resolved": "https://registry.npmjs.org/onetime/-/onetime-5.1.2.tgz", "integrity": "sha512-kbpaSSGJTWdAY5KPVeMOKXSrPtr8C8C7wodJbcsd51jRnmD+GZu8Y0VoU6Dm5Z4vWr0Ig/1NKuWRKf7j5aaYSg==", "dev": true, "dependencies": { "mimic-fn": "^2.1.0" }, "engines": { "node": ">=6" }, "funding": { "url": "https://github.com/sponsors/sindresorhus" } }, "node_modules/p-each-series": { "version": "2.2.0", "resolved": "https://registry.npmjs.org/p-each-series/-/p-each-series-2.2.0.tgz", "integrity": "sha512-ycIL2+1V32th+8scbpTvyHNaHe02z0sjgh91XXjAk+ZeXoPN4Z46DVUnzdso0aX4KckKw0FNNFHdjZ2UsZvxiA==", "dev": true, "engines": { "node": ">=8" }, "funding": { "url": "https://github.com/sponsors/sindresorhus" } }, "node_modules/p-finally": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/p-finally/-/p-finally-1.0.0.tgz", "integrity": "sha512-LICb2p9CB7FS+0eR1oqWnHhp0FljGLZCWBE9aix0Uye9W8LTQPwMTYVGWQWIw9RdQiDg4+epXQODwIYJtSJaow==", "dev": true, "engines": { "node": ">=4" } }, "node_modules/p-limit": { "version": "2.3.0", "resolved": "https://registry.npmjs.org/p-limit/-/p-limit-2.3.0.tgz", "integrity": "sha512-//88mFWSJx8lxCzwdAABTJL2MyWB12+eIY7MDL2SqLmAkeKU9qxRvWuSyTjm3FUmpBEMuFfckAIqEaVGUDxb6w==", "dev": true, "dependencies": { "p-try": "^2.0.0" }, "engines": { "node": ">=6" }, "funding": { "url": "https://github.com/sponsors/sindresorhus" } }, "node_modules/p-locate": { "version": "4.1.0", "resolved": "https://registry.npmjs.org/p-locate/-/p-locate-4.1.0.tgz", "integrity": "sha512-R79ZZ/0wAxKGu3oYMlz8jy/kbhsNrS7SKZ7PxEHBgJ5+F2mtFW2fK2cOtBh1cHYkQsbzFV7I+EoRKe6Yt0oK7A==", "dev": true, "dependencies": { "p-limit": "^2.2.0" }, "engines": { "node": ">=8" } }, "node_modules/p-try": { "version": "2.2.0", "resolved": "https://registry.npmjs.org/p-try/-/p-try-2.2.0.tgz", "integrity": "sha512-R4nPAVTAU0B9D35/Gk3uJf/7XYbQcyohSKdvAxIRSNghFl4e71hVoGnBNQz9cWaXxO2I10KTC+3jMdvvoKw6dQ==", "dev": true, "engines": { "node": ">=6" } }, "node_modules/parse-json": { "version": "5.2.0", "resolved": "https://registry.npmjs.org/parse-json/-/parse-json-5.2.0.tgz", "integrity": "sha512-ayCKvm/phCGxOkYRSCM82iDwct8/EonSEgCSxWxD7ve6jHggsFl4fZVQBPRNgQoKiuV/odhFrGzQXZwbifC8Rg==", "dev": true, "dependencies": { "@babel/code-frame": "^7.0.0", "error-ex": "^1.3.1", "json-parse-even-better-errors": "^2.3.0", "lines-and-columns": "^1.1.6" }, "engines": { "node": ">=8" }, "funding": { "url": "https://github.com/sponsors/sindresorhus" } }, "node_modules/parse5": { "version": "6.0.1", "resolved": "https://registry.npmjs.org/parse5/-/parse5-6.0.1.tgz", "integrity": "sha512-Ofn/CTFzRGTTxwpNEs9PP93gXShHcTq255nzRYSKe8AkVpZY7e1fpmTfOyoIvjP5HG7Z2ZM7VS9PPhQGW2pOpw==", "dev": true }, "node_modules/pascalcase": { "version": "0.1.1", "resolved": "https://registry.npmjs.org/pascalcase/-/pascalcase-0.1.1.tgz", "integrity": "sha512-XHXfu/yOQRy9vYOtUDVMN60OEJjW013GoObG1o+xwQTpB9eYJX/BjXMsdW13ZDPruFhYYn0AG22w0xgQMwl3Nw==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/path-exists": { "version": "4.0.0", "resolved": "https://registry.npmjs.org/path-exists/-/path-exists-4.0.0.tgz", "integrity": "sha512-ak9Qy5Q7jYb2Wwcey5Fpvg2KoAc/ZIhLSLOSBmRmygPsGwkVVt0fZa0qrtMz+m6tJTAHfZQ8FnmB4MG4LWy7/w==", "dev": true, "engines": { "node": ">=8" } }, "node_modules/path-is-absolute": { "version": "1.0.1", "resolved": "https://registry.npmjs.org/path-is-absolute/-/path-is-absolute-1.0.1.tgz", "integrity": "sha512-AVbw3UJ2e9bq64vSaS9Am0fje1Pa8pbGqTTsmXfaIiMpnr5DlDhfJOuLj9Sf95ZPVDAUerDfEk88MPmPe7UCQg==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/path-key": { "version": "3.1.1", "resolved": "https://registry.npmjs.org/path-key/-/path-key-3.1.1.tgz", "integrity": "sha512-ojmeN0qd+y0jszEtoY48r0Peq5dwMEkIlCOu6Q5f41lfkswXuKtYrhgoTpLnyIcHm24Uhqx+5Tqm2InSwLhE6Q==", "dev": true, "engines": { "node": ">=8" } }, "node_modules/path-parse": { "version": "1.0.7", "resolved": "https://registry.npmjs.org/path-parse/-/path-parse-1.0.7.tgz", "integrity": "sha512-LDJzPVEEEPR+y48z93A0Ed0yXb8pAByGWo/k5YYdYgpY2/2EsOsksJrq7lOHxryrVOn1ejG6oAp8ahvOIQD8sw==", "dev": true }, "node_modules/picocolors": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/picocolors/-/picocolors-1.0.0.tgz", "integrity": "sha512-1fygroTLlHu66zi26VoTDv8yRgm0Fccecssto+MhsZ0D/DGW2sm8E8AjW7NU5VVTRt5GxbeZ5qBuJr+HyLYkjQ==", "dev": true }, "node_modules/picomatch": { "version": "2.3.1", "resolved": "https://registry.npmjs.org/picomatch/-/picomatch-2.3.1.tgz", "integrity": "sha512-JU3teHTNjmE2VCGFzuY8EXzCDVwEqB2a8fsIvwaStHhAWJEeVd1o1QD80CU6+ZdEXXSLbSsuLwJjkCBWqRQUVA==", "dev": true, "engines": { "node": ">=8.6" }, "funding": { "url": "https://github.com/sponsors/jonschlinkert" } }, "node_modules/pirates": { "version": "4.0.6", "resolved": "https://registry.npmjs.org/pirates/-/pirates-4.0.6.tgz", "integrity": "sha512-saLsH7WeYYPiD25LDuLRRY/i+6HaPYr6G1OUlN39otzkSTxKnubR9RTxS3/Kk50s1g2JTgFwWQDQyplC5/SHZg==", "dev": true, "engines": { "node": ">= 6" } }, "node_modules/pkg-dir": { "version": "4.2.0", "resolved": "https://registry.npmjs.org/pkg-dir/-/pkg-dir-4.2.0.tgz", "integrity": "sha512-HRDzbaKjC+AOWVXxAU/x54COGeIv9eb+6CkDSQoNTt4XyWoIJvuPsXizxu/Fr23EiekbtZwmh1IcIG/l/a10GQ==", "dev": true, "dependencies": { "find-up": "^4.0.0" }, "engines": { "node": ">=8" } }, "node_modules/posix-character-classes": { "version": "0.1.1", "resolved": "https://registry.npmjs.org/posix-character-classes/-/posix-character-classes-0.1.1.tgz", "integrity": "sha512-xTgYBc3fuo7Yt7JbiuFxSYGToMoz8fLoE6TC9Wx1P/u+LfeThMOAqmuyECnlBaaJb+u1m9hHiXUEtwW4OzfUJg==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/pretty-format": { "version": "26.6.2", "resolved": "https://registry.npmjs.org/pretty-format/-/pretty-format-26.6.2.tgz", "integrity": "sha512-7AeGuCYNGmycyQbCqd/3PWH4eOoX/OiCa0uphp57NVTeAGdJGaAliecxwBDHYQCIvrW7aDBZCYeNTP/WX69mkg==", "dev": true, "dependencies": { "@jest/types": "^26.6.2", "ansi-regex": "^5.0.0", "ansi-styles": "^4.0.0", "react-is": "^17.0.1" }, "engines": { "node": ">= 10" } }, "node_modules/prompts": { "version": "2.4.2", "resolved": "https://registry.npmjs.org/prompts/-/prompts-2.4.2.tgz", "integrity": "sha512-NxNv/kLguCA7p3jE8oL2aEBsrJWgAakBpgmgK6lpPWV+WuOmY6r2/zbAVnP+T8bQlA0nzHXSJSJW0Hq7ylaD2Q==", "dev": true, "dependencies": { "kleur": "^3.0.3", "sisteransi": "^1.0.5" }, "engines": { "node": ">= 6" } }, "node_modules/psl": { "version": "1.9.0", "resolved": "https://registry.npmjs.org/psl/-/psl-1.9.0.tgz", "integrity": "sha512-E/ZsdU4HLs/68gYzgGTkMicWTLPdAftJLfJFlLUAAKZGkStNU72sZjT66SnMDVOfOWY/YAoiD7Jxa9iHvngcag==", "dev": true }, "node_modules/pump": { "version": "3.0.0", "resolved": "https://registry.npmjs.org/pump/-/pump-3.0.0.tgz", "integrity": "sha512-LwZy+p3SFs1Pytd/jYct4wpv49HiYCqd9Rlc5ZVdk0V+8Yzv6jR5Blk3TRmPL1ft69TxP0IMZGJ+WPFU2BFhww==", "dev": true, "dependencies": { "end-of-stream": "^1.1.0", "once": "^1.3.1" } }, "node_modules/punycode": { "version": "2.3.0", "resolved": "https://registry.npmjs.org/punycode/-/punycode-2.3.0.tgz", "integrity": "sha512-rRV+zQD8tVFys26lAGR9WUuS4iUAngJScM+ZRSKtvl5tKeZ2t5bvdNFdNHBW9FWR4guGHlgmsZ1G7BSm2wTbuA==", "dev": true, "engines": { "node": ">=6" } }, "node_modules/querystringify": { "version": "2.2.0", "resolved": "https://registry.npmjs.org/querystringify/-/querystringify-2.2.0.tgz", "integrity": "sha512-FIqgj2EUvTa7R50u0rGsyTftzjYmv/a3hO345bZNrqabNqjtgiDMgmo4mkUjd+nzU5oF3dClKqFIPUKybUyqoQ==", "dev": true }, "node_modules/react-is": { "version": "17.0.2", "resolved": "https://registry.npmjs.org/react-is/-/react-is-17.0.2.tgz", "integrity": "sha512-w2GsyukL62IJnlaff/nRegPQR94C/XXamvMWmSHRJ4y7Ts/4ocGRmTHvOs8PSE6pB3dWOrD/nueuU5sduBsQ4w==", "dev": true }, "node_modules/read-pkg": { "version": "5.2.0", "resolved": "https://registry.npmjs.org/read-pkg/-/read-pkg-5.2.0.tgz", "integrity": "sha512-Ug69mNOpfvKDAc2Q8DRpMjjzdtrnv9HcSMX+4VsZxD1aZ6ZzrIE7rlzXBtWTyhULSMKg076AW6WR5iZpD0JiOg==", "dev": true, "dependencies": { "@types/normalize-package-data": "^2.4.0", "normalize-package-data": "^2.5.0", "parse-json": "^5.0.0", "type-fest": "^0.6.0" }, "engines": { "node": ">=8" } }, "node_modules/read-pkg-up": { "version": "7.0.1", "resolved": "https://registry.npmjs.org/read-pkg-up/-/read-pkg-up-7.0.1.tgz", "integrity": "sha512-zK0TB7Xd6JpCLmlLmufqykGE+/TlOePD6qKClNW7hHDKFh/J7/7gCWGR7joEQEW1bKq3a3yUZSObOoWLFQ4ohg==", "dev": true, "dependencies": { "find-up": "^4.1.0", "read-pkg": "^5.2.0", "type-fest": "^0.8.1" }, "engines": { "node": ">=8" }, "funding": { "url": "https://github.com/sponsors/sindresorhus" } }, "node_modules/read-pkg-up/node_modules/type-fest": { "version": "0.8.1", "resolved": "https://registry.npmjs.org/type-fest/-/type-fest-0.8.1.tgz", "integrity": "sha512-4dbzIzqvjtgiM5rw1k5rEHtBANKmdudhGyBEajN01fEyhaAIhsoKNy6y7+IN93IfpFtwY9iqi7kD+xwKhQsNJA==", "dev": true, "engines": { "node": ">=8" } }, "node_modules/read-pkg/node_modules/type-fest": { "version": "0.6.0", "resolved": "https://registry.npmjs.org/type-fest/-/type-fest-0.6.0.tgz", "integrity": "sha512-q+MB8nYR1KDLrgr4G5yemftpMC7/QLqVndBmEEdqzmNj5dcFOO4Oo8qlwZE3ULT3+Zim1F8Kq4cBnikNhlCMlg==", "dev": true, "engines": { "node": ">=8" } }, "node_modules/regex-not": { "version": "1.0.2", "resolved": "https://registry.npmjs.org/regex-not/-/regex-not-1.0.2.tgz", "integrity": "sha512-J6SDjUgDxQj5NusnOtdFxDwN/+HWykR8GELwctJ7mdqhcyy1xEc4SRFHUXvxTp661YaVKAjfRLZ9cCqS6tn32A==", "dev": true, "dependencies": { "extend-shallow": "^3.0.2", "safe-regex": "^1.1.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/remove-trailing-separator": { "version": "1.1.0", "resolved": "https://registry.npmjs.org/remove-trailing-separator/-/remove-trailing-separator-1.1.0.tgz", "integrity": "sha512-/hS+Y0u3aOfIETiaiirUFwDBDzmXPvO+jAfKTitUngIPzdKc6Z0LoFjM/CK5PL4C+eKwHohlHAb6H0VFfmmUsw==", "dev": true }, "node_modules/repeat-element": { "version": "1.1.4", "resolved": "https://registry.npmjs.org/repeat-element/-/repeat-element-1.1.4.tgz", "integrity": "sha512-LFiNfRcSu7KK3evMyYOuCzv3L10TW7yC1G2/+StMjK8Y6Vqd2MG7r/Qjw4ghtuCOjFvlnms/iMmLqpvW/ES/WQ==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/repeat-string": { "version": "1.6.1", "resolved": "https://registry.npmjs.org/repeat-string/-/repeat-string-1.6.1.tgz", "integrity": "sha512-PV0dzCYDNfRi1jCDbJzpW7jNNDRuCOG/jI5ctQcGKt/clZD+YcPS3yIlWuTJMmESC8aevCFmWJy5wjAFgNqN6w==", "dev": true, "engines": { "node": ">=0.10" } }, "node_modules/require-directory": { "version": "2.1.1", "resolved": "https://registry.npmjs.org/require-directory/-/require-directory-2.1.1.tgz", "integrity": "sha512-fGxEI7+wsG9xrvdjsrlmL22OMTTiHRwAMroiEeMgq8gzoLC/PQr7RsRDSTLUg/bZAZtF+TVIkHc6/4RIKrui+Q==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/require-main-filename": { "version": "2.0.0", "resolved": "https://registry.npmjs.org/require-main-filename/-/require-main-filename-2.0.0.tgz", "integrity": "sha512-NKN5kMDylKuldxYLSUfrbo5Tuzh4hd+2E8NPPX02mZtn1VuREQToYe/ZdlJy+J3uCpfaiGF05e7B8W0iXbQHmg==", "dev": true }, "node_modules/requires-port": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/requires-port/-/requires-port-1.0.0.tgz", "integrity": "sha512-KigOCHcocU3XODJxsu8i/j8T9tzT4adHiecwORRQ0ZZFcp7ahwXuRU1m+yuO90C5ZUyGeGfocHDI14M3L3yDAQ==", "dev": true }, "node_modules/resolve": { "version": "1.22.4", "resolved": "https://registry.npmjs.org/resolve/-/resolve-1.22.4.tgz", "integrity": "sha512-PXNdCiPqDqeUou+w1C2eTQbNfxKSuMxqTCuvlmmMsk1NWHL5fRrhY6Pl0qEYYc6+QqGClco1Qj8XnjPego4wfg==", "dev": true, "dependencies": { "is-core-module": "^2.13.0", "path-parse": "^1.0.7", "supports-preserve-symlinks-flag": "^1.0.0" }, "bin": { "resolve": "bin/resolve" }, "funding": { "url": "https://github.com/sponsors/ljharb" } }, "node_modules/resolve-cwd": { "version": "3.0.0", "resolved": "https://registry.npmjs.org/resolve-cwd/-/resolve-cwd-3.0.0.tgz", "integrity": "sha512-OrZaX2Mb+rJCpH/6CpSqt9xFVpN++x01XnN2ie9g6P5/3xelLAkXWVADpdz1IHD/KFfEXyE6V0U01OQ3UO2rEg==", "dev": true, "dependencies": { "resolve-from": "^5.0.0" }, "engines": { "node": ">=8" } }, "node_modules/resolve-from": { "version": "5.0.0", "resolved": "https://registry.npmjs.org/resolve-from/-/resolve-from-5.0.0.tgz", "integrity": "sha512-qYg9KP24dD5qka9J47d0aVky0N+b4fTU89LN9iDnjB5waksiC49rvMB0PrUJQGoTmH50XPiqOvAjDfaijGxYZw==", "dev": true, "engines": { "node": ">=8" } }, "node_modules/resolve-url": { "version": "0.2.1", "resolved": "https://registry.npmjs.org/resolve-url/-/resolve-url-0.2.1.tgz", "integrity": "sha512-ZuF55hVUQaaczgOIwqWzkEcEidmlD/xl44x1UZnhOXcYuFN2S6+rcxpG+C1N3So0wvNI3DmJICUFfu2SxhBmvg==", "deprecated": "https://github.com/lydell/resolve-url#deprecated", "dev": true }, "node_modules/ret": { "version": "0.1.15", "resolved": "https://registry.npmjs.org/ret/-/ret-0.1.15.tgz", "integrity": "sha512-TTlYpa+OL+vMMNG24xSlQGEJ3B/RzEfUlLct7b5G/ytav+wPrplCpVMFuwzXbkecJrb6IYo1iFb0S9v37754mg==", "dev": true, "engines": { "node": ">=0.12" } }, "node_modules/rimraf": { "version": "3.0.2", "resolved": "https://registry.npmjs.org/rimraf/-/rimraf-3.0.2.tgz", "integrity": "sha512-JZkJMZkAGFFPP2YqXZXPbMlMBgsxzE8ILs4lMIX/2o0L9UBw9O/Y3o6wFw/i9YLapcUJWwqbi3kdxIPdC62TIA==", "dev": true, "dependencies": { "glob": "^7.1.3" }, "bin": { "rimraf": "bin.js" }, "funding": { "url": "https://github.com/sponsors/isaacs" } }, "node_modules/rsvp": { "version": "4.8.5", "resolved": "https://registry.npmjs.org/rsvp/-/rsvp-4.8.5.tgz", "integrity": "sha512-nfMOlASu9OnRJo1mbEk2cz0D56a1MBNrJ7orjRZQG10XDyuvwksKbuXNp6qa+kbn839HwjwhBzhFmdsaEAfauA==", "dev": true, "engines": { "node": "6.* || >= 7.*" } }, "node_modules/safe-regex": { "version": "1.1.0", "resolved": "https://registry.npmjs.org/safe-regex/-/safe-regex-1.1.0.tgz", "integrity": "sha512-aJXcif4xnaNUzvUuC5gcb46oTS7zvg4jpMTnuqtrEPlR3vFr4pxtdTwaF1Qs3Enjn9HK+ZlwQui+a7z0SywIzg==", "dev": true, "dependencies": { "ret": "~0.1.10" } }, "node_modules/safer-buffer": { "version": "2.1.2", "resolved": "https://registry.npmjs.org/safer-buffer/-/safer-buffer-2.1.2.tgz", "integrity": "sha512-YZo3K82SD7Riyi0E1EQPojLz7kpepnSQI9IyPbHHg1XXXevb5dJI7tpyN2ADxGcQbHG7vcyRHk0cbwqcQriUtg==", "dev": true }, "node_modules/sane": { "version": "4.1.0", "resolved": "https://registry.npmjs.org/sane/-/sane-4.1.0.tgz", "integrity": "sha512-hhbzAgTIX8O7SHfp2c8/kREfEn4qO/9q8C9beyY6+tvZ87EpoZ3i1RIEvp27YBswnNbY9mWd6paKVmKbAgLfZA==", "deprecated": "some dependency vulnerabilities fixed, support for node < 10 dropped, and newer ECMAScript syntax/features added", "dev": true, "dependencies": { "@cnakazawa/watch": "^1.0.3", "anymatch": "^2.0.0", "capture-exit": "^2.0.0", "exec-sh": "^0.3.2", "execa": "^1.0.0", "fb-watchman": "^2.0.0", "micromatch": "^3.1.4", "minimist": "^1.1.1", "walker": "~1.0.5" }, "bin": { "sane": "src/cli.js" }, "engines": { "node": "6.* || 8.* || >= 10.*" } }, "node_modules/sane/node_modules/anymatch": { "version": "2.0.0", "resolved": "https://registry.npmjs.org/anymatch/-/anymatch-2.0.0.tgz", "integrity": "sha512-5teOsQWABXHHBFP9y3skS5P3d/WfWXpv3FUpy+LorMrNYaT9pI4oLMQX7jzQ2KklNpGpWHzdCXTDT2Y3XGlZBw==", "dev": true, "dependencies": { "micromatch": "^3.1.4", "normalize-path": "^2.1.1" } }, "node_modules/sane/node_modules/braces": { "version": "2.3.2", "resolved": "https://registry.npmjs.org/braces/-/braces-2.3.2.tgz", "integrity": "sha512-aNdbnj9P8PjdXU4ybaWLK2IF3jc/EoDYbC7AazW6to3TRsfXxscC9UXOB5iDiEQrkyIbWp2SLQda4+QAa7nc3w==", "dev": true, "dependencies": { "arr-flatten": "^1.1.0", "array-unique": "^0.3.2", "extend-shallow": "^2.0.1", "fill-range": "^4.0.0", "isobject": "^3.0.1", "repeat-element": "^1.1.2", "snapdragon": "^0.8.1", "snapdragon-node": "^2.0.1", "split-string": "^3.0.2", "to-regex": "^3.0.1" }, "engines": { "node": ">=0.10.0" } }, "node_modules/sane/node_modules/braces/node_modules/extend-shallow": { "version": "2.0.1", "resolved": "https://registry.npmjs.org/extend-shallow/-/extend-shallow-2.0.1.tgz", "integrity": "sha512-zCnTtlxNoAiDc3gqY2aYAWFx7XWWiasuF2K8Me5WbN8otHKTUKBwjPtNpRs/rbUZm7KxWAaNj7P1a/p52GbVug==", "dev": true, "dependencies": { "is-extendable": "^0.1.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/sane/node_modules/cross-spawn": { "version": "6.0.5", "resolved": "https://registry.npmjs.org/cross-spawn/-/cross-spawn-6.0.5.tgz", "integrity": "sha512-eTVLrBSt7fjbDygz805pMnstIs2VTBNkRm0qxZd+M7A5XDdxVRWO5MxGBXZhjY4cqLYLdtrGqRf8mBPmzwSpWQ==", "dev": true, "dependencies": { "nice-try": "^1.0.4", "path-key": "^2.0.1", "semver": "^5.5.0", "shebang-command": "^1.2.0", "which": "^1.2.9" }, "engines": { "node": ">=4.8" } }, "node_modules/sane/node_modules/execa": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/execa/-/execa-1.0.0.tgz", "integrity": "sha512-adbxcyWV46qiHyvSp50TKt05tB4tK3HcmF7/nxfAdhnox83seTDbwnaqKO4sXRy7roHAIFqJP/Rw/AuEbX61LA==", "dev": true, "dependencies": { "cross-spawn": "^6.0.0", "get-stream": "^4.0.0", "is-stream": "^1.1.0", "npm-run-path": "^2.0.0", "p-finally": "^1.0.0", "signal-exit": "^3.0.0", "strip-eof": "^1.0.0" }, "engines": { "node": ">=6" } }, "node_modules/sane/node_modules/fill-range": { "version": "4.0.0", "resolved": "https://registry.npmjs.org/fill-range/-/fill-range-4.0.0.tgz", "integrity": "sha512-VcpLTWqWDiTerugjj8e3+esbg+skS3M9e54UuR3iCeIDMXCLTsAH8hTSzDQU/X6/6t3eYkOKoZSef2PlU6U1XQ==", "dev": true, "dependencies": { "extend-shallow": "^2.0.1", "is-number": "^3.0.0", "repeat-string": "^1.6.1", "to-regex-range": "^2.1.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/sane/node_modules/fill-range/node_modules/extend-shallow": { "version": "2.0.1", "resolved": "https://registry.npmjs.org/extend-shallow/-/extend-shallow-2.0.1.tgz", "integrity": "sha512-zCnTtlxNoAiDc3gqY2aYAWFx7XWWiasuF2K8Me5WbN8otHKTUKBwjPtNpRs/rbUZm7KxWAaNj7P1a/p52GbVug==", "dev": true, "dependencies": { "is-extendable": "^0.1.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/sane/node_modules/get-stream": { "version": "4.1.0", "resolved": "https://registry.npmjs.org/get-stream/-/get-stream-4.1.0.tgz", "integrity": "sha512-GMat4EJ5161kIy2HevLlr4luNjBgvmj413KaQA7jt4V8B4RDsfpHk7WQ9GVqfYyyx8OS/L66Kox+rJRNklLK7w==", "dev": true, "dependencies": { "pump": "^3.0.0" }, "engines": { "node": ">=6" } }, "node_modules/sane/node_modules/is-extendable": { "version": "0.1.1", "resolved": "https://registry.npmjs.org/is-extendable/-/is-extendable-0.1.1.tgz", "integrity": "sha512-5BMULNob1vgFX6EjQw5izWDxrecWK9AM72rugNr0TFldMOi0fj6Jk+zeKIt0xGj4cEfQIJth4w3OKWOJ4f+AFw==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/sane/node_modules/is-number": { "version": "3.0.0", "resolved": "https://registry.npmjs.org/is-number/-/is-number-3.0.0.tgz", "integrity": "sha512-4cboCqIpliH+mAvFNegjZQ4kgKc3ZUhQVr3HvWbSh5q3WH2v82ct+T2Y1hdU5Gdtorx/cLifQjqCbL7bpznLTg==", "dev": true, "dependencies": { "kind-of": "^3.0.2" }, "engines": { "node": ">=0.10.0" } }, "node_modules/sane/node_modules/is-number/node_modules/kind-of": { "version": "3.2.2", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-3.2.2.tgz", "integrity": "sha512-NOW9QQXMoZGg/oqnVNoNTTIFEIid1627WCffUBJEdMxYApq7mNE7CpzucIPc+ZQg25Phej7IJSmX3hO+oblOtQ==", "dev": true, "dependencies": { "is-buffer": "^1.1.5" }, "engines": { "node": ">=0.10.0" } }, "node_modules/sane/node_modules/is-stream": { "version": "1.1.0", "resolved": "https://registry.npmjs.org/is-stream/-/is-stream-1.1.0.tgz", "integrity": "sha512-uQPm8kcs47jx38atAcWTVxyltQYoPT68y9aWYdV6yWXSyW8mzSat0TL6CiWdZeCdF3KrAvpVtnHbTv4RN+rqdQ==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/sane/node_modules/micromatch": { "version": "3.1.10", "resolved": "https://registry.npmjs.org/micromatch/-/micromatch-3.1.10.tgz", "integrity": "sha512-MWikgl9n9M3w+bpsY3He8L+w9eF9338xRl8IAO5viDizwSzziFEyUzo2xrrloB64ADbTf8uA8vRqqttDTOmccg==", "dev": true, "dependencies": { "arr-diff": "^4.0.0", "array-unique": "^0.3.2", "braces": "^2.3.1", "define-property": "^2.0.2", "extend-shallow": "^3.0.2", "extglob": "^2.0.4", "fragment-cache": "^0.2.1", "kind-of": "^6.0.2", "nanomatch": "^1.2.9", "object.pick": "^1.3.0", "regex-not": "^1.0.0", "snapdragon": "^0.8.1", "to-regex": "^3.0.2" }, "engines": { "node": ">=0.10.0" } }, "node_modules/sane/node_modules/normalize-path": { "version": "2.1.1", "resolved": "https://registry.npmjs.org/normalize-path/-/normalize-path-2.1.1.tgz", "integrity": "sha512-3pKJwH184Xo/lnH6oyP1q2pMd7HcypqqmRs91/6/i2CGtWwIKGCkOOMTm/zXbgTEWHw1uNpNi/igc3ePOYHb6w==", "dev": true, "dependencies": { "remove-trailing-separator": "^1.0.1" }, "engines": { "node": ">=0.10.0" } }, "node_modules/sane/node_modules/npm-run-path": { "version": "2.0.2", "resolved": "https://registry.npmjs.org/npm-run-path/-/npm-run-path-2.0.2.tgz", "integrity": "sha512-lJxZYlT4DW/bRUtFh1MQIWqmLwQfAxnqWG4HhEdjMlkrJYnJn0Jrr2u3mgxqaWsdiBc76TYkTG/mhrnYTuzfHw==", "dev": true, "dependencies": { "path-key": "^2.0.0" }, "engines": { "node": ">=4" } }, "node_modules/sane/node_modules/path-key": { "version": "2.0.1", "resolved": "https://registry.npmjs.org/path-key/-/path-key-2.0.1.tgz", "integrity": "sha512-fEHGKCSmUSDPv4uoj8AlD+joPlq3peND+HRYyxFz4KPw4z926S/b8rIuFs2FYJg3BwsxJf6A9/3eIdLaYC+9Dw==", "dev": true, "engines": { "node": ">=4" } }, "node_modules/sane/node_modules/semver": { "version": "5.7.2", "resolved": "https://registry.npmjs.org/semver/-/semver-5.7.2.tgz", "integrity": "sha512-cBznnQ9KjJqU67B52RMC65CMarK2600WFnbkcaiwWq3xy/5haFJlshgnpjovMVJ+Hff49d8GEn0b87C5pDQ10g==", "dev": true, "bin": { "semver": "bin/semver" } }, "node_modules/sane/node_modules/shebang-command": { "version": "1.2.0", "resolved": "https://registry.npmjs.org/shebang-command/-/shebang-command-1.2.0.tgz", "integrity": "sha512-EV3L1+UQWGor21OmnvojK36mhg+TyIKDh3iFBKBohr5xeXIhNBcx8oWdgkTEEQ+BEFFYdLRuqMfd5L84N1V5Vg==", "dev": true, "dependencies": { "shebang-regex": "^1.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/sane/node_modules/shebang-regex": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/shebang-regex/-/shebang-regex-1.0.0.tgz", "integrity": "sha512-wpoSFAxys6b2a2wHZ1XpDSgD7N9iVjg29Ph9uV/uaP9Ex/KXlkTZTeddxDPSYQpgvzKLGJke2UU0AzoGCjNIvQ==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/sane/node_modules/to-regex-range": { "version": "2.1.1", "resolved": "https://registry.npmjs.org/to-regex-range/-/to-regex-range-2.1.1.tgz", "integrity": "sha512-ZZWNfCjUokXXDGXFpZehJIkZqq91BcULFq/Pi7M5i4JnxXdhMKAK682z8bCW3o8Hj1wuuzoKcW3DfVzaP6VuNg==", "dev": true, "dependencies": { "is-number": "^3.0.0", "repeat-string": "^1.6.1" }, "engines": { "node": ">=0.10.0" } }, "node_modules/sane/node_modules/which": { "version": "1.3.1", "resolved": "https://registry.npmjs.org/which/-/which-1.3.1.tgz", "integrity": "sha512-HxJdYWq1MTIQbJ3nw0cqssHoTNU267KlrDuGZ1WYlxDStUtKUhOaJmh112/TZmHxxUfuJqPXSOm7tDyas0OSIQ==", "dev": true, "dependencies": { "isexe": "^2.0.0" }, "bin": { "which": "bin/which" } }, "node_modules/saxes": { "version": "5.0.1", "resolved": "https://registry.npmjs.org/saxes/-/saxes-5.0.1.tgz", "integrity": "sha512-5LBh1Tls8c9xgGjw3QrMwETmTMVk0oFgvrFSvWx62llR2hcEInrKNZ2GZCCuuy2lvWrdl5jhbpeqc5hRYKFOcw==", "dev": true, "dependencies": { "xmlchars": "^2.2.0" }, "engines": { "node": ">=10" } }, "node_modules/semver": { "version": "6.3.1", "resolved": "https://registry.npmjs.org/semver/-/semver-6.3.1.tgz", "integrity": "sha512-BR7VvDCVHO+q2xBEWskxS6DJE1qRnb7DxzUrogb71CWoSficBxYsiAGd+Kl0mmq/MprG9yArRkyrQxTO6XjMzA==", "dev": true, "bin": { "semver": "bin/semver.js" } }, "node_modules/set-blocking": { "version": "2.0.0", "resolved": "https://registry.npmjs.org/set-blocking/-/set-blocking-2.0.0.tgz", "integrity": "sha512-KiKBS8AnWGEyLzofFfmvKwpdPzqiy16LvQfK3yv/fVH7Bj13/wl3JSR1J+rfgRE9q7xUJK4qvgS8raSOeLUehw==", "dev": true }, "node_modules/set-value": { "version": "2.0.1", "resolved": "https://registry.npmjs.org/set-value/-/set-value-2.0.1.tgz", "integrity": "sha512-JxHc1weCN68wRY0fhCoXpyK55m/XPHafOmK4UWD7m2CI14GMcFypt4w/0+NV5f/ZMby2F6S2wwA7fgynh9gWSw==", "dev": true, "dependencies": { "extend-shallow": "^2.0.1", "is-extendable": "^0.1.1", "is-plain-object": "^2.0.3", "split-string": "^3.0.1" }, "engines": { "node": ">=0.10.0" } }, "node_modules/set-value/node_modules/extend-shallow": { "version": "2.0.1", "resolved": "https://registry.npmjs.org/extend-shallow/-/extend-shallow-2.0.1.tgz", "integrity": "sha512-zCnTtlxNoAiDc3gqY2aYAWFx7XWWiasuF2K8Me5WbN8otHKTUKBwjPtNpRs/rbUZm7KxWAaNj7P1a/p52GbVug==", "dev": true, "dependencies": { "is-extendable": "^0.1.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/set-value/node_modules/is-extendable": { "version": "0.1.1", "resolved": "https://registry.npmjs.org/is-extendable/-/is-extendable-0.1.1.tgz", "integrity": "sha512-5BMULNob1vgFX6EjQw5izWDxrecWK9AM72rugNr0TFldMOi0fj6Jk+zeKIt0xGj4cEfQIJth4w3OKWOJ4f+AFw==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/shebang-command": { "version": "2.0.0", "resolved": "https://registry.npmjs.org/shebang-command/-/shebang-command-2.0.0.tgz", "integrity": "sha512-kHxr2zZpYtdmrN1qDjrrX/Z1rR1kG8Dx+gkpK1G4eXmvXswmcE1hTWBWYUzlraYw1/yZp6YuDY77YtvbN0dmDA==", "dev": true, "dependencies": { "shebang-regex": "^3.0.0" }, "engines": { "node": ">=8" } }, "node_modules/shebang-regex": { "version": "3.0.0", "resolved": "https://registry.npmjs.org/shebang-regex/-/shebang-regex-3.0.0.tgz", "integrity": "sha512-7++dFhtcx3353uBaq8DDR4NuxBetBzC7ZQOhmTQInHEd6bSrXdiEyzCvG07Z44UYdLShWUyXt5M/yhz8ekcb1A==", "dev": true, "engines": { "node": ">=8" } }, "node_modules/shellwords": { "version": "0.1.1", "resolved": "https://registry.npmjs.org/shellwords/-/shellwords-0.1.1.tgz", "integrity": "sha512-vFwSUfQvqybiICwZY5+DAWIPLKsWO31Q91JSKl3UYv+K5c2QRPzn0qzec6QPu1Qc9eHYItiP3NdJqNVqetYAww==", "dev": true, "optional": true }, "node_modules/signal-exit": { "version": "3.0.7", "resolved": "https://registry.npmjs.org/signal-exit/-/signal-exit-3.0.7.tgz", "integrity": "sha512-wnD2ZE+l+SPC/uoS0vXeE9L1+0wuaMqKlfz9AMUo38JsyLSBWSFcHR1Rri62LZc12vLr1gb3jl7iwQhgwpAbGQ==", "dev": true }, "node_modules/sisteransi": { "version": "1.0.5", "resolved": "https://registry.npmjs.org/sisteransi/-/sisteransi-1.0.5.tgz", "integrity": "sha512-bLGGlR1QxBcynn2d5YmDX4MGjlZvy2MRBDRNHLJ8VI6l6+9FUiyTFNJ0IveOSP0bcXgVDPRcfGqA0pjaqUpfVg==", "dev": true }, "node_modules/slash": { "version": "3.0.0", "resolved": "https://registry.npmjs.org/slash/-/slash-3.0.0.tgz", "integrity": "sha512-g9Q1haeby36OSStwb4ntCGGGaKsaVSjQ68fBxoQcutl5fS1vuY18H3wSt3jFyFtrkx+Kz0V1G85A4MyAdDMi2Q==", "dev": true, "engines": { "node": ">=8" } }, "node_modules/snapdragon": { "version": "0.8.2", "resolved": "https://registry.npmjs.org/snapdragon/-/snapdragon-0.8.2.tgz", "integrity": "sha512-FtyOnWN/wCHTVXOMwvSv26d+ko5vWlIDD6zoUJ7LW8vh+ZBC8QdljveRP+crNrtBwioEUWy/4dMtbBjA4ioNlg==", "dev": true, "dependencies": { "base": "^0.11.1", "debug": "^2.2.0", "define-property": "^0.2.5", "extend-shallow": "^2.0.1", "map-cache": "^0.2.2", "source-map": "^0.5.6", "source-map-resolve": "^0.5.0", "use": "^3.1.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/snapdragon-node": { "version": "2.1.1", "resolved": "https://registry.npmjs.org/snapdragon-node/-/snapdragon-node-2.1.1.tgz", "integrity": "sha512-O27l4xaMYt/RSQ5TR3vpWCAB5Kb/czIcqUFOM/C4fYcLnbZUc1PkjTAMjof2pBWaSTwOUd6qUHcFGVGj7aIwnw==", "dev": true, "dependencies": { "define-property": "^1.0.0", "isobject": "^3.0.0", "snapdragon-util": "^3.0.1" }, "engines": { "node": ">=0.10.0" } }, "node_modules/snapdragon-node/node_modules/define-property": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/define-property/-/define-property-1.0.0.tgz", "integrity": "sha512-cZTYKFWspt9jZsMscWo8sc/5lbPC9Q0N5nBLgb+Yd915iL3udB1uFgS3B8YCx66UVHq018DAVFoee7x+gxggeA==", "dev": true, "dependencies": { "is-descriptor": "^1.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/snapdragon-util": { "version": "3.0.1", "resolved": "https://registry.npmjs.org/snapdragon-util/-/snapdragon-util-3.0.1.tgz", "integrity": "sha512-mbKkMdQKsjX4BAL4bRYTj21edOf8cN7XHdYUJEe+Zn99hVEYcMvKPct1IqNe7+AZPirn8BCDOQBHQZknqmKlZQ==", "dev": true, "dependencies": { "kind-of": "^3.2.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/snapdragon-util/node_modules/kind-of": { "version": "3.2.2", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-3.2.2.tgz", "integrity": "sha512-NOW9QQXMoZGg/oqnVNoNTTIFEIid1627WCffUBJEdMxYApq7mNE7CpzucIPc+ZQg25Phej7IJSmX3hO+oblOtQ==", "dev": true, "dependencies": { "is-buffer": "^1.1.5" }, "engines": { "node": ">=0.10.0" } }, "node_modules/snapdragon/node_modules/debug": { "version": "2.6.9", "resolved": "https://registry.npmjs.org/debug/-/debug-2.6.9.tgz", "integrity": "sha512-bC7ElrdJaJnPbAP+1EotYvqZsb3ecl5wi6Bfi6BJTUcNowp6cvspg0jXznRTKDjm/E7AdgFBVeAPVMNcKGsHMA==", "dev": true, "dependencies": { "ms": "2.0.0" } }, "node_modules/snapdragon/node_modules/define-property": { "version": "0.2.5", "resolved": "https://registry.npmjs.org/define-property/-/define-property-0.2.5.tgz", "integrity": "sha512-Rr7ADjQZenceVOAKop6ALkkRAmH1A4Gx9hV/7ZujPUN2rkATqFO0JZLZInbAjpZYoJ1gUx8MRMQVkYemcbMSTA==", "dev": true, "dependencies": { "is-descriptor": "^0.1.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/snapdragon/node_modules/extend-shallow": { "version": "2.0.1", "resolved": "https://registry.npmjs.org/extend-shallow/-/extend-shallow-2.0.1.tgz", "integrity": "sha512-zCnTtlxNoAiDc3gqY2aYAWFx7XWWiasuF2K8Me5WbN8otHKTUKBwjPtNpRs/rbUZm7KxWAaNj7P1a/p52GbVug==", "dev": true, "dependencies": { "is-extendable": "^0.1.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/snapdragon/node_modules/is-accessor-descriptor": { "version": "0.1.6", "resolved": "https://registry.npmjs.org/is-accessor-descriptor/-/is-accessor-descriptor-0.1.6.tgz", "integrity": "sha512-e1BM1qnDbMRG3ll2U9dSK0UMHuWOs3pY3AtcFsmvwPtKL3MML/Q86i+GilLfvqEs4GW+ExB91tQ3Ig9noDIZ+A==", "dev": true, "dependencies": { "kind-of": "^3.0.2" }, "engines": { "node": ">=0.10.0" } }, "node_modules/snapdragon/node_modules/is-accessor-descriptor/node_modules/kind-of": { "version": "3.2.2", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-3.2.2.tgz", "integrity": "sha512-NOW9QQXMoZGg/oqnVNoNTTIFEIid1627WCffUBJEdMxYApq7mNE7CpzucIPc+ZQg25Phej7IJSmX3hO+oblOtQ==", "dev": true, "dependencies": { "is-buffer": "^1.1.5" }, "engines": { "node": ">=0.10.0" } }, "node_modules/snapdragon/node_modules/is-data-descriptor": { "version": "0.1.4", "resolved": "https://registry.npmjs.org/is-data-descriptor/-/is-data-descriptor-0.1.4.tgz", "integrity": "sha512-+w9D5ulSoBNlmw9OHn3U2v51SyoCd0he+bB3xMl62oijhrspxowjU+AIcDY0N3iEJbUEkB15IlMASQsxYigvXg==", "dev": true, "dependencies": { "kind-of": "^3.0.2" }, "engines": { "node": ">=0.10.0" } }, "node_modules/snapdragon/node_modules/is-data-descriptor/node_modules/kind-of": { "version": "3.2.2", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-3.2.2.tgz", "integrity": "sha512-NOW9QQXMoZGg/oqnVNoNTTIFEIid1627WCffUBJEdMxYApq7mNE7CpzucIPc+ZQg25Phej7IJSmX3hO+oblOtQ==", "dev": true, "dependencies": { "is-buffer": "^1.1.5" }, "engines": { "node": ">=0.10.0" } }, "node_modules/snapdragon/node_modules/is-descriptor": { "version": "0.1.6", "resolved": "https://registry.npmjs.org/is-descriptor/-/is-descriptor-0.1.6.tgz", "integrity": "sha512-avDYr0SB3DwO9zsMov0gKCESFYqCnE4hq/4z3TdUlukEy5t9C0YRq7HLrsN52NAcqXKaepeCD0n+B0arnVG3Hg==", "dev": true, "dependencies": { "is-accessor-descriptor": "^0.1.6", "is-data-descriptor": "^0.1.4", "kind-of": "^5.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/snapdragon/node_modules/is-extendable": { "version": "0.1.1", "resolved": "https://registry.npmjs.org/is-extendable/-/is-extendable-0.1.1.tgz", "integrity": "sha512-5BMULNob1vgFX6EjQw5izWDxrecWK9AM72rugNr0TFldMOi0fj6Jk+zeKIt0xGj4cEfQIJth4w3OKWOJ4f+AFw==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/snapdragon/node_modules/kind-of": { "version": "5.1.0", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-5.1.0.tgz", "integrity": "sha512-NGEErnH6F2vUuXDh+OlbcKW7/wOcfdRHaZ7VWtqCztfHri/++YKmP51OdWeGPuqCOba6kk2OTe5d02VmTB80Pw==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/snapdragon/node_modules/ms": { "version": "2.0.0", "resolved": "https://registry.npmjs.org/ms/-/ms-2.0.0.tgz", "integrity": "sha512-Tpp60P6IUJDTuOq/5Z8cdskzJujfwqfOTkrwIwj7IRISpnkJnT6SyJ4PCPnGMoFjC9ddhal5KVIYtAt97ix05A==", "dev": true }, "node_modules/snapdragon/node_modules/source-map": { "version": "0.5.7", "resolved": "https://registry.npmjs.org/source-map/-/source-map-0.5.7.tgz", "integrity": "sha512-LbrmJOMUSdEVxIKvdcJzQC+nQhe8FUZQTXQy6+I75skNgn3OoQ0DZA8YnFa7gp8tqtL3KPf1kmo0R5DoApeSGQ==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/source-map": { "version": "0.6.1", "resolved": "https://registry.npmjs.org/source-map/-/source-map-0.6.1.tgz", "integrity": "sha512-UjgapumWlbMhkBgzT7Ykc5YXUT46F0iKu8SGXq0bcwP5dz/h0Plj6enJqjz1Zbq2l5WaqYnrVbwWOWMyF3F47g==", "engines": { "node": ">=0.10.0" } }, "node_modules/source-map-resolve": { "version": "0.5.3", "resolved": "https://registry.npmjs.org/source-map-resolve/-/source-map-resolve-0.5.3.tgz", "integrity": "sha512-Htz+RnsXWk5+P2slx5Jh3Q66vhQj1Cllm0zvnaY98+NFx+Dv2CF/f5O/t8x+KaNdrdIAsruNzoh/KpialbqAnw==", "deprecated": "See https://github.com/lydell/source-map-resolve#deprecated", "dev": true, "dependencies": { "atob": "^2.1.2", "decode-uri-component": "^0.2.0", "resolve-url": "^0.2.1", "source-map-url": "^0.4.0", "urix": "^0.1.0" } }, "node_modules/source-map-support": { "version": "0.5.21", "resolved": "https://registry.npmjs.org/source-map-support/-/source-map-support-0.5.21.tgz", "integrity": "sha512-uBHU3L3czsIyYXKX88fdrGovxdSCoTGDRZ6SYXtSRxLZUzHg5P/66Ht6uoUlHu9EZod+inXhKo3qQgwXUT/y1w==", "dependencies": { "buffer-from": "^1.0.0", "source-map": "^0.6.0" } }, "node_modules/source-map-url": { "version": "0.4.1", "resolved": "https://registry.npmjs.org/source-map-url/-/source-map-url-0.4.1.tgz", "integrity": "sha512-cPiFOTLUKvJFIg4SKVScy4ilPPW6rFgMgfuZJPNoDuMs3nC1HbMUycBoJw77xFIp6z1UJQJOfx6C9GMH80DiTw==", "deprecated": "See https://github.com/lydell/source-map-url#deprecated", "dev": true }, "node_modules/spdx-correct": { "version": "3.2.0", "resolved": "https://registry.npmjs.org/spdx-correct/-/spdx-correct-3.2.0.tgz", "integrity": "sha512-kN9dJbvnySHULIluDHy32WHRUu3Og7B9sbY7tsFLctQkIqnMh3hErYgdMjTYuqmcXX+lK5T1lnUt3G7zNswmZA==", "dev": true, "dependencies": { "spdx-expression-parse": "^3.0.0", "spdx-license-ids": "^3.0.0" } }, "node_modules/spdx-exceptions": { "version": "2.3.0", "resolved": "https://registry.npmjs.org/spdx-exceptions/-/spdx-exceptions-2.3.0.tgz", "integrity": "sha512-/tTrYOC7PPI1nUAgx34hUpqXuyJG+DTHJTnIULG4rDygi4xu/tfgmq1e1cIRwRzwZgo4NLySi+ricLkZkw4i5A==", "dev": true }, "node_modules/spdx-expression-parse": { "version": "3.0.1", "resolved": "https://registry.npmjs.org/spdx-expression-parse/-/spdx-expression-parse-3.0.1.tgz", "integrity": "sha512-cbqHunsQWnJNE6KhVSMsMeH5H/L9EpymbzqTQ3uLwNCLZ1Q481oWaofqH7nO6V07xlXwY6PhQdQ2IedWx/ZK4Q==", "dev": true, "dependencies": { "spdx-exceptions": "^2.1.0", "spdx-license-ids": "^3.0.0" } }, "node_modules/spdx-license-ids": { "version": "3.0.13", "resolved": "https://registry.npmjs.org/spdx-license-ids/-/spdx-license-ids-3.0.13.tgz", "integrity": "sha512-XkD+zwiqXHikFZm4AX/7JSCXA98U5Db4AFd5XUg/+9UNtnH75+Z9KxtpYiJZx36mUDVOwH83pl7yvCer6ewM3w==", "dev": true }, "node_modules/split-string": { "version": "3.1.0", "resolved": "https://registry.npmjs.org/split-string/-/split-string-3.1.0.tgz", "integrity": "sha512-NzNVhJDYpwceVVii8/Hu6DKfD2G+NrQHlS/V/qgv763EYudVwEcMQNxd2lh+0VrUByXN/oJkl5grOhYWvQUYiw==", "dev": true, "dependencies": { "extend-shallow": "^3.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/sprintf-js": { "version": "1.0.3", "resolved": "https://registry.npmjs.org/sprintf-js/-/sprintf-js-1.0.3.tgz", "integrity": "sha512-D9cPgkvLlV3t3IzL0D0YLvGA9Ahk4PcvVwUbN0dSGr1aP0Nrt4AEnTUbuGvquEC0mA64Gqt1fzirlRs5ibXx8g==", "dev": true }, "node_modules/stack-utils": { "version": "2.0.6", "resolved": "https://registry.npmjs.org/stack-utils/-/stack-utils-2.0.6.tgz", "integrity": "sha512-XlkWvfIm6RmsWtNJx+uqtKLS8eqFbxUg0ZzLXqY0caEy9l7hruX8IpiDnjsLavoBgqCCR71TqWO8MaXYheJ3RQ==", "dev": true, "dependencies": { "escape-string-regexp": "^2.0.0" }, "engines": { "node": ">=10" } }, "node_modules/static-extend": { "version": "0.1.2", "resolved": "https://registry.npmjs.org/static-extend/-/static-extend-0.1.2.tgz", "integrity": "sha512-72E9+uLc27Mt718pMHt9VMNiAL4LMsmDbBva8mxWUCkT07fSzEGMYUCk0XWY6lp0j6RBAG4cJ3mWuZv2OE3s0g==", "dev": true, "dependencies": { "define-property": "^0.2.5", "object-copy": "^0.1.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/static-extend/node_modules/define-property": { "version": "0.2.5", "resolved": "https://registry.npmjs.org/define-property/-/define-property-0.2.5.tgz", "integrity": "sha512-Rr7ADjQZenceVOAKop6ALkkRAmH1A4Gx9hV/7ZujPUN2rkATqFO0JZLZInbAjpZYoJ1gUx8MRMQVkYemcbMSTA==", "dev": true, "dependencies": { "is-descriptor": "^0.1.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/static-extend/node_modules/is-accessor-descriptor": { "version": "0.1.6", "resolved": "https://registry.npmjs.org/is-accessor-descriptor/-/is-accessor-descriptor-0.1.6.tgz", "integrity": "sha512-e1BM1qnDbMRG3ll2U9dSK0UMHuWOs3pY3AtcFsmvwPtKL3MML/Q86i+GilLfvqEs4GW+ExB91tQ3Ig9noDIZ+A==", "dev": true, "dependencies": { "kind-of": "^3.0.2" }, "engines": { "node": ">=0.10.0" } }, "node_modules/static-extend/node_modules/is-accessor-descriptor/node_modules/kind-of": { "version": "3.2.2", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-3.2.2.tgz", "integrity": "sha512-NOW9QQXMoZGg/oqnVNoNTTIFEIid1627WCffUBJEdMxYApq7mNE7CpzucIPc+ZQg25Phej7IJSmX3hO+oblOtQ==", "dev": true, "dependencies": { "is-buffer": "^1.1.5" }, "engines": { "node": ">=0.10.0" } }, "node_modules/static-extend/node_modules/is-data-descriptor": { "version": "0.1.4", "resolved": "https://registry.npmjs.org/is-data-descriptor/-/is-data-descriptor-0.1.4.tgz", "integrity": "sha512-+w9D5ulSoBNlmw9OHn3U2v51SyoCd0he+bB3xMl62oijhrspxowjU+AIcDY0N3iEJbUEkB15IlMASQsxYigvXg==", "dev": true, "dependencies": { "kind-of": "^3.0.2" }, "engines": { "node": ">=0.10.0" } }, "node_modules/static-extend/node_modules/is-data-descriptor/node_modules/kind-of": { "version": "3.2.2", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-3.2.2.tgz", "integrity": "sha512-NOW9QQXMoZGg/oqnVNoNTTIFEIid1627WCffUBJEdMxYApq7mNE7CpzucIPc+ZQg25Phej7IJSmX3hO+oblOtQ==", "dev": true, "dependencies": { "is-buffer": "^1.1.5" }, "engines": { "node": ">=0.10.0" } }, "node_modules/static-extend/node_modules/is-descriptor": { "version": "0.1.6", "resolved": "https://registry.npmjs.org/is-descriptor/-/is-descriptor-0.1.6.tgz", "integrity": "sha512-avDYr0SB3DwO9zsMov0gKCESFYqCnE4hq/4z3TdUlukEy5t9C0YRq7HLrsN52NAcqXKaepeCD0n+B0arnVG3Hg==", "dev": true, "dependencies": { "is-accessor-descriptor": "^0.1.6", "is-data-descriptor": "^0.1.4", "kind-of": "^5.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/static-extend/node_modules/kind-of": { "version": "5.1.0", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-5.1.0.tgz", "integrity": "sha512-NGEErnH6F2vUuXDh+OlbcKW7/wOcfdRHaZ7VWtqCztfHri/++YKmP51OdWeGPuqCOba6kk2OTe5d02VmTB80Pw==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/string-length": { "version": "4.0.2", "resolved": "https://registry.npmjs.org/string-length/-/string-length-4.0.2.tgz", "integrity": "sha512-+l6rNN5fYHNhZZy41RXsYptCjA2Igmq4EG7kZAYFQI1E1VTXarr6ZPXBg6eq7Y6eK4FEhY6AJlyuFIb/v/S0VQ==", "dev": true, "dependencies": { "char-regex": "^1.0.2", "strip-ansi": "^6.0.0" }, "engines": { "node": ">=10" } }, "node_modules/string-width": { "version": "4.2.3", "resolved": "https://registry.npmjs.org/string-width/-/string-width-4.2.3.tgz", "integrity": "sha512-wKyQRQpjJ0sIp62ErSZdGsjMJWsap5oRNihHhu6G7JVO/9jIB6UyevL+tXuOqrng8j/cxKTWyWUwvSTriiZz/g==", "dev": true, "dependencies": { "emoji-regex": "^8.0.0", "is-fullwidth-code-point": "^3.0.0", "strip-ansi": "^6.0.1" }, "engines": { "node": ">=8" } }, "node_modules/strip-ansi": { "version": "6.0.1", "resolved": "https://registry.npmjs.org/strip-ansi/-/strip-ansi-6.0.1.tgz", "integrity": "sha512-Y38VPSHcqkFrCpFnQ9vuSXmquuv5oXOKpGeT6aGrr3o3Gc9AlVa6JBfUSOCnbxGGZF+/0ooI7KrPuUSztUdU5A==", "dev": true, "dependencies": { "ansi-regex": "^5.0.1" }, "engines": { "node": ">=8" } }, "node_modules/strip-bom": { "version": "4.0.0", "resolved": "https://registry.npmjs.org/strip-bom/-/strip-bom-4.0.0.tgz", "integrity": "sha512-3xurFv5tEgii33Zi8Jtp55wEIILR9eh34FAW00PZf+JnSsTmV/ioewSgQl97JHvgjoRGwPShsWm+IdrxB35d0w==", "dev": true, "engines": { "node": ">=8" } }, "node_modules/strip-eof": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/strip-eof/-/strip-eof-1.0.0.tgz", "integrity": "sha512-7FCwGGmx8mD5xQd3RPUvnSpUXHM3BWuzjtpD4TXsfcZ9EL4azvVVUscFYwD9nx8Kh+uCBC00XBtAykoMHwTh8Q==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/strip-final-newline": { "version": "2.0.0", "resolved": "https://registry.npmjs.org/strip-final-newline/-/strip-final-newline-2.0.0.tgz", "integrity": "sha512-BrpvfNAE3dcvq7ll3xVumzjKjZQ5tI1sEUIKr3Uoks0XUl45St3FlatVqef9prk4jRDzhW6WZg+3bk93y6pLjA==", "dev": true, "engines": { "node": ">=6" } }, "node_modules/supports-color": { "version": "7.2.0", "resolved": "https://registry.npmjs.org/supports-color/-/supports-color-7.2.0.tgz", "integrity": "sha512-qpCAvRl9stuOHveKsn7HncJRvv501qIacKzQlO/+Lwxc9+0q2wLyv4Dfvt80/DPn2pqOBsJdDiogXGR9+OvwRw==", "dev": true, "dependencies": { "has-flag": "^4.0.0" }, "engines": { "node": ">=8" } }, "node_modules/supports-hyperlinks": { "version": "2.3.0", "resolved": "https://registry.npmjs.org/supports-hyperlinks/-/supports-hyperlinks-2.3.0.tgz", "integrity": "sha512-RpsAZlpWcDwOPQA22aCH4J0t7L8JmAvsCxfOSEwm7cQs3LshN36QaTkwd70DnBOXDWGssw2eUoc8CaRWT0XunA==", "dev": true, "dependencies": { "has-flag": "^4.0.0", "supports-color": "^7.0.0" }, "engines": { "node": ">=8" } }, "node_modules/supports-preserve-symlinks-flag": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/supports-preserve-symlinks-flag/-/supports-preserve-symlinks-flag-1.0.0.tgz", "integrity": "sha512-ot0WnXS9fgdkgIcePe6RHNk1WA8+muPa6cSjeR3V8K27q9BB1rTE3R1p7Hv0z1ZyAc8s6Vvv8DIyWf681MAt0w==", "dev": true, "engines": { "node": ">= 0.4" }, "funding": { "url": "https://github.com/sponsors/ljharb" } }, "node_modules/symbol-tree": { "version": "3.2.4", "resolved": "https://registry.npmjs.org/symbol-tree/-/symbol-tree-3.2.4.tgz", "integrity": "sha512-9QNk5KwDF+Bvz+PyObkmSYjI5ksVUYtjW7AU22r2NKcfLJcXp96hkDWU3+XndOsUb+AQ9QhfzfCT2O+CNWT5Tw==", "dev": true }, "node_modules/terminal-link": { "version": "2.1.1", "resolved": "https://registry.npmjs.org/terminal-link/-/terminal-link-2.1.1.tgz", "integrity": "sha512-un0FmiRUQNr5PJqy9kP7c40F5BOfpGlYTrxonDChEZB7pzZxRNp/bt+ymiy9/npwXya9KH99nJ/GXFIiUkYGFQ==", "dev": true, "dependencies": { "ansi-escapes": "^4.2.1", "supports-hyperlinks": "^2.0.0" }, "engines": { "node": ">=8" }, "funding": { "url": "https://github.com/sponsors/sindresorhus" } }, "node_modules/test-exclude": { "version": "6.0.0", "resolved": "https://registry.npmjs.org/test-exclude/-/test-exclude-6.0.0.tgz", "integrity": "sha512-cAGWPIyOHU6zlmg88jwm7VRyXnMN7iV68OGAbYDk/Mh/xC/pzVPlQtY6ngoIH/5/tciuhGfvESU8GrHrcxD56w==", "dev": true, "dependencies": { "@istanbuljs/schema": "^0.1.2", "glob": "^7.1.4", "minimatch": "^3.0.4" }, "engines": { "node": ">=8" } }, "node_modules/throat": { "version": "5.0.0", "resolved": "https://registry.npmjs.org/throat/-/throat-5.0.0.tgz", "integrity": "sha512-fcwX4mndzpLQKBS1DVYhGAcYaYt7vsHNIvQV+WXMvnow5cgjPphq5CaayLaGsjRdSCKZFNGt7/GYAuXaNOiYCA==", "dev": true }, "node_modules/tmpl": { "version": "1.0.5", "resolved": "https://registry.npmjs.org/tmpl/-/tmpl-1.0.5.tgz", "integrity": "sha512-3f0uOEAQwIqGuWW2MVzYg8fV/QNnc/IpuJNG837rLuczAaLVHslWHZQj4IGiEl5Hs3kkbhwL9Ab7Hrsmuj+Smw==", "dev": true }, "node_modules/to-fast-properties": { "version": "2.0.0", "resolved": "https://registry.npmjs.org/to-fast-properties/-/to-fast-properties-2.0.0.tgz", "integrity": "sha512-/OaKK0xYrs3DmxRYqL/yDc+FxFUVYhDlXMhRmv3z915w2HF1tnN1omB354j8VUGO/hbRzyD6Y3sA7v7GS/ceog==", "dev": true, "engines": { "node": ">=4" } }, "node_modules/to-object-path": { "version": "0.3.0", "resolved": "https://registry.npmjs.org/to-object-path/-/to-object-path-0.3.0.tgz", "integrity": "sha512-9mWHdnGRuh3onocaHzukyvCZhzvr6tiflAy/JRFXcJX0TjgfWA9pk9t8CMbzmBE4Jfw58pXbkngtBtqYxzNEyg==", "dev": true, "dependencies": { "kind-of": "^3.0.2" }, "engines": { "node": ">=0.10.0" } }, "node_modules/to-object-path/node_modules/kind-of": { "version": "3.2.2", "resolved": "https://registry.npmjs.org/kind-of/-/kind-of-3.2.2.tgz", "integrity": "sha512-NOW9QQXMoZGg/oqnVNoNTTIFEIid1627WCffUBJEdMxYApq7mNE7CpzucIPc+ZQg25Phej7IJSmX3hO+oblOtQ==", "dev": true, "dependencies": { "is-buffer": "^1.1.5" }, "engines": { "node": ">=0.10.0" } }, "node_modules/to-regex": { "version": "3.0.2", "resolved": "https://registry.npmjs.org/to-regex/-/to-regex-3.0.2.tgz", "integrity": "sha512-FWtleNAtZ/Ki2qtqej2CXTOayOH9bHDQF+Q48VpWyDXjbYxA4Yz8iDB31zXOBUlOHHKidDbqGVrTUvQMPmBGBw==", "dev": true, "dependencies": { "define-property": "^2.0.2", "extend-shallow": "^3.0.2", "regex-not": "^1.0.2", "safe-regex": "^1.1.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/to-regex-range": { "version": "5.0.1", "resolved": "https://registry.npmjs.org/to-regex-range/-/to-regex-range-5.0.1.tgz", "integrity": "sha512-65P7iz6X5yEr1cwcgvQxbbIw7Uk3gOy5dIdtZ4rDveLqhrdJP+Li/Hx6tyK0NEb+2GCyneCMJiGqrADCSNk8sQ==", "dev": true, "dependencies": { "is-number": "^7.0.0" }, "engines": { "node": ">=8.0" } }, "node_modules/tough-cookie": { "version": "4.1.3", "resolved": "https://registry.npmjs.org/tough-cookie/-/tough-cookie-4.1.3.tgz", "integrity": "sha512-aX/y5pVRkfRnfmuX+OdbSdXvPe6ieKX/G2s7e98f4poJHnqH3281gDPm/metm6E/WRamfx7WC4HUqkWHfQHprw==", "dev": true, "dependencies": { "psl": "^1.1.33", "punycode": "^2.1.1", "universalify": "^0.2.0", "url-parse": "^1.5.3" }, "engines": { "node": ">=6" } }, "node_modules/tr46": { "version": "2.1.0", "resolved": "https://registry.npmjs.org/tr46/-/tr46-2.1.0.tgz", "integrity": "sha512-15Ih7phfcdP5YxqiB+iDtLoaTz4Nd35+IiAv0kQ5FNKHzXgdWqPoTIqEDDJmXceQt4JZk6lVPT8lnDlPpGDppw==", "dev": true, "dependencies": { "punycode": "^2.1.1" }, "engines": { "node": ">=8" } }, "node_modules/ts-jest": { "version": "26.5.6", "resolved": "https://registry.npmjs.org/ts-jest/-/ts-jest-26.5.6.tgz", "integrity": "sha512-rua+rCP8DxpA8b4DQD/6X2HQS8Zy/xzViVYfEs2OQu68tkCuKLV0Md8pmX55+W24uRIyAsf/BajRfxOs+R2MKA==", "dev": true, "dependencies": { "bs-logger": "0.x", "buffer-from": "1.x", "fast-json-stable-stringify": "2.x", "jest-util": "^26.1.0", "json5": "2.x", "lodash": "4.x", "make-error": "1.x", "mkdirp": "1.x", "semver": "7.x", "yargs-parser": "20.x" }, "bin": { "ts-jest": "cli.js" }, "engines": { "node": ">= 10" }, "peerDependencies": { "jest": ">=26 <27", "typescript": ">=3.8 <5.0" } }, "node_modules/ts-jest/node_modules/lru-cache": { "version": "6.0.0", "resolved": "https://registry.npmjs.org/lru-cache/-/lru-cache-6.0.0.tgz", "integrity": "sha512-Jo6dJ04CmSjuznwJSS3pUeWmd/H0ffTlkXXgwZi+eq1UCmqQwCh+eLsYOYCwY991i2Fah4h1BEMCx4qThGbsiA==", "dev": true, "dependencies": { "yallist": "^4.0.0" }, "engines": { "node": ">=10" } }, "node_modules/ts-jest/node_modules/semver": { "version": "7.5.4", "resolved": "https://registry.npmjs.org/semver/-/semver-7.5.4.tgz", "integrity": "sha512-1bCSESV6Pv+i21Hvpxp3Dx+pSD8lIPt8uVjRrxAUt/nbswYc+tK6Y2btiULjd4+fnq15PX+nqQDC7Oft7WkwcA==", "dev": true, "dependencies": { "lru-cache": "^6.0.0" }, "bin": { "semver": "bin/semver.js" }, "engines": { "node": ">=10" } }, "node_modules/ts-jest/node_modules/yallist": { "version": "4.0.0", "resolved": "https://registry.npmjs.org/yallist/-/yallist-4.0.0.tgz", "integrity": "sha512-3wdGidZyq5PB084XLES5TpOSRA3wjXAlIWMhum2kRcv/41Sn2emQ0dycQW4uZXLejwKvg6EsvbdlVL+FYEct7A==", "dev": true }, "node_modules/ts-node": { "version": "9.1.1", "resolved": "https://registry.npmjs.org/ts-node/-/ts-node-9.1.1.tgz", "integrity": "sha512-hPlt7ZACERQGf03M253ytLY3dHbGNGrAq9qIHWUY9XHYl1z7wYngSr3OQ5xmui8o2AaxsONxIzjafLUiWBo1Fg==", "dev": true, "dependencies": { "arg": "^4.1.0", "create-require": "^1.1.0", "diff": "^4.0.1", "make-error": "^1.1.1", "source-map-support": "^0.5.17", "yn": "3.1.1" }, "bin": { "ts-node": "dist/bin.js", "ts-node-script": "dist/bin-script.js", "ts-node-transpile-only": "dist/bin-transpile.js", "ts-script": "dist/bin-script-deprecated.js" }, "engines": { "node": ">=10.0.0" }, "peerDependencies": { "typescript": ">=2.7" } }, "node_modules/tslib": { "version": "2.3.1", "resolved": "https://registry.npmjs.org/tslib/-/tslib-2.3.1.tgz", "integrity": "sha512-77EbyPPpMz+FRFRuAFlWMtmgUWGe9UOG2Z25NqCwiIjRhOf5iKGuzSe5P2w1laq+FkRy4p+PCuVkJSGkzTEKVw==" }, "node_modules/type-detect": { "version": "4.0.8", "resolved": "https://registry.npmjs.org/type-detect/-/type-detect-4.0.8.tgz", "integrity": "sha512-0fr/mIH1dlO+x7TlcMy+bIDqKPsw/70tVyeHW787goQjhmqaZe10uwLujubK9q9Lg6Fiho1KUKDYz0Z7k7g5/g==", "dev": true, "engines": { "node": ">=4" } }, "node_modules/type-fest": { "version": "0.21.3", "resolved": "https://registry.npmjs.org/type-fest/-/type-fest-0.21.3.tgz", "integrity": "sha512-t0rzBq87m3fVcduHDUFhKmyyX+9eo6WQjZvf51Ea/M0Q7+T374Jp1aUiyUl0GKxp8M/OETVHSDvmkyPgvX+X2w==", "dev": true, "engines": { "node": ">=10" }, "funding": { "url": "https://github.com/sponsors/sindresorhus" } }, "node_modules/typedarray-to-buffer": { "version": "3.1.5", "resolved": "https://registry.npmjs.org/typedarray-to-buffer/-/typedarray-to-buffer-3.1.5.tgz", "integrity": "sha512-zdu8XMNEDepKKR+XYOXAVPtWui0ly0NtohUscw+UmaHiAWT8hrV1rr//H6V+0DvJ3OQ19S979M0laLfX8rm82Q==", "dev": true, "dependencies": { "is-typedarray": "^1.0.0" } }, "node_modules/typescript": { "version": "3.9.10", "resolved": "https://registry.npmjs.org/typescript/-/typescript-3.9.10.tgz", "integrity": "sha512-w6fIxVE/H1PkLKcCPsFqKE7Kv7QUwhU8qQY2MueZXWx5cPZdwFupLgKK3vntcK98BtNHZtAF4LA/yl2a7k8R6Q==", "dev": true, "bin": { "tsc": "bin/tsc", "tsserver": "bin/tsserver" }, "engines": { "node": ">=4.2.0" } }, "node_modules/union-value": { "version": "1.0.1", "resolved": "https://registry.npmjs.org/union-value/-/union-value-1.0.1.tgz", "integrity": "sha512-tJfXmxMeWYnczCVs7XAEvIV7ieppALdyepWMkHkwciRpZraG/xwT+s2JN8+pr1+8jCRf80FFzvr+MpQeeoF4Xg==", "dev": true, "dependencies": { "arr-union": "^3.1.0", "get-value": "^2.0.6", "is-extendable": "^0.1.1", "set-value": "^2.0.1" }, "engines": { "node": ">=0.10.0" } }, "node_modules/union-value/node_modules/is-extendable": { "version": "0.1.1", "resolved": "https://registry.npmjs.org/is-extendable/-/is-extendable-0.1.1.tgz", "integrity": "sha512-5BMULNob1vgFX6EjQw5izWDxrecWK9AM72rugNr0TFldMOi0fj6Jk+zeKIt0xGj4cEfQIJth4w3OKWOJ4f+AFw==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/universalify": { "version": "0.2.0", "resolved": "https://registry.npmjs.org/universalify/-/universalify-0.2.0.tgz", "integrity": "sha512-CJ1QgKmNg3CwvAv/kOFmtnEN05f0D/cn9QntgNOQlQF9dgvVTHj3t+8JPdjqawCHk7V/KA+fbUqzZ9XWhcqPUg==", "dev": true, "engines": { "node": ">= 4.0.0" } }, "node_modules/unset-value": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/unset-value/-/unset-value-1.0.0.tgz", "integrity": "sha512-PcA2tsuGSF9cnySLHTLSh2qrQiJ70mn+r+Glzxv2TWZblxsxCC52BDlZoPCsz7STd9pN7EZetkWZBAvk4cgZdQ==", "dev": true, "dependencies": { "has-value": "^0.3.1", "isobject": "^3.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/unset-value/node_modules/has-value": { "version": "0.3.1", "resolved": "https://registry.npmjs.org/has-value/-/has-value-0.3.1.tgz", "integrity": "sha512-gpG936j8/MzaeID5Yif+577c17TxaDmhuyVgSwtnL/q8UUTySg8Mecb+8Cf1otgLoD7DDH75axp86ER7LFsf3Q==", "dev": true, "dependencies": { "get-value": "^2.0.3", "has-values": "^0.1.4", "isobject": "^2.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/unset-value/node_modules/has-value/node_modules/isobject": { "version": "2.1.0", "resolved": "https://registry.npmjs.org/isobject/-/isobject-2.1.0.tgz", "integrity": "sha512-+OUdGJlgjOBZDfxnDjYYG6zp487z0JGNQq3cYQYg5f5hKR+syHMsaztzGeml/4kGG55CSpKSpWTY+jYGgsHLgA==", "dev": true, "dependencies": { "isarray": "1.0.0" }, "engines": { "node": ">=0.10.0" } }, "node_modules/unset-value/node_modules/has-values": { "version": "0.1.4", "resolved": "https://registry.npmjs.org/has-values/-/has-values-0.1.4.tgz", "integrity": "sha512-J8S0cEdWuQbqD9//tlZxiMuMNmxB8PlEwvYwuxsTmR1G5RXUePEX/SJn7aD0GMLieuZYSwNH0cQuJGwnYunXRQ==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/update-browserslist-db": { "version": "1.0.11", "resolved": "https://registry.npmjs.org/update-browserslist-db/-/update-browserslist-db-1.0.11.tgz", "integrity": "sha512-dCwEFf0/oT85M1fHBg4F0jtLwJrutGoHSQXCh7u4o2t1drG+c0a9Flnqww6XUKSfQMPpJBRjU8d4RXB09qtvaA==", "dev": true, "funding": [ { "type": "opencollective", "url": "https://opencollective.com/browserslist" }, { "type": "tidelift", "url": "https://tidelift.com/funding/github/npm/browserslist" }, { "type": "github", "url": "https://github.com/sponsors/ai" } ], "dependencies": { "escalade": "^3.1.1", "picocolors": "^1.0.0" }, "bin": { "update-browserslist-db": "cli.js" }, "peerDependencies": { "browserslist": ">= 4.21.0" } }, "node_modules/urix": { "version": "0.1.0", "resolved": "https://registry.npmjs.org/urix/-/urix-0.1.0.tgz", "integrity": "sha512-Am1ousAhSLBeB9cG/7k7r2R0zj50uDRlZHPGbazid5s9rlF1F/QKYObEKSIunSjIOkJZqwRRLpvewjEkM7pSqg==", "deprecated": "Please see https://github.com/lydell/urix#deprecated", "dev": true }, "node_modules/url-parse": { "version": "1.5.10", "resolved": "https://registry.npmjs.org/url-parse/-/url-parse-1.5.10.tgz", "integrity": "sha512-WypcfiRhfeUP9vvF0j6rw0J3hrWrw6iZv3+22h6iRMJ/8z1Tj6XfLP4DsUix5MhMPnXpiHDoKyoZ/bdCkwBCiQ==", "dev": true, "dependencies": { "querystringify": "^2.1.1", "requires-port": "^1.0.0" } }, "node_modules/use": { "version": "3.1.1", "resolved": "https://registry.npmjs.org/use/-/use-3.1.1.tgz", "integrity": "sha512-cwESVXlO3url9YWlFW/TA9cshCEhtu7IKJ/p5soJ/gGpj7vbvFrAY/eIioQ6Dw23KjZhYgiIo8HOs1nQ2vr/oQ==", "dev": true, "engines": { "node": ">=0.10.0" } }, "node_modules/uuid": { "version": "8.3.2", "resolved": "https://registry.npmjs.org/uuid/-/uuid-8.3.2.tgz", "integrity": "sha512-+NYs2QeMWy+GWFOEm9xnn6HCDp0l7QBD7ml8zLUmJ+93Q5NF0NocErnwkTkXVFNiX3/fpC6afS8Dhb/gz7R7eg==", "dev": true, "optional": true, "bin": { "uuid": "dist/bin/uuid" } }, "node_modules/v8-to-istanbul": { "version": "7.1.2", "resolved": "https://registry.npmjs.org/v8-to-istanbul/-/v8-to-istanbul-7.1.2.tgz", "integrity": "sha512-TxNb7YEUwkLXCQYeudi6lgQ/SZrzNO4kMdlqVxaZPUIUjCv6iSSypUQX70kNBSERpQ8fk48+d61FXk+tgqcWow==", "dev": true, "dependencies": { "@types/istanbul-lib-coverage": "^2.0.1", "convert-source-map": "^1.6.0", "source-map": "^0.7.3" }, "engines": { "node": ">=10.10.0" } }, "node_modules/v8-to-istanbul/node_modules/source-map": { "version": "0.7.4", "resolved": "https://registry.npmjs.org/source-map/-/source-map-0.7.4.tgz", "integrity": "sha512-l3BikUxvPOcn5E74dZiq5BGsTb5yEwhaTSzccU6t4sDOH8NWJCstKO5QT2CvtFoK6F0saL7p9xHAqHOlCPJygA==", "dev": true, "engines": { "node": ">= 8" } }, "node_modules/validate-npm-package-license": { "version": "3.0.4", "resolved": "https://registry.npmjs.org/validate-npm-package-license/-/validate-npm-package-license-3.0.4.tgz", "integrity": "sha512-DpKm2Ui/xN7/HQKCtpZxoRWBhZ9Z0kqtygG8XCgNQ8ZlDnxuQmWhj566j8fN4Cu3/JmbhsDo7fcAJq4s9h27Ew==", "dev": true, "dependencies": { "spdx-correct": "^3.0.0", "spdx-expression-parse": "^3.0.0" } }, "node_modules/w3c-hr-time": { "version": "1.0.2", "resolved": "https://registry.npmjs.org/w3c-hr-time/-/w3c-hr-time-1.0.2.tgz", "integrity": "sha512-z8P5DvDNjKDoFIHK7q8r8lackT6l+jo/Ye3HOle7l9nICP9lf1Ci25fy9vHd0JOWewkIFzXIEig3TdKT7JQ5fQ==", "deprecated": "Use your platform's native performance.now() and performance.timeOrigin.", "dev": true, "dependencies": { "browser-process-hrtime": "^1.0.0" } }, "node_modules/w3c-xmlserializer": { "version": "2.0.0", "resolved": "https://registry.npmjs.org/w3c-xmlserializer/-/w3c-xmlserializer-2.0.0.tgz", "integrity": "sha512-4tzD0mF8iSiMiNs30BiLO3EpfGLZUT2MSX/G+o7ZywDzliWQ3OPtTZ0PTC3B3ca1UAf4cJMHB+2Bf56EriJuRA==", "dev": true, "dependencies": { "xml-name-validator": "^3.0.0" }, "engines": { "node": ">=10" } }, "node_modules/walker": { "version": "1.0.8", "resolved": "https://registry.npmjs.org/walker/-/walker-1.0.8.tgz", "integrity": "sha512-ts/8E8l5b7kY0vlWLewOkDXMmPdLcVV4GmOQLyxuSswIJsweeFZtAsMF7k1Nszz+TYBQrlYRmzOnr398y1JemQ==", "dev": true, "dependencies": { "makeerror": "1.0.12" } }, "node_modules/webidl-conversions": { "version": "6.1.0", "resolved": "https://registry.npmjs.org/webidl-conversions/-/webidl-conversions-6.1.0.tgz", "integrity": "sha512-qBIvFLGiBpLjfwmYAaHPXsn+ho5xZnGvyGvsarywGNc8VyQJUMHJ8OBKGGrPER0okBeMDaan4mNBlgBROxuI8w==", "dev": true, "engines": { "node": ">=10.4" } }, "node_modules/whatwg-encoding": { "version": "1.0.5", "resolved": "https://registry.npmjs.org/whatwg-encoding/-/whatwg-encoding-1.0.5.tgz", "integrity": "sha512-b5lim54JOPN9HtzvK9HFXvBma/rnfFeqsic0hSpjtDbVxR3dJKLc+KB4V6GgiGOvl7CY/KNh8rxSo9DKQrnUEw==", "dev": true, "dependencies": { "iconv-lite": "0.4.24" } }, "node_modules/whatwg-mimetype": { "version": "2.3.0", "resolved": "https://registry.npmjs.org/whatwg-mimetype/-/whatwg-mimetype-2.3.0.tgz", "integrity": "sha512-M4yMwr6mAnQz76TbJm914+gPpB/nCwvZbJU28cUD6dR004SAxDLOOSUaB1JDRqLtaOV/vi0IC5lEAGFgrjGv/g==", "dev": true }, "node_modules/whatwg-url": { "version": "8.7.0", "resolved": "https://registry.npmjs.org/whatwg-url/-/whatwg-url-8.7.0.tgz", "integrity": "sha512-gAojqb/m9Q8a5IV96E3fHJM70AzCkgt4uXYX2O7EmuyOnLrViCQlsEBmF9UQIu3/aeAIp2U17rtbpZWNntQqdg==", "dev": true, "dependencies": { "lodash": "^4.7.0", "tr46": "^2.1.0", "webidl-conversions": "^6.1.0" }, "engines": { "node": ">=10" } }, "node_modules/which": { "version": "2.0.2", "resolved": "https://registry.npmjs.org/which/-/which-2.0.2.tgz", "integrity": "sha512-BLI3Tl1TW3Pvl70l3yq3Y64i+awpwXqsGBYWkkqMtnbXgrMD+yj7rhW0kuEDxzJaYXGjEW5ogapKNMEKNMjibA==", "dev": true, "dependencies": { "isexe": "^2.0.0" }, "bin": { "node-which": "bin/node-which" }, "engines": { "node": ">= 8" } }, "node_modules/which-module": { "version": "2.0.1", "resolved": "https://registry.npmjs.org/which-module/-/which-module-2.0.1.tgz", "integrity": "sha512-iBdZ57RDvnOR9AGBhML2vFZf7h8vmBjhoaZqODJBFWHVtKkDmKuHai3cx5PgVMrX5YDNp27AofYbAwctSS+vhQ==", "dev": true }, "node_modules/wrap-ansi": { "version": "6.2.0", "resolved": "https://registry.npmjs.org/wrap-ansi/-/wrap-ansi-6.2.0.tgz", "integrity": "sha512-r6lPcBGxZXlIcymEu7InxDMhdW0KDxpLgoFLcguasxCaJ/SOIZwINatK9KY/tf+ZrlywOKU0UDj3ATXUBfxJXA==", "dev": true, "dependencies": { "ansi-styles": "^4.0.0", "string-width": "^4.1.0", "strip-ansi": "^6.0.0" }, "engines": { "node": ">=8" } }, "node_modules/wrappy": { "version": "1.0.2", "resolved": "https://registry.npmjs.org/wrappy/-/wrappy-1.0.2.tgz", "integrity": "sha512-l4Sp/DRseor9wL6EvV2+TuQn63dMkPjZ/sp9XkghTEbV9KlPS1xUsZ3u7/IQO4wxtcFB4bgpQPRcR3QCvezPcQ==", "dev": true }, "node_modules/write-file-atomic": { "version": "3.0.3", "resolved": "https://registry.npmjs.org/write-file-atomic/-/write-file-atomic-3.0.3.tgz", "integrity": "sha512-AvHcyZ5JnSfq3ioSyjrBkH9yW4m7Ayk8/9My/DD9onKeu/94fwrMocemO2QAJFAlnnDN+ZDS+ZjAR5ua1/PV/Q==", "dev": true, "dependencies": { "imurmurhash": "^0.1.4", "is-typedarray": "^1.0.0", "signal-exit": "^3.0.2", "typedarray-to-buffer": "^3.1.5" } }, "node_modules/ws": { "version": "7.5.9", "resolved": "https://registry.npmjs.org/ws/-/ws-7.5.9.tgz", "integrity": "sha512-F+P9Jil7UiSKSkppIiD94dN07AwvFixvLIj1Og1Rl9GGMuNipJnV9JzjD6XuqmAeiswGvUmNLjr5cFuXwNS77Q==", "dev": true, "engines": { "node": ">=8.3.0" }, "peerDependencies": { "bufferutil": "^4.0.1", "utf-8-validate": "^5.0.2" }, "peerDependenciesMeta": { "bufferutil": { "optional": true }, "utf-8-validate": { "optional": true } } }, "node_modules/xml-name-validator": { "version": "3.0.0", "resolved": "https://registry.npmjs.org/xml-name-validator/-/xml-name-validator-3.0.0.tgz", "integrity": "sha512-A5CUptxDsvxKJEU3yO6DuWBSJz/qizqzJKOMIfUJHETbBw/sFaDxgd6fxm1ewUaM0jZ444Fc5vC5ROYurg/4Pw==", "dev": true }, "node_modules/xmlchars": { "version": "2.2.0", "resolved": "https://registry.npmjs.org/xmlchars/-/xmlchars-2.2.0.tgz", "integrity": "sha512-JZnDKK8B0RCDw84FNdDAIpZK+JuJw+s7Lz8nksI7SIuU3UXJJslUthsi+uWBUYOwPFwW7W7PRLRfUKpxjtjFCw==", "dev": true }, "node_modules/y18n": { "version": "4.0.3", "resolved": "https://registry.npmjs.org/y18n/-/y18n-4.0.3.tgz", "integrity": "sha512-JKhqTOwSrqNA1NY5lSztJ1GrBiUodLMmIZuLiDaMRJ+itFd+ABVE8XBjOvIWL+rSqNDC74LCSFmlb/U4UZ4hJQ==", "dev": true }, "node_modules/yallist": { "version": "3.1.1", "resolved": "https://registry.npmjs.org/yallist/-/yallist-3.1.1.tgz", "integrity": "sha512-a4UGQaWPH59mOXUYnAG2ewncQS4i4F43Tv3JoAM+s2VDAmS9NsK8GpDMLrCHPksFT7h3K6TOoUNn2pb7RoXx4g==", "dev": true }, "node_modules/yargs": { "version": "15.4.1", "resolved": "https://registry.npmjs.org/yargs/-/yargs-15.4.1.tgz", "integrity": "sha512-aePbxDmcYW++PaqBsJ+HYUFwCdv4LVvdnhBy78E57PIor8/OVvhMrADFFEDh8DHDFRv/O9i3lPhsENjO7QX0+A==", "dev": true, "dependencies": { "cliui": "^6.0.0", "decamelize": "^1.2.0", "find-up": "^4.1.0", "get-caller-file": "^2.0.1", "require-directory": "^2.1.1", "require-main-filename": "^2.0.0", "set-blocking": "^2.0.0", "string-width": "^4.2.0", "which-module": "^2.0.0", "y18n": "^4.0.0", "yargs-parser": "^18.1.2" }, "engines": { "node": ">=8" } }, "node_modules/yargs-parser": { "version": "20.2.9", "resolved": "https://registry.npmjs.org/yargs-parser/-/yargs-parser-20.2.9.tgz", "integrity": "sha512-y11nGElTIV+CT3Zv9t7VKl+Q3hTQoT9a1Qzezhhl6Rp21gJ/IVTW7Z3y9EWXhuUBC2Shnf+DX0antecpAwSP8w==", "dev": true, "engines": { "node": ">=10" } }, "node_modules/yargs/node_modules/yargs-parser": { "version": "18.1.3", "resolved": "https://registry.npmjs.org/yargs-parser/-/yargs-parser-18.1.3.tgz", "integrity": "sha512-o50j0JeToy/4K6OZcaQmW6lyXXKhq7csREXcDwk2omFPJEwUNOVtJKvmDr9EI1fAJZUyZcRF7kxGBWmRXudrCQ==", "dev": true, "dependencies": { "camelcase": "^5.0.0", "decamelize": "^1.2.0" }, "engines": { "node": ">=6" } }, "node_modules/yn": { "version": "3.1.1", "resolved": "https://registry.npmjs.org/yn/-/yn-3.1.1.tgz", "integrity": "sha512-Ux4ygGWsu2c7isFWe8Yu1YluJmqVhxqK2cLXNQA5AcC3QfbGNpM7fu0Y8b/z16pXLnFxZYvWhd3fhBY9DLmC6Q==", "dev": true, "engines": { "node": ">=6" } } } }
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/CONTRIBUTING.md
# Contributing Guidelines Thank you for your interest in contributing to our project. Whether it's a bug report, new feature, correction, or additional documentation, we greatly value feedback and contributions from our community. Please read through this document before submitting any issues or pull requests to ensure we have all the necessary information to effectively respond to your bug report or contribution. ## Reporting Bugs/Feature Requests We welcome you to use the GitHub issue tracker to report bugs or suggest features. When filing an issue, please check existing open, or recently closed, issues to make sure somebody else hasn't already reported the issue. Please try to include as much information as you can. Details like these are incredibly useful: * A reproducible test case or series of steps * The version of our code being used * Any modifications you've made relevant to the bug * Anything unusual about your environment or deployment ## Contributing via Pull Requests Contributions via pull requests are much appreciated. Before sending us a pull request, please ensure that: 1. You are working against the latest source on the *main* branch. 2. You check existing open, and recently merged, pull requests to make sure someone else hasn't addressed the problem already. 3. You open an issue to discuss any significant work - we would hate for your time to be wasted. To send us a pull request, please: 1. Fork the repository. 2. Modify the source; please focus on the specific change you are contributing. If you also reformat all the code, it will be hard for us to focus on your change. 3. Ensure local tests pass. 4. Commit to your fork using clear commit messages. 5. Send us a pull request, answering any default questions in the pull request interface. 6. Pay attention to any automated CI failures reported in the pull request, and stay involved in the conversation. GitHub provides additional document on [forking a repository](https://help.github.com/articles/fork-a-repo/) and [creating a pull request](https://help.github.com/articles/creating-a-pull-request/). ## Finding contributions to work on Looking at the existing issues is a great way to find something to contribute on. As our projects, by default, use the default GitHub issue labels (enhancement/bug/duplicate/help wanted/invalid/question/wontfix), looking at any 'help wanted' issues is a great place to start. ## Code of Conduct This project has adopted the [Amazon Open Source Code of Conduct](https://aws.github.io/code-of-conduct). For more information see the [Code of Conduct FAQ](https://aws.github.io/code-of-conduct-faq) or contact [email protected] with any additional questions or comments. ## Security issue notifications If you discover a potential security issue in this project we ask that you notify AWS/Amazon Security via our [vulnerability reporting page](http://aws.amazon.com/security/vulnerability-reporting/). Please do **not** create a public github issue. ## Licensing See the [LICENSE](LICENSE) file for our project's licensing. We will ask you to confirm the licensing of your contribution.
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/cdk.json
{ "app": "npx ts-node --prefer-ts-exts bin/omni-app.ts", "watch": { "include": [ "**" ], "exclude": [ "README.md", "cdk*.json", "**/*.d.ts", "**/*.js", "tsconfig.json", "package*.json", "yarn.lock", "node_modules", "test" ] }, "context": { "@aws-cdk/aws-apigateway:usagePlanKeyOrderInsensitiveId": true, "@aws-cdk/core:stackRelativeExports": true, "@aws-cdk/aws-rds:lowercaseDbIdentifier": true, "@aws-cdk/aws-lambda:recognizeVersionProps": true, "@aws-cdk/aws-cloudfront:defaultSecurityPolicyTLSv1.2_2021": true, "@aws-cdk-containers/ecs-service-extensions:enableDefaultLogDriver": true, "@aws-cdk/aws-ec2:uniqueImdsv2TemplateName": true, "@aws-cdk/core:target-partitions": [ "aws", "aws-cn" ] } }
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/jest.config.js
/* Copyright 2022 Amazon.com, Inc. or its affiliates. All Rights Reserved. SPDX-License-Identifier: LicenseRef-.amazon.com.-AmznSL-1.0 Licensed under the Amazon Software License http://aws.amazon.com/asl/ */ module.exports = { testEnvironment: 'node', roots: ['<rootDir>/test'], testMatch: ['**/*.test.ts'], transform: { '^.+\\.tsx?$': 'ts-jest' } };
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/deploy.sh
#!/bin/bash -e # Copyright 2022 Amazon.com, Inc. or its affiliates. All Rights Reserved. # SPDX-License-Identifier: LicenseRef-.amazon.com.-AmznSL-1.0 # Licensed under the Amazon Software License http://aws.amazon.com/asl/ printf "BUILDING STACK...\n" ACCOUNT_ID=$(aws sts get-caller-identity | grep -Eo '"Account"[^,]*' | grep -Eo '[^:]*$') if [ -z "$ACCOUNT_ID" ]; then printf "\n[ERROR] Failed to get AWS Account ID. Verify your shell is configured with AWS and try again." exit 1 fi printf "\nUsing AWS Account: %s\n" "$ACCOUNT_ID" if test -f ".env"; then printf "\nSourcing environment from '.env'.\n" printf "%s\n" "$(cat .env)" else printf "\n[WARNING] No .env found. Creating default .env file.\n" DEFAULT_STACK_NAME="omni-app" DEFAULT_REGION="us-west-2" touch .env echo "export APP_STACK_NAME=${DEFAULT_STACK_NAME}" >> .env echo "export AWS_DEFAULT_REGION=${DEFAULT_REGION}" >> .env fi source .env if [[ -z "${APP_STACK_NAME}" ]]; then printf "\n[ERROR] Missing Required ENV variable APP_STACK_NAME" exit 1 fi printf "\nDEPLOYING STACK...\n" cdk bootstrap && \ cdk synth && \ cdk deploy --require-approval never
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/README.md
# NVIDIA Omniverse Nucleus on Amazon EC2 NVIDIA Omniverse is a scalable, multi-GPU, real-time platform for building and operating metaverse applications, based on Pixar's Universal Scene Description (USD) and NVIDIA RTX technology. USD is a powerful, extensible 3D framework and ecosystem that enables 3D designers and developers to connect and collaborate between industry-leading 3D content creation, rendering, and simulation applications. Omniverse helps individual creators to connect and enhance their 3D artistic process, and enterprises to build and simulate large scale virtual worlds for industrial applications. With Omniverse, everyone involved in the lifecycle of 3D data has access to high-quality visualizations, authoring, and review tools. Teams do not need additional overhead to manage complex 3D data pipelines. Instead, they can focus on their unique contributions to bring value to the market. Non-technical stakeholders do not need to subject themselves to applications with steep learning curves, nor do results need to be compromised for the sake of iteration reviews. To support distributed Omniverse users, Nucleus should be deployed in a secure environment. With on-demand compute, storage, and networking resources, AWS infrastructure is well suited to all spatial computing workloads, including Omniverse Nucleus. This repository provides the steps and infrastructure for an Omniverse Enterprise Nucleus Server deployment on Amazon EC2. ## Contents * [Prerequisites](#prerequisites) * [Deployment](#deployment) * [Architecture](#architecture) * [Troubleshooting](#troubleshooting) * [Getting Help](#getting-help) * [Changelog](#changelog) * [Security](#security) * [License](#license) * [References](#references) ## Prerequisites - AWS CLI - https://docs.aws.amazon.com/cli/latest/userguide/getting-started-install.html - AWS CDK - https://docs.aws.amazon.com/cdk/v2/guide/getting_started.html#getting_started_install - Docker - https://www.docker.com/products/docker-desktop/ - Python 3.9 or greater - https://www.python.org - Access to NVIDIA Enterprise Omniverse Nucleus packages - https://docs.omniverse.nvidia.com/prod_nucleus/prod_nucleus/enterprise/installation/quick_start_tips.html - A Route53 Public Hosted Zone - https://docs.aws.amazon.com/Route53/latest/DeveloperGuide/CreatingHostedZone.html **To learn more, reference the official documentation from NVIDIA:** https://docs.omniverse.nvidia.com/prod_nucleus/prod_nucleus/enterprise/cloud_aws_ec2.html ## Architecture ![architecture](/diagrams/architecture.png) ## Deployment ### 1. Download Nucleus Deployment Artifacts from NVIDIA Place them in `./src/tools/nucleusServer/stack` For example: `./src/tools/nucleusServer/stack/nucleus-stack-2022.1.0+tag-2022.1.0.gitlab.3983146.613004ac.tar.gz` Consult NVIDIA documentation to find the appropriate packages. > Note This deployment has a templated copy of `nucleus-stack.env` located at `./src/tools/nucleusServer/templates/nucleus-stack.env` this may need to be updated if NVIDIA makes changes to the `nucleus-stack.env` file packaged with their archive. > > The same applies to NVIDIA's reverse proxy `nginx.conf` located at `./src/tools/reverseProxy/templates/nginx.conf` ### 2. configure .env file create ./.env Set the following variables ``` export APP_STACK_NAME=omni-app export AWS_DEFAULT_REGION=us-west-2 # STACK INPUTS export OMNIVERSE_ARTIFACTS_BUCKETNAME=example-bucket-name export ROOT_DOMAIN=example-domain.com export NUCLEUS_SERVER_PREFIX=nucleus export NUCLEUS_BUILD=nucleus-stack-2022.1.0+tag-2022.1.0.gitlab.3983146.613004ac # from Step 1 export ALLOWED_CIDR_RANGE_01=cidr-range-with-public-access export DEV_MODE=true ``` > NOTE: This deployment assumes you have a public hosted zone in Route53 for the ROOT_DOMAIN, this deployment will add a CNAME record to that hosted zone ### 3. Run the deployment The following script will run cdk deploy. The calling process must be authenticated with sufficient permissions to deploy AWS resources. ``` chmod +x ./deploy.sh ./deploy.sh ``` > NOTE: deployment requires a running docker session for building Python Lambda functions > NOTE: It can take a few minutes for the instances to get up and running. After the deployment script finishes, review your EC2 instances and check that they are in a running state. ### 4. Test the connection Test a connection to `<NUCLEUS_SERVER_PREFIX>.<ROOT_DOMAIN>` from within the ALLOWED_CIDR_RANGE set in the `.env` file. Do so by browsing to `https://<NUCLUES_SERVER_PREFIX>.<ROOT_DOMAIN>` in your web browser. The default admin username for the Nucleus server is 'omniverse'. You can find the password in a Secrets Manager resource via the AWS Secrets Manager Console. Alternatively, from the Omniverse WebUI, you can create a new username and password. ## Troubleshooting ### Unable to connect to the Nucleus Server If you are not able to connect to to the Nucleus server, review the status of the Nginx service, and the Nucleus docker stack. To do so, connect to your instances from the EC2 Console via Session Manager - https://docs.aws.amazon.com/AWSEC2/latest/UserGuide/session-manager.html. - On the Nginx Server, run `sudo journalctl -u nginx.service`, if this is produces no output the Nginx service is not running. - On the Nucleus server, run `sudo docker ps`, you should see a list of Nucleus containers up. If there are issues with either of these, it is likely there was an issue with the Lambda and/or SSM run commands that configure the instances. Browse to the Lambda Console (https://us-west-2.console.aws.amazon.com/lambda/home?region=us-west-2#/functions) and search for the respective Lambda Functions: - STACK_NAME-ReverseProxyConfig-CustomResource - STACK_NAME-NucleusServerConfig-CustomResource Review the function CloudWatch Logs. ​ ### No service log entries, or unable to restart nitro-enclave service If there are issues with either of these, it is likely there was an issue with the Lambda and/or SSM run commands that configure the instances. Browse to the Lambda Console and search for the `STACK_NAME-ReverseProxyConfig-CustomResource` Lambda Function, then review the CloudWatch Logs. At times the Reverse Proxy custom resource Lambda function does not trigger on a initial stack deployment. If the reverse proxy instance is in a running state, but there are now invocations/logs, terminate the instance and give the auto scaling group a few minutes to create another one, and then try again. Afterwards, check the CloudWatch Logs for the Lambda function: `ReverseProxyAutoScalingLifecycleLambdaFunction` ### Additional Nginx Commands View Nitro Enclaves Service Logs: `sudo journalctl -u nginx.service` Viewing Nginx Logs `sudo cat /var/log/nginx/error.log` `sudo cat /var/log/nginx/access.log` Restart Nginx `systemctl restart nginx.service` ### Additional Nucleus server notes Review NVIDIA's Documentation - https://docs.omniverse.nvidia.com/prod_nucleus/prod_nucleus/enterprise/installation/quick_start_tips.html default base stack and config location: `/opt/ove/` default omniverse data dir: `/var/lib/omni/nucleus-data` Interacting with the Nucleus Server docker compose stack: `sudo docker-compose --env-file ./nucleus-stack.env -f ./nucleus-stack-ssl.yml pull` `sudo docker-compose --env-file ./nucleus-stack.env -f ./nucleus-stack-ssl.yml up -d` `sudo docker-compose --env-file ./nucleus-stack.env -f ./nucleus-stack-ssl.yml down` `sudo docker-compose --env-file ./nucleus-stack.env -f ./nucleus-stack-ssl.yml ps` Generate new secrets `sudo rm -fr secrets && sudo ./generate-sample-insecure-secrets.sh` ## Getting Help If you have questions as you explore this sample project, post them to the Issues section of this repository. To report bugs, request new features, or contribute to this open source project, see [CONTRIBUTING.md](./CONTRIBUTING.md). ## Changelog To view the history and recent changes to this repository, see [CHANGELOG.md](./CHANGELOG.md) ## Security See [CONTRIBUTING](./CONTRIBUTING.md) for more information. ## License This sample code is licensed under the MIT-0 License. See the [LICENSE](./LICENSE) file. ## References ### NVIDIA Omniverse [Learn more about the NVIDIA Omniverse Platform](https://www.nvidia.com/en-us/omniverse/) ### Omniverse Nucleus [Learn more about the NVIDIA Omniverse Nucleus](https://docs.omniverse.nvidia.com/prod_nucleus/prod_nucleus/overview.html)
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/tsconfig.json
{ "compilerOptions": { "target": "ES2018", "module": "commonjs", "lib": [ "es2018" ], "declaration": true, "strict": true, "noImplicitAny": true, "strictNullChecks": true, "noImplicitThis": true, "alwaysStrict": true, "noUnusedLocals": false, "noUnusedParameters": false, "noImplicitReturns": true, "noFallthroughCasesInSwitch": false, "inlineSourceMap": true, "inlineSources": true, "experimentalDecorators": true, "strictPropertyInitialization": false, "typeRoots": [ "./node_modules/@types" ] }, "exclude": [ "node_modules", "cdk.out" ] }
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/test/omni-app.test.ts
// import * as cdk from 'aws-cdk-lib'; // import { Template } from 'aws-cdk-lib/assertions'; // import * as OmniApp from '../lib/omni-app-stack'; // example test. To run these tests, uncomment this file along with the // example resource in lib/omni-app-stack.ts test('SQS Queue Created', () => { // const app = new cdk.App(); // // WHEN // const stack = new OmniApp.OmniAppStack(app, 'MyTestStack'); // // THEN // const template = Template.fromStack(stack); // template.hasResourceProperties('AWS::SQS::Queue', { // VisibilityTimeout: 300 // }); });
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/tools/nucleusServer/setup.py
# Copyright 2022 Amazon.com, Inc. or its affiliates. All Rights Reserved. # SPDX-License-Identifier: LicenseRef-.amazon.com.-AmznSL-1.0 # Licensed under the Amazon Software License http://aws.amazon.com/asl/ from setuptools import setup with open("README.md", "r") as fh: long_description = fh.read() setup( name="Nucleus Server Tools", version="1.0", py_modules=[ 'nst' ], install_requires=[ "boto3", "python-dotenv", "Click" ], entry_points=''' [console_scripts] nst=nst_cli:main ''' )
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/tools/nucleusServer/nst_cli.py
# Copyright 2022 Amazon.com, Inc. or its affiliates. All Rights Reserved. # SPDX-License-Identifier: LicenseRef-.amazon.com.-AmznSL-1.0 # Licensed under the Amazon Software License http://aws.amazon.com/asl/ # Copyright 2022 Amazon.com, Inc. or its affiliates. All Rights Reserved. # SPDX-License-Identifier: LicenseRef-.amazon.com.-AmznSL-1.0 # Licensed under the Amazon Software License http://aws.amazon.com/asl/ """ helper tools for omniverse nucleus deployment configuration """ # std lib modules import os import logging from pathlib import Path # 3rd party modules import click import nst.logger as logger pass_config = click.make_pass_decorator(object, ensure=True) @click.group() @pass_config def main(config): pass @main.command() @pass_config @click.option("--my_opt_arg") def hello_world(config, my_opt_arg): logger.info(f"Hello World: {my_opt_arg=}") @main.command() @pass_config @click.option("--server-ip", required=True) @click.option("--reverse-proxy-domain", required=True) @click.option("--instance-name", required=True) @click.option("--master-password", required=True) @click.option("--service-password", required=True) @click.option("--data-root", required=True) def generate_nucleus_stack_env( config, server_ip, reverse_proxy_domain, instance_name, master_password, service_password, data_root, ): logger.info( f"generate_nucleus_stack_env:{server_ip=},{reverse_proxy_domain=},{instance_name=},{master_password=},{service_password=},{data_root=}" ) tools_path = "/".join(list(Path(__file__).parts[:-1])) cur_dir_path = "." template_name = "nucleus-stack.env" template_path = f"{tools_path}/templates/{template_name}" output_path = f"{cur_dir_path}/{template_name}" if not Path(template_path).is_file(): raise Exception("File not found: {template_path}") data = "" with open(template_path, "r") as file: data = file.read() data = data.format( SERVER_IP_OR_HOST=server_ip, REVERSE_PROXY_DOMAIN=reverse_proxy_domain, INSTANCE_NAME=instance_name, MASTER_PASSWORD=master_password, SERVICE_PASSWORD=service_password, DATA_ROOT=data_root, ACCEPT_EULA="1", SECURITY_REVIEWED="1", ) with open(f"{output_path}", "w") as file: file.write(data) logger.info(output_path)
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/tools/nucleusServer/requirements.txt
-e .
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/tools/nucleusServer/README.md
# Tools for configuring Nuclues Server The contents of this directory are zipped and then deployed to the nuclues server
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/tools/nucleusServer/nst/__init__.py
# Copyright 2022 Amazon.com, Inc. or its affiliates. All Rights Reserved. # SPDX-License-Identifier: LicenseRef-.amazon.com.-AmznSL-1.0 # Licensed under the Amazon Software License http://aws.amazon.com/asl/
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/tools/nucleusServer/nst/logger.py
# Copyright 2022 Amazon.com, Inc. or its affiliates. All Rights Reserved. # SPDX-License-Identifier: LicenseRef-.amazon.com.-AmznSL-1.0 # Licensed under the Amazon Software License http://aws.amazon.com/asl/ import os import logging LOG_LEVEL = os.getenv('LOG_LEVEL', 'DEBUG') logger = logging.getLogger() logger.setLevel(LOG_LEVEL) def info(*args): print(*args) def debug(*args): print(*args) def warning(*args): print(*args) def error(*args): print(*args)
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/tools/reverseProxy/rpt_cli.py
# Copyright 2022 Amazon.com, Inc. or its affiliates. All Rights Reserved. # SPDX-License-Identifier: LicenseRef-.amazon.com.-AmznSL-1.0 # Licensed under the Amazon Software License http://aws.amazon.com/asl/ """ helper tools for reverse proxy nginx configuration """ # std lib modules import os import logging from pathlib import Path # 3rd party modules import click import rpt.logger as logger pass_config = click.make_pass_decorator(object, ensure=True) @click.group() @pass_config def main(config): pass @main.command() @pass_config def hello_world(config): logger.info(f'Hello World') @main.command() @pass_config @click.option("--cert-arn", required=True) def generate_acm_yaml(config, cert_arn): logger.info(f'generate_acm_yaml: {cert_arn=}') tools_path = '/'.join(list(Path(__file__).parts[:-1])) cur_dir_path = '.' template_path = f'{tools_path}/templates/acm.yaml' output_path = f'{cur_dir_path}/acm.yaml' logger.info(Path(template_path).is_file()) data = '' with open(template_path, 'r') as file: data = file.read() data = data.format(cert_arn=cert_arn) with open(f'{output_path}', 'w') as file: file.write(data) logger.info(output_path) @main.command() @pass_config @click.option("--domain", required=True) @click.option("--server-address", required=True) def generate_nginx_config(config, domain, server_address): logger.info(f'generate_nginx_config: {domain=}') nginx_template_path = os.path.join( os.getcwd(), 'templates', 'nginx.conf') if Path(nginx_template_path).is_file(): logger.info(f"NGINX template found at: {nginx_template_path}") else: raise Exception( f"ERROR: No NGINX template found at: {nginx_template_path}") output_path = f'/etc/nginx/nginx.conf' if Path(output_path).is_file(): logger.info(f"NGINX default configuration found at: {output_path}") else: raise Exception( f"ERROR: No NGINX default configuration found at: {output_path}. Verify NGINX installation.") data = '' with open(nginx_template_path, 'r') as file: data = file.read() data = data.format(PUBLIC_DOMAIN=domain, NUCLEUS_SERVER_DOMAIN=server_address) with open(output_path, 'w') as file: file.write(data) logger.info(output_path)
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/tools/reverseProxy/setup.py
# Copyright 2022 Amazon.com, Inc. or its affiliates. All Rights Reserved. # SPDX-License-Identifier: LicenseRef-.amazon.com.-AmznSL-1.0 # Licensed under the Amazon Software License http://aws.amazon.com/asl/ from setuptools import setup with open("README.md", "r") as fh: long_description = fh.read() setup( name="Reverse Proxy Tools", version="1.0", py_modules=["rpt"], install_requires=["boto3", "python-dotenv", "Click"], entry_points=""" [console_scripts] rpt=rpt_cli:main """, )
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/tools/reverseProxy/requirements.txt
-e .
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/tools/reverseProxy/README.md
# Tools for configuring Nginx Reverse Proxy The contents of this directory are zipped and then deployed to the reverse proxy server
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/tools/reverseProxy/rpt/__init__.py
# Copyright 2022 Amazon.com, Inc. or its affiliates. All Rights Reserved. # SPDX-License-Identifier: LicenseRef-.amazon.com.-AmznSL-1.0 # Licensed under the Amazon Software License http://aws.amazon.com/asl/
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/tools/reverseProxy/rpt/logger.py
# Copyright 2022 Amazon.com, Inc. or its affiliates. All Rights Reserved. # SPDX-License-Identifier: LicenseRef-.amazon.com.-AmznSL-1.0 # Licensed under the Amazon Software License http://aws.amazon.com/asl/ import os import logging LOG_LEVEL = os.getenv('LOG_LEVEL', 'DEBUG') logger = logging.getLogger() logger.setLevel(LOG_LEVEL) def info(*args): print(*args) def debug(*args): print(*args) def warning(*args): print(*args) def error(*args): print(*args)
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/tools/reverseProxy/templates/acm.yaml
# Copyright 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved. # SPDX-License-Identifier: Apache-2.0 --- # ACM for Nitro Enclaves config. # # This is an example of setting up ACM, with Nitro Enclaves and nginx. # You can take this file and then: # - copy it to /etc/nitro_enclaves/acm.yaml; # - fill in your ACM certificate ARN in the `certificate_arn` field below; # - make sure /etc/nginx/nginx.conf is set up to: # - use the pkcs11 SSL engine, and; # - include the stanza file configured below (under `NginxStanza`) # somewhere in the nginx.conf `server` section; # - start the nitro-enclaves-acm service. # # Enclave general configuration enclave: # Number of vCPUs to be assigned to the enclave cpu_count: 2 # Memory (in MiB) to be assigned to the enclave memory_mib: 256 tokens: # A label for this PKCS#11 token - label: nginx-acm-token # Configure a managed token, sourced from an ACM certificate. source: Acm: # The certificate ARN # Note: this certificate must have been associated with the # IAM role assigned to the instance on which ACM for # Nitro Enclaves is run. certificate_arn: "{cert_arn}" target: NginxStanza: # Path to the nginx stanza to be written by the ACM service whenever # the certificate configuration changes (e.g. after a certificate renewal). # This file must be included from the main nginx config `server` section, # as it will contain the TLS nginx configuration directives. path: /etc/pki/nginx/nginx-acm.conf # Stanza file owner (i.e. the user nginx is configured to run as). user: nginx
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/lambda/customResources/reverseProxyConfig/index.py
import os import logging import json from crhelper import CfnResource import aws_utils.ssm as ssm import aws_utils.ec2 as ec2 import config.reverseProxy as config LOG_LEVEL = os.getenv("LOG_LEVEL", "DEBUG") logger = logging.getLogger() logger.setLevel(LOG_LEVEL) helper = CfnResource( json_logging=False, log_level="DEBUG", boto_level="CRITICAL" ) @helper.create def create(event, context): logger.info("Create Event: %s", json.dumps(event, indent=2)) response = update_config( event["ResourceProperties"]["STACK_NAME"], event["ResourceProperties"]["ARTIFACTS_BUCKET_NAME"], event["ResourceProperties"]["FULL_DOMAIN"], event["ResourceProperties"]["RP_AUTOSCALING_GROUP_NAME"], ) logger.info("Run Command Results: %s", json.dumps(response, indent=2)) @helper.update def update(event, context): logger.info("Update Event: %s", json.dumps(event, indent=2)) response = update_config( event["ResourceProperties"]["STACK_NAME"], event["ResourceProperties"]["ARTIFACTS_BUCKET_NAME"], event["ResourceProperties"]["FULL_DOMAIN"], event["ResourceProperties"]["RP_AUTOSCALING_GROUP_NAME"], ) logger.info("Run Command Results: %s", json.dumps(response, indent=2)) def update_config( stack_name, artifacts_bucket_name, full_domain, rp_autoscaling_group_name ): # get nucleus main instance id nucleus_instances = [] try: nucleus_instances = ec2.get_instances_by_tag( "Name", f"{stack_name}/NucleusServer") except Exception as e: raise Exception( f"Failed to get nucleus instances by name. {e}") logger.info(f"Nucleus Instances: {nucleus_instances}") # get nucleus main hostname nucleus_hostname = ec2.get_instance_private_dns_name(nucleus_instances[0]) logger.info(f"Nucleus Hostname: {nucleus_hostname}") # generate config for reverse proxy servers commands = [] try: commands = config.get_config( artifacts_bucket_name, nucleus_hostname, full_domain) logger.debug(commands) except Exception as e: raise Exception(f"Failed to get Reverse Proxy config. {e}") # get reverse proxy instance ids rp_instances = ec2.get_autoscaling_instance(rp_autoscaling_group_name) if rp_instances is None: return None logger.info(rp_instances) # run config commands response = [] for i in rp_instances: r = ssm.run_commands( i, commands, document="AWS-RunShellScript" ) response.append(r) return response @helper.delete def delete(event, context): logger.info("Delete Event: %s", json.dumps(event, indent=2)) def handler(event, context): helper(event, context)
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/lambda/customResources/reverseProxyConfig/requirements.txt
crhelper
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/lambda/customResources/nucleusServerConfig/index.py
# Copyright 2022 Amazon.com, Inc. or its affiliates. All Rights Reserved. # SPDX-License-Identifier: LicenseRef-.amazon.com.-AmznSL-1.0 # Licensed under the Amazon Software License http://aws.amazon.com/asl/ import os import logging import json from crhelper import CfnResource import aws_utils.ssm as ssm import aws_utils.sm as sm import config.nucleus as config LOG_LEVEL = os.getenv("LOG_LEVEL", "INFO") logger = logging.getLogger() logger.setLevel(LOG_LEVEL) helper = CfnResource(json_logging=False, log_level="DEBUG", boto_level="CRITICAL") @helper.create def create(event, context): logger.info("Create Event: %s", json.dumps(event, indent=2)) instanceId = event["ResourceProperties"]["instanceId"] reverseProxyDomain = event["ResourceProperties"]["reverseProxyDomain"] artifactsBucket = event["ResourceProperties"]["artifactsBucket"] nucleusBuild = event["ResourceProperties"]["nucleusBuild"] ovMainLoginSecretArn = event["ResourceProperties"]["ovMainLoginSecretArn"] ovServiceLoginSecretArn = event["ResourceProperties"]["ovServiceLoginSecretArn"] response = update_nucleus_config( instanceId, artifactsBucket, reverseProxyDomain, nucleusBuild, ovMainLoginSecretArn, ovServiceLoginSecretArn, ) logger.info("Run Command Results: %s", json.dumps(response, indent=2)) @helper.update def update(event, context): logger.info("Update Event: %s", json.dumps(event, indent=2)) instanceId = event["ResourceProperties"]["instanceId"] reverseProxyDomain = event["ResourceProperties"]["reverseProxyDomain"] artifactsBucket = event["ResourceProperties"]["artifactsBucket"] nucleusBuild = event["ResourceProperties"]["nucleusBuild"] ovMainLoginSecretArn = event["ResourceProperties"]["ovMainLoginSecretArn"] ovServiceLoginSecretArn = event["ResourceProperties"]["ovServiceLoginSecretArn"] response = update_nucleus_config( instanceId, artifactsBucket, reverseProxyDomain, nucleusBuild, ovMainLoginSecretArn, ovServiceLoginSecretArn, ) logger.info("Run Command Results: %s", json.dumps(response, indent=2)) def update_nucleus_config( instanceId, artifactsBucket, reverseProxyDomain, nucleusBuild, ovMainLoginSecretArn, ovServiceLoginSecretArn, ): ovMainLoginSecret = sm.get_secret(ovMainLoginSecretArn) ovServiceLoginSecret = sm.get_secret(ovServiceLoginSecretArn) ovMainLoginPassword = ovMainLoginSecret["password"] ovServiceLoginPassword = ovServiceLoginSecret["password"] # generate config for reverse proxy servers commands = [] try: commands = config.get_config( artifactsBucket, reverseProxyDomain, nucleusBuild, ovMainLoginPassword, ovServiceLoginPassword) logger.debug(commands) except Exception as e: raise Exception("Failed to get Reverse Proxy config. {}".format(e)) for p in commands: print(p) response = ssm.run_commands( instanceId, commands, document="AWS-RunShellScript") return response @helper.delete def delete(event, context): logger.info("Delete Event: %s", json.dumps(event, indent=2)) def handler(event, context): helper(event, context)
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/lambda/customResources/nucleusServerConfig/requirements.txt
crhelper
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/lambda/asgLifeCycleHooks/reverseProxy/index.py
# Copyright 2022 Amazon.com, Inc. or its affiliates. All Rights Reserved. # SPDX-License-Identifier: LicenseRef-.amazon.com.-AmznSL-1.0 # Licensed under the Amazon Software License http://aws.amazon.com/asl/ import boto3 import os import json import logging import traceback from botocore.exceptions import ClientError import aws_utils.ssm as ssm import aws_utils.r53 as r53 import aws_utils.ec2 as ec2 import config.reverseProxy as config logger = logging.getLogger() logger.setLevel(logging.INFO) autoscaling = boto3.client("autoscaling") ARTIFACTS_BUCKET = os.environ["ARTIFACTS_BUCKET"] NUCLEUS_ROOT_DOMAIN = os.environ["NUCLEUS_ROOT_DOMAIN"] NUCLEUS_DOMAIN_PREFIX = os.environ["NUCLEUS_DOMAIN_PREFIX"] NUCLEUS_SERVER_ADDRESS = os.environ["NUCLEUS_SERVER_ADDRESS"] def send_lifecycle_action(event, result): try: response = autoscaling.complete_lifecycle_action( LifecycleHookName=event["detail"]["LifecycleHookName"], AutoScalingGroupName=event["detail"]["AutoScalingGroupName"], LifecycleActionToken=event["detail"]["LifecycleActionToken"], LifecycleActionResult=result, InstanceId=event["detail"]["EC2InstanceId"], ) logger.info(response) except ClientError as e: message = "Error completing lifecycle action: {}".format(e) logger.error(message) raise Exception(message) return def update_nginix_config( instanceId, artifactsBucket, nucleusServerAddress, domain ): # generate config for reverse proxy servers commands = [] try: commands = config.get_config( artifactsBucket, nucleusServerAddress, domain) logger.debug(commands) except Exception as e: raise Exception("Failed to get Reverse Proxy config. {}".format(e)) response = ssm.run_commands( instanceId, commands, document="AWS-RunShellScript" ) return response def handler(event, context): logger.info("Event: %s", json.dumps(event, indent=2)) instanceId = event["detail"]["EC2InstanceId"] transition = event["detail"]["LifecycleTransition"] if transition == "autoscaling:EC2_INSTANCE_LAUNCHING": try: update_nginix_config( instanceId, ARTIFACTS_BUCKET, NUCLEUS_SERVER_ADDRESS, f"{NUCLEUS_DOMAIN_PREFIX}.{NUCLEUS_ROOT_DOMAIN}", ) send_lifecycle_action(event, "CONTINUE") except Exception as e: message = "Error running command: {}".format(e) logger.warning(traceback.format_exc()) logger.error(message) send_lifecycle_action(event, "ABANDON") elif transition == "autoscaling:EC2_INSTANCE_TERMINATING": try: send_lifecycle_action(event, "CONTINUE") except Exception as e: message = "Error running command: {}".format(e) logger.warning(traceback.format_exc()) logger.error(message) send_lifecycle_action(event, "ABANDON") logger.info("Execution Complete") return
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/lambda/common/requirements.txt
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/lambda/common/aws_utils/ec2.py
# Copyright 2022 Amazon.com, Inc. or its affiliates. All Rights Reserved. # SPDX-License-Identifier: LicenseRef-.amazon.com.-AmznSL-1.0 # Licensed under the Amazon Software License http://aws.amazon.com/asl/ import os import logging import boto3 from botocore.exceptions import ClientError LOG_LEVEL = os.getenv("LOG_LEVEL", "DEBUG") logger = logging.getLogger() logger.setLevel(LOG_LEVEL) client = boto3.client("ec2") ec2_resource = boto3.resource("ec2") autoscaling = boto3.client("autoscaling") def get_instance_public_dns_name(instanceId): instance = get_instance_description(instanceId) if instance is None: return None return instance["PublicDnsName"] def get_instance_private_dns_name(instanceId): instance = get_instance_description(instanceId) if instance is None: return None return instance["PrivateDnsName"] def get_instance_description(instanceId): response = client.describe_instances( InstanceIds=[instanceId], ) instances = response["Reservations"][0]["Instances"] if not instances: return None return instances[0] def get_instance_status(instanceId): response = client.describe_instance_status( Filters=[ { "Name": "string", "Values": [ "string", ], }, ], InstanceIds=[ "string", ], MaxResults=123, NextToken="string", DryRun=True | False, IncludeAllInstances=True | False, ) statuses = response["InstanceStatuses"][0] status = {"instanceStatus": None, "systemStatus": None} if statuses: status = { "instanceStatus": statuses["InstanceStatus"]["Status"], "systemStatus": statuses["SystemStatus"]["Status"], } return status def get_autoscaling_instance(groupName): response = autoscaling.describe_auto_scaling_groups( AutoScalingGroupNames=[groupName] ) logger.debug(response) instances = response['AutoScalingGroups'][0]["Instances"] if not instances: return None instanceIds = [] for i in instances: instanceIds.append(i["InstanceId"]) return instanceIds def update_tag_value(resourceIds: list, tagKey: str, tagValue: str): client.create_tags( Resources=resourceIds, Tags=[{ 'Key': tagKey, 'Value': tagValue }], ) def delete_tag(resourceIds: list, tagKey: str, tagValue: str): response = client.delete_tags( Resources=resourceIds, Tags=[{ 'Key': tagKey, 'Value': tagValue }], ) return response def get_instance_state(id): instance = ec2_resource.Instance(id) return instance.state['Name'] def get_instances_by_tag(tagKey, tagValue): instances = ec2_resource.instances.filter( Filters=[{'Name': 'tag:{}'.format(tagKey), 'Values': [tagValue]}]) if not instances: return None instanceIds = [] for i in instances: instanceIds.append(i.id) return instanceIds def get_instances_by_name(name): instances = get_instances_by_tag("Name", name) if not instances: logger.error(f"ERROR: Failed to get instances by tag: Name, {name}") return None return instances def get_active_instance(instances): for i in instances: instance_state = get_instance_state(i) logger.info(f"Instance: {i}. State: {instance_state}") if instance_state == "running" or instance_state == "pending": return i logger.warn(f"Instances are not active") return None def get_volumes_by_instance_id(id): instance = ec2_resource.Instance(id) volumes = instance.volumes.all() volumeIds = [] for i in volumes: volumeIds.append(i.id) return volumeIds def terminate_instances(instance_ids): response = client.terminate_instances(InstanceIds=instance_ids) logger.info(response) return response
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/lambda/common/aws_utils/ssm.py
# Copyright 2022 Amazon.com, Inc. or its affiliates. All Rights Reserved. # SPDX-License-Identifier: LicenseRef-.amazon.com.-AmznSL-1.0 # Licensed under the Amazon Software License http://aws.amazon.com/asl/ import os import time import logging import boto3 from botocore.exceptions import ClientError LOG_LEVEL = os.getenv("LOG_LEVEL", "DEBUG") logger = logging.getLogger() logger.setLevel(LOG_LEVEL) client = boto3.client("ssm") def get_param_value(name) -> str: response = client.get_parameter(Name=name) logger.info(response) return response['Parameter']['Value'] def update_param_value(name, value) -> bool: response = client.put_parameter(Name=name, Value=value, Overwrite=True) logger.info(response) try: return (response['Version'] > 0) except ClientError as e: message = "Error calling SendCommand: {}".format(e) logger.error(message) return False def run_commands( instance_id, commands, document="AWS-RunPowerShellScript", comment="aws_utils.ssm.run_commands" ): """alt document options: AWS-RunShellScript """ # Run Commands logger.info("Calling SendCommand: {} for instance: {}".format( commands, instance_id)) attempt = 0 response = None while attempt < 20: attempt = attempt + 1 try: time.sleep(10 * attempt) logger.info("SendCommand, attempt #: {}".format(attempt)) response = client.send_command( InstanceIds=[instance_id], DocumentName=document, Parameters={"commands": commands}, Comment=comment, CloudWatchOutputConfig={ "CloudWatchLogGroupName": instance_id, "CloudWatchOutputEnabled": True, }, ) logger.info(response) if "Command" in response: break if attempt == 10: message = "Command did not execute successfully in time allowed." raise Exception(message) except ClientError as e: message = "Error calling SendCommand: {}".format(e) logger.error(message) continue if not response: message = "Command did not execute successfully in time allowed." raise Exception(message) # Check Command Status command_id = response["Command"]["CommandId"] logger.info( "Calling GetCommandInvocation for command: {} for instance: {}".format( command_id, instance_id ) ) attempt = 0 result = None while attempt < 10: attempt = attempt + 1 try: time.sleep(10 * attempt) logger.info("GetCommandInvocation, attempt #: {}".format(attempt)) result = client.get_command_invocation( CommandId=command_id, InstanceId=instance_id, ) if result["Status"] == "InProgress": logger.info("Command is running.") continue elif result["Status"] == "Success": logger.info("Command Output: {}".format( result["StandardOutputContent"])) if result["StandardErrorContent"]: message = "Command returned STDERR: {}".format( result["StandardErrorContent"]) logger.warning(message) break elif result["Status"] == "Failed": message = "Error Running Command: {}".format( result["StandardErrorContent"]) logger.error(message) raise Exception(message) else: message = "Command has an unhandled status, will continue: {}".format( e) logger.warning(message) continue except client.exceptions.InvocationDoesNotExist as e: message = "Error calling GetCommandInvocation: {}".format(e) logger.error(message) raise Exception(message) if not result or result["Status"] != "Success": message = "Command did not execute successfully in time allowed." raise Exception(message) return result
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/lambda/common/aws_utils/r53.py
# Copyright 2022 Amazon.com, Inc. or its affiliates. All Rights Reserved. # SPDX-License-Identifier: LicenseRef-.amazon.com.-AmznSL-1.0 # Licensed under the Amazon Software License http://aws.amazon.com/asl/ import boto3 client = boto3.client("route53") def update_hosted_zone_cname_record(hostedZoneID, rootDomain, domainPrefix, serverAddress): fqdn = f"{domainPrefix}.{rootDomain}" response = client.change_resource_record_sets( HostedZoneId=hostedZoneID, ChangeBatch={ "Comment": "Updating {fqdn}->{serverAddress} CNAME record", "Changes": [ { "Action": "UPSERT", "ResourceRecordSet": { "Name": fqdn, "Type": "CNAME", "TTL": 300, "ResourceRecords": [{"Value": serverAddress}], }, } ], }, ) return response def delete_hosted_zone_cname_record(hostedZoneID, rootDomain, domainPrefix, serverAddress): response = client.change_resource_record_sets( HostedZoneId=hostedZoneID, ChangeBatch={ "Comment": "string", "Changes": [ { "Action": "DELETE", "ResourceRecordSet": { "Name": f"{domainPrefix}.{rootDomain}", "Type": "CNAME", "ResourceRecords": [{"Value": serverAddress}], }, } ], }, ) # botocore.errorfactory.InvalidInput: An error occurred (InvalidInput) when calling the ChangeResourceRecordSets operation: Invalid request: # Expected exactly one of [AliasTarget, all of [TTL, and ResourceRecords], or TrafficPolicyInstanceId], but found none in Change with # [Action=DELETE, Name=nucleus-dev.awsps.myinstance.com, Type=CNAME, SetIdentifier=null] return response
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/lambda/common/aws_utils/__init__.py
# Copyright 2022 Amazon.com, Inc. or its affiliates. All Rights Reserved. # SPDX-License-Identifier: LicenseRef-.amazon.com.-AmznSL-1.0 # Licensed under the Amazon Software License http://aws.amazon.com/asl/
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/lambda/common/aws_utils/sm.py
# Copyright 2022 Amazon.com, Inc. or its affiliates. All Rights Reserved. # SPDX-License-Identifier: LicenseRef-.amazon.com.-AmznSL-1.0 # Licensed under the Amazon Software License http://aws.amazon.com/asl/ import json import boto3 SM = boto3.client("secretsmanager") def get_secret(secret_name): response = SM.get_secret_value(SecretId=secret_name) secret = json.loads(response["SecretString"]) return secret
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/lambda/common/config/nucleus.py
def start_nucleus_config() -> list[str]: return ''' cd /opt/ove/base_stack || exit 1 echo "STARTING NUCLEUS STACK ----------------------------------" docker-compose --env-file nucleus-stack.env -f nucleus-stack-ssl.yml start '''.splitlines() def stop_nucleus_config() -> list[str]: return ''' cd /opt/ove/base_stack || exit 1 echo "STOPPING NUCLEUS STACK ----------------------------------" docker-compose --env-file nucleus-stack.env -f nucleus-stack-ssl.yml stop '''.splitlines() def restart_nucleus_config() -> list[str]: return ''' cd /opt/ove/base_stack || exit 1 echo "RESTARTING NUCLEUS STACK ----------------------------------" docker-compose --env-file nucleus-stack.env -f nucleus-stack-ssl.yml restart '''.splitlines() def get_config(artifacts_bucket_name: str, full_domain: str, nucleus_build: str, ov_main_password: str, ov_service_password: str) -> list[str]: return f''' echo "------------------------ NUCLEUS SERVER CONFIG ------------------------" echo "UPDATING AND INSTALLING DEPS ----------------------------------" sudo apt-get update -y -q && sudo apt-get upgrade -y sudo apt-get install dialog apt-utils -y echo "INSTALLING AWS CLI ----------------------------------" sudo curl "https://awscli.amazonaws.com/awscli-exe-linux-x86_64.zip" -o "awscliv2.zip" sudo apt-get install unzip sudo unzip awscliv2.zip sudo ./aws/install sudo rm awscliv2.zip sudo rm -fr ./aws/install echo "INSTALLING PYTHON ----------------------------------" sudo apt-get -y install python3.9 sudo curl https://bootstrap.pypa.io/get-pip.py -o get-pip.py sudo python3.9 get-pip.py sudo pip3 install --upgrade pip sudo pip3 --version echo "INSTALLING DOCKER ----------------------------------" sudo apt-get remove docker docker-engine docker.io containerd runc sudo apt-get -y install apt-transport-https ca-certificates curl gnupg-agent software-properties-common curl -fsSL https://download.docker.com/linux/ubuntu/gpg | sudo apt-key add - sudo add-apt-repository "deb [arch=amd64] https://download.docker.com/linux/ubuntu $(lsb_release -cs) stable" sudo apt-get -y update sudo apt-get -y install docker-ce docker-ce-cli containerd.io sudo systemctl enable --now docker echo "INSTALLING DOCKER COMPOSE ----------------------------------" sudo curl -L "https://github.com/docker/compose/releases/download/1.29.2/docker-compose-$(uname -s)-$(uname -m)" -o /usr/local/bin/docker-compose sudo chmod +x /usr/local/bin/docker-compose echo "INSTALLING NUCLEUS TOOLS ----------------------------------" sudo mkdir -p /opt/ove cd /opt/ove || exit 1 aws s3 cp --recursive s3://{artifacts_bucket_name}/tools/nucleusServer/ ./nucleusServer cd nucleusServer || exit 1 sudo pip3 install -r requirements.txt echo "UNPACKAGING NUCLEUS STACK ----------------------------------" sudo tar xzvf stack/{nucleus_build}.tar.gz -C /opt/ove --strip-components=1 cd /opt/ove/base_stack || exit 1 omniverse_data_path=/var/lib/omni/nucleus-data nucleusHost=$(curl -s http://169.254.169.254/latest/meta-data/hostname) sudo nst generate-nucleus-stack-env --server-ip $nucleusHost --reverse-proxy-domain {full_domain} --instance-name nucleus_server --master-password {ov_main_password} --service-password {ov_service_password} --data-root $omniverse_data_path chmod +x ./generate-sample-insecure-secrets.sh ./generate-sample-insecure-secrets.sh echo "PULLING NUCLEUS IMAGES ----------------------------------" docker-compose --env-file nucleus-stack.env -f nucleus-stack-ssl.yml pull echo "STARTING NUCLEUS STACK ----------------------------------" docker-compose --env-file nucleus-stack.env -f nucleus-stack-ssl.yml up -d docker-compose --env-file nucleus-stack.env -f nucleus-stack-ssl.yml ps -a '''.splitlines()
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/src/lambda/common/config/reverseProxy.py
def get_config(artifacts_bucket_name: str, nucleus_address: str, full_domain: str) -> list[str]: return f''' echo "------------------------ REVERSE PROXY CONFIG ------------------------" echo "UPDATING PACKAGES ----------------------------------" sudo yum update -y echo "INSTALLING DEPENDENCIES ----------------------------------" sudo yum install -y aws-cfn-bootstrap gcc openssl-devel bzip2-devel libffi-devel zlib-devel echo "INSTALLING NGINX ----------------------------------" sudo yum install -y amazon-linux-extras sudo amazon-linux-extras enable nginx1 sudo yum install -y nginx sudo nginx -v echo "INSTALLING PYTHON ----------------------------------" sudo wget https://www.python.org/ftp/python/3.9.9/Python-3.9.9.tgz -P /opt/python3.9 cd /opt/python3.9 || exit 1 sudo tar xzf Python-3.9.9.tgz cd Python-3.9.9 || exit 1 sudo ./configure --prefix=/usr --enable-optimizations sudo make install echo "------------------------ REVERSE PROXY CONFIG ------------------------" echo "INSTALLING REVERSE PROXY TOOLS ----------------------------------" cd /opt || exit 1 sudo aws s3 cp --recursive s3://{artifacts_bucket_name}/tools/reverseProxy/ ./reverseProxy cd reverseProxy || exit 1 pip3 --version sudo pip3 install -r requirements.txt sudo rpt generate-nginx-config --domain {full_domain} --server-address {nucleus_address} echo "STARTING NGINX ----------------------------------" sudo service nginx restart '''.splitlines()
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/bin/omni-app.ts
#!/usr/bin/env node import 'source-map-support/register'; import * as cdk from 'aws-cdk-lib'; import { AppStack } from '../lib/omni-app-stack'; import { NagSuppressions } from 'cdk-nag'; import { cleanEnv, makeValidator, str, bool, host } from 'envalid'; import { regions } from '../lib/utils/regions'; import * as dotenv from 'dotenv'; dotenv.config(); const stackname = makeValidator((x) => { if (/^[A-Za-z][A-Za-z-0-9]{0,126}[A-Za-z0-9]$/.test(x)) return x; else throw new Error( `Invalid Stack name: ${x}. Can contain only alphanumeric characters (case-sensitive) and hyphens. It must start with an alphabetic character and can't be longer than 128 characters.` ); }); const bucketname = makeValidator((x) => { if (/(?!(^xn--|-s3alias$))^[a-z0-9][a-z0-9-]{1,61}[a-z0-9]$/.test(x)) return x; else throw new Error( `Invalid Bucket name: ${x}. Can contain only lowercase alphanumeric characters and hyphens. It must start with an alphabetic character and must be between 3 and 63 characters characters.` ); }); const domainprefix = makeValidator((x) => { if (/^[A-Za-z][A-Za-z-0-9]{0,126}[A-Za-z0-9]$/.test(x)) return x; else throw new Error( `Invalid Domain Prefix: ${x}. Can contain only alphanumeric characters (case-sensitive) and hyphens. It must start with an alphabetic character and can't be longer than 128 characters.` ); }); const cidrrange = makeValidator((x) => { if (/^([0-9]{1,3}\.){3}[0-9]{1,3}(\/([0-9]|[1-2][0-9]|3[0-2]))?$/.test(x)) return x; else throw new Error(`Invalid CIDR Range: ${x}`); }); const env = cleanEnv(process.env, { APP_STACK_NAME: stackname({ default: 'omni-app' }), DEV_MODE: bool({ default: false }), AWS_DEFAULT_REGION: str({ choices: regions }), OMNIVERSE_ARTIFACTS_BUCKETNAME: bucketname(), ROOT_DOMAIN: host(), NUCLEUS_SERVER_PREFIX: domainprefix(), NUCLEUS_BUILD: str({ default: 'nucleus-stack-2022.1.0+tag-2022.1.0.gitlab.3983146.613004ac' }), ALLOWED_CIDR_RANGE_01: cidrrange(), ALLOWED_CIDR_RANGE_02: cidrrange({ default: '' }), ALLOWED_CIDR_RANGE_03: cidrrange({ default: '' }) }); // console.log(env); let stackName = env.APP_STACK_NAME; if (env.DEV_MODE) { stackName += "-dev"; } const app = new cdk.App(); const stack = new AppStack(app, stackName, { /* If you don't specify 'env', this stack will be environment-agnostic. * Account/Region-dependent features and context lookups will not work, * but a single synthesized template can be deployed anywhere. */ /* Uncomment the next line to specialize this stack for the AWS Account * and Region that are implied by the current CLI configuration. */ env: { account: process.env.CDK_DEFAULT_ACCOUNT, region: process.env.CDK_DEFAULT_REGION } /* Uncomment the next line if you know exactly what Account and Region you * want to deploy the stack to. */ // env: { account: '123456789012', region: 'us-east-1' }, /* For more information, see https://docs.aws.amazon.com/cdk/latest/guide/environments.html */ }); // Uncomment for security review // cdk.Aspects.of(app).add(new AwsSolutionsChecks({ verbose: true })); NagSuppressions.addStackSuppressions(stack, [ { id: 'AwsSolutions-IAM4', reason: 'Auto-generated resource with managed policy', appliesTo: ['Policy::arn:<AWS::Partition>:iam::aws:policy/service-role/AWSLambdaBasicExecutionRole'] }, { id: 'AwsSolutions-IAM4', reason: 'Internal Config rule requires AmazonSSMManagedInstanceCore be added to instances', appliesTo: ['Policy::arn:<AWS::Partition>:iam::aws:policy/AmazonSSMManagedInstanceCore'] } ]);
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/lib/omni-app-stack.ts
import { Stack, StackProps } from 'aws-cdk-lib'; import { Construct } from 'constructs'; import { RevProxyResources } from './constructs/reverseProxy'; import { NucleusServerResources } from './constructs/nucleusServer'; import { VpcResources } from './constructs/vpc'; import { RemovalPolicy } from 'aws-cdk-lib'; import { NagSuppressions } from 'cdk-nag'; import { cleanEnv, str, bool } from 'envalid'; import * as lambda from 'aws-cdk-lib/aws-lambda'; import * as pyLambda from '@aws-cdk/aws-lambda-python-alpha'; import * as dotenv from 'dotenv'; import { StorageResources } from './constructs/storageResources'; import { LoadBalancerConstruct } from './constructs/loadBalancer'; import { Route53Resources } from './constructs/route53'; dotenv.config(); const env = cleanEnv(process.env, { DEV_MODE: bool({ default: false }), OMNIVERSE_ARTIFACTS_BUCKETNAME: str({ default: '' }), ROOT_DOMAIN: str({ default: '' }), NUCLEUS_SERVER_PREFIX: str({ default: '' }) }); export class AppStack extends Stack { constructor(scope: Construct, id: string, props?: StackProps) { super(scope, id, props); const stackName: string = Stack.of(this).stackName; const region: string = Stack.of(this).region; var removalPolicy = RemovalPolicy.RETAIN; var autoDelete = false; if (env.DEV_MODE == true) { removalPolicy = RemovalPolicy.DESTROY; autoDelete = true; } const { artifactsBucket } = new StorageResources(this, "StorageResources", { bucketName: env.OMNIVERSE_ARTIFACTS_BUCKETNAME, autoDelete: autoDelete, removalPolicy: removalPolicy }); const { certificate, hostedZone } = new Route53Resources(this, 'Route53Resources', { rootDomain: env.ROOT_DOMAIN, }); const commonUtilsLambdaLayer = new pyLambda.PythonLayerVersion(this, 'CommonUtilsLayer', { entry: 'src/lambda/common', compatibleRuntimes: [lambda.Runtime.PYTHON_3_9], description: 'Data Model Schema Layer', layerVersionName: 'common_utils_layer', }); const vpcResources = new VpcResources(this, 'VpcResources', { removalPolicy: removalPolicy, }); const nucleusServerResources = new NucleusServerResources(this, 'NucleusServerResources', { removalPolicy: removalPolicy, vpc: vpcResources.vpc, subnets: vpcResources.subnets.nucleus, artifactsBucket: artifactsBucket, nucleusServerSG: vpcResources.securityGroups.nucleus, lambdaLayers: [commonUtilsLambdaLayer], }); const reverseProxyResources = new RevProxyResources(this, 'RevProxyResources', { removalPolicy: removalPolicy, artifactsBucket: artifactsBucket, vpc: vpcResources.vpc, subnets: vpcResources.subnets.reverseProxy, securityGroup: vpcResources.securityGroups.reverseProxy, lambdaLayers: [commonUtilsLambdaLayer], nucleusServerInstance: nucleusServerResources.nucleusServerInstance, }); reverseProxyResources.node.addDependency(nucleusServerResources); new LoadBalancerConstruct(this, 'LoadBalancerConstruct', { removalPolicy: removalPolicy, autoDelete: autoDelete, vpc: vpcResources.vpc, subnets: vpcResources.subnets.loadBalancer, securityGroup: vpcResources.securityGroups.loadBalancer, domainPrefix: env.NUCLEUS_SERVER_PREFIX, rootDomain: env.ROOT_DOMAIN, certificate: certificate, hostedZone: hostedZone, autoScalingGroup: reverseProxyResources.autoScalingGroup, }); // ------------------------------- // NagSuppressions // ------------------------------- for (let i = 0; i < this.node.children.length; i++) { const child = this.node.children[i]; if (child.constructor.name === 'LogRetentionFunction') { NagSuppressions.addResourceSuppressionsByPath( this, `/${stackName}/${child.node.id}/ServiceRole/DefaultPolicy/Resource`, [{ id: 'AwsSolutions-IAM5', reason: 'Auto-generated resource with wildcard policy' }] ); } } } }
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/lib/constructs/storageResources.ts
import { Fn, Stack } from 'aws-cdk-lib'; import { Construct } from 'constructs'; import { RemovalPolicy, CfnOutput } from 'aws-cdk-lib'; import * as s3 from 'aws-cdk-lib/aws-s3'; import * as deployment from 'aws-cdk-lib/aws-s3-deployment'; import * as path from 'path'; export interface StorageResourcesProps { removalPolicy: RemovalPolicy, autoDelete: boolean; bucketName?: string; }; export class StorageResources extends Construct { public readonly artifactsBucket: s3.Bucket; constructor(scope: Construct, id: string, props: StorageResourcesProps) { super(scope, id); const bucketName = props.bucketName ?? `${Stack.of(this).stackName}-omniverse-nucleus-artifacts-bucket`; const sourceBucket = new s3.Bucket(this, 'ArtifactsBucket', { bucketName: bucketName, autoDeleteObjects: props.autoDelete, removalPolicy: props.removalPolicy, }); const artifactsDeployment = new deployment.BucketDeployment(this, "ArtifactsDeployment", { sources: [deployment.Source.asset(path.join(__dirname, "..", "..", "src", "tools"))], destinationBucket: sourceBucket, destinationKeyPrefix: "tools", extract: true, exclude: ["*.DS_Store"] }); this.artifactsBucket = artifactsDeployment.deployedBucket as s3.Bucket; /** * CFN Outputs */ new CfnOutput(this, "ArtifactsBucketName", { value: this.artifactsBucket.bucketName, }).overrideLogicalId("ArtifactsBucketName"); new CfnOutput(this, "DeployedObjectKeys", { value: Fn.select(0, artifactsDeployment.objectKeys) }); } }
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/lib/constructs/reverseProxy.ts
import { Construct } from 'constructs'; import { Stack, RemovalPolicy, Tags } from 'aws-cdk-lib'; import { NagSuppressions } from 'cdk-nag'; import { CustomResource } from './common/customResource'; import { cleanEnv, str } from 'envalid'; import { AutoScalingResources } from './autoscaling'; import * as iam from 'aws-cdk-lib/aws-iam'; import * as s3 from 'aws-cdk-lib/aws-s3'; import * as ec2 from 'aws-cdk-lib/aws-ec2'; import * as pyLambda from '@aws-cdk/aws-lambda-python-alpha'; import * as dotenv from 'dotenv'; import * as asg from 'aws-cdk-lib/aws-autoscaling'; dotenv.config(); const env = cleanEnv(process.env, { ROOT_DOMAIN: str({ default: '' }), NUCLEUS_SERVER_PREFIX: str({ default: 'nucleus' }), }); export type ConstructProps = { removalPolicy: RemovalPolicy; artifactsBucket: s3.IBucket; vpc: ec2.Vpc; subnets: ec2.ISubnet[]; securityGroup: ec2.SecurityGroup; lambdaLayers: pyLambda.PythonLayerVersion[]; nucleusServerInstance: ec2.Instance; }; export class RevProxyResources extends Construct { public readonly autoScalingGroup: asg.AutoScalingGroup; constructor(scope: Construct, id: string, props: ConstructProps) { super(scope, id); const region: string = Stack.of(this).region; const account: string = Stack.of(this).account; const stackName: string = Stack.of(this).stackName; const instanceRole = new iam.Role(this, 'ReverseProxyInstanceRole', { assumedBy: new iam.ServicePrincipal('ec2.amazonaws.com'), description: 'EC2 Instance Role', managedPolicies: [iam.ManagedPolicy.fromAwsManagedPolicyName('AmazonSSMManagedInstanceCore')], inlinePolicies: { reverseProxyInstancePolicy: new iam.PolicyDocument({ statements: [ new iam.PolicyStatement({ resources: [ `${props.artifactsBucket.bucketArn}`, `${props.artifactsBucket.bucketArn}/*`, ], actions: ['s3:ListBucket', 's3:GetObject'], }), new iam.PolicyStatement({ actions: [ 'logs:CreateLogGroup', 'logs:CreateLogStream', 'logs:DescribeLogStreams', 'logs:PutLogEvents', ], resources: [`arn:aws:logs:${region}:${account}:log-group:/aws/ssm/*`], }), ], }), } }); const ebsVolume: ec2.BlockDevice = { deviceName: '/dev/xvda', volume: ec2.BlockDeviceVolume.ebs(8, { encrypted: true, }), }; // -------------------------------------------------------------------- // AUTO SCALING RESOURCES // -------------------------------------------------------------------- const launchTemplate = new ec2.LaunchTemplate(this, 'launchTemplate', { launchTemplateName: 'NginxReverseProxy', instanceType: new ec2.InstanceType('t3.medium'), machineImage: ec2.MachineImage.latestAmazonLinux({ generation: ec2.AmazonLinuxGeneration.AMAZON_LINUX_2 }), blockDevices: [ebsVolume], role: instanceRole, securityGroup: props.securityGroup, detailedMonitoring: true, userData: ec2.UserData.forLinux() }); Tags.of(launchTemplate).add('Name', `${stackName}/ReverseProxyServer`); const reverseProxyConfigPolicy = new iam.PolicyDocument({ statements: [ new iam.PolicyStatement({ actions: ['ssm:GetCommandInvocation'], resources: [`arn:aws:ssm:${region}:${account}:*`], }), new iam.PolicyStatement({ actions: ['ssm:SendCommand'], resources: [`arn:aws:ssm:*:*:document/*`, `arn:aws:ec2:${region}:${account}:instance/*`], }), new iam.PolicyStatement({ actions: ['ssm:GetParameters', 'ssm:GetParameter', 'ssm:GetParametersByPath'], resources: [`arn:aws:ssm:${region}:${account}:parameter/*`], }), new iam.PolicyStatement({ actions: ['ec2:DescribeTags', 'ec2:CreateTags', 'ec2:DeleteTags'], resources: ['*'], }), new iam.PolicyStatement({ actions: ['ec2:DescribeInstances', 'ec2:DescribeInstanceStatus'], resources: ['*'], }), ], }); const autoScalingResources = new AutoScalingResources( this, 'ReverseProxyAutoScalingResources', { name: 'ReverseProxy', removalPolicy: props.removalPolicy, artifactsBucket: props.artifactsBucket, vpcResources: { vpc: props.vpc, subnets: props.subnets, }, launchTemplate: launchTemplate, capacity: { min: 1, max: 1, }, lambdaResources: { entry: './src/lambda/asgLifeCycleHooks/reverseProxy', layers: props.lambdaLayers, environment: { ARTIFACTS_BUCKET: props.artifactsBucket.bucketName, NUCLEUS_ROOT_DOMAIN: env.ROOT_DOMAIN, NUCLEUS_DOMAIN_PREFIX: env.NUCLEUS_SERVER_PREFIX, NUCLEUS_SERVER_ADDRESS: props.nucleusServerInstance.instancePrivateDnsName, }, policies: { reverseProxyConfigPolicy: reverseProxyConfigPolicy, }, }, } ); autoScalingResources.autoScalingGroup.scaleOnCpuUtilization('ReverseProxyScalingPolicy', { targetUtilizationPercent: 75, }); this.autoScalingGroup = autoScalingResources.autoScalingGroup; // -------------------------------------------------------------------- // CUSTOM RESOURCE - Reverse Proxy Configuration // -------------------------------------------------------------------- const reverseProxyConfigLambdaPolicy = new iam.PolicyDocument({ statements: [ new iam.PolicyStatement({ actions: ['ssm:SendCommand'], resources: [`arn:aws:ec2:${region}:${account}:instance/*`], }), new iam.PolicyStatement({ actions: ['ssm:SendCommand'], resources: ['arn:aws:ssm:*:*:document/*'], }), new iam.PolicyStatement({ actions: ['ssm:GetCommandInvocation'], resources: [`arn:aws:ssm:${region}:${account}:*`], }), new iam.PolicyStatement({ actions: ['ssm:GetParameters', 'ssm:GetParameter', 'ssm:GetParametersByPath'], resources: [`arn:aws:ssm:${region}:${account}:parameter/*`], }), new iam.PolicyStatement({ actions: ['ec2:DescribeInstances'], resources: ['*'], }), new iam.PolicyStatement({ actions: ['autoscaling:DescribeAutoScalingGroups'], resources: ['*'], }), new iam.PolicyStatement({ actions: ['ec2:DescribeTags', 'ec2:CreateTags'], resources: ['*'], }), ], }); const reverseProxyConfig = new CustomResource(this, 'ReverseProxyCustomResource', { lambdaName: 'ReverseProxyConfig', lambdaCodePath: './src/lambda/customResources/reverseProxyConfig', lambdaPolicyDocument: reverseProxyConfigLambdaPolicy, lambdaLayers: props.lambdaLayers, removalPolicy: props.removalPolicy, resourceProps: { nounce: 2, STACK_NAME: stackName, ARTIFACTS_BUCKET_NAME: props.artifactsBucket.bucketName, FULL_DOMAIN: `${env.NUCLEUS_SERVER_PREFIX}.${env.ROOT_DOMAIN}`, RP_AUTOSCALING_GROUP_NAME: autoScalingResources.autoScalingGroup.autoScalingGroupName, }, }); reverseProxyConfig.node.addDependency(this.autoScalingGroup); // ------------------------------------ // CDK_NAG suppressions // ------------------------------------ NagSuppressions.addResourceSuppressions( instanceRole, [ { id: 'AwsSolutions-IAM5', reason: 'Wildcard Permissions: Unable to know which objects exist ahead of time. Need to use wildcard', }, { id: 'AwsSolutions-IAM4', reason: 'Suppress AwsSolutions-IAM4 for AWS Managed Policies policy/AmazonSSMManagedInstanceCore', }, ], true ); } }
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/lib/constructs/loadBalancer.ts
import { Construct } from 'constructs'; import { Duration, RemovalPolicy } from 'aws-cdk-lib'; import { ISubnet, SecurityGroup, Vpc } from 'aws-cdk-lib/aws-ec2'; import { Certificate } from 'aws-cdk-lib/aws-certificatemanager'; import { ARecord, IHostedZone, RecordTarget } from 'aws-cdk-lib/aws-route53'; import { LoadBalancerTarget } from 'aws-cdk-lib/aws-route53-targets'; import { AutoScalingGroup } from 'aws-cdk-lib/aws-autoscaling'; import * as elb from 'aws-cdk-lib/aws-elasticloadbalancingv2'; import * as s3 from 'aws-cdk-lib/aws-s3'; export interface LoadBalancerProps { removalPolicy: RemovalPolicy; autoDelete: boolean; vpc: Vpc; subnets: ISubnet[]; securityGroup: SecurityGroup; domainPrefix: string; rootDomain: string; certificate: Certificate; hostedZone: IHostedZone; autoScalingGroup: AutoScalingGroup; } export class LoadBalancerConstruct extends Construct { public readonly loadBalancer: elb.ApplicationLoadBalancer; /** * Creates a cross-account role allowing the AWS Prototyping Team * to access customer accounts by assuming the role. * @param scope the construct scope. * @param id the identifier given the construct.np * @param props the construct configuration. */ constructor(scope: Construct, id: string, props: LoadBalancerProps) { super(scope, id); // create new Application Load Balancer this.loadBalancer = new elb.ApplicationLoadBalancer(this, 'LoadBalancer', { vpc: props.vpc, vpcSubnets: { subnets: props.subnets }, securityGroup: props.securityGroup, internetFacing: true, http2Enabled: true, }); // removal policy -- change in config this.loadBalancer.applyRemovalPolicy(props.removalPolicy ?? RemovalPolicy.DESTROY); // access logs for load balancer this.loadBalancer.logAccessLogs( new s3.Bucket(this, 'LoadBalancerAccessLogsBucket', { encryption: s3.BucketEncryption.S3_MANAGED, removalPolicy: props.removalPolicy, autoDeleteObjects: props.autoDelete, enforceSSL: true, publicReadAccess: false, blockPublicAccess: s3.BlockPublicAccess.BLOCK_ALL, serverAccessLogsPrefix: 'bucket-logs', }), 'loadBalancer-logs' ); // add ALB as target for Route 53 Hosted Zone new ARecord(this, 'LoadBalancerAliasRecord', { zone: props.hostedZone, recordName: `${props.domainPrefix}.${props.rootDomain}`, ttl: Duration.seconds(300), target: RecordTarget.fromAlias(new LoadBalancerTarget(this.loadBalancer)), }); // -------------------------------------------------------------------- // Target Groups // -------------------------------------------------------------------- const targetGroup = new elb.ApplicationTargetGroup(this, 'TargetGroup', { protocol: elb.ApplicationProtocol.HTTP, protocolVersion: elb.ApplicationProtocolVersion.HTTP1, targetType: elb.TargetType.INSTANCE, vpc: props.vpc, targets: [props.autoScalingGroup], healthCheck: { port: '80', path: '/healthcheck', }, }); // -------------------------------------------------------------------- // LISTENERS // -------------------------------------------------------------------- const httpListener = this.loadBalancer.addRedirect({ sourceProtocol: elb.ApplicationProtocol.HTTP, sourcePort: 80, targetProtocol: elb.ApplicationProtocol.HTTPS, targetPort: 443, }); const sslListener = this.loadBalancer.addListener('SSLListener', { protocol: elb.ApplicationProtocol.HTTPS, port: 443, sslPolicy: elb.SslPolicy.TLS12, certificates: [props.certificate], defaultTargetGroups: [targetGroup], }); } }
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/lib/constructs/route53.ts
import { Construct } from 'constructs'; import { HostedZone, IHostedZone } from 'aws-cdk-lib/aws-route53'; import { Certificate, CertificateValidation } from 'aws-cdk-lib/aws-certificatemanager'; export interface Route53Props { rootDomain: string; } export class Route53Resources extends Construct { public readonly hostedZone: IHostedZone; public readonly certificate: Certificate; constructor(scope: Construct, id: string, props: Route53Props) { super(scope, id); this.hostedZone = HostedZone.fromLookup(this, 'PublicHostedZone', { domainName: props.rootDomain, }); this.certificate = new Certificate(this, 'PublicCertificate', { domainName: props.rootDomain, subjectAlternativeNames: [`*.${props.rootDomain}`], validation: CertificateValidation.fromDns(this.hostedZone), }); } }
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/lib/constructs/vpc.ts
import { CfnOutput, RemovalPolicy, Stack } from 'aws-cdk-lib'; import { Construct } from 'constructs'; import { LogGroup, RetentionDays } from 'aws-cdk-lib/aws-logs'; import { cleanEnv, str } from 'envalid'; import * as ec2 from 'aws-cdk-lib/aws-ec2'; import * as dotenv from 'dotenv'; import { NagSuppressions } from 'cdk-nag'; dotenv.config(); const env = cleanEnv(process.env, { ALLOWED_CIDR_RANGE_01: str({ default: '' }), ROOT_DOMAIN: str({ default: '' }), }); export interface VpcResourcesProps { removalPolicy: RemovalPolicy; } export class VpcResources extends Construct { public readonly vpc: ec2.Vpc; public readonly securityGroups: { loadBalancer: ec2.SecurityGroup; workstation: ec2.SecurityGroup; reverseProxy: ec2.SecurityGroup; nucleus: ec2.SecurityGroup; }; public readonly subnets: { loadBalancer: ec2.ISubnet[]; workstation: ec2.ISubnet[]; reverseProxy: ec2.ISubnet[]; nucleus: ec2.ISubnet[]; }; /** * Creates a cross-account role allowing the AWS Prototyping Team * to access customer accounts by assuming the role. * @param scope the construct scope. * @param id the identifier given the construct.np * @param props the construct configuration. */ constructor(scope: Construct, id: string, props: VpcResourcesProps) { super(scope, id); const stackName = Stack.of(this).stackName; // ------------------------------------------------------------------------ // Subnets // ------------------------------------------------------------------------ const natGatewaySubnet: ec2.SubnetConfiguration = { name: 'NatGatewayPublicSubnet', subnetType: ec2.SubnetType.PUBLIC, cidrMask: 28, // 16 }; const loadBalancerSubnetConfig: ec2.SubnetConfiguration = { name: 'LoadBalancerPrivateSubnet', subnetType: ec2.SubnetType.PRIVATE_WITH_EGRESS, cidrMask: 22, // 1024 }; const workstationSubnetConfig: ec2.SubnetConfiguration = { name: 'WorkstationPublicSubnet', subnetType: ec2.SubnetType.PRIVATE_WITH_EGRESS, cidrMask: 22, // 1024 }; const reverseProxySubnetConfig: ec2.SubnetConfiguration = { name: 'ReverseProxyPublicSubnet', subnetType: ec2.SubnetType.PRIVATE_WITH_EGRESS, cidrMask: 22, // 1024 }; const nucleusSubnetConfig: ec2.SubnetConfiguration = { name: 'NucleusPrivateSubnet', subnetType: ec2.SubnetType.PRIVATE_WITH_EGRESS, cidrMask: 22, // 1024 }; // ------------------------------------------------------------------------ // VPC // ------------------------------------------------------------------------ const cloudWatchLogs = new LogGroup(this, 'CloudWatchVPCLogs', { retention: RetentionDays.ONE_WEEK, removalPolicy: props.removalPolicy, }); // Elastic IP for NatGateway const eip = new ec2.CfnEIP(this, 'NATGatewayEIP', { domain: 'vpc', }); const natGatewayProvider = ec2.NatProvider.gateway({ eipAllocationIds: [eip.attrAllocationId], }); const cidrRange: string = '10.0.0.0/16'; // 65,536 this.vpc = new ec2.Vpc(this, 'OmniVpc', { ipAddresses: ec2.IpAddresses.cidr(cidrRange), natGateways: 1, subnetConfiguration: [ natGatewaySubnet, loadBalancerSubnetConfig, workstationSubnetConfig, reverseProxySubnetConfig, nucleusSubnetConfig, ], natGatewayProvider: natGatewayProvider, flowLogs: { 'vpc-logs': { destination: ec2.FlowLogDestination.toCloudWatchLogs(cloudWatchLogs), trafficType: ec2.FlowLogTrafficType.ALL, }, }, createInternetGateway: true, }); this.vpc.selectSubnets({ subnetGroupName: loadBalancerSubnetConfig.name, }).subnets.forEach((subnet: ec2.ISubnet) => { (subnet as ec2.Subnet).addRoute('AllowedCidrRoute', { destinationCidrBlock: env.ALLOWED_CIDR_RANGE_01, routerType: ec2.RouterType.GATEWAY, routerId: this.vpc.internetGatewayId!, enablesInternetConnectivity: true, }); }); this.subnets = { loadBalancer: this.vpc.selectSubnets({ subnetGroupName: loadBalancerSubnetConfig.name, }).subnets, workstation: this.vpc.selectSubnets({ subnetGroupName: workstationSubnetConfig.name, }).subnets, reverseProxy: this.vpc.selectSubnets({ subnetGroupName: reverseProxySubnetConfig.name, }).subnets, nucleus: this.vpc.selectSubnets({ subnetGroupName: nucleusSubnetConfig.name, }).subnets, }; // ------------------------------------------------------------------------ // Security Groups // ------------------------------------------------------------------------ const natGatewaySG = new ec2.SecurityGroup(this, 'NatGatewaySG', { securityGroupName: `${stackName}-nat-gateway-sg`, description: 'NAT Gateway Security Group', vpc: this.vpc, allowAllOutbound: true, }); const loadBalancerSG = new ec2.SecurityGroup(this, 'LoadBalancerSG', { securityGroupName: `${stackName}-load-balancer-sg`, description: 'Load Balancer Security Group', vpc: this.vpc, allowAllOutbound: true, }); const workstationSG = new ec2.SecurityGroup(this, 'WorkstationSG', { securityGroupName: `${stackName}-workstation-sg`, description: 'Workstation Security Group', vpc: this.vpc, allowAllOutbound: true, }); const reverseProxySG = new ec2.SecurityGroup(this, 'ReverseProxySG', { securityGroupName: `${stackName}-reverse-proxy-sg`, description: 'Reverse Proxy Security Group', vpc: this.vpc, allowAllOutbound: true, }); const nucleusSG = new ec2.SecurityGroup(this, 'NucleusSG', { securityGroupName: `${stackName}-nucleus-sg`, description: 'Nucleus Server Security Group', vpc: this.vpc, allowAllOutbound: true, }); const ssmEndpointSG = new ec2.SecurityGroup(this, 'SSMEndpointSG', { vpc: this.vpc, allowAllOutbound: true, description: 'SSM Endpoint Security Group', }); // loadBalancerSG rules loadBalancerSG.addIngressRule(ec2.Peer.ipv4(env.ALLOWED_CIDR_RANGE_01), ec2.Port.tcp(80), 'HTTP access'); loadBalancerSG.addIngressRule(ec2.Peer.ipv4(env.ALLOWED_CIDR_RANGE_01), ec2.Port.tcp(443), 'HTTPS access'); loadBalancerSG.addIngressRule(ec2.Peer.ipv4(cidrRange), ec2.Port.tcp(443), 'VPC Access'); loadBalancerSG.addIngressRule(ec2.Peer.securityGroupId(workstationSG.securityGroupId), ec2.Port.tcp(80), 'Workstation access'); loadBalancerSG.addIngressRule(ec2.Peer.securityGroupId(workstationSG.securityGroupId), ec2.Port.tcp(443), 'Workstation access'); loadBalancerSG.addIngressRule(ec2.Peer.securityGroupId(natGatewaySG.securityGroupId), ec2.Port.tcp(443), 'NAT access'); reverseProxySG.addIngressRule(ec2.Peer.ipv4(cidrRange), ec2.Port.tcp(443), 'VPC Access'); reverseProxySG.addIngressRule(ec2.Peer.securityGroupId(natGatewaySG.securityGroupId), ec2.Port.tcp(443), 'NAT access'); // nucleusSG rules const nucleusRules = [ { port: 80, desc: 'HTTP Access' }, { port: 8080, desc: 'Nucleus Web2' }, { port: 3019, desc: 'Nucleus API' }, { port: 3030, desc: 'Nucleus LFT' }, { port: 3333, desc: 'Nucleus Discovery' }, { port: 3100, desc: 'Nucleus Auth' }, { port: 3180, desc: 'Nucleus Login' }, { port: 3020, desc: 'Nucleus Tagging2' }, { port: 3400, desc: 'Nucleus Search2' }, { port: 34080, desc: 'Nucleus Navigator' }, ]; nucleusRules.forEach((rule) => { nucleusSG.addIngressRule( ec2.Peer.securityGroupId(reverseProxySG.securityGroupId), ec2.Port.tcp(rule.port), rule.desc ); }); nucleusSG.addIngressRule(ec2.Peer.ipv4(cidrRange), ec2.Port.tcp(443), 'VPC access'); nucleusSG.addIngressRule(ec2.Peer.securityGroupId(natGatewaySG.securityGroupId), ec2.Port.tcp(443), 'NAT access'); // workstationSG rules workstationSG.addIngressRule(ec2.Peer.ipv4(env.ALLOWED_CIDR_RANGE_01), ec2.Port.tcp(443), 'HTTPS access'); workstationSG.addIngressRule(ec2.Peer.ipv4(env.ALLOWED_CIDR_RANGE_01), ec2.Port.udp(8443), 'UDP access'); workstationSG.addIngressRule(ec2.Peer.ipv4(cidrRange), ec2.Port.tcp(443), 'VPC access'); workstationSG.addIngressRule(ec2.Peer.securityGroupId(natGatewaySG.securityGroupId), ec2.Port.tcp(443), 'NAT access'); this.securityGroups = { loadBalancer: loadBalancerSG, workstation: workstationSG, reverseProxy: reverseProxySG, nucleus: nucleusSG, }; // ssm endpoint rules ssmEndpointSG.addIngressRule(ec2.Peer.ipv4(cidrRange), ec2.Port.tcp(443), 'HTTPS Access'); // ------------------------------------------------------------------------ // Service Endpoints // ------------------------------------------------------------------------ const s3Endpoint: ec2.GatewayVpcEndpoint = this.vpc.addGatewayEndpoint('S3GatewayEndpoint', { service: ec2.GatewayVpcEndpointAwsService.S3, subnets: [{ subnets: this.subnets.nucleus }, { subnets: this.subnets.reverseProxy }], }); const ssmEndpoint: ec2.InterfaceVpcEndpoint = this.vpc.addInterfaceEndpoint( 'ssm-interface-endpoint', { service: ec2.InterfaceVpcEndpointAwsService.SSM, subnets: { subnets: this.subnets.nucleus }, securityGroups: [this.securityGroups.nucleus], open: false, } ); // ------------------------------------------------------------------------ // Outputs // ------------------------------------------------------------------------ new CfnOutput(this, 'VpcID', { value: this.vpc.vpcId, }); // ------------------------------------ // CDK_NAG (security scan) suppressions // ------------------------------------ NagSuppressions.addResourceSuppressions( reverseProxySG, [ { id: 'AwsSolutions-EC23', reason: 'Security Group inbound access can be modified in the app configuration. For production, this will be set to the IP range for the local network.', }, ], true ); NagSuppressions.addResourceSuppressions( nucleusSG, [ { id: 'AwsSolutions-EC23', reason: 'Security Group inbound access can be modified in the app configuration. For production, this will be set to the IP range for the local network.', }, ], true ); NagSuppressions.addResourceSuppressions( loadBalancerSG, [ { id: 'AwsSolutions-EC23', reason: 'Security Group inbound access can be modified in the app configuration. For production, this will be set to the IP range for the local network.', }, ], true ); } }
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/lib/constructs/nucleusServer.ts
import { Construct } from 'constructs'; import { Stack, Tags, RemovalPolicy } from 'aws-cdk-lib'; import { NagSuppressions } from 'cdk-nag'; import { CustomResource } from './common/customResource'; import { cleanEnv, bool, str } from 'envalid'; import * as iam from 'aws-cdk-lib/aws-iam'; import * as s3 from 'aws-cdk-lib/aws-s3'; import * as ec2 from 'aws-cdk-lib/aws-ec2'; import * as secretsmanager from 'aws-cdk-lib/aws-secretsmanager'; import * as pyLambda from '@aws-cdk/aws-lambda-python-alpha'; import * as dotenv from 'dotenv'; import * as fs from 'fs'; import * as path from 'path'; dotenv.config(); const env = cleanEnv(process.env, { ALLOWED_CIDR_RANGE_01: str({ default: '' }), ALLOWED_CIDR_RANGE_02: str({ default: '' }), DEV_MODE: bool({ default: false }), ROOT_DOMAIN: str({ default: '' }), NUCLEUS_SERVER_PREFIX: str({ default: 'nucleus' }), NUCLEUS_BUILD: str({ default: '' }), }); export type ConstructProps = { removalPolicy: RemovalPolicy; vpc: ec2.Vpc; subnets: ec2.ISubnet[]; artifactsBucket: s3.IBucket; nucleusServerSG: ec2.SecurityGroup; lambdaLayers: pyLambda.PythonLayerVersion[]; }; export class NucleusServerResources extends Construct { public readonly nucleusServerInstance: ec2.Instance; constructor(scope: Construct, id: string, props: ConstructProps) { super(scope, id); const region: string = Stack.of(this).region; const account: string = Stack.of(this).account; const stackName: string = Stack.of(this).stackName; const fullDomainName = `${env.NUCLEUS_SERVER_PREFIX}.${env.ROOT_DOMAIN}`; // Templated secret const ovMainLogin = new secretsmanager.Secret(this, 'ovMainLogin', { generateSecretString: { secretStringTemplate: JSON.stringify({ username: 'omniverse' }), excludePunctuation: true, generateStringKey: 'password', }, }); // Templated secret const ovServiceLogin = new secretsmanager.Secret(this, 'ovServiceLogin', { generateSecretString: { secretStringTemplate: JSON.stringify({ username: 'omniverse' }), excludePunctuation: true, generateStringKey: 'password', }, }); const instance_role = new iam.Role(this, 'InstanceRole', { assumedBy: new iam.ServicePrincipal('ec2.amazonaws.com'), description: 'EC2 Instance Role', managedPolicies: [iam.ManagedPolicy.fromAwsManagedPolicyName('AmazonSSMManagedInstanceCore')], }); const ebs_volume: ec2.BlockDevice = { deviceName: '/dev/sda1', volume: ec2.BlockDeviceVolume.ebs(512, { encrypted: true, }), }; // Canonical, Ubuntu, 20.04 LTS, amd64 const nucleusServerAMI = ec2.MachineImage.fromSsmParameter( '/aws/service/canonical/ubuntu/server/focal/stable/current/amd64/hvm/ebs-gp2/ami-id', { os: ec2.OperatingSystemType.LINUX, } ); this.nucleusServerInstance = new ec2.Instance(this, 'NucleusServer', { instanceType: new ec2.InstanceType('c5.4xlarge'), machineImage: nucleusServerAMI, blockDevices: [ebs_volume], vpc: props.vpc, role: instance_role, securityGroup: props.nucleusServerSG, vpcSubnets: { subnets: props.subnets }, detailedMonitoring: true, }); this.nucleusServerInstance.applyRemovalPolicy(props.removalPolicy); Tags.of(this.nucleusServerInstance).add('Name', `${stackName}/NucleusServer`); // artifacts bucket instance_role.addToPolicy( new iam.PolicyStatement({ resources: [`${props.artifactsBucket.bucketArn}`, `${props.artifactsBucket.bucketArn}/*`], actions: ['s3:ListBucket', 's3:GetObject'], }) ); instance_role.addToPolicy( new iam.PolicyStatement({ actions: [ 'logs:CreateLogGroup', 'logs:CreateLogStream', 'logs:DescribeLogStreams', 'logs:PutLogEvents', ], resources: ['arn:aws:logs:*:*:log-group:/aws/ssm/*'], }) ); // -------------------------------------------------------------------- // CUSTOM RESOURCE - Nucleus Server Config // -------------------------------------------------------------------- // Custom Resource to manage nucleus server configuration const nucleusConfigLambdaPolicy = new iam.PolicyDocument({ statements: [ new iam.PolicyStatement({ actions: ['ssm:SendCommand'], resources: [ `arn:aws:ec2:${region}:${account}:instance/${this.nucleusServerInstance.instanceId}`, ], }), new iam.PolicyStatement({ actions: ['ssm:SendCommand'], resources: ['arn:aws:ssm:*:*:document/*'], }), new iam.PolicyStatement({ actions: ['ssm:GetCommandInvocation'], resources: [`arn:aws:ssm:${region}:${account}:*`], }), new iam.PolicyStatement({ actions: ['secretsmanager:GetSecretValue', 'secretsmanager:DescribeSecret'], resources: [ovMainLogin.secretArn, ovServiceLogin.secretArn], }), ], }); const nucleusServerConfig = new CustomResource(this, 'NucleusServerConfig', { lambdaName: 'NucleusServerConfig', lambdaCodePath: './src/lambda/customResources/nucleusServerConfig', lambdaPolicyDocument: nucleusConfigLambdaPolicy, resourceProps: { nounce: 2, instanceId: this.nucleusServerInstance.instanceId, reverseProxyDomain: fullDomainName, nucleusBuild: env.NUCLEUS_BUILD, artifactsBucket: props.artifactsBucket.bucketName, ovMainLoginSecretArn: ovMainLogin.secretName, ovServiceLoginSecretArn: ovServiceLogin.secretArn, }, lambdaLayers: props.lambdaLayers, removalPolicy: props.removalPolicy }); nucleusServerConfig.resource.node.addDependency(this.nucleusServerInstance); // ------------------------------- // CDK_NAG (security scan) suppressions // ------------------------------- NagSuppressions.addResourceSuppressions( ovMainLogin, [ { id: 'AwsSolutions-SMG4', reason: 'Auto rotate secrets: Secrets Manager used to hold credentials required for deployment. Will be replaced by SSO strategy in production', }, ], true ); NagSuppressions.addResourceSuppressions( ovServiceLogin, [ { id: 'AwsSolutions-SMG4', reason: 'Auto rotate secrets: Secrets Manager used to hold credentials required for deployment. Will be replaced by SSO strategy in production', }, ], true ); NagSuppressions.addResourceSuppressions( instance_role, [ { id: 'AwsSolutions-IAM5', reason: 'Wildcard Permissions: Unable to know which objects exist ahead of time. Need to use wildcard', }, ], true ); NagSuppressions.addResourceSuppressions( this.nucleusServerInstance, [ { id: 'AwsSolutions-EC29', reason: 'CDK_NAG is not recognizing the applied removalPolicy', }, ], true ); } }
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/lib/constructs/autoscaling.ts
import { Construct } from 'constructs'; import { Stack, Duration, RemovalPolicy } from 'aws-cdk-lib'; import * as autoscaling from 'aws-cdk-lib/aws-autoscaling'; import * as ec2 from 'aws-cdk-lib/aws-ec2'; import * as iam from 'aws-cdk-lib/aws-iam'; import * as s3 from 'aws-cdk-lib/aws-s3'; import * as pyLambda from '@aws-cdk/aws-lambda-python-alpha'; import * as lambda from 'aws-cdk-lib/aws-lambda'; import * as logs from 'aws-cdk-lib/aws-logs'; import * as events from 'aws-cdk-lib/aws-events'; import * as targets from 'aws-cdk-lib/aws-events-targets'; import { NagSuppressions } from 'cdk-nag'; export interface AutoScalingResourceProps { name: string; removalPolicy: RemovalPolicy; artifactsBucket: s3.IBucket; vpcResources: { vpc: ec2.Vpc; subnets: ec2.ISubnet[]; }; launchTemplate: ec2.LaunchTemplate; capacity: { min: number; max: number; }; lambdaResources?: { entry: string; layers: pyLambda.PythonLayerVersion[]; environment: { [key: string]: string; }; policies?: { [key: string]: iam.PolicyDocument; }; }; } export class AutoScalingResources extends Construct { public readonly autoScalingGroup: autoscaling.AutoScalingGroup; constructor(scope: Construct, id: string, props: AutoScalingResourceProps) { super(scope, id); const region: string = Stack.of(this).region; const account: string = Stack.of(this).account; this.autoScalingGroup = new autoscaling.AutoScalingGroup( this, `${props.name}AutoScalingGroup`, { vpc: props.vpcResources.vpc, vpcSubnets: { subnets: props.vpcResources.subnets }, minCapacity: props.capacity.min, maxCapacity: props.capacity.max, launchTemplate: props.launchTemplate, updatePolicy: autoscaling.UpdatePolicy.replacingUpdate(), healthCheck: autoscaling.HealthCheck.ec2({ grace: Duration.minutes(1) }), } ); if (props.lambdaResources != undefined) { // Scale Up Lifecycle Hook this.autoScalingGroup.addLifecycleHook(`${props.name}ScaleUpLifecycleHook`, { heartbeatTimeout: Duration.seconds(300), defaultResult: autoscaling.DefaultResult.ABANDON, lifecycleTransition: autoscaling.LifecycleTransition.INSTANCE_LAUNCHING, }); // Scale Down Lifecycle Hook this.autoScalingGroup.addLifecycleHook(`${props.name}ScaleDownLifecycleHook`, { heartbeatTimeout: Duration.seconds(300), defaultResult: autoscaling.DefaultResult.ABANDON, lifecycleTransition: autoscaling.LifecycleTransition.INSTANCE_TERMINATING, }); const lifecycleLambdaPolicy = new iam.PolicyDocument({ statements: [ new iam.PolicyStatement({ resources: [`${this.autoScalingGroup.autoScalingGroupArn}`], actions: ['autoscaling:CompleteLifecycleAction'], }), new iam.PolicyStatement({ actions: ['autoscaling:DescribeAutoScalingGroups'], resources: ['*'], }), new iam.PolicyStatement({ resources: [ `arn:aws:ssm:${region}::document/AWS-RunPowerShellScript`, `arn:aws:ssm:${region}::document/AWS-RunShellScript`, ], actions: ['ssm:SendCommand'], }), new iam.PolicyStatement({ resources: ['arn:aws:ec2:*:*:instance/*'], actions: ['ssm:SendCommand'], conditions: { StringEquals: { 'iam:ssm:ResourceTag/aws:autoscaling:groupName': this.autoScalingGroup.autoScalingGroupName, }, }, }), new iam.PolicyStatement({ resources: ['*'], actions: ['ssm:GetCommandInvocation'], }), ], }); const configLambdaPolicy = new iam.PolicyDocument({ statements: [ new iam.PolicyStatement({ actions: ['ssm:SendCommand'], resources: [`arn:aws:ec2:${region}:${account}:instance/*`], }), new iam.PolicyStatement({ actions: ['ec2:DescribeInstances', 'ec2:DescribeInstanceStatus'], resources: [`*`], }), new iam.PolicyStatement({ actions: ['ssm:SendCommand'], resources: ['arn:aws:ssm:*:*:document/*'], }), new iam.PolicyStatement({ actions: ['ssm:GetCommandInvocation'], resources: [`arn:aws:ssm:${region}:${account}:*`], }), ], }); const lifecycleLambdaRole = new iam.Role(this, `${props.name}LifecycleLambdaRole`, { assumedBy: new iam.ServicePrincipal('lambda.amazonaws.com'), managedPolicies: [iam.ManagedPolicy.fromAwsManagedPolicyName('service-role/AWSLambdaVPCAccessExecutionRole')], inlinePolicies: { lifecycleLambdaPolicy: lifecycleLambdaPolicy, configLambdaPolicy: configLambdaPolicy, ...props.lambdaResources.policies, }, }); const lambdaName = `${props.name}AutoScalingLifecycleLambdaFunction`.slice(0, 64); const logGroup = new logs.LogGroup(this, 'LifecycleLambdaFnLogGroup', { retention: logs.RetentionDays.ONE_WEEK, removalPolicy: props.removalPolicy, }); const lifecycleLambdaFn = new pyLambda.PythonFunction( this, `${props.name}LifecycleLambdaFn`, { functionName: lambdaName, runtime: lambda.Runtime.PYTHON_3_9, handler: 'handler', entry: props.lambdaResources.entry, role: lifecycleLambdaRole, timeout: Duration.minutes(5), layers: props.lambdaResources.layers, environment: props.lambdaResources.environment, vpc: props.vpcResources.vpc, vpcSubnets: { subnets: props.vpcResources.subnets }, } ); lifecycleLambdaFn.node.addDependency(logGroup); lifecycleLambdaFn.addToRolePolicy( new iam.PolicyStatement({ actions: ['logs:CreateLogStream', 'logs:PutLogEvents'], resources: [logGroup.logGroupArn], }) ); const rule = new events.Rule(this, `${props.name}EventRule`, { eventPattern: { source: ['aws.autoscaling'], detailType: [ 'EC2 Instance-launch Lifecycle Action', 'EC2 Instance-terminate Lifecycle Action', ], detail: { AutoScalingGroupName: [this.autoScalingGroup.autoScalingGroupName], }, }, }); rule.node.addDependency(lifecycleLambdaFn); rule.addTarget(new targets.LambdaFunction(lifecycleLambdaFn)); NagSuppressions.addResourceSuppressions( lifecycleLambdaRole, [ { id: 'AwsSolutions-IAM5', reason: 'Wildcard Permissions: This is a Dummy Policy with minimal actions. This policy is updated on the fly by the revProxyCertAssociation custom resource', }, ], true ); } NagSuppressions.addResourceSuppressions( this.autoScalingGroup, [ { id: 'AwsSolutions-AS3', reason: 'Autoscaling Event notifications: Backlogged, will provide guidance in production document', }, ], true ); } }
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/lib/constructs/common/customResource.ts
import { Construct } from 'constructs'; import { Duration, Stack, RemovalPolicy } from 'aws-cdk-lib'; import { NagSuppressions } from 'cdk-nag'; import * as cdk from 'aws-cdk-lib'; import * as iam from 'aws-cdk-lib/aws-iam'; import * as logs from 'aws-cdk-lib/aws-logs'; import * as cr from 'aws-cdk-lib/custom-resources'; import * as lambda from 'aws-cdk-lib/aws-lambda'; import * as pyLambda from '@aws-cdk/aws-lambda-python-alpha'; import fs = require('fs'); import crypto = require('crypto'); interface LooseTypeObject { [key: string]: any; } export type ConstructProps = { lambdaName: string; lambdaCodePath: string; lambdaPolicyDocument: iam.PolicyDocument; resourceProps: LooseTypeObject; removalPolicy: RemovalPolicy; lambdaLayers?: pyLambda.PythonLayerVersion[]; }; export class CustomResource extends Construct { public readonly resource: cdk.CustomResource; constructor(scope: Construct, id: string, props: ConstructProps) { super(scope, id); const region: string = Stack.of(this).region; const account: string = Stack.of(this).account; const lambdaRole = new iam.Role(this, 'lambdaRole', { assumedBy: new iam.ServicePrincipal('lambda.amazonaws.com'), inlinePolicies: { lambdaPolicyDocument: props.lambdaPolicyDocument, }, }); const lambdaName = `${Stack.of(this).stackName}-${props.lambdaName}-CustomResource`.slice(0, 64); const lambdaLogGroup = `/aws/lambda/${lambdaName}`; const logGroup = new logs.LogGroup(this, 'lambdaFnLogGroup', { logGroupName: lambdaLogGroup, retention: logs.RetentionDays.ONE_WEEK, removalPolicy: props.removalPolicy ?? RemovalPolicy.DESTROY, }); const lambdaFn = new pyLambda.PythonFunction(this, 'lambdaFn', { functionName: lambdaName, runtime: lambda.Runtime.PYTHON_3_9, handler: 'handler', entry: props.lambdaCodePath, role: lambdaRole, timeout: Duration.minutes(5), layers: props.lambdaLayers || [], }); lambdaFn.node.addDependency(logGroup); lambdaFn.addToRolePolicy( new iam.PolicyStatement({ actions: ['logs:CreateLogStream', 'logs:PutLogEvents'], resources: [logGroup.logGroupArn], }) ); const provider = new cr.Provider(this, 'provider', { onEventHandler: lambdaFn, }); // force resource to update when code changes const fileBuffer = fs.readFileSync(`${props.lambdaCodePath}/index.py`); const hashSum = crypto.createHash('sha256'); hashSum.update(fileBuffer); const hex = hashSum.digest('hex'); props.resourceProps.codeHash = hex; props.resourceProps.region = region; this.resource = new cdk.CustomResource(this, 'resource', { serviceToken: provider.serviceToken, properties: props.resourceProps, }); // Nag NagSuppressions NagSuppressions.addResourceSuppressions( lambdaRole, [ { id: 'AwsSolutions-IAM5', reason: 'Wildcard Permissions: Unable to know which objects exist ahead of time. Need to use wildcard', }, ], true ); NagSuppressions.addResourceSuppressions( provider, [ { id: 'AwsSolutions-IAM4', reason: 'Auto-generated resource with managed policy', }, { id: 'AwsSolutions-IAM5', reason: 'Auto-generated resource with wildcard policy', }, { id: 'AwsSolutions-L1', reason: 'Auto-generated resource not configured to use the latest runtime', }, ], true ); } }
aws-samples/nvidia-omniverse-nucleus-on-amazon-ec2/lib/utils/regions.ts
export const regions = [ 'us-east-1', 'us-east-2', 'us-west-1', 'us-west-2', 'af-south-1', 'ap-east-1', 'ap-south-2', 'ap-southeast-3', 'ap-south-1', 'ap-northeast-3', 'ap-northeast-2', 'ap-southeast-1', 'ap-southeast-2', 'ap-northeast-1', 'ca-central-1', 'eu-central-1', 'eu-west-1', 'eu-west-2', 'eu-south-1', 'eu-west-3', 'eu-south-2', 'eu-north-1', 'eu-central-2', 'me-south-1', 'me-central-1', 'sa-east-1' ];
arhix52/Strelka/conanfile.py
import os from conan import ConanFile from conan.tools.cmake import cmake_layout from conan.tools.files import copy class StrelkaRecipe(ConanFile): settings = "os", "compiler", "build_type", "arch" generators = "CMakeToolchain", "CMakeDeps" def requirements(self): self.requires("glm/cci.20230113") self.requires("spdlog/[>=1.4.1]") self.requires("imgui/1.89.3") self.requires("glfw/3.3.8") self.requires("stb/cci.20230920") self.requires("glad/0.1.36") self.requires("doctest/2.4.11") self.requires("cxxopts/3.1.1") self.requires("tinygltf/2.8.19") self.requires("nlohmann_json/3.11.3") def generate(self): copy(self, "*glfw*", os.path.join(self.dependencies["imgui"].package_folder, "res", "bindings"), os.path.join(self.source_folder, "external", "imgui")) copy(self, "*opengl3*", os.path.join(self.dependencies["imgui"].package_folder, "res", "bindings"), os.path.join(self.source_folder, "external", "imgui")) copy(self, "*metal*", os.path.join(self.dependencies["imgui"].package_folder, "res", "bindings"), os.path.join(self.source_folder, "external", "imgui")) def layout(self): cmake_layout(self)
arhix52/Strelka/BuildOpenUSD.md
USD building: VS2019 + python 3.10 To build debug on windows: python USD\build_scripts\build_usd.py "C:\work\USD_build_debug" --python --materialx --build-variant debug For USD 23.03 you could use VS2022 Linux: * python3 ./OpenUSD/build_scripts/build_usd.py /home/<user>/work/OpenUSD_build/ --python --materialx
arhix52/Strelka/CMakeLists.txt
cmake_minimum_required(VERSION 3.22) project(Strelka LANGUAGES CXX) set(CMAKE_CXX_STANDARD 17) set(CMAKE_CXX_STANDARD_REQUIRED ON) set(CMAKE_CXX_EXTENSIONS OFF) # Set to TRUE to enable USD set(ENABLE_HYDRA FALSE) if(NOT DEFINED CMAKE_CUDA_STANDARD) set(CMAKE_CUDA_STANDARD 11) set(CMAKE_CUDA_STANDARD_REQUIRED ON) endif() set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_SOURCE_DIR}/cmake/") set(CMAKE_EXPORT_COMPILE_COMMANDS ON) set(CMAKE_POSITION_INDEPENDENT_CODE ON) if(UNIX AND NOT APPLE) set(LINUX TRUE) endif() if(WIN32) add_compile_definitions(NOMINMAX) add_compile_definitions(_USE_MATH_DEFINES) add_compile_definitions(_ALLOW_ITERATOR_DEBUG_LEVEL_MISMATCH) endif() set(ROOT_HOME ${CMAKE_CURRENT_LIST_DIR}) set(OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}) add_subdirectory(src/log) add_subdirectory(src/settings) add_subdirectory(src/render) add_subdirectory(src/scene) add_subdirectory(src/materialmanager) add_subdirectory(src/display) if (ENABLE_HYDRA) add_subdirectory(src/HdStrelka) add_subdirectory(src/hdRunner) endif() add_subdirectory(src/sceneloader) add_subdirectory(src/app) if(WIN32 OR LINUX) add_subdirectory(tests) endif()
arhix52/Strelka/build.sh
#!/bin/bash if [ "$#" -ne 1 ] && [ "$#" -ne 2 ]; then echo "Usage: $0 <build_type> [clean]" exit 1 fi build_type="$1" clean_option="$2" # Function to convert the input parameter to start with a capital letter ucfirst() { echo "$1" | awk '{print toupper(substr($0,1,1)) tolower(substr($0,2))}' } # Convert the build_type to start with a capital letter build_type=$(ucfirst "$build_type") # Step 1: Install Conan dependencies conan install . -c tools.cmake.cmaketoolchain:generator=Ninja -c tools.system.package_manager:mode=install -c tools.system.package_manager:sudo=True --build=missing --settings=build_type="$build_type" # Step 2: Navigate to the build directory cd build/"$build_type" # Check if the "clean" option is specified if [ "$clean_option" == "clean" ]; then # Clean the build directory cmake --build . --target clean fi # Step 3: Source the Conan environment variables source ./generators/conanbuild.sh # Step 4: Run CMake with the appropriate toolchain file cmake ../.. -G Ninja -DCMAKE_TOOLCHAIN_FILE=generators/conan_toolchain.cmake -DCMAKE_BUILD_TYPE="$build_type" # Step 5: Build the project and capture the time start_time=$(date +%s) cmake --build . end_time=$(date +%s) # Calculate the elapsed time elapsed_time=$((end_time - start_time)) # Output the build time echo "Build completed in $elapsed_time seconds."
arhix52/Strelka/README.md
# Strelka Path tracing render based on NVIDIA OptiX + NVIDIA MDL and Apple Metal ## OpenUSD Hydra render delegate ![Kitchen Set from OpenUSD](images/Kitchen_2048i_4d_2048spp_0.png) ## Basis curves support ![Hairs](images/hairmat_2_light_10000i_6d_10000spp_0.png) ![Einar](images/einar_1024i_3d_1024spp_0.png) ## Project Dependencies OpenUSD https://github.com/PixarAnimationStudios/OpenUSD * Set evn var: `USD_DIR=c:\work\USD_build` OptiX * Set evn var: `OPTIX_DIR=C:\work\OptiX SDK 8.0.0` Download MDL sdk (for example: mdl-sdk-367100.2992): https://developer.nvidia.com/nvidia-mdl-sdk-get-started * unzip content to /external/mdl-sdk/ LLVM 12.0.1 (https://github.com/llvm/llvm-project/releases/tag/llvmorg-12.0.1) for MDL ptx code generator * for win: https://github.com/llvm/llvm-project/releases/download/llvmorg-12.0.1/LLVM-12.0.1-win64.exe * for linux: https://github.com/llvm/llvm-project/releases/download/llvmorg-12.0.1/clang+llvm-12.0.1-x86_64-linux-gnu-ubuntu-16.04.tar.xz * install it to `c:\work` for example * add to PATH: `c:\work\LLVM\bin` * extract 2 header files files from external/clang12_patched to `C:\work\LLVM\lib\clang\12.0.1\include` Strelka uses conan https://conan.io/ * install conan: `pip install conan` * install ninja [https://ninja-build.org/] build system: `sudo apt install ninja-build` detect conan profile: `conan profile detect --force` 1. `conan install . --build=missing --settings=build_type=Debug` 2. `cd build` 3. `cmake .. -G "Visual Studio 17 2022" -DCMAKE_TOOLCHAIN_FILE=generators\conan_toolchain.cmake` 4. `cmake --build . --config Debug` On Mac/Linux: 1. `conan install . -c tools.cmake.cmaketoolchain:generator=Ninja -c tools.system.package_manager:mode=install -c tools.system.package_manager:sudo=True --build=missing --settings=build_type=Debug` 2. `cd build/Debug` 3. `source ./generators/conanbuild.sh` 4. `cmake ../.. -DCMAKE_TOOLCHAIN_FILE=generators/conan_toolchain.cmake -DCMAKE_BUILD_TYPE=Debug` 5. `cmake --build .` #### Installation #### Launch ## Synopsis Strelka -s <USD Scene path> [OPTION...] positional parameters -s, --scene arg scene path (default: "") -i, --iteration arg Iteration to capture (default: -1) -h, --help Print usage To set log level use `export SPDLOG_LEVEL=debug` The available log levels are: trace, debug, info, warn, and err. ## Example ./Strelka -s misc/coffeemaker.usdc -i 100 ## USD USD env: export USD_DIR=/Users/<user>/work/usd_build/ export PATH=/Users/<user>/work/usd_build/bin:$PATH export PYTHONPATH=/Users/<user>/work/usd_build/lib/python:$PYTHONPATH Install plugin: cmake --install . --component HdStrelka ## License * USD plugin design and material translation code based on Pablo Gatling code: https://github.com/pablode/gatling
arhix52/Strelka/src/HdStrelka/RenderParam.h
#pragma once #include "pxr/pxr.h" #include "pxr/imaging/hd/renderDelegate.h" #include "pxr/imaging/hd/renderThread.h" #include <scene/scene.h> PXR_NAMESPACE_OPEN_SCOPE class HdStrelkaRenderParam final : public HdRenderParam { public: HdStrelkaRenderParam(oka::Scene* scene, HdRenderThread* renderThread, std::atomic<int>* sceneVersion) : mScene(scene), mRenderThread(renderThread), mSceneVersion(sceneVersion) { } virtual ~HdStrelkaRenderParam() = default; /// Accessor for the top-level embree scene. oka::Scene* AcquireSceneForEdit() { mRenderThread->StopRender(); (*mSceneVersion)++; return mScene; } private: oka::Scene* mScene; /// A handle to the global render thread. HdRenderThread* mRenderThread; /// A version counter for edits to mScene. std::atomic<int>* mSceneVersion; }; PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/BasisCurves.h
#pragma once #include <pxr/pxr.h> #include <pxr/imaging/hd/basisCurves.h> #include <scene/scene.h> #include <pxr/base/gf/vec2f.h> PXR_NAMESPACE_OPEN_SCOPE class HdStrelkaBasisCurves final : public HdBasisCurves { public: HF_MALLOC_TAG_NEW("new HdStrelkaBasicCurves"); HdStrelkaBasisCurves(const SdfPath& id, oka::Scene* scene); ~HdStrelkaBasisCurves() override; void Sync(HdSceneDelegate* sceneDelegate, HdRenderParam* renderParam, HdDirtyBits* dirtyBits, const TfToken& reprToken) override; HdDirtyBits GetInitialDirtyBitsMask() const override; void _ConvertCurve(); const std::vector<glm::float3>& GetPoints() const; const std::vector<float>& GetWidths() const; const std::vector<uint32_t>& GetVertexCounts() const; const GfMatrix4d& GetPrototypeTransform() const; const char* getName() const; protected: void _InitRepr(const TfToken& reprName, HdDirtyBits* dirtyBits) override; HdDirtyBits _PropagateDirtyBits(HdDirtyBits bits) const override; private: bool _FindPrimvar(HdSceneDelegate* sceneDelegate, const TfToken& primvarName, HdInterpolation& interpolation) const; void _PullPrimvars(HdSceneDelegate* sceneDelegate, VtVec3fArray& points, VtVec3fArray& normals, VtFloatArray& widths, bool& indexedNormals, bool& indexedUVs, GfVec3f& color, bool& hasColor) const; void _UpdateGeometry(HdSceneDelegate* sceneDelegate); oka::Scene* mScene; std::string mName; GfVec3f mColor; VtIntArray mVertexCounts; VtVec3fArray mPoints; VtVec3fArray mNormals; VtFloatArray mWidths; GfMatrix4d m_prototypeTransform; HdBasisCurvesTopology mTopology; std::vector<glm::float3> mCurvePoints; std::vector<float> mCurveWidths; std::vector<uint32_t> mCurveVertexCounts; // std::vector<GfVec2f> m_uvs; }; PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/Tokens.cpp
#include "Tokens.h" PXR_NAMESPACE_OPEN_SCOPE TF_DEFINE_PUBLIC_TOKENS(HdStrelkaSettingsTokens, HD_STRELKA_SETTINGS_TOKENS); TF_DEFINE_PUBLIC_TOKENS(HdStrelkaNodeIdentifiers, HD_STRELKA_NODE_IDENTIFIER_TOKENS); TF_DEFINE_PUBLIC_TOKENS(HdStrelkaSourceTypes, HD_STRELKA_SOURCE_TYPE_TOKENS); TF_DEFINE_PUBLIC_TOKENS(HdStrelkaDiscoveryTypes, HD_STRELKA_DISCOVERY_TYPE_TOKENS); TF_DEFINE_PUBLIC_TOKENS(HdStrelkaRenderContexts, HD_STRELKA_RENDER_CONTEXT_TOKENS); TF_DEFINE_PUBLIC_TOKENS(HdStrelkaNodeContexts, HD_STRELKA_NODE_CONTEXT_TOKENS); PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/MdlDiscoveryPlugin.h
#pragma once #include <pxr/usd/ndr/discoveryPlugin.h> PXR_NAMESPACE_OPEN_SCOPE class HdStrelkaMdlDiscoveryPlugin final : public NdrDiscoveryPlugin { public: NdrNodeDiscoveryResultVec DiscoverNodes(const Context& ctx) override; const NdrStringVec& GetSearchURIs() const override; }; PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/Material.h
#pragma once #include "materialmanager.h" #include "MaterialNetworkTranslator.h" #include <pxr/imaging/hd/material.h> #include <pxr/imaging/hd/sceneDelegate.h> PXR_NAMESPACE_OPEN_SCOPE class HdStrelkaMaterial final : public HdMaterial { public: HF_MALLOC_TAG_NEW("new HdStrelkaMaterial"); HdStrelkaMaterial(const SdfPath& id, const MaterialNetworkTranslator& translator); ~HdStrelkaMaterial() override; HdDirtyBits GetInitialDirtyBitsMask() const override; void Sync(HdSceneDelegate* sceneDelegate, HdRenderParam* renderParam, HdDirtyBits* dirtyBits) override; const std::string& GetStrelkaMaterial() const; bool isMdl() const { return mIsMdl; } std::string getFileUri() { return mMdlFileUri; } std::string getSubIdentifier() { return mMdlSubIdentifier; } const std::vector<oka::MaterialManager::Param>& getParams() const { return mMaterialParams; } private: const MaterialNetworkTranslator& m_translator; bool mIsMdl = false; std::string mMaterialXCode; // MDL related std::string mMdlFileUri; std::string mMdlSubIdentifier; std::vector<oka::MaterialManager::Param> mMaterialParams; }; PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/Light.cpp
#include "Light.h" #include <glm/glm.hpp> #include <glm/gtc/matrix_transform.hpp> #include <glm/gtc/type_ptr.hpp> #include <glm/gtx/compatibility.hpp> #include <pxr/imaging/hd/instancer.h> #include <pxr/imaging/hd/meshUtil.h> #include <pxr/imaging/hd/smoothNormals.h> #include <pxr/imaging/hd/vertexAdjacency.h> PXR_NAMESPACE_OPEN_SCOPE // Lookup table from: // Colour Rendering of Spectra // by John Walker // https://www.fourmilab.ch/documents/specrend/specrend.c // // Covers range from 1000k to 10000k in 500k steps // assuming Rec709 / sRGB colorspace chromaticity. // // NOTE: 6500K doesn't give a pure white because the D65 // illuminant used by Rec. 709 doesn't lie on the // Planckian Locus. We would need to compute the // Correlated Colour Temperature (CCT) using Ohno's // method to get pure white. Maybe one day. // // Note that the beginning and ending knots are repeated to simplify // boundary behavior. The last 4 knots represent the segment starting // at 1.0. // static GfVec3f const _blackbodyRGB[] = { GfVec3f(1.000000f, 0.027490f, 0.000000f), // 1000 K (Approximation) GfVec3f(1.000000f, 0.027490f, 0.000000f), // 1000 K (Approximation) GfVec3f(1.000000f, 0.149664f, 0.000000f), // 1500 K (Approximation) GfVec3f(1.000000f, 0.256644f, 0.008095f), // 2000 K GfVec3f(1.000000f, 0.372033f, 0.067450f), // 2500 K GfVec3f(1.000000f, 0.476725f, 0.153601f), // 3000 K GfVec3f(1.000000f, 0.570376f, 0.259196f), // 3500 K GfVec3f(1.000000f, 0.653480f, 0.377155f), // 4000 K GfVec3f(1.000000f, 0.726878f, 0.501606f), // 4500 K GfVec3f(1.000000f, 0.791543f, 0.628050f), // 5000 K GfVec3f(1.000000f, 0.848462f, 0.753228f), // 5500 K GfVec3f(1.000000f, 0.898581f, 0.874905f), // 6000 K GfVec3f(1.000000f, 0.942771f, 0.991642f), // 6500 K GfVec3f(0.906947f, 0.890456f, 1.000000f), // 7000 K GfVec3f(0.828247f, 0.841838f, 1.000000f), // 7500 K GfVec3f(0.765791f, 0.801896f, 1.000000f), // 8000 K GfVec3f(0.715255f, 0.768579f, 1.000000f), // 8500 K GfVec3f(0.673683f, 0.740423f, 1.000000f), // 9000 K GfVec3f(0.638992f, 0.716359f, 1.000000f), // 9500 K GfVec3f(0.609681f, 0.695588f, 1.000000f), // 10000 K GfVec3f(0.609681f, 0.695588f, 1.000000f), // 10000 K GfVec3f(0.609681f, 0.695588f, 1.000000f) // 10000 K }; // Catmull-Rom basis static const float _basis[4][4] = { { -0.5f, 1.5f, -1.5f, 0.5f }, { 1.f, -2.5f, 2.0f, -0.5f }, { -0.5f, 0.0f, 0.5f, 0.0f }, { 0.f, 1.0f, 0.0f, 0.0f } }; static inline float _Rec709RgbToLuma(const GfVec3f& rgb) { return GfDot(rgb, GfVec3f(0.2126f, 0.7152f, 0.0722f)); } static GfVec3f _BlackbodyTemperatureAsRgb(float temp) { // Catmull-Rom interpolation of _blackbodyRGB constexpr int numKnots = sizeof(_blackbodyRGB) / sizeof(_blackbodyRGB[0]); // Parametric distance along spline const float u_spline = GfClamp((temp - 1000.0f) / 9000.0f, 0.0f, 1.0f); // Last 4 knots represent a trailing segment starting at u_spline==1.0, // to simplify boundary behavior constexpr int numSegs = (numKnots - 4); const float x = u_spline * numSegs; const int seg = int(floor(x)); const float u_seg = x - seg; // Parameter within segment // Knot values for this segment GfVec3f k0 = _blackbodyRGB[seg + 0]; GfVec3f k1 = _blackbodyRGB[seg + 1]; GfVec3f k2 = _blackbodyRGB[seg + 2]; GfVec3f k3 = _blackbodyRGB[seg + 3]; // Compute cubic coefficients. Could fold constants (zero, one) here // if speed is a concern. GfVec3f a = _basis[0][0] * k0 + _basis[0][1] * k1 + _basis[0][2] * k2 + _basis[0][3] * k3; GfVec3f b = _basis[1][0] * k0 + _basis[1][1] * k1 + _basis[1][2] * k2 + _basis[1][3] * k3; GfVec3f c = _basis[2][0] * k0 + _basis[2][1] * k1 + _basis[2][2] * k2 + _basis[2][3] * k3; GfVec3f d = _basis[3][0] * k0 + _basis[3][1] * k1 + _basis[3][2] * k2 + _basis[3][3] * k3; // Eval cubic polynomial. GfVec3f rgb = ((a * u_seg + b) * u_seg + c) * u_seg + d; // Normalize to the same luminance as (1,1,1) rgb /= _Rec709RgbToLuma(rgb); // Clamp at zero, since the spline can produce small negative values, // e.g. in the blue component at 1300k. rgb[0] = GfMax(rgb[0], 0.f); rgb[1] = GfMax(rgb[1], 0.f); rgb[2] = GfMax(rgb[2], 0.f); return rgb; } HdStrelkaLight::HdStrelkaLight(const SdfPath& id, TfToken const& lightType) : HdLight(id), mLightType(lightType) { } HdStrelkaLight::~HdStrelkaLight() { } void HdStrelkaLight::Sync(HdSceneDelegate* sceneDelegate, HdRenderParam* renderParam, HdDirtyBits* dirtyBits) { TF_UNUSED(renderParam); bool pullLight = (*dirtyBits & DirtyBits::DirtyParams); *dirtyBits = DirtyBits::Clean; if (!pullLight) { return; } const SdfPath& id = GetId(); // const VtValue& resource = sceneDelegate->GetMaterialResource(id); // Get the color of the light GfVec3f hdc = sceneDelegate->GetLightParamValue(id, HdLightTokens->color).Get<GfVec3f>(); // Color temperature VtValue enableColorTemperatureVal = sceneDelegate->GetLightParamValue(id, HdLightTokens->enableColorTemperature); if (enableColorTemperatureVal.GetWithDefault<bool>(false)) { VtValue colorTemperatureVal = sceneDelegate->GetLightParamValue(id, HdLightTokens->colorTemperature); if (colorTemperatureVal.IsHolding<float>()) { float colorTemperature = colorTemperatureVal.Get<float>(); hdc = GfCompMult(hdc, _BlackbodyTemperatureAsRgb(colorTemperature)); } } // Intensity float intensity = sceneDelegate->GetLightParamValue(id, HdLightTokens->intensity).Get<float>(); // Exposure float exposure = sceneDelegate->GetLightParamValue(id, HdLightTokens->exposure).Get<float>(); intensity *= powf(2.0f, GfClamp(exposure, -50.0f, 50.0f)); // Transform { GfMatrix4d transform = sceneDelegate->GetTransform(id); glm::float4x4 xform; for (int i = 0; i < 4; ++i) { for (int j = 0; j < 4; ++j) { xform[i][j] = (float)transform[i][j]; } } mLightDesc.xform = xform; mLightDesc.useXform = true; } mLightDesc.color = glm::float3(hdc[0], hdc[1], hdc[2]); mLightDesc.intensity = intensity; if (mLightType == HdPrimTypeTokens->rectLight) { mLightDesc.type = 0; float width = 0.0f; float height = 0.0f; VtValue widthVal = sceneDelegate->GetLightParamValue(id, HdLightTokens->width); if (widthVal.IsHolding<float>()) { width = widthVal.Get<float>(); } VtValue heightVal = sceneDelegate->GetLightParamValue(id, HdLightTokens->height); if (heightVal.IsHolding<float>()) { height = heightVal.Get<float>(); } mLightDesc.height = height; mLightDesc.width = width; } else if (mLightType == HdPrimTypeTokens->diskLight || mLightType == HdPrimTypeTokens->sphereLight) { mLightDesc.type = mLightType == HdPrimTypeTokens->diskLight ? 1 : 2; float radius = 0.0; VtValue radiusVal = sceneDelegate->GetLightParamValue(id, HdLightTokens->radius); if (radiusVal.IsHolding<float>()) { radius = radiusVal.Get<float>(); } mLightDesc.radius = radius * mLightDesc.xform[0][0]; // uniform scale } else if (mLightType == HdPrimTypeTokens->distantLight) { float angle = 0.0f; mLightDesc.type = 3; // TODO: move to enum VtValue angleVal = sceneDelegate->GetLightParamValue(id, HdLightTokens->angle); if (angleVal.IsHolding<float>()) { angle = angleVal.Get<float>(); } mLightDesc.halfAngle = angle * 0.5f * (M_PI / 180.0f); mLightDesc.intensity /= M_PI * powf(sin(mLightDesc.halfAngle), 2.0f); } } HdDirtyBits HdStrelkaLight::GetInitialDirtyBitsMask() const { return (DirtyParams | DirtyTransform); } oka::Scene::UniformLightDesc HdStrelkaLight::getLightDesc() { return mLightDesc; } PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/MdlParserPlugin.cpp
// Copyright (C) 2021 Pablo Delgado Krämer // // This program is free software: you can redistribute it and/or modify // it under the terms of the GNU General Public License as published by // the Free Software Foundation, either version 3 of the License, or // (at your option) any later version. // // This program is distributed in the hope that it will be useful, // but WITHOUT ANY WARRANTY; without even the implied warranty of // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the // GNU General Public License for more details. // // You should have received a copy of the GNU General Public License // along with this program. If not, see <https://www.gnu.org/licenses/>. #include "MdlParserPlugin.h" #include <pxr/base/tf/staticTokens.h> #include <pxr/usd/sdr/shaderNode.h> #include <pxr/usd/ar/resolver.h> #include "pxr/usd/ar/resolvedPath.h" #include "pxr/usd/ar/asset.h" #include <pxr/usd/ar/ar.h> //#include "Tokens.h" PXR_NAMESPACE_OPEN_SCOPE NDR_REGISTER_PARSER_PLUGIN(HdStrelkaMdlParserPlugin); // clang-format off TF_DEFINE_PRIVATE_TOKENS(_tokens, (mdl) (subIdentifier)); // clang-format on NdrNodeUniquePtr HdStrelkaMdlParserPlugin::Parse(const NdrNodeDiscoveryResult& discoveryResult) { NdrTokenMap metadata = discoveryResult.metadata; metadata[_tokens->subIdentifier] = discoveryResult.subIdentifier; return std::make_unique<SdrShaderNode>(discoveryResult.identifier, discoveryResult.version, discoveryResult.name, discoveryResult.family, _tokens->mdl, discoveryResult.sourceType, discoveryResult.uri, discoveryResult.resolvedUri, NdrPropertyUniquePtrVec{}, metadata); } const NdrTokenVec& HdStrelkaMdlParserPlugin::GetDiscoveryTypes() const { static NdrTokenVec s_discoveryTypes{ _tokens->mdl }; return s_discoveryTypes; } const TfToken& HdStrelkaMdlParserPlugin::GetSourceType() const { return _tokens->mdl; } PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/Instancer.cpp
// Copyright (C) 2021 Pablo Delgado Krämer // // This program is free software: you can redistribute it and/or modify // it under the terms of the GNU General Public License as published by // the Free Software Foundation, either version 3 of the License, or // (at your option) any later version. // // This program is distributed in the hope that it will be useful, // but WITHOUT ANY WARRANTY; without even the implied warranty of // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the // GNU General Public License for more details. // // You should have received a copy of the GNU General Public License // along with this program. If not, see <https://www.gnu.org/licenses/>. #include "Instancer.h" #include <pxr/base/gf/quatd.h> #include <pxr/imaging/hd/sceneDelegate.h> PXR_NAMESPACE_OPEN_SCOPE HdStrelkaInstancer::HdStrelkaInstancer(HdSceneDelegate* delegate, const SdfPath& id) : HdInstancer(delegate, id) { } HdStrelkaInstancer::~HdStrelkaInstancer() { } void HdStrelkaInstancer::Sync(HdSceneDelegate* sceneDelegate, HdRenderParam* renderParam, HdDirtyBits* dirtyBits) { TF_UNUSED(renderParam); _UpdateInstancer(sceneDelegate, dirtyBits); const SdfPath& id = GetId(); if (!HdChangeTracker::IsAnyPrimvarDirty(*dirtyBits, id)) { return; } const HdPrimvarDescriptorVector& primvars = sceneDelegate->GetPrimvarDescriptors(id, HdInterpolation::HdInterpolationInstance); for (const HdPrimvarDescriptor& primvar : primvars) { TfToken primName = primvar.name; if (primName != HdInstancerTokens->translate && primName != HdInstancerTokens->rotate && primName != HdInstancerTokens->scale && primName != HdInstancerTokens->instanceTransform) { continue; } if (!HdChangeTracker::IsPrimvarDirty(*dirtyBits, id, primName)) { continue; } VtValue value = sceneDelegate->Get(id, primName); m_primvarMap[primName] = value; } } VtMatrix4dArray HdStrelkaInstancer::ComputeInstanceTransforms(const SdfPath& prototypeId) { HdSceneDelegate* sceneDelegate = GetDelegate(); const SdfPath& id = GetId(); // Calculate instance transforms for this instancer. VtValue boxedTranslates = m_primvarMap[HdInstancerTokens->translate]; VtValue boxedRotates = m_primvarMap[HdInstancerTokens->rotate]; VtValue boxedScales = m_primvarMap[HdInstancerTokens->scale]; VtValue boxedInstanceTransforms = m_primvarMap[HdInstancerTokens->instanceTransform]; VtVec3fArray translates; if (boxedTranslates.IsHolding<VtVec3fArray>()) { translates = boxedTranslates.UncheckedGet<VtVec3fArray>(); } else if (!boxedTranslates.IsEmpty()) { TF_CODING_WARNING("Instancer translate values are not of type Vec3f!"); } VtVec4fArray rotates; if (boxedRotates.IsHolding<VtVec4fArray>()) { rotates = boxedRotates.Get<VtVec4fArray>(); } else if (!boxedRotates.IsEmpty()) { TF_CODING_WARNING("Instancer rotate values are not of type Vec3f!"); } VtVec3fArray scales; if (boxedScales.IsHolding<VtVec3fArray>()) { scales = boxedScales.Get<VtVec3fArray>(); } else if (!boxedScales.IsEmpty()) { TF_CODING_WARNING("Instancer scale values are not of type Vec3f!"); } VtMatrix4dArray instanceTransforms; if (boxedInstanceTransforms.IsHolding<VtMatrix4dArray>()) { instanceTransforms = boxedInstanceTransforms.Get<VtMatrix4dArray>(); } GfMatrix4d instancerTransform = sceneDelegate->GetInstancerTransform(id); const VtIntArray& instanceIndices = sceneDelegate->GetInstanceIndices(id, prototypeId); VtMatrix4dArray transforms; transforms.resize(instanceIndices.size()); for (size_t i = 0; i < instanceIndices.size(); i++) { int instanceIndex = instanceIndices[i]; GfMatrix4d mat = instancerTransform; GfMatrix4d temp; if (i < translates.size()) { auto trans = GfVec3d(translates[instanceIndex]); temp.SetTranslate(trans); mat = temp * mat; } if (i < rotates.size()) { GfVec4f rot = rotates[instanceIndex]; temp.SetRotate(GfQuatd(rot[0], rot[1], rot[2], rot[3])); mat = temp * mat; } if (i < scales.size()) { auto scale = GfVec3d(scales[instanceIndex]); temp.SetScale(scale); mat = temp * mat; } if (i < instanceTransforms.size()) { temp = instanceTransforms[instanceIndex]; mat = temp * mat; } transforms[i] = mat; } // Calculate instance transforms for all instancer instances. const SdfPath& parentId = GetParentId(); if (parentId.IsEmpty()) { return transforms; } const HdRenderIndex& renderIndex = sceneDelegate->GetRenderIndex(); HdInstancer* boxedParentInstancer = renderIndex.GetInstancer(parentId); HdStrelkaInstancer* parentInstancer = dynamic_cast<HdStrelkaInstancer*>(boxedParentInstancer); VtMatrix4dArray parentTransforms = parentInstancer->ComputeInstanceTransforms(id); VtMatrix4dArray transformProducts; transformProducts.resize(parentTransforms.size() * transforms.size()); for (size_t i = 0; i < parentTransforms.size(); i++) { for (size_t j = 0; j < transforms.size(); j++) { size_t index = i * transforms.size() + j; transformProducts[index] = transforms[j] * parentTransforms[i]; } } return transformProducts; } PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/RenderDelegate.h
#pragma once #include <pxr/imaging/hd/renderDelegate.h> #include "MaterialNetworkTranslator.h" #include <render/common.h> #include <scene/scene.h> #include <render/render.h> PXR_NAMESPACE_OPEN_SCOPE class HdStrelkaRenderDelegate final : public HdRenderDelegate { public: HdStrelkaRenderDelegate(const HdRenderSettingsMap& settingsMap, const MaterialNetworkTranslator& translator); ~HdStrelkaRenderDelegate() override; void SetDrivers(HdDriverVector const& drivers) override; HdRenderSettingDescriptorList GetRenderSettingDescriptors() const override; HdRenderPassSharedPtr CreateRenderPass(HdRenderIndex* index, const HdRprimCollection& collection) override; HdResourceRegistrySharedPtr GetResourceRegistry() const override; void CommitResources(HdChangeTracker* tracker) override; HdInstancer* CreateInstancer(HdSceneDelegate* delegate, const SdfPath& id) override; void DestroyInstancer(HdInstancer* instancer) override; HdAovDescriptor GetDefaultAovDescriptor(const TfToken& name) const override; /* Rprim */ const TfTokenVector& GetSupportedRprimTypes() const override; HdRprim* CreateRprim(const TfToken& typeId, const SdfPath& rprimId) override; void DestroyRprim(HdRprim* rPrim) override; /* Sprim */ const TfTokenVector& GetSupportedSprimTypes() const override; HdSprim* CreateSprim(const TfToken& typeId, const SdfPath& sprimId) override; HdSprim* CreateFallbackSprim(const TfToken& typeId) override; void DestroySprim(HdSprim* sprim) override; /* Bprim */ const TfTokenVector& GetSupportedBprimTypes() const override; HdBprim* CreateBprim(const TfToken& typeId, const SdfPath& bprimId) override; HdBprim* CreateFallbackBprim(const TfToken& typeId) override; void DestroyBprim(HdBprim* bprim) override; TfToken GetMaterialBindingPurpose() const override; // In a USD file, there can be multiple networks associated with a material: // token outputs:mdl:surface.connect = </Root/Glass.outputs:out> // token outputs:surface.connect = </Root/GlassPreviewSurface.outputs:surface> // This function returns the order of preference used when selecting one for rendering. TfTokenVector GetMaterialRenderContexts() const override; TfTokenVector GetShaderSourceTypes() const override; oka::SharedContext& getSharedContext(); private: const MaterialNetworkTranslator& m_translator; HdRenderSettingDescriptorList m_settingDescriptors; HdResourceRegistrySharedPtr m_resourceRegistry; const TfTokenVector SUPPORTED_BPRIM_TYPES = { HdPrimTypeTokens->renderBuffer }; const TfTokenVector SUPPORTED_RPRIM_TYPES = { HdPrimTypeTokens->mesh, HdPrimTypeTokens->basisCurves }; const TfTokenVector SUPPORTED_SPRIM_TYPES = { HdPrimTypeTokens->camera, HdPrimTypeTokens->material, HdPrimTypeTokens->light, HdPrimTypeTokens->rectLight, HdPrimTypeTokens->diskLight, HdPrimTypeTokens->sphereLight, HdPrimTypeTokens->distantLight, }; oka::SharedContext* mSharedCtx; oka::Scene mScene; oka::Render* mRenderer; }; PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/RenderDelegate.cpp
#include "RenderDelegate.h" #include "Camera.h" #include "Instancer.h" #include "Light.h" #include "Material.h" #include "Mesh.h" #include "BasisCurves.h" #include "RenderBuffer.h" #include "RenderPass.h" #include "Tokens.h" #include <pxr/base/gf/vec4f.h> #include <pxr/imaging/hd/resourceRegistry.h> #include <log.h> #include <memory> PXR_NAMESPACE_OPEN_SCOPE TF_DEFINE_PRIVATE_TOKENS(_Tokens, (HdStrelkaDriver)); HdStrelkaRenderDelegate::HdStrelkaRenderDelegate(const HdRenderSettingsMap& settingsMap, const MaterialNetworkTranslator& translator) : m_translator(translator) { m_resourceRegistry = std::make_shared<HdResourceRegistry>(); m_settingDescriptors.push_back( HdRenderSettingDescriptor{ "Samples per pixel", HdStrelkaSettingsTokens->spp, VtValue{ 8 } }); m_settingDescriptors.push_back( HdRenderSettingDescriptor{ "Max bounces", HdStrelkaSettingsTokens->max_bounces, VtValue{ 4 } }); _PopulateDefaultSettings(m_settingDescriptors); for (const auto& setting : settingsMap) { const TfToken& key = setting.first; const VtValue& value = setting.second; _settingsMap[key] = value; } oka::RenderType type = oka::RenderType::eOptiX; #ifdef __APPLE__ type = oka::RenderType::eMetal; #endif mRenderer = oka::RenderFactory::createRender(type); mRenderer->setScene(&mScene); } HdStrelkaRenderDelegate::~HdStrelkaRenderDelegate() { } void HdStrelkaRenderDelegate::SetDrivers(HdDriverVector const& drivers) { for (HdDriver* hdDriver : drivers) { if (hdDriver->name == _Tokens->HdStrelkaDriver && hdDriver->driver.IsHolding<oka::SharedContext*>()) { assert(mRenderer); mSharedCtx = hdDriver->driver.UncheckedGet<oka::SharedContext*>(); mRenderer->setSharedContext(mSharedCtx); mRenderer->init(); mSharedCtx->mRender = mRenderer; break; } } } HdRenderSettingDescriptorList HdStrelkaRenderDelegate::GetRenderSettingDescriptors() const { return m_settingDescriptors; } HdRenderPassSharedPtr HdStrelkaRenderDelegate::CreateRenderPass(HdRenderIndex* index, const HdRprimCollection& collection) { return HdRenderPassSharedPtr(new HdStrelkaRenderPass(index, collection, _settingsMap, mRenderer, &mScene)); } HdResourceRegistrySharedPtr HdStrelkaRenderDelegate::GetResourceRegistry() const { return m_resourceRegistry; } void HdStrelkaRenderDelegate::CommitResources(HdChangeTracker* tracker) { TF_UNUSED(tracker); // We delay BVH building and GPU uploads to the next render call. } HdInstancer* HdStrelkaRenderDelegate::CreateInstancer(HdSceneDelegate* delegate, const SdfPath& id) { return new HdStrelkaInstancer(delegate, id); } void HdStrelkaRenderDelegate::DestroyInstancer(HdInstancer* instancer) { delete instancer; } HdAovDescriptor HdStrelkaRenderDelegate::GetDefaultAovDescriptor(const TfToken& name) const { TF_UNUSED(name); HdAovDescriptor aovDescriptor; aovDescriptor.format = HdFormatFloat32Vec4; aovDescriptor.multiSampled = false; aovDescriptor.clearValue = GfVec4f(0.0f, 0.0f, 0.0f, 0.0f); return aovDescriptor; } const TfTokenVector& HdStrelkaRenderDelegate::GetSupportedRprimTypes() const { return SUPPORTED_RPRIM_TYPES; } HdRprim* HdStrelkaRenderDelegate::CreateRprim(const TfToken& typeId, const SdfPath& rprimId) { if (typeId == HdPrimTypeTokens->mesh) { return new HdStrelkaMesh(rprimId, &mScene); } else if (typeId == HdPrimTypeTokens->basisCurves) { return new HdStrelkaBasisCurves(rprimId, &mScene); } STRELKA_ERROR("Unknown Rprim Type {}", typeId.GetText()); return nullptr; } void HdStrelkaRenderDelegate::DestroyRprim(HdRprim* rprim) { delete rprim; } const TfTokenVector& HdStrelkaRenderDelegate::GetSupportedSprimTypes() const { return SUPPORTED_SPRIM_TYPES; } HdSprim* HdStrelkaRenderDelegate::CreateSprim(const TfToken& typeId, const SdfPath& sprimId) { STRELKA_DEBUG("CreateSprim Type: {}", typeId.GetText()); if (sprimId.IsEmpty()) { STRELKA_DEBUG("skipping creation of empty sprim path"); return nullptr; } HdSprim* res = nullptr; if (typeId == HdPrimTypeTokens->camera) { res = new HdStrelkaCamera(sprimId, mScene); } else if (typeId == HdPrimTypeTokens->material) { res = new HdStrelkaMaterial(sprimId, m_translator); } else if (typeId == HdPrimTypeTokens->rectLight || typeId == HdPrimTypeTokens->diskLight || typeId == HdPrimTypeTokens->sphereLight || typeId == HdPrimTypeTokens->distantLight) { res = new HdStrelkaLight(sprimId, typeId); } else { STRELKA_ERROR("Unknown Sprim Type {}", typeId.GetText()); } return res; } HdSprim* HdStrelkaRenderDelegate::CreateFallbackSprim(const TfToken& typeId) { const SdfPath& sprimId = SdfPath::EmptyPath(); return CreateSprim(typeId, sprimId); } void HdStrelkaRenderDelegate::DestroySprim(HdSprim* sprim) { delete sprim; } const TfTokenVector& HdStrelkaRenderDelegate::GetSupportedBprimTypes() const { return SUPPORTED_BPRIM_TYPES; } HdBprim* HdStrelkaRenderDelegate::CreateBprim(const TfToken& typeId, const SdfPath& bprimId) { if (typeId == HdPrimTypeTokens->renderBuffer) { return new HdStrelkaRenderBuffer(bprimId, mSharedCtx); } return nullptr; } HdBprim* HdStrelkaRenderDelegate::CreateFallbackBprim(const TfToken& typeId) { const SdfPath& bprimId = SdfPath::EmptyPath(); return CreateBprim(typeId, bprimId); } void HdStrelkaRenderDelegate::DestroyBprim(HdBprim* bprim) { delete bprim; } TfToken HdStrelkaRenderDelegate::GetMaterialBindingPurpose() const { //return HdTokens->full; return HdTokens->preview; } TfTokenVector HdStrelkaRenderDelegate::GetMaterialRenderContexts() const { return TfTokenVector{ HdStrelkaRenderContexts->mtlx, HdStrelkaRenderContexts->mdl }; } TfTokenVector HdStrelkaRenderDelegate::GetShaderSourceTypes() const { return TfTokenVector{ HdStrelkaSourceTypes->mtlx, HdStrelkaSourceTypes->mdl }; } oka::SharedContext& HdStrelkaRenderDelegate::getSharedContext() { return mRenderer->getSharedContext(); } PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/BasisCurves.cpp
#include "BasisCurves.h" #include <log.h> PXR_NAMESPACE_OPEN_SCOPE void HdStrelkaBasisCurves::Sync(HdSceneDelegate* sceneDelegate, HdRenderParam* renderParam, HdDirtyBits* dirtyBits, const TfToken& reprToken) { TF_UNUSED(renderParam); TF_UNUSED(reprToken); HdRenderIndex& renderIndex = sceneDelegate->GetRenderIndex(); const SdfPath& id = GetId(); mName = id.GetText(); STRELKA_INFO("Curve Name: {}", mName.c_str()); if (*dirtyBits & HdChangeTracker::DirtyMaterialId) { const SdfPath& materialId = sceneDelegate->GetMaterialId(id); SetMaterialId(materialId); } if (*dirtyBits & HdChangeTracker::DirtyTopology) { mTopology = sceneDelegate->GetBasisCurvesTopology(id); } if (*dirtyBits & HdChangeTracker::DirtyTransform) { m_prototypeTransform = sceneDelegate->GetTransform(id); } bool updateGeometry = (*dirtyBits & HdChangeTracker::DirtyPoints) | (*dirtyBits & HdChangeTracker::DirtyNormals) | (*dirtyBits & HdChangeTracker::DirtyTopology); *dirtyBits = HdChangeTracker::Clean; if (!updateGeometry) { return; } // m_faces.clear(); mPoints.clear(); mNormals.clear(); _UpdateGeometry(sceneDelegate); } bool HdStrelkaBasisCurves::_FindPrimvar(HdSceneDelegate* sceneDelegate, const TfToken& primvarName, HdInterpolation& interpolation) const { HdInterpolation interpolations[] = { HdInterpolation::HdInterpolationVertex, HdInterpolation::HdInterpolationFaceVarying, HdInterpolation::HdInterpolationConstant, HdInterpolation::HdInterpolationUniform, HdInterpolation::HdInterpolationVarying, HdInterpolation::HdInterpolationInstance }; for (HdInterpolation i : interpolations) { const auto& primvarDescs = GetPrimvarDescriptors(sceneDelegate, i); for (const HdPrimvarDescriptor& primvar : primvarDescs) { if (primvar.name == primvarName) { interpolation = i; return true; } } } return false; } void HdStrelkaBasisCurves::_PullPrimvars(HdSceneDelegate* sceneDelegate, VtVec3fArray& points, VtVec3fArray& normals, VtFloatArray& widths, bool& indexedNormals, bool& indexedUVs, GfVec3f& color, bool& hasColor) const { const SdfPath& id = GetId(); // Handle points. HdInterpolation pointInterpolation; bool foundPoints = _FindPrimvar(sceneDelegate, HdTokens->points, pointInterpolation); if (!foundPoints) { STRELKA_ERROR("Points primvar not found!"); return; } else if (pointInterpolation != HdInterpolation::HdInterpolationVertex) { STRELKA_ERROR("Points primvar is not vertex-interpolated!"); return; } VtValue boxedPoints = sceneDelegate->Get(id, HdTokens->points); points = boxedPoints.Get<VtVec3fArray>(); // Handle color. HdInterpolation colorInterpolation; bool foundColor = _FindPrimvar(sceneDelegate, HdTokens->displayColor, colorInterpolation); if (foundColor && colorInterpolation == HdInterpolation::HdInterpolationConstant) { VtValue boxedColors = sceneDelegate->Get(id, HdTokens->displayColor); const VtVec3fArray& colors = boxedColors.Get<VtVec3fArray>(); color = colors[0]; hasColor = true; } HdBasisCurvesTopology topology = GetBasisCurvesTopology(sceneDelegate); VtIntArray curveVertexCounts = topology.GetCurveVertexCounts(); // Handle normals. HdInterpolation normalInterpolation; bool foundNormals = _FindPrimvar(sceneDelegate, HdTokens->normals, normalInterpolation); if (foundNormals && normalInterpolation == HdInterpolation::HdInterpolationVarying) { VtValue boxedNormals = sceneDelegate->Get(id, HdTokens->normals); normals = boxedNormals.Get<VtVec3fArray>(); indexedNormals = true; } // Handle width. HdInterpolation widthInterpolation; bool foundWidth = _FindPrimvar(sceneDelegate, HdTokens->widths, widthInterpolation); if (foundWidth) { VtValue boxedWidths = sceneDelegate->Get(id, HdTokens->widths); widths = boxedWidths.Get<VtFloatArray>(); } } void HdStrelkaBasisCurves::_UpdateGeometry(HdSceneDelegate* sceneDelegate) { const HdBasisCurvesTopology& topology = mTopology; const SdfPath& id = GetId(); // Get USD Curve Metadata mVertexCounts = topology.GetCurveVertexCounts(); TfToken curveType = topology.GetCurveType(); TfToken curveBasis = topology.GetCurveBasis(); TfToken curveWrap = topology.GetCurveWrap(); size_t num_curves = mVertexCounts.size(); size_t num_keys = 0; bool indexedNormals; bool indexedUVs; bool hasColor = true; _PullPrimvars(sceneDelegate, mPoints, mNormals, mWidths, indexedNormals, indexedUVs, mColor, hasColor); _ConvertCurve(); } HdStrelkaBasisCurves::HdStrelkaBasisCurves(const SdfPath& id, oka::Scene* scene) : HdBasisCurves(id), mScene(scene) { } HdStrelkaBasisCurves::~HdStrelkaBasisCurves() { } HdDirtyBits HdStrelkaBasisCurves::GetInitialDirtyBitsMask() const { return HdChangeTracker::DirtyPoints | HdChangeTracker::DirtyNormals | HdChangeTracker::DirtyTopology | HdChangeTracker::DirtyInstancer | HdChangeTracker::DirtyInstanceIndex | HdChangeTracker::DirtyTransform | HdChangeTracker::DirtyMaterialId | HdChangeTracker::DirtyPrimvar; } HdDirtyBits HdStrelkaBasisCurves::_PropagateDirtyBits(HdDirtyBits bits) const { return bits; } void HdStrelkaBasisCurves::_InitRepr(const TfToken& reprName, HdDirtyBits* dirtyBits) { TF_UNUSED(reprName); TF_UNUSED(dirtyBits); } void HdStrelkaBasisCurves::_ConvertCurve() { // calculate phantom points // https://raytracing-docs.nvidia.com/optix7/guide/index.html#curves#differences-between-curves-spheres-and-triangles glm::float3 p1 = glm::float3(mPoints[0][0], mPoints[0][1], mPoints[0][2]); glm::float3 p2 = glm::float3(mPoints[1][0], mPoints[1][1], mPoints[1][2]); glm::float3 p0 = p1 + (p1 - p2); mCurvePoints.push_back(p0); for (const GfVec3f& p : mPoints) { mCurvePoints.push_back(glm::float3(p[0], p[1], p[2])); } int n = mPoints.size() - 1; glm::float3 pn = glm::float3(mPoints[n][0], mPoints[n][1], mPoints[n][2]); glm::float3 pn1 = glm::float3(mPoints[n - 1][0], mPoints[n - 1][1], mPoints[n - 1][2]); glm::float3 pnn = pn + (pn - pn1); mCurvePoints.push_back(pnn); mCurveWidths.push_back(mWidths[0] * 0.5); assert((mWidths.size() == mPoints.size()) || (mWidths.size() == 1)); if (mWidths.size() == 1) { for (int i = 0; i < mPoints.size(); ++i) { mCurveWidths.push_back(mWidths[0] * 0.5); } } else { for (const float w : mWidths) { mCurveWidths.push_back(w * 0.5f); } } mCurveWidths.push_back(mCurveWidths.back()); for (const int i : mVertexCounts) { mCurveVertexCounts.push_back(i); } } const std::vector<glm::float3>& HdStrelkaBasisCurves::GetPoints() const { return mCurvePoints; } const std::vector<float>& HdStrelkaBasisCurves::GetWidths() const { return mCurveWidths; } const std::vector<uint32_t>& HdStrelkaBasisCurves::GetVertexCounts() const { return mCurveVertexCounts; } const GfMatrix4d& HdStrelkaBasisCurves::GetPrototypeTransform() const { return m_prototypeTransform; } const char* HdStrelkaBasisCurves::getName() const { return mName.c_str(); } PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/RenderBuffer.cpp
#include "RenderBuffer.h" #include "render.h" #include <pxr/base/gf/vec3i.h> PXR_NAMESPACE_OPEN_SCOPE HdStrelkaRenderBuffer::HdStrelkaRenderBuffer(const SdfPath& id, oka::SharedContext* ctx) : HdRenderBuffer(id), mCtx(ctx) { m_isMapped = false; m_isConverged = false; m_bufferMem = nullptr; } HdStrelkaRenderBuffer::~HdStrelkaRenderBuffer() { _Deallocate(); } bool HdStrelkaRenderBuffer::Allocate(const GfVec3i& dimensions, HdFormat format, bool multiSampled) { if (dimensions[2] != 1) { return false; } m_width = dimensions[0]; m_height = dimensions[1]; m_format = format; m_isMultiSampled = multiSampled; size_t size = m_width * m_height * HdDataSizeOfFormat(m_format); m_bufferMem = realloc(m_bufferMem, size); if (!m_bufferMem) { return false; } if (mResult) { mResult->resize(m_width, m_height); } else { oka::BufferDesc desc{}; desc.format = oka::BufferFormat::FLOAT4; desc.width = m_width; desc.height = m_height; mResult = mCtx->mRender->createBuffer(desc); } if (!mResult) { return false; } return true; } unsigned int HdStrelkaRenderBuffer::GetWidth() const { return m_width; } unsigned int HdStrelkaRenderBuffer::GetHeight() const { return m_height; } unsigned int HdStrelkaRenderBuffer::GetDepth() const { return 1u; } HdFormat HdStrelkaRenderBuffer::GetFormat() const { return m_format; } bool HdStrelkaRenderBuffer::IsMultiSampled() const { return m_isMultiSampled; } VtValue HdStrelkaRenderBuffer::GetResource(bool multiSampled) const { return VtValue((uint8_t*)mResult); } bool HdStrelkaRenderBuffer::IsConverged() const { return m_isConverged; } void HdStrelkaRenderBuffer::SetConverged(bool converged) { m_isConverged = converged; } void* HdStrelkaRenderBuffer::Map() { m_isMapped = true; return m_bufferMem; } bool HdStrelkaRenderBuffer::IsMapped() const { return m_isMapped; } void HdStrelkaRenderBuffer::Unmap() { m_isMapped = false; } void HdStrelkaRenderBuffer::Resolve() { } void HdStrelkaRenderBuffer::_Deallocate() { free(m_bufferMem); delete mResult; } PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/Tokens.h
#pragma once #include <pxr/base/tf/staticTokens.h> PXR_NAMESPACE_OPEN_SCOPE #define HD_STRELKA_SETTINGS_TOKENS \ ((spp, "spp"))((max_bounces, "max-bounces")) // mtlx node identifier is given by usdMtlx. #define HD_STRELKA_NODE_IDENTIFIER_TOKENS \ (mtlx)(mdl) #define HD_STRELKA_SOURCE_TYPE_TOKENS \ (mtlx)(mdl) #define HD_STRELKA_DISCOVERY_TYPE_TOKENS \ (mtlx)(mdl) #define HD_STRELKA_RENDER_CONTEXT_TOKENS \ (mtlx)(mdl) #define HD_STRELKA_NODE_CONTEXT_TOKENS \ (mtlx)(mdl) #define HD_STRELKA_NODE_METADATA_TOKENS \ (subIdentifier) TF_DECLARE_PUBLIC_TOKENS(HdStrelkaSettingsTokens, HD_STRELKA_SETTINGS_TOKENS); TF_DECLARE_PUBLIC_TOKENS(HdStrelkaNodeIdentifiers, HD_STRELKA_NODE_IDENTIFIER_TOKENS); TF_DECLARE_PUBLIC_TOKENS(HdStrelkaSourceTypes, HD_STRELKA_SOURCE_TYPE_TOKENS); TF_DECLARE_PUBLIC_TOKENS(HdStrelkaDiscoveryTypes, HD_STRELKA_DISCOVERY_TYPE_TOKENS); TF_DECLARE_PUBLIC_TOKENS(HdStrelkaRenderContexts, HD_STRELKA_RENDER_CONTEXT_TOKENS); TF_DECLARE_PUBLIC_TOKENS(HdStrelkaNodeContexts, HD_STRELKA_NODE_CONTEXT_TOKENS); TF_DECLARE_PUBLIC_TOKENS(HdStrelkaNodeMetadata, HD_STRELKA_NODE_METADATA_TOKENS); PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/Camera.h
#pragma once #include <pxr/imaging/hd/camera.h> #include <scene/scene.h> PXR_NAMESPACE_OPEN_SCOPE class HdStrelkaCamera final : public HdCamera { public: HdStrelkaCamera(const SdfPath& id, oka::Scene& scene); ~HdStrelkaCamera() override; public: float GetVFov() const; uint32_t GetCameraIndex() const; public: void Sync(HdSceneDelegate* sceneDelegate, HdRenderParam* renderParam, HdDirtyBits* dirtyBits) override; HdDirtyBits GetInitialDirtyBitsMask() const override; private: oka::Camera _ConstructStrelkaCamera(); float m_vfov; oka::Scene& mScene; uint32_t mCameraIndex = -1; }; PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/MdlDiscoveryPlugin.cpp
#include "MdlDiscoveryPlugin.h" #include <pxr/base/tf/staticTokens.h> //#include "Tokens.h" PXR_NAMESPACE_OPEN_SCOPE // clang-format off TF_DEFINE_PRIVATE_TOKENS(_tokens, (mdl) ); // clang-format on NDR_REGISTER_DISCOVERY_PLUGIN(HdStrelkaMdlDiscoveryPlugin); NdrNodeDiscoveryResultVec HdStrelkaMdlDiscoveryPlugin::DiscoverNodes(const Context& ctx) { NdrNodeDiscoveryResultVec result; NdrNodeDiscoveryResult mdlNode( /* identifier */ _tokens->mdl, /* version */ NdrVersion(1), /* name */ _tokens->mdl, /* family */ TfToken(), /* discoveryType */ _tokens->mdl, /* sourceType */ _tokens->mdl, /* uri */ std::string(), /* resolvedUri */ std::string()); result.push_back(mdlNode); return result; } const NdrStringVec& HdStrelkaMdlDiscoveryPlugin::GetSearchURIs() const { static const NdrStringVec s_searchURIs; return s_searchURIs; } PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/plugInfo.json
{ "Plugins": [ { "Info": { "Types": { "HdStrelkaRendererPlugin": { "bases": [ "HdRendererPlugin" ], "displayName": "Strelka", "priority": 99 }, "HdStrelkaMdlDiscoveryPlugin": { "bases": ["NdrDiscoveryPlugin"], "displayName": "MDL Discovery" }, "HdStrelkaMdlParserPlugin": { "bases": ["NdrParserPlugin"], "displayName": "MDL Node Parser" } } }, "LibraryPath": "../HdStrelka.dylib", "Name": "HdStrelka", "ResourcePath": "resources", "Root": "..", "Type": "library" } ] }
arhix52/Strelka/src/HdStrelka/CMakeLists.txt
cmake_minimum_required(VERSION 3.22) find_package(USD REQUIRED HINTS ${USD_DIR} NAMES pxr) message(STATUS "USD LIBRARY: ${USD_DIR}") set(CMAKE_EXPORT_COMPILE_COMMANDS ON) set(CMAKE_POSITION_INDEPENDENT_CODE ON) set(CMAKE_CXX_STANDARD 17) set(CMAKE_CXX_STANDARD_REQUIRED ON) set(CMAKE_CXX_EXTENSIONS OFF) add_compile_definitions(BOOST_NO_CXX98_FUNCTION_BASE) # Hydra plugin set(HD_PLUGIN_SOURCES ${ROOT_HOME}/include/HdStrelka/RendererPlugin.h ${ROOT_HOME}/src/HdStrelka/RendererPlugin.cpp ${ROOT_HOME}/src/HdStrelka/RenderParam.h ${ROOT_HOME}/src/HdStrelka/RenderBuffer.h ${ROOT_HOME}/src/HdStrelka/RenderDelegate.h ${ROOT_HOME}/src/HdStrelka/RenderPass.h ${ROOT_HOME}/src/HdStrelka/RenderBuffer.cpp ${ROOT_HOME}/src/HdStrelka/RenderDelegate.cpp ${ROOT_HOME}/src/HdStrelka/RenderPass.cpp ${ROOT_HOME}/src/HdStrelka/Instancer.h ${ROOT_HOME}/src/HdStrelka/Instancer.cpp ${ROOT_HOME}/src/HdStrelka/Material.h ${ROOT_HOME}/src/HdStrelka/Material.cpp ${ROOT_HOME}/src/HdStrelka/Camera.h ${ROOT_HOME}/src/HdStrelka/Camera.cpp ${ROOT_HOME}/src/HdStrelka/Mesh.h ${ROOT_HOME}/src/HdStrelka/Mesh.cpp ${ROOT_HOME}/src/HdStrelka/BasisCurves.h ${ROOT_HOME}/src/HdStrelka/BasisCurves.cpp ${ROOT_HOME}/src/HdStrelka/Light.h ${ROOT_HOME}/src/HdStrelka/Light.cpp ${ROOT_HOME}/src/HdStrelka/Tokens.h ${ROOT_HOME}/src/HdStrelka/Tokens.cpp ${ROOT_HOME}/src/HdStrelka/MaterialNetworkTranslator.h ${ROOT_HOME}/src/HdStrelka/MaterialNetworkTranslator.cpp ${ROOT_HOME}/src/HdStrelka/MdlParserPlugin.h ${ROOT_HOME}/src/HdStrelka/MdlParserPlugin.cpp ${ROOT_HOME}/src/HdStrelka/MdlDiscoveryPlugin.h ${ROOT_HOME}/src/HdStrelka/MdlDiscoveryPlugin.cpp) set(HD_PLUGIN_NAME HdStrelka) set(Boost_USE_STATIC_LIBS OFF) set(BUILD_SHARED_LIBS ON) add_library(${HD_PLUGIN_NAME} SHARED ${HD_PLUGIN_SOURCES}) set_target_properties( ${HD_PLUGIN_NAME} PROPERTIES LINKER_LANGUAGE CXX CXX_STANDARD 17 CXX_STANDARD_REQUIRED ON CXX_EXTENSIONS OFF INSTALL_RPATH_USE_LINK_PATH TRUE # The other libs in the plugin dir have no "lib" prefix, so let's # match this PREFIX "") target_compile_definitions( ${HD_PLUGIN_NAME} PUBLIC # Required for PLUG_THIS_PLUGIN macro MFB_PACKAGE_NAME=${HD_PLUGIN_NAME} PRIVATE # Workaround for # https://github.com/PixarAnimationStudios/USD/issues/1471#issuecomment-799813477 "$<$<OR:$<CONFIG:>,$<CONFIG:Debug>>:TBB_USE_DEBUG>") # Workaround for https://github.com/PixarAnimationStudios/USD/issues/1279 if(MSVC_VERSION GREATER_EQUAL 1920) target_compile_options(${HD_PLUGIN_NAME} PRIVATE "/Zc:inline-") endif() set(Boost_USE_STATIC_LIBS OFF) set(BUILD_SHARED_LIBS ON) target_include_directories(${HD_PLUGIN_NAME} PUBLIC ${ROOT_HOME}/include/log) target_include_directories(${HD_PLUGIN_NAME} PUBLIC ${ROOT_HOME}/include/HdStrelka) target_include_directories(${HD_PLUGIN_NAME} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) target_include_directories(${HD_PLUGIN_NAME} PUBLIC hd) target_include_directories(${HD_PLUGIN_NAME} PRIVATE usdImaging hdMtlx) # Add the linker options to suppress the MSVCRT conflict warning if(WIN32) target_link_options(${HD_PLUGIN_NAME} PRIVATE "/NODEFAULTLIB:MSVCRT") target_link_options(${HD_PLUGIN_NAME} PRIVATE "/NODEFAULTLIB:LIBCMT") endif() if(WIN32 OR LINUX) target_link_libraries( ${HD_PLUGIN_NAME} PRIVATE usdImaging hdMtlx render scene materialmanager PUBLIC hd) endif() if(APPLE) target_include_directories(${HD_PLUGIN_NAME} PUBLIC ${ROOT_HOME}/include/materialmanager) target_link_libraries( ${HD_PLUGIN_NAME} PRIVATE usdImaging hdMtlx render scene PUBLIC hd) target_link_libraries(${HD_PLUGIN_NAME} PUBLIC "-framework Foundation") target_link_libraries(${HD_PLUGIN_NAME} PUBLIC "-framework QuartzCore") target_link_libraries(${HD_PLUGIN_NAME} PUBLIC "-framework Metal") target_link_libraries(${HD_PLUGIN_NAME} PUBLIC "-framework MetalKit") endif(APPLE) target_link_libraries(${HD_PLUGIN_NAME} PUBLIC logger) set(PLUGINFO_PATH "${CMAKE_CURRENT_BINARY_DIR}/plugInfo.json") set(CMAKE_INSTALL_PREFIX "${USD_DIR}/plugin/usd/") file(READ ${CMAKE_CURRENT_SOURCE_DIR}/plugInfo.json.in PLUGINFO) file( GENERATE OUTPUT "${PLUGINFO_PATH}" CONTENT ${PLUGINFO}) install( FILES "${PLUGINFO_PATH}" DESTINATION "${CMAKE_INSTALL_PREFIX}/HdStrelka/resources" COMPONENT ${HD_PLUGIN_NAME}) install( TARGETS ${HD_PLUGIN_NAME} LIBRARY DESTINATION "${CMAKE_INSTALL_PREFIX}" COMPONENT ${HD_PLUGIN_NAME} RUNTIME DESTINATION "${CMAKE_INSTALL_PREFIX}" COMPONENT ${HD_PLUGIN_NAME} ARCHIVE DESTINATION "${CMAKE_INSTALL_PREFIX}" COMPONENT ${HD_PLUGIN_NAME})
arhix52/Strelka/src/HdStrelka/Material.cpp
#include "Material.h" #include <pxr/base/gf/vec2f.h> #include <pxr/usd/sdr/registry.h> #include <pxr/usdImaging/usdImaging/tokens.h> #include <log.h> PXR_NAMESPACE_OPEN_SCOPE HdStrelkaMaterial::HdStrelkaMaterial(const SdfPath& id, const MaterialNetworkTranslator& translator) : HdMaterial(id), m_translator(translator) { } HdStrelkaMaterial::~HdStrelkaMaterial() = default; HdDirtyBits HdStrelkaMaterial::GetInitialDirtyBitsMask() const { // return DirtyBits::DirtyParams; return DirtyBits::AllDirty; } void HdStrelkaMaterial::Sync(HdSceneDelegate* sceneDelegate, HdRenderParam* renderParam, HdDirtyBits* dirtyBits) { TF_UNUSED(renderParam); const bool pullMaterial = (*dirtyBits & DirtyBits::DirtyParams) != 0u; *dirtyBits = DirtyBits::Clean; if (!pullMaterial) { return; } const SdfPath& id = GetId(); const std::string& name = id.GetString(); STRELKA_INFO("Hydra Material: {}", name.c_str()); const VtValue& resource = sceneDelegate->GetMaterialResource(id); if (!resource.IsHolding<HdMaterialNetworkMap>()) { return; } auto networkMap = resource.GetWithDefault<HdMaterialNetworkMap>(); HdMaterialNetwork& surfaceNetwork = networkMap.map[HdMaterialTerminalTokens->surface]; bool isUsdPreviewSurface = false; HdMaterialNode* previewSurfaceNode = nullptr; // store material parameters uint32_t nodeIdx = 0; for (auto& node : surfaceNetwork.nodes) { STRELKA_DEBUG("Node #{}: {}", nodeIdx, node.path.GetText()); if (node.identifier == UsdImagingTokens->UsdPreviewSurface) { previewSurfaceNode = &node; isUsdPreviewSurface = true; } for (const auto& params : node.parameters) { const std::string& name = params.first.GetString(); const TfType type = params.second.GetType(); STRELKA_DEBUG("Node name: {}\tParam name: {}\t{}", node.path.GetName(), name.c_str(), params.second.GetTypeName().c_str()); if (type.IsA<GfVec3f>()) { oka::MaterialManager::Param param; param.name = params.first; param.type = oka::MaterialManager::Param::Type::eFloat3; GfVec3f val = params.second.Get<GfVec3f>(); param.value.resize(sizeof(val)); memcpy(param.value.data(), &val, sizeof(val)); mMaterialParams.push_back(param); } else if (type.IsA<GfVec4f>()) { oka::MaterialManager::Param param; param.name = params.first; param.type = oka::MaterialManager::Param::Type::eFloat4; GfVec4f val = params.second.Get<GfVec4f>(); param.value.resize(sizeof(val)); memcpy(param.value.data(), &val, sizeof(val)); mMaterialParams.push_back(param); } else if (type.IsA<float>()) { oka::MaterialManager::Param param; param.name = params.first; param.type = oka::MaterialManager::Param::Type::eFloat; float val = params.second.Get<float>(); param.value.resize(sizeof(val)); memcpy(param.value.data(), &val, sizeof(val)); mMaterialParams.push_back(param); } else if (type.IsA<int>()) { oka::MaterialManager::Param param; param.name = params.first; param.type = oka::MaterialManager::Param::Type::eInt; int val = params.second.Get<int>(); param.value.resize(sizeof(val)); memcpy(param.value.data(), &val, sizeof(val)); mMaterialParams.push_back(param); } else if (type.IsA<bool>()) { oka::MaterialManager::Param param; param.name = params.first; param.type = oka::MaterialManager::Param::Type::eBool; bool val = params.second.Get<bool>(); param.value.resize(sizeof(val)); memcpy(param.value.data(), &val, sizeof(val)); mMaterialParams.push_back(param); } else if (type.IsA<SdfAssetPath>()) { oka::MaterialManager::Param param; param.name = node.path.GetName() + "_" + std::string(params.first); param.type = oka::MaterialManager::Param::Type::eTexture; const SdfAssetPath val = params.second.Get<SdfAssetPath>(); // STRELKA_DEBUG("path: {}", val.GetAssetPath().c_str()); STRELKA_DEBUG("path: {}", val.GetResolvedPath().c_str()); // std::string texPath = val.GetAssetPath(); std::string texPath = val.GetResolvedPath(); if (!texPath.empty()) { param.value.resize(texPath.size()); memcpy(param.value.data(), texPath.data(), texPath.size()); mMaterialParams.push_back(param); } } else if (type.IsA<GfVec2f>()) { oka::MaterialManager::Param param; param.name = params.first; param.type = oka::MaterialManager::Param::Type::eFloat2; GfVec2f val = params.second.Get<GfVec2f>(); param.value.resize(sizeof(val)); memcpy(param.value.data(), &val, sizeof(val)); mMaterialParams.push_back(param); } else if (type.IsA<TfToken>()) { const TfToken val = params.second.Get<TfToken>(); STRELKA_DEBUG("TfToken: {}", val.GetText()); } else if (type.IsA<std::string>()) { const std::string val = params.second.Get<std::string>(); STRELKA_DEBUG("String: {}", val.c_str()); } else { STRELKA_ERROR("Unknown parameter type!\n"); } } nodeIdx++; } bool isVolume = false; const HdMaterialNetwork2 network = HdConvertToHdMaterialNetwork2(networkMap, &isVolume); if (isVolume) { STRELKA_ERROR("Volume %s unsupported", id.GetText()); return; } if (isUsdPreviewSurface) { mMaterialXCode = m_translator.ParseNetwork(id, network); // STRELKA_DEBUG("MaterialX code:\n {}\n", mMaterialXCode.c_str()); } else { // MDL const bool res = MaterialNetworkTranslator::ParseMdlNetwork(network, mMdlFileUri, mMdlSubIdentifier); if (!res) { STRELKA_ERROR("Failed to translate material, replace to default!"); mMdlFileUri = "default.mdl"; mMdlSubIdentifier = "default_material"; } mIsMdl = true; } } const std::string& HdStrelkaMaterial::GetStrelkaMaterial() const { return mMaterialXCode; } PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/Camera.cpp
#include "Camera.h" #include <pxr/imaging/hd/sceneDelegate.h> #include <pxr/base/gf/vec4d.h> #include <pxr/base/gf/camera.h> #include <cmath> #include <glm/glm.hpp> #include <glm/gtc/matrix_transform.hpp> #include <glm/gtc/quaternion.hpp> #include <glm/gtc/type_ptr.hpp> #include <glm/gtx/compatibility.hpp> #include <glm/gtx/matrix_decompose.hpp> PXR_NAMESPACE_OPEN_SCOPE HdStrelkaCamera::HdStrelkaCamera(const SdfPath& id, oka::Scene& scene) : HdCamera(id), mScene(scene), m_vfov(M_PI_2) { const std::string& name = id.GetString(); oka::Camera okaCamera; okaCamera.name = name; mCameraIndex = mScene.addCamera(okaCamera); } HdStrelkaCamera::~HdStrelkaCamera() { } float HdStrelkaCamera::GetVFov() const { return m_vfov; } uint32_t HdStrelkaCamera::GetCameraIndex() const { return mCameraIndex; } void HdStrelkaCamera::Sync(HdSceneDelegate* sceneDelegate, HdRenderParam* renderParam, HdDirtyBits* dirtyBits) { HdDirtyBits dirtyBitsCopy = *dirtyBits; HdCamera::Sync(sceneDelegate, renderParam, &dirtyBitsCopy); if (*dirtyBits & DirtyBits::DirtyParams) { // See https://wiki.panotools.org/Field_of_View float aperture = _verticalAperture * GfCamera::APERTURE_UNIT; float focalLength = _focalLength * GfCamera::FOCAL_LENGTH_UNIT; float vfov = 2.0f * std::atan(aperture / (2.0f * focalLength)); m_vfov = vfov; oka::Camera cam = _ConstructStrelkaCamera(); mScene.updateCamera(cam, mCameraIndex); } *dirtyBits = DirtyBits::Clean; } HdDirtyBits HdStrelkaCamera::GetInitialDirtyBitsMask() const { return DirtyBits::DirtyParams | DirtyBits::DirtyTransform; } oka::Camera HdStrelkaCamera::_ConstructStrelkaCamera() { oka::Camera strelkaCamera; GfMatrix4d perspMatrix = ComputeProjectionMatrix(); GfMatrix4d absInvViewMatrix = GetTransform(); GfMatrix4d relViewMatrix = absInvViewMatrix; //*m_rootMatrix; glm::float4x4 xform; for (int i = 0; i < 4; ++i) { for (int j = 0; j < 4; ++j) { xform[i][j] = (float)relViewMatrix[i][j]; } } glm::float4x4 persp; for (int i = 0; i < 4; ++i) { for (int j = 0; j < 4; ++j) { persp[i][j] = (float)perspMatrix[i][j]; } } { glm::vec3 scale; glm::quat rotation; glm::vec3 translation; glm::vec3 skew; glm::vec4 perspective; glm::decompose(xform, scale, rotation, translation, skew, perspective); rotation = glm::conjugate(rotation); strelkaCamera.position = translation * scale; strelkaCamera.mOrientation = rotation; } strelkaCamera.matrices.perspective = persp; strelkaCamera.matrices.invPerspective = glm::inverse(persp); strelkaCamera.fov = glm::degrees(GetVFov()); const std::string& name = GetId().GetString(); strelkaCamera.name = name; return strelkaCamera; } PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/RenderPass.cpp
#include "RenderPass.h" #include "Camera.h" #include "Instancer.h" #include "Material.h" #include "Mesh.h" #include "BasisCurves.h" #include "Light.h" #include "RenderBuffer.h" #include "Tokens.h" #include <pxr/base/gf/matrix3d.h> #include <pxr/base/gf/quatd.h> #include <pxr/imaging/hd/renderDelegate.h> #include <pxr/imaging/hd/renderPassState.h> #include <pxr/imaging/hd/rprim.h> #include <pxr/imaging/hd/basisCurves.h> #include <log.h> #include <glm/glm.hpp> #include <glm/gtc/matrix_transform.hpp> #include <glm/gtc/type_ptr.hpp> #include <glm/gtx/compatibility.hpp> PXR_NAMESPACE_OPEN_SCOPE HdStrelkaRenderPass::HdStrelkaRenderPass(HdRenderIndex* index, const HdRprimCollection& collection, const HdRenderSettingsMap& settings, oka::Render* renderer, oka::Scene* scene) : HdRenderPass(index, collection), m_settings(settings), m_isConverged(false), m_lastSceneStateVersion(UINT32_MAX), m_lastRenderSettingsVersion(UINT32_MAX), mRenderer(renderer), mScene(scene) { } HdStrelkaRenderPass::~HdStrelkaRenderPass() { } bool HdStrelkaRenderPass::IsConverged() const { return m_isConverged; } // valid range of coordinates [-1; 1] uint32_t packNormal(const glm::float3& normal) { uint32_t packed = (uint32_t)((normal.x + 1.0f) / 2.0f * 511.99999f); packed += (uint32_t)((normal.y + 1.0f) / 2.0f * 511.99999f) << 10; packed += (uint32_t)((normal.z + 1.0f) / 2.0f * 511.99999f) << 20; return packed; } // valid range of coordinates [-10; 10] uint32_t packUV(const glm::float2& uv) { int32_t packed = (uint32_t)((uv.x + 10.0f) / 20.0f * 16383.99999f); packed += (uint32_t)((uv.y + 10.0f) / 20.0f * 16383.99999f) << 16; return packed; } void HdStrelkaRenderPass::_BakeMeshInstance(const HdStrelkaMesh* mesh, GfMatrix4d transform, uint32_t materialIndex) { const GfMatrix4d normalMatrix = transform.GetInverse().GetTranspose(); const std::vector<GfVec3f>& meshPoints = mesh->GetPoints(); const std::vector<GfVec3f>& meshNormals = mesh->GetNormals(); const std::vector<GfVec3f>& meshTangents = mesh->GetTangents(); const std::vector<GfVec3i>& meshFaces = mesh->GetFaces(); const std::vector<GfVec2f>& meshUVs = mesh->GetUVs(); TF_VERIFY(meshPoints.size() == meshNormals.size()); const size_t vertexCount = meshPoints.size(); std::vector<oka::Scene::Vertex> vertices(vertexCount); std::vector<uint32_t> indices(meshFaces.size() * 3); for (size_t j = 0; j < meshFaces.size(); ++j) { const GfVec3i& vertexIndices = meshFaces[j]; indices[j * 3 + 0] = vertexIndices[0]; indices[j * 3 + 1] = vertexIndices[1]; indices[j * 3 + 2] = vertexIndices[2]; } for (size_t j = 0; j < vertexCount; ++j) { const GfVec3f& point = meshPoints[j]; const GfVec3f& normal = meshNormals[j]; const GfVec3f& tangent = meshTangents[j]; oka::Scene::Vertex& vertex = vertices[j]; vertex.pos[0] = point[0]; vertex.pos[1] = point[1]; vertex.pos[2] = point[2]; const glm::float3 glmNormal = glm::float3(normal[0], normal[1], normal[2]); vertex.normal = packNormal(glmNormal); const glm::float3 glmTangent = glm::float3(tangent[0], tangent[1], tangent[2]); vertex.tangent = packNormal(glmTangent); // Texture coord if (!meshUVs.empty()) { const GfVec2f& uv = meshUVs[j]; const glm::float2 glmUV = glm::float2(uv[0], 1.0f - uv[1]); // Flip v coordinate vertex.uv = packUV(glmUV); } } glm::float4x4 glmTransform; for (int i = 0; i < 4; ++i) { for (int j = 0; j < 4; ++j) { glmTransform[i][j] = (float)transform[i][j]; } } uint32_t meshId = mScene->createMesh(vertices, indices); assert(meshId != -1); uint32_t instId = mScene->createInstance(oka::Instance::Type::eMesh, meshId, materialIndex, glmTransform); assert(instId != -1); } void HdStrelkaRenderPass::_BakeMeshes(HdRenderIndex* renderIndex, GfMatrix4d rootTransform) { TfHashMap<SdfPath, uint32_t, SdfPath::Hash> materialMapping; materialMapping[SdfPath::EmptyPath()] = 0; auto getOrCreateMaterial = [&](const SdfPath& materialId) { uint32_t materialIndex = 0; if (materialMapping.find(materialId) != materialMapping.end()) { materialIndex = materialMapping[materialId]; } else { HdSprim* sprim = renderIndex->GetSprim(HdPrimTypeTokens->material, materialId); if (!sprim) { STRELKA_ERROR("Cannot retrive material!"); return 0u; } HdStrelkaMaterial* material = dynamic_cast<HdStrelkaMaterial*>(sprim); if (material->isMdl()) { const std::string& fileUri = material->getFileUri(); const std::string& name = material->getSubIdentifier(); oka::Scene::MaterialDescription materialDesc; materialDesc.file = fileUri; materialDesc.name = name; materialDesc.type = oka::Scene::MaterialDescription::Type::eMdl; materialDesc.params = material->getParams(); materialIndex = mScene->addMaterial(materialDesc); } else { const std::string& code = material->GetStrelkaMaterial(); const std::string& name = material->getSubIdentifier(); oka::Scene::MaterialDescription materialDesc; materialDesc.name = name; materialDesc.code = code; materialDesc.type = oka::Scene::MaterialDescription::Type::eMaterialX; materialDesc.params = material->getParams(); materialIndex = mScene->addMaterial(materialDesc); } materialMapping[materialId] = materialIndex; } return materialIndex; }; for (const auto& rprimId : renderIndex->GetRprimIds()) { const HdRprim* rprim = renderIndex->GetRprim(rprimId); if (dynamic_cast<const HdMesh*>(rprim)) { const HdStrelkaMesh* mesh = dynamic_cast<const HdStrelkaMesh*>(rprim); if (!mesh->IsVisible()) { // TODO: add UI/setting control here continue; } const TfToken renderTag = mesh->GetRenderTag(); if ((renderTag != "geometry") && (renderTag != "render")) { // skip all proxy meshes continue; } VtMatrix4dArray transforms; const SdfPath& instancerId = mesh->GetInstancerId(); if (instancerId.IsEmpty()) { transforms.resize(1); transforms[0] = GfMatrix4d(1.0); } else { HdInstancer* boxedInstancer = renderIndex->GetInstancer(instancerId); HdStrelkaInstancer* instancer = dynamic_cast<HdStrelkaInstancer*>(boxedInstancer); const SdfPath& meshId = mesh->GetId(); transforms = instancer->ComputeInstanceTransforms(meshId); } const SdfPath& materialId = mesh->GetMaterialId(); const std::string& materialName = materialId.GetString(); STRELKA_INFO("Hydra: Mesh: {0} \t Material: {1}", mesh->getName(), materialName.c_str()); uint32_t materialIndex = 0; if (materialId.IsEmpty()) { GfVec3f color(1.0f); if (mesh->HasColor()) { color = mesh->GetColor(); } // materialName += "_color"; const std::string& fileUri = "default.mdl"; const std::string& name = "default_material"; oka::Scene::MaterialDescription material; material.file = fileUri; material.name = name; material.type = oka::Scene::MaterialDescription::Type::eMdl; material.color = glm::float3(color[0], color[1], color[2]); material.hasColor = true; oka::MaterialManager::Param colorParam = {}; colorParam.name = "diffuse_color"; colorParam.type = oka::MaterialManager::Param::Type::eFloat3; colorParam.value.resize(sizeof(float) * 3); memcpy(colorParam.value.data(), glm::value_ptr(material.color), sizeof(float) * 3); material.params.push_back(colorParam); materialIndex = mScene->addMaterial(material); } else { materialIndex = getOrCreateMaterial(materialId); } const GfMatrix4d& prototypeTransform = mesh->GetPrototypeTransform(); for (size_t i = 0; i < transforms.size(); i++) { const GfMatrix4d transform = prototypeTransform * transforms[i]; // *rootTransform; // GfMatrix4d transform = GfMatrix4d(1.0); _BakeMeshInstance(mesh, transform, materialIndex); } } else if (dynamic_cast<const HdBasisCurves*>(rprim)) { const HdStrelkaBasisCurves* curve = dynamic_cast<const HdStrelkaBasisCurves*>(rprim); const std::vector<glm::float3>& points = curve->GetPoints(); const std::vector<float>& widths = curve->GetWidths(); const std::vector<uint32_t>& vertexCounts = curve->GetVertexCounts(); const SdfPath& materialId = curve->GetMaterialId(); const std::string& materialName = materialId.GetString(); STRELKA_INFO("Hydra: Curve: {0} \t Material: {1}", curve->getName(), materialName.c_str()); const uint32_t materialIndex = getOrCreateMaterial(materialId); const GfMatrix4d& prototypeTransform = curve->GetPrototypeTransform(); glm::float4x4 glmTransform; for (int i = 0; i < 4; ++i) { for (int j = 0; j < 4; ++j) { glmTransform[i][j] = (float)prototypeTransform[i][j]; } } uint32_t curveId = mScene->createCurve(oka::Curve::Type::eCubic, vertexCounts, points, widths); mScene->createInstance(oka::Instance::Type::eCurve, curveId, materialIndex, glmTransform, -1); } } STRELKA_INFO("Meshes: {}", mScene->getMeshes().size()); STRELKA_INFO("Instances: {}", mScene->getInstances().size()); STRELKA_INFO("Materials: {}", mScene->getMaterials().size()); STRELKA_INFO("Curves: {}", mScene->getCurves().size()); } void HdStrelkaRenderPass::_Execute(const HdRenderPassStateSharedPtr& renderPassState, const TfTokenVector& renderTags) { TF_UNUSED(renderTags); HD_TRACE_FUNCTION(); HF_MALLOC_TAG_FUNCTION(); m_isConverged = false; const auto* camera = dynamic_cast<const HdStrelkaCamera*>(renderPassState->GetCamera()); if (!camera) { return; } const HdRenderPassAovBindingVector& aovBindings = renderPassState->GetAovBindings(); if (aovBindings.empty()) { return; } const HdRenderPassAovBinding* colorAovBinding = nullptr; for (const HdRenderPassAovBinding& aovBinding : aovBindings) { if (aovBinding.aovName != HdAovTokens->color) { HdStrelkaRenderBuffer* renderBuffer = dynamic_cast<HdStrelkaRenderBuffer*>(aovBinding.renderBuffer); renderBuffer->SetConverged(true); continue; } colorAovBinding = &aovBinding; } if (!colorAovBinding) { return; } HdRenderIndex* renderIndex = GetRenderIndex(); HdChangeTracker& changeTracker = renderIndex->GetChangeTracker(); HdRenderDelegate* renderDelegate = renderIndex->GetRenderDelegate(); HdStrelkaRenderBuffer* renderBuffer = dynamic_cast<HdStrelkaRenderBuffer*>(colorAovBinding->renderBuffer); uint32_t sceneStateVersion = changeTracker.GetSceneStateVersion(); uint32_t renderSettingsStateVersion = renderDelegate->GetRenderSettingsVersion(); bool sceneChanged = (sceneStateVersion != m_lastSceneStateVersion); bool renderSettingsChanged = (renderSettingsStateVersion != m_lastRenderSettingsVersion); // if (!sceneChanged && !renderSettingsChanged) //{ // renderBuffer->SetConverged(true); // return; //} oka::Buffer* outputImage = renderBuffer->GetResource(false).UncheckedGet<oka::Buffer*>(); renderBuffer->SetConverged(false); m_lastSceneStateVersion = sceneStateVersion; m_lastRenderSettingsVersion = renderSettingsStateVersion; // Transform scene into camera space to increase floating point precision. GfMatrix4d viewMatrix = camera->GetTransform().GetInverse(); static int counter = 0; if (counter == 0) { ++counter; _BakeMeshes(renderIndex, viewMatrix); m_rootMatrix = viewMatrix; mRenderer->setScene(mScene); const uint32_t camIndex = camera->GetCameraIndex(); // mRenderer->setActiveCameraIndex(camIndex); oka::Scene::UniformLightDesc desc{}; desc.color = glm::float3(1.0f); desc.height = 0.4f; desc.width = 0.4f; desc.position = glm::float3(0, 1.1, 0.67); desc.orientation = glm::float3(179.68, 29.77, -89.97); desc.intensity = 160.0f; static const TfTokenVector lightTypes = { HdPrimTypeTokens->domeLight, HdPrimTypeTokens->simpleLight, HdPrimTypeTokens->sphereLight, HdPrimTypeTokens->rectLight, HdPrimTypeTokens->diskLight, HdPrimTypeTokens->cylinderLight, HdPrimTypeTokens->distantLight }; size_t count = 0; // TF_FOR_ALL(it, lightTypes) { // TODO: refactor this to more generic code, templates? if (renderIndex->IsSprimTypeSupported(HdPrimTypeTokens->rectLight)) { SdfPathVector sprimPaths = renderIndex->GetSprimSubtree(HdPrimTypeTokens->rectLight, SdfPath::AbsoluteRootPath()); for (int lightIdx = 0; lightIdx < sprimPaths.size(); ++lightIdx) { HdSprim* sprim = renderIndex->GetSprim(HdPrimTypeTokens->rectLight, sprimPaths[lightIdx]); HdStrelkaLight* light = dynamic_cast<HdStrelkaLight*>(sprim); mScene->createLight(light->getLightDesc()); } } if (renderIndex->IsSprimTypeSupported(HdPrimTypeTokens->diskLight)) { SdfPathVector sprimPaths = renderIndex->GetSprimSubtree(HdPrimTypeTokens->diskLight, SdfPath::AbsoluteRootPath()); for (int lightIdx = 0; lightIdx < sprimPaths.size(); ++lightIdx) { HdSprim* sprim = renderIndex->GetSprim(HdPrimTypeTokens->diskLight, sprimPaths[lightIdx]); HdStrelkaLight* light = dynamic_cast<HdStrelkaLight*>(sprim); mScene->createLight(light->getLightDesc()); } } if (renderIndex->IsSprimTypeSupported(HdPrimTypeTokens->sphereLight)) { SdfPathVector sprimPaths = renderIndex->GetSprimSubtree(HdPrimTypeTokens->sphereLight, SdfPath::AbsoluteRootPath()); for (int lightIdx = 0; lightIdx < sprimPaths.size(); ++lightIdx) { HdSprim* sprim = renderIndex->GetSprim(HdPrimTypeTokens->sphereLight, sprimPaths[lightIdx]); HdStrelkaLight* light = dynamic_cast<HdStrelkaLight*>(sprim); mScene->createLight(light->getLightDesc()); } } if (renderIndex->IsSprimTypeSupported(HdPrimTypeTokens->distantLight)) { SdfPathVector sprimPaths = renderIndex->GetSprimSubtree(HdPrimTypeTokens->distantLight, SdfPath::AbsoluteRootPath()); for (int lightIdx = 0; lightIdx < sprimPaths.size(); ++lightIdx) { HdSprim* sprim = renderIndex->GetSprim(HdPrimTypeTokens->distantLight, sprimPaths[lightIdx]); HdStrelkaLight* light = dynamic_cast<HdStrelkaLight*>(sprim); mScene->createLight(light->getLightDesc()); } } } } // mScene.createLight(desc); float* img_data = (float*)renderBuffer->Map(); mRenderer->render(outputImage); renderBuffer->Unmap(); // renderBuffer->SetConverged(true); m_isConverged = true; } PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/MaterialNetworkTranslator.h
// Copyright (C) 2021 Pablo Delgado Krämer // // This program is free software: you can redistribute it and/or modify // it under the terms of the GNU General Public License as published by // the Free Software Foundation, either version 3 of the License, or // (at your option) any later version. // // This program is distributed in the hope that it will be useful, // but WITHOUT ANY WARRANTY; without even the implied warranty of // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the // GNU General Public License for more details. // // You should have received a copy of the GNU General Public License // along with this program. If not, see <https://www.gnu.org/licenses/>. #pragma once #include <pxr/usd/sdf/path.h> #include <string> #include <MaterialXCore/Document.h> #include <memory> PXR_NAMESPACE_OPEN_SCOPE struct HdMaterialNetwork2; class MaterialNetworkTranslator { public: MaterialNetworkTranslator(const std::string& mtlxLibPath); std::string ParseNetwork(const SdfPath& id, const HdMaterialNetwork2& network) const; static bool ParseMdlNetwork(const HdMaterialNetwork2& network, std::string& fileUri, std::string& subIdentifier); private: MaterialX::DocumentPtr CreateMaterialXDocumentFromNetwork(const SdfPath& id, const HdMaterialNetwork2& network) const; void patchMaterialNetwork(HdMaterialNetwork2& network) const; private: MaterialX::DocumentPtr m_nodeLib; }; PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/Mesh.cpp
#include "Mesh.h" #include <pxr/imaging/hd/instancer.h> #include <pxr/imaging/hd/meshUtil.h> #include <pxr/imaging/hd/smoothNormals.h> #include <pxr/imaging/hd/vertexAdjacency.h> #include <log.h> PXR_NAMESPACE_OPEN_SCOPE // clang-format off TF_DEFINE_PRIVATE_TOKENS(_tokens, (st) ); // clang-format on HdStrelkaMesh::HdStrelkaMesh(const SdfPath& id, oka::Scene* scene) : HdMesh(id), mPrototypeTransform(1.0), mColor(0.0, 0.0, 0.0), mHasColor(false), mScene(scene) { } HdStrelkaMesh::~HdStrelkaMesh() = default; void HdStrelkaMesh::Sync(HdSceneDelegate* sceneDelegate, HdRenderParam* renderParam, HdDirtyBits* dirtyBits, const TfToken& reprToken) { TF_UNUSED(renderParam); TF_UNUSED(reprToken); HD_TRACE_FUNCTION(); HF_MALLOC_TAG_FUNCTION(); HdRenderIndex& renderIndex = sceneDelegate->GetRenderIndex(); if ((*dirtyBits & HdChangeTracker::DirtyInstancer) | (*dirtyBits & HdChangeTracker::DirtyInstanceIndex)) { HdDirtyBits dirtyBitsCopy = *dirtyBits; _UpdateInstancer(sceneDelegate, &dirtyBitsCopy); const SdfPath& instancerId = GetInstancerId(); HdInstancer::_SyncInstancerAndParents(renderIndex, instancerId); } const SdfPath& id = GetId(); mName = id.GetText(); if (*dirtyBits & HdChangeTracker::DirtyMaterialId) { const SdfPath& materialId = sceneDelegate->GetMaterialId(id); SetMaterialId(materialId); } if (*dirtyBits & HdChangeTracker::DirtyTransform) { mPrototypeTransform = sceneDelegate->GetTransform(id); } const bool updateGeometry = (*dirtyBits & HdChangeTracker::DirtyPoints) | (*dirtyBits & HdChangeTracker::DirtyNormals) | (*dirtyBits & HdChangeTracker::DirtyTopology); *dirtyBits = HdChangeTracker::Clean; if (!updateGeometry) { return; } mFaces.clear(); mPoints.clear(); mNormals.clear(); _UpdateGeometry(sceneDelegate); } // valid range of coordinates [-1; 1] static uint32_t packNormal(const glm::float3& normal) { uint32_t packed = (uint32_t)((normal.x + 1.0f) / 2.0f * 511.99999f); packed += (uint32_t)((normal.y + 1.0f) / 2.0f * 511.99999f) << 10; packed += (uint32_t)((normal.z + 1.0f) / 2.0f * 511.99999f) << 20; return packed; } void HdStrelkaMesh::_ConvertMesh() { const std::vector<GfVec3f>& meshPoints = GetPoints(); const std::vector<GfVec3f>& meshNormals = GetNormals(); const std::vector<GfVec3i>& meshFaces = GetFaces(); TF_VERIFY(meshPoints.size() == meshNormals.size()); const size_t vertexCount = meshPoints.size(); std::vector<oka::Scene::Vertex> vertices(vertexCount); std::vector<uint32_t> indices(meshFaces.size() * 3); for (size_t j = 0; j < meshFaces.size(); ++j) { const GfVec3i& vertexIndices = meshFaces[j]; indices[j * 3 + 0] = vertexIndices[0]; indices[j * 3 + 1] = vertexIndices[1]; indices[j * 3 + 2] = vertexIndices[2]; } for (size_t j = 0; j < vertexCount; ++j) { const GfVec3f& point = meshPoints[j]; const GfVec3f& normal = meshNormals[j]; oka::Scene::Vertex& vertex = vertices[j]; vertex.pos[0] = point[0]; vertex.pos[1] = point[1]; vertex.pos[2] = point[2]; const glm::float3 glmNormal = glm::float3(normal[0], normal[1], normal[2]); vertex.normal = packNormal(glmNormal); } mStrelkaMeshId = mScene->createMesh(vertices, indices); assert(mStrelkaMeshId != -1); } void HdStrelkaMesh::_UpdateGeometry(HdSceneDelegate* sceneDelegate) { const HdMeshTopology& topology = GetMeshTopology(sceneDelegate); const SdfPath& id = GetId(); const HdMeshUtil meshUtil(&topology, id); VtVec3iArray indices; VtIntArray primitiveParams; meshUtil.ComputeTriangleIndices(&indices, &primitiveParams); VtVec3fArray points; VtVec3fArray normals; VtVec2fArray uvs; bool indexedNormals; bool indexedUVs; _PullPrimvars(sceneDelegate, points, normals, uvs, indexedNormals, indexedUVs, mColor, mHasColor); const bool hasUVs = !uvs.empty(); for (int i = 0; i < indices.size(); i++) { GfVec3i newFaceIndices(i * 3 + 0, i * 3 + 1, i * 3 + 2); mFaces.push_back(newFaceIndices); const GfVec3i& faceIndices = indices[i]; mPoints.push_back(points[faceIndices[0]]); mPoints.push_back(points[faceIndices[1]]); mPoints.push_back(points[faceIndices[2]]); auto computeTangent = [](const GfVec3f& normal) { GfVec3f c1 = GfCross(normal, GfVec3f(1.0f, 0.0f, 0.0f)); GfVec3f c2 = GfCross(normal, GfVec3f(0.0f, 1.0f, 0.0f)); GfVec3f tangent; if (c1.GetLengthSq() > c2.GetLengthSq()) { tangent = c1; } else { tangent = c2; } GfNormalize(&tangent); return tangent; }; mNormals.push_back(normals[indexedNormals ? faceIndices[0] : newFaceIndices[0]]); mTangents.push_back(computeTangent(normals[indexedNormals ? faceIndices[0] : newFaceIndices[0]])); mNormals.push_back(normals[indexedNormals ? faceIndices[1] : newFaceIndices[1]]); mTangents.push_back(computeTangent(normals[indexedNormals ? faceIndices[1] : newFaceIndices[1]])); mNormals.push_back(normals[indexedNormals ? faceIndices[2] : newFaceIndices[2]]); mTangents.push_back(computeTangent(normals[indexedNormals ? faceIndices[2] : newFaceIndices[2]])); if (hasUVs) { mUvs.push_back(uvs[indexedUVs ? faceIndices[0] : newFaceIndices[0]]); mUvs.push_back(uvs[indexedUVs ? faceIndices[1] : newFaceIndices[1]]); mUvs.push_back(uvs[indexedUVs ? faceIndices[2] : newFaceIndices[2]]); } } } bool HdStrelkaMesh::_FindPrimvar(HdSceneDelegate* sceneDelegate, const TfToken& primvarName, HdInterpolation& interpolation) const { const HdInterpolation interpolations[] = { HdInterpolation::HdInterpolationVertex, HdInterpolation::HdInterpolationFaceVarying, HdInterpolation::HdInterpolationConstant, HdInterpolation::HdInterpolationUniform, HdInterpolation::HdInterpolationVarying, HdInterpolation::HdInterpolationInstance }; for (const HdInterpolation& currInteroplation : interpolations) { const auto& primvarDescs = GetPrimvarDescriptors(sceneDelegate, currInteroplation); for (const HdPrimvarDescriptor& primvar : primvarDescs) { if (primvar.name == primvarName) { interpolation = currInteroplation; return true; } } } return false; } void HdStrelkaMesh::_PullPrimvars(HdSceneDelegate* sceneDelegate, VtVec3fArray& points, VtVec3fArray& normals, VtVec2fArray& uvs, bool& indexedNormals, bool& indexedUVs, GfVec3f& color, bool& hasColor) const { const SdfPath& id = GetId(); // Handle points. HdInterpolation pointInterpolation; const bool foundPoints = _FindPrimvar(sceneDelegate, HdTokens->points, pointInterpolation); if (!foundPoints) { TF_RUNTIME_ERROR("Points primvar not found!"); return; } else if (pointInterpolation != HdInterpolation::HdInterpolationVertex) { TF_RUNTIME_ERROR("Points primvar is not vertex-interpolated!"); return; } const VtValue boxedPoints = sceneDelegate->Get(id, HdTokens->points); points = boxedPoints.Get<VtVec3fArray>(); // Handle color. HdInterpolation colorInterpolation; const bool foundColor = _FindPrimvar(sceneDelegate, HdTokens->displayColor, colorInterpolation); if (foundColor && colorInterpolation == HdInterpolation::HdInterpolationConstant) { const VtValue boxedColors = sceneDelegate->Get(id, HdTokens->displayColor); const VtVec3fArray& colors = boxedColors.Get<VtVec3fArray>(); color = colors[0]; hasColor = true; } const HdMeshTopology topology = GetMeshTopology(sceneDelegate); // Handle normals. HdInterpolation normalInterpolation; const bool foundNormals = _FindPrimvar(sceneDelegate, HdTokens->normals, normalInterpolation); if (foundNormals && normalInterpolation == HdInterpolation::HdInterpolationVertex) { const VtValue boxedNormals = sceneDelegate->Get(id, HdTokens->normals); normals = boxedNormals.Get<VtVec3fArray>(); indexedNormals = true; } if (foundNormals && normalInterpolation == HdInterpolation::HdInterpolationFaceVarying) { const VtValue boxedFvNormals = sceneDelegate->Get(id, HdTokens->normals); const VtVec3fArray& fvNormals = boxedFvNormals.Get<VtVec3fArray>(); const HdMeshUtil meshUtil(&topology, id); VtValue boxedTriangulatedNormals; if (!meshUtil.ComputeTriangulatedFaceVaryingPrimvar( fvNormals.cdata(), fvNormals.size(), HdTypeFloatVec3, &boxedTriangulatedNormals)) { TF_CODING_ERROR("Unable to triangulate face-varying normals of %s", id.GetText()); } normals = boxedTriangulatedNormals.Get<VtVec3fArray>(); indexedNormals = false; } else { Hd_VertexAdjacency adjacency; adjacency.BuildAdjacencyTable(&topology); normals = Hd_SmoothNormals::ComputeSmoothNormals(&adjacency, points.size(), points.cdata()); indexedNormals = true; } // Handle texture coords HdInterpolation textureCoordInterpolation; const bool foundTextureCoord = _FindPrimvar(sceneDelegate, _tokens->st, textureCoordInterpolation); if (foundTextureCoord && textureCoordInterpolation == HdInterpolationVertex) { uvs = sceneDelegate->Get(id, _tokens->st).Get<VtVec2fArray>(); indexedUVs = true; } if (foundTextureCoord && textureCoordInterpolation == HdInterpolation::HdInterpolationFaceVarying) { const VtValue boxedUVs = sceneDelegate->Get(id, _tokens->st); const VtVec2fArray& fvUVs = boxedUVs.Get<VtVec2fArray>(); const HdMeshUtil meshUtil(&topology, id); VtValue boxedTriangulatedUVS; if (!meshUtil.ComputeTriangulatedFaceVaryingPrimvar( fvUVs.cdata(), fvUVs.size(), HdTypeFloatVec2, &boxedTriangulatedUVS)) { TF_CODING_ERROR("Unable to triangulate face-varying UVs of %s", id.GetText()); } uvs = boxedTriangulatedUVS.Get<VtVec2fArray>(); indexedUVs = false; } } const TfTokenVector& HdStrelkaMesh::GetBuiltinPrimvarNames() const { return BUILTIN_PRIMVAR_NAMES; } const std::vector<GfVec3f>& HdStrelkaMesh::GetPoints() const { return mPoints; } const std::vector<GfVec3f>& HdStrelkaMesh::GetNormals() const { return mNormals; } const std::vector<GfVec3f>& HdStrelkaMesh::GetTangents() const { return mTangents; } const std::vector<GfVec3i>& HdStrelkaMesh::GetFaces() const { return mFaces; } const std::vector<GfVec2f>& HdStrelkaMesh::GetUVs() const { return mUvs; } const GfMatrix4d& HdStrelkaMesh::GetPrototypeTransform() const { return mPrototypeTransform; } const GfVec3f& HdStrelkaMesh::GetColor() const { return mColor; } bool HdStrelkaMesh::HasColor() const { return mHasColor; } const char* HdStrelkaMesh::getName() const { return mName.c_str(); } HdDirtyBits HdStrelkaMesh::GetInitialDirtyBitsMask() const { return HdChangeTracker::DirtyPoints | HdChangeTracker::DirtyNormals | HdChangeTracker::DirtyTopology | HdChangeTracker::DirtyInstancer | HdChangeTracker::DirtyInstanceIndex | HdChangeTracker::DirtyTransform | HdChangeTracker::DirtyMaterialId | HdChangeTracker::DirtyPrimvar; } HdDirtyBits HdStrelkaMesh::_PropagateDirtyBits(HdDirtyBits bits) const { return bits; } void HdStrelkaMesh::_InitRepr(const TfToken& reprName, HdDirtyBits* dirtyBits) { TF_UNUSED(reprName); TF_UNUSED(dirtyBits); } PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/Instancer.h
// Copyright (C) 2021 Pablo Delgado Krämer // // This program is free software: you can redistribute it and/or modify // it under the terms of the GNU General Public License as published by // the Free Software Foundation, either version 3 of the License, or // (at your option) any later version. // // This program is distributed in the hope that it will be useful, // but WITHOUT ANY WARRANTY; without even the implied warranty of // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the // GNU General Public License for more details. // // You should have received a copy of the GNU General Public License // along with this program. If not, see <https://www.gnu.org/licenses/>. #pragma once #include <pxr/imaging/hd/instancer.h> PXR_NAMESPACE_OPEN_SCOPE class HdStrelkaInstancer final : public HdInstancer { public: HdStrelkaInstancer(HdSceneDelegate* delegate, const SdfPath& id); ~HdStrelkaInstancer() override; public: VtMatrix4dArray ComputeInstanceTransforms(const SdfPath& prototypeId); void Sync(HdSceneDelegate* sceneDelegate, HdRenderParam* renderParam, HdDirtyBits* dirtyBits) override; private: TfHashMap<TfToken, VtValue, TfToken::HashFunctor> m_primvarMap; }; PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/Light.h
#pragma once #include "pxr/pxr.h" #include <pxr/imaging/hd/light.h> #include <pxr/imaging/hd/sceneDelegate.h> #include <scene/scene.h> PXR_NAMESPACE_OPEN_SCOPE class HdStrelkaLight final : public HdLight { public: HF_MALLOC_TAG_NEW("new HdStrelkaLight"); HdStrelkaLight(const SdfPath& id, TfToken const& lightType); ~HdStrelkaLight() override; public: void Sync(HdSceneDelegate* delegate, HdRenderParam* renderParam, HdDirtyBits* dirtyBits) override; HdDirtyBits GetInitialDirtyBitsMask() const override; oka::Scene::UniformLightDesc getLightDesc(); private: TfToken mLightType; oka::Scene::UniformLightDesc mLightDesc; }; PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/MdlParserPlugin.h
// Copyright (C) 2021 Pablo Delgado Krämer // // This program is free software: you can redistribute it and/or modify // it under the terms of the GNU General Public License as published by // the Free Software Foundation, either version 3 of the License, or // (at your option) any later version. // // This program is distributed in the hope that it will be useful, // but WITHOUT ANY WARRANTY; without even the implied warranty of // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the // GNU General Public License for more details. // // You should have received a copy of the GNU General Public License // along with this program. If not, see <https://www.gnu.org/licenses/>. #pragma once #include <pxr/usd/ndr/parserPlugin.h> PXR_NAMESPACE_OPEN_SCOPE class HdStrelkaMdlParserPlugin final : public NdrParserPlugin { public: NdrNodeUniquePtr Parse(const NdrNodeDiscoveryResult& discoveryResult) override; const NdrTokenVec& GetDiscoveryTypes() const override; const TfToken& GetSourceType() const override; }; PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/MaterialNetworkTranslator.cpp
// Copyright (C) 2021 Pablo Delgado Krämer // // This program is free software: you can redistribute it and/or modify // it under the terms of the GNU General Public License as published by // the Free Software Foundation, either version 3 of the License, or // (at your option) any later version. // // This program is distributed in the hope that it will be useful, // but WITHOUT ANY WARRANTY; without even the implied warranty of // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the // GNU General Public License for more details. // // You should have received a copy of the GNU General Public License // along with this program. If not, see <https://www.gnu.org/licenses/>. #include "MaterialNetworkTranslator.h" #include <pxr/imaging/hd/material.h> #include <pxr/usd/sdr/registry.h> #include <pxr/imaging/hdMtlx/hdMtlx.h> #include <pxr/imaging/hd/tokens.h> #include <MaterialXCore/Document.h> #include <MaterialXCore/Library.h> #include <MaterialXCore/Material.h> #include <MaterialXCore/Definition.h> #include <MaterialXFormat/File.h> #include <MaterialXFormat/Util.h> #include "Tokens.h" using std::string; namespace mx = MaterialX; PXR_NAMESPACE_OPEN_SCOPE // clang-format off TF_DEFINE_PRIVATE_TOKENS( _tokens, // USD node types (UsdPreviewSurface) (UsdUVTexture) (UsdTransform2d) (UsdPrimvarReader_float) (UsdPrimvarReader_float2) (UsdPrimvarReader_float3) (UsdPrimvarReader_float4) (UsdPrimvarReader_int) (UsdPrimvarReader_string) (UsdPrimvarReader_normal) (UsdPrimvarReader_point) (UsdPrimvarReader_vector) (UsdPrimvarReader_matrix) // MaterialX USD node type equivalents (ND_UsdPreviewSurface_surfaceshader) (ND_UsdUVTexture) (ND_UsdPrimvarReader_integer) (ND_UsdPrimvarReader_boolean) (ND_UsdPrimvarReader_string) (ND_UsdPrimvarReader_float) (ND_UsdPrimvarReader_vector2) (ND_UsdPrimvarReader_vector3) (ND_UsdPrimvarReader_vector4) (ND_UsdTransform2d) (ND_UsdPrimvarReader_matrix44) (mdl) (subIdentifier) (ND_convert_color3_vector3) (diffuse_color_constant) (normal) (rgb) (in) (out) ); // clang-format on bool _ConvertNodesToMaterialXNodes(const HdMaterialNetwork2& network, HdMaterialNetwork2& mtlxNetwork) { mtlxNetwork = network; for (auto& node : mtlxNetwork.nodes) { TfToken& nodeTypeId = node.second.nodeTypeId; SdrRegistry& sdrRegistry = SdrRegistry::GetInstance(); if (sdrRegistry.GetShaderNodeByIdentifierAndType(nodeTypeId, HdStrelkaDiscoveryTypes->mtlx)) { continue; } if (nodeTypeId == _tokens->UsdPreviewSurface) { nodeTypeId = _tokens->ND_UsdPreviewSurface_surfaceshader; } else if (nodeTypeId == _tokens->UsdUVTexture) { nodeTypeId = _tokens->ND_UsdUVTexture; } else if (nodeTypeId == _tokens->UsdTransform2d) { nodeTypeId = _tokens->ND_UsdTransform2d; } else if (nodeTypeId == _tokens->UsdPrimvarReader_float) { nodeTypeId = _tokens->ND_UsdPrimvarReader_float; } else if (nodeTypeId == _tokens->UsdPrimvarReader_float2) { nodeTypeId = _tokens->ND_UsdPrimvarReader_vector2; } else if (nodeTypeId == _tokens->UsdPrimvarReader_float3) { nodeTypeId = _tokens->ND_UsdPrimvarReader_vector3; } else if (nodeTypeId == _tokens->UsdPrimvarReader_float4) { nodeTypeId = _tokens->ND_UsdPrimvarReader_vector4; } else if (nodeTypeId == _tokens->UsdPrimvarReader_int) { nodeTypeId = _tokens->ND_UsdPrimvarReader_integer; } else if (nodeTypeId == _tokens->UsdPrimvarReader_string) { nodeTypeId = _tokens->ND_UsdPrimvarReader_string; } else if (nodeTypeId == _tokens->UsdPrimvarReader_normal) { nodeTypeId = _tokens->ND_UsdPrimvarReader_vector3; } else if (nodeTypeId == _tokens->UsdPrimvarReader_point) { nodeTypeId = _tokens->ND_UsdPrimvarReader_vector3; } else if (nodeTypeId == _tokens->UsdPrimvarReader_vector) { nodeTypeId = _tokens->ND_UsdPrimvarReader_vector3; } else if (nodeTypeId == _tokens->UsdPrimvarReader_matrix) { nodeTypeId = _tokens->ND_UsdPrimvarReader_matrix44; } else { TF_WARN("Unable to translate material node of type %s to MaterialX counterpart", nodeTypeId.GetText()); return false; } } return true; } bool GetMaterialNetworkSurfaceTerminal(const HdMaterialNetwork2& network2, HdMaterialNode2& surfaceTerminal, SdfPath& terminalPath) { const auto& connectionIt = network2.terminals.find(HdMaterialTerminalTokens->surface); if (connectionIt == network2.terminals.end()) { return false; } const HdMaterialConnection2& connection = connectionIt->second; terminalPath = connection.upstreamNode; const auto& nodeIt = network2.nodes.find(terminalPath); if (nodeIt == network2.nodes.end()) { return false; } surfaceTerminal = nodeIt->second; return true; } MaterialNetworkTranslator::MaterialNetworkTranslator(const std::string& mtlxLibPath) { m_nodeLib = mx::createDocument(); const mx::FilePathVec libFolders; // All directories if left empty. const mx::FileSearchPath folderSearchPath(mtlxLibPath); mx::loadLibraries(libFolders, folderSearchPath, m_nodeLib); } std::string MaterialNetworkTranslator::ParseNetwork(const SdfPath& id, const HdMaterialNetwork2& network) const { HdMaterialNetwork2 mtlxNetwork; if (!_ConvertNodesToMaterialXNodes(network, mtlxNetwork)) { return ""; } patchMaterialNetwork(mtlxNetwork); const mx::DocumentPtr doc = CreateMaterialXDocumentFromNetwork(id, mtlxNetwork); if (!doc) { return ""; } mx::string docStr = mx::writeToXmlString(doc); return docStr; } bool MaterialNetworkTranslator::ParseMdlNetwork(const HdMaterialNetwork2& network, std::string& fileUri, std::string& subIdentifier) { if (network.nodes.size() == 1) { const HdMaterialNode2& node = network.nodes.begin()->second; SdrRegistry& sdrRegistry = SdrRegistry::GetInstance(); SdrShaderNodeConstPtr sdrNode = sdrRegistry.GetShaderNodeByIdentifier(node.nodeTypeId); if ((sdrNode == nullptr) || sdrNode->GetContext() != _tokens->mdl) { return false; } const NdrTokenMap& metadata = sdrNode->GetMetadata(); const auto& subIdentifierIt = metadata.find(_tokens->subIdentifier); TF_DEV_AXIOM(subIdentifierIt != metadata.end()); subIdentifier = (*subIdentifierIt).second; fileUri = sdrNode->GetResolvedImplementationURI(); return true; } TF_RUNTIME_ERROR("Unsupported multi-node MDL material!"); return false; } mx::DocumentPtr MaterialNetworkTranslator::CreateMaterialXDocumentFromNetwork(const SdfPath& id, const HdMaterialNetwork2& network) const { HdMaterialNode2 surfaceTerminal; SdfPath terminalPath; if (!GetMaterialNetworkSurfaceTerminal(network, surfaceTerminal, terminalPath)) { TF_WARN("Unable to find surface terminal for material network"); return nullptr; } HdMtlxTexturePrimvarData mxHdData; return HdMtlxCreateMtlxDocumentFromHdNetwork(network, surfaceTerminal, terminalPath, id, m_nodeLib, &mxHdData); } void MaterialNetworkTranslator::patchMaterialNetwork(HdMaterialNetwork2& network) const { for (auto& pathNodePair : network.nodes) { HdMaterialNode2& node = pathNodePair.second; if (node.nodeTypeId != _tokens->ND_UsdPreviewSurface_surfaceshader) { continue; } auto& inputs = node.inputConnections; const auto patchColor3Vector3InputConnection = [&inputs, &network](const TfToken& inputName) { auto inputIt = inputs.find(inputName); if (inputIt == inputs.end()) { return; } auto& connections = inputIt->second; for (HdMaterialConnection2& connection : connections) { if (connection.upstreamOutputName != _tokens->rgb) { continue; } SdfPath upstreamNodePath = connection.upstreamNode; SdfPath convertNodePath = upstreamNodePath; for (int i = 0; network.nodes.count(convertNodePath) > 0; i++) { const std::string convertNodeName = "convert" + std::to_string(i); convertNodePath = upstreamNodePath.AppendElementString(convertNodeName); } HdMaterialNode2 convertNode; convertNode.nodeTypeId = _tokens->ND_convert_color3_vector3; convertNode.inputConnections[_tokens->in] = { { upstreamNodePath, _tokens->rgb } }; network.nodes[convertNodePath] = convertNode; connection.upstreamNode = convertNodePath; connection.upstreamOutputName = _tokens->out; } }; patchColor3Vector3InputConnection(_tokens->normal); } } PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/Mesh.h
#pragma once #include <pxr/pxr.h> #include <pxr/imaging/hd/mesh.h> #include <scene/scene.h> #include <pxr/base/gf/vec2f.h> PXR_NAMESPACE_OPEN_SCOPE class HdStrelkaMesh final : public HdMesh { public: HF_MALLOC_TAG_NEW("new HdStrelkaMesh"); HdStrelkaMesh(const SdfPath& id, oka::Scene* scene); ~HdStrelkaMesh() override; void Sync(HdSceneDelegate* delegate, HdRenderParam* renderParam, HdDirtyBits* dirtyBits, const TfToken& reprToken) override; HdDirtyBits GetInitialDirtyBitsMask() const override; const TfTokenVector& GetBuiltinPrimvarNames() const override; const std::vector<GfVec3f>& GetPoints() const; const std::vector<GfVec3f>& GetNormals() const; const std::vector<GfVec3f>& GetTangents() const; const std::vector<GfVec3i>& GetFaces() const; const std::vector<GfVec2f>& GetUVs() const; const GfMatrix4d& GetPrototypeTransform() const; const GfVec3f& GetColor() const; bool HasColor() const; const char* getName() const; protected: HdDirtyBits _PropagateDirtyBits(HdDirtyBits bits) const override; void _InitRepr(const TfToken& reprName, HdDirtyBits* dirtyBits) override; private: void _ConvertMesh(); void _UpdateGeometry(HdSceneDelegate* sceneDelegate); bool _FindPrimvar(HdSceneDelegate* sceneDelegate, const TfToken& primvarName, HdInterpolation& interpolation) const; void _PullPrimvars(HdSceneDelegate* sceneDelegate, VtVec3fArray& points, VtVec3fArray& normals, VtVec2fArray& uvs, bool& indexedNormals, bool& indexedUVs, GfVec3f& color, bool& hasColor) const; const TfTokenVector BUILTIN_PRIMVAR_NAMES = { HdTokens->points, HdTokens->normals }; GfMatrix4d mPrototypeTransform; std::vector<GfVec3f> mPoints; std::vector<GfVec3f> mNormals; std::vector<GfVec3f> mTangents; std::vector<GfVec2f> mUvs; std::vector<GfVec3i> mFaces; GfVec3f mColor; bool mHasColor; oka::Scene* mScene; std::string mName; uint32_t mStrelkaMeshId; }; PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/RenderBuffer.h
#pragma once #include <pxr/imaging/hd/renderBuffer.h> #include <pxr/pxr.h> #include <render/common.h> #include <render/buffer.h> PXR_NAMESPACE_OPEN_SCOPE class HdStrelkaRenderBuffer final : public HdRenderBuffer { public: HdStrelkaRenderBuffer(const SdfPath& id, oka::SharedContext* ctx); ~HdStrelkaRenderBuffer() override; public: bool Allocate(const GfVec3i& dimensions, HdFormat format, bool multiSamples) override; public: unsigned int GetWidth() const override; unsigned int GetHeight() const override; unsigned int GetDepth() const override; HdFormat GetFormat() const override; bool IsMultiSampled() const override; VtValue GetResource(bool multiSampled) const override; public: bool IsConverged() const override; void SetConverged(bool converged); public: void* Map() override; bool IsMapped() const override; void Unmap() override; void Resolve() override; protected: void _Deallocate() override; private: // oka::Image* mResult = nullptr; oka::SharedContext* mCtx = nullptr; oka::Buffer* mResult = nullptr; void* m_bufferMem = nullptr; uint32_t m_width; uint32_t m_height; HdFormat m_format; bool m_isMultiSampled; bool m_isMapped; bool m_isConverged; }; PXR_NAMESPACE_CLOSE_SCOPE
arhix52/Strelka/src/HdStrelka/RenderPass.h
#pragma once #include <pxr/imaging/hd/renderDelegate.h> #include <pxr/imaging/hd/renderPass.h> #include <pxr/pxr.h> #include <scene/camera.h> #include <scene/scene.h> #include <render/render.h> PXR_NAMESPACE_OPEN_SCOPE class HdStrelkaCamera; class HdStrelkaMesh; class HdStrelkaRenderPass final : public HdRenderPass { public: HdStrelkaRenderPass(HdRenderIndex* index, const HdRprimCollection& collection, const HdRenderSettingsMap& settings, oka::Render* renderer, oka::Scene* scene); ~HdStrelkaRenderPass() override; bool IsConverged() const override; protected: void _Execute(const HdRenderPassStateSharedPtr& renderPassState, const TfTokenVector& renderTags) override; private: void _BakeMeshInstance(const HdStrelkaMesh* mesh, GfMatrix4d transform, uint32_t materialIndex); void _BakeMeshes(HdRenderIndex* renderIndex, GfMatrix4d rootTransform); const HdRenderSettingsMap& m_settings; bool m_isConverged; uint32_t m_lastSceneStateVersion; uint32_t m_lastRenderSettingsVersion; GfMatrix4d m_rootMatrix; oka::Scene* mScene; // ptr to global render oka::Render* mRenderer; }; PXR_NAMESPACE_CLOSE_SCOPE