[
  {
    "path": "LICENSE",
    "content": "MIT License\n\nCopyright (c) 2018 Jesse Weisberg\n\nPermission is hereby granted, free of charge, to any person obtaining a copy\nof this software and associated documentation files (the \"Software\"), to deal\nin the Software without restriction, including without limitation the rights\nto use, copy, modify, merge, publish, distribute, sublicense, and/or sell\ncopies of the Software, and to permit persons to whom the Software is\nfurnished to do so, subject to the following conditions:\n\nThe above copyright notice and this permission notice shall be included in all\ncopies or substantial portions of the Software.\n\nTHE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\nIMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\nFITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE\nAUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER\nLIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,\nOUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE\nSOFTWARE.\n"
  },
  {
    "path": "README.md",
    "content": "# moveo_ros\nROS packages that can be used to plan and execute motion trajectories for the BCN3D Moveo robotic arm in simulation and real-life.\n### [Video Demo Here!](https://youtu.be/2RcTTqs17O8)\n\n- **_New Feature_: Object-Specific Pick and Place** (With an ordinary webcam, Tensorflow, OpenCV, and ROS, you can 'pick and place' (or sort) objects that are detected in real-time)\n\t- **[Video Demo](https://youtu.be/kkUbyFa2MWc)**\n\t- **[How to Use](https://github.com/jesseweisberg/moveo_ros/tree/master/moveo_moveit/scripts)**\n\n\n\n## How to Use:\n\n### Getting the BCN3D Simulation Working with Motion Planning\n![moveit_screenshot.png](/moveit_screenshot.png)\n\n1. Make sure you have ROS installed correctly with a functioning workspace-- I used ROS Kinetic on Ubuntu 16.04 (if you have a different distro, you may need to change some things).  I currently have 'moveo_ros' in the 'src' folder of my catkin workspace.\n\n2. To plan and execute trajectories for the Moveo in simulation (RVIZ with Moveit plugin), execute the following terminal command:\n\t```\n\troslaunch moveo_moveit_config demo.launch\n\t```\n\n3. Once the window loads, in the bottom-left corner check \"Allow Approximate IK Solutions.\"  Then click on the \"Planning\" tab in the MotionPlanning panel of RVIZ.  Select a new goal state by either dragging the interactive marker (light blue ball on the end effector) or under \"Select Goal State.\"  Once goal state is updated, \"Plan and Execute\" will plan and execute the trajectory from the start state to the updated goal state.\n\n\n### Moving the real robot, synced with the simulated robot's trajectories.\n4. Make sure you download the AccelStepper ([AccelStepper Library Download](http://www.airspayce.com/mikem/arduino/AccelStepper/AccelStepper-1.57.zip)) and ros_lib ([rosserial-arduino tutorial](http://wiki.ros.org/rosserial_arduino/Tutorials/Arduino%20IDE%20Setup)) libraries into your Arduino environment.\n\t- If ros_lib already exists in your Arduino libraries (<Arduino sketchbook>/libraries), follow the last troubleshooting tip or you'll get an error saying \"ArmJointState.h: no such file\".  ROS makes you remove ros_lib and regenerate it every time you introduce a new custom message.\n\n5. Change the pin layout between your robot and the RAMPS 1.4 in **'moveo_moveit_arduino.ino'** and upload the file to your Arduino (I'm using MEGA 2560).  Make sure the robot and the simulation are in the same position (to set the simulation upright initially-- select \"Upright\" from \"Select Goal States\" in RVIZ.\n\n6. In 'moveit_convert.cpp' replace the stepsPerRevolution array with the steps/revolution (or microsteps/revolution) of each of your motors.  (Note: if you don't already know these values, you can experimentally get how many microsteps/revolution your motors have using the MultiStepperTest.ino and recording/eyeballing the results)\n\n7. With the simulation already running, execute each of the following commands in it's own, separate terminal: \n\t- ``` rosrun rosserial_python serial_node.py /dev/ttyUSB0 ```(establishes rosserial node that communicates with Arduino)\n\t- ```rosrun moveo_moveit moveit_convert ``` (converts simulation joint_state rotations to steps and publishes on the /joint_steps topic, which the Arduino script subscribes to)\n\t- ```rostopic pub gripper_angle std_msgs/UInt16 <angle 0-180> ```(publishes gripper_angle)\n\n**Now, whatever trajectories are planned and executed in simulation are echoed on the real robot.**\n\n## About Directories\n### moveo_urdf\nContains the URDF (Unified Robot Description File) for the BCN3D Moveo. Necessary for simulation in RVIZ and moveit configuration.\n\n### moveo_moveit_config\nConfiguration for moveit, a motion planning framework that has a plugin in RVIZ, which is what we are using here.\n\n### moveo_moveit\n- _moveit_convert.cpp_: Converts simulation 'joint\\_state' rotations (from the 'move\\_group/fake\\_controller\\_joint\\_states' topic) to steps and publishes on the /joint\\_steps topic.  Joint\\_steps is an array of 6 Int16 values (though we only have 5 joints in this case) that represent the accumulated steps executed by each joint since the moveit\\_convert node has started running. \n\n- _move\\_group\\_interface\\_coor\\_1.cpp_: Can hardcode a pose/position for the end effector in the script and plan/execute a trajectory there.  Also reads/outputs the current pose/position of the end effector.\n\n## Troubleshooting\n- After step 7, there should be 3 new topics created: \n\t- **/joint\\_steps**: steps necessary to move each motor to desired position\n\t- **/joint\\_steps\\_feedback**: same as /joint_steps, except published back by arduino to check that information is being received by Arduino correctly \n\t- **/gripper\\_angle**: current angle of the gripper\n\n- **To move Moveo from the command line:**\n\t- ```rostopic pub joint_steps moveo_moveit/ArmJointState <Joint1 Joint2 Joint3 Joint4 Joint5 0>```  \n\t- Change \"Joint1, Joint2, etc.\" to the number of steps you want each joint to move.\n\n- **Use ```rostopic list``` and search for these topics to check if they are currently running**\n\n- **Use ```rostopic echo /<topic>``` to view the data on \\<topic> in your terminal** \n\n- If you get the following ```\"error: moveo_moveit/ArmJointState.h: No such file or directory\"```, perform the following steps in terminal:\n\t```\n\tcd <Arduino sketchbook>/libraries\n\trm -rf ros_lib \n\trosrun rosserial_arduino make_libraries.py .\n\t```\n\t- More info on the ROS wiki: \n\t\t- Section 2.2 here: (http://wiki.ros.org/rosserial_arduino/Tutorials/Arduino%20IDE%20Setup)\n\t\t- (http://wiki.ros.org/rosserial/Tutorials/Adding%20Other%20Messages)\n\t\n- Here is my current layout and wiring schematic for reference:\n![aerialRobotSketch.pdf](/aerial_robot_sketch.png)\n"
  },
  {
    "path": "moveo_moveit/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 2.8.3)\nproject(moveo_moveit)\n\nadd_compile_options(-std=c++11)\n\nfind_package(Eigen3 REQUIRED)\n\n# Eigen 3.2 (Wily) only provides EIGEN3_INCLUDE_DIR, not EIGEN3_INCLUDE_DIRS\nif(NOT EIGEN3_INCLUDE_DIRS)\n  set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR})\nendif()\n\nfind_package(catkin REQUIRED\n  COMPONENTS\n    roscpp\n    rospy\n    std_msgs\n    moveit_core\n    moveit_ros_planning\n    moveit_ros_planning_interface\n    pluginlib\n    geometric_shapes\n    moveit_visual_tools\n)\n\nfind_package(Boost REQUIRED system filesystem date_time thread)\n\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## Generate messages in the 'msg' folder\nadd_message_files(\n  FILES\n  ArmJointState.msg\n)\n\n\n## Generate added messages and services with any dependencies listed here\ngenerate_messages(\n  DEPENDENCIES\n  sensor_msgs\n  std_msgs\n)\n\ncatkin_package(\n  CATKIN_DEPENDS\n    moveit_core\n    moveit_ros_planning_interface\n    interactive_markers\n  DEPENDS\n    EIGEN3\n)\n\n###########\n## Build ##\n###########\n\ninclude_directories(SYSTEM ${Boost_INCLUDE_DIR} ${EIGEN3_INCLUDE_DIRS})\ninclude_directories(${catkin_INCLUDE_DIRS})\nlink_directories(${catkin_LIBRARY_DIRS})\n\n## Declare a C++ executable\nadd_executable(moveit_convert src/moveit_convert.cpp)\nadd_executable(move_group_1 src/move_group_interface_coor_1.cpp)\n\nadd_dependencies(moveit_convert moveo_moveit_generate_messages_cpp)\n## Specify libraries to link a library or executable target against\ncatkin_install_python(PROGRAMS scripts/moveo_objrec_publisher.py\n  DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})\n\ntarget_link_libraries(moveit_convert\n  ${catkin_LIBRARIES}\n)\ntarget_link_libraries(move_group_1\n  ${catkin_LIBRARIES}\n)\n\n\n"
  },
  {
    "path": "moveo_moveit/moveo_moveit_arduino/MultiStepperTest/MultiStepperTest.ino",
    "content": "// MultiStepper.pde\n// -*- mode: C++ -*-\n// Use MultiStepper class to manage multiple steppers and make them all move to \n// the same position at the same time for linear 2d (or 3d) motion.\n\n#include <AccelStepper.h>\n#include <MultiStepper.h>\n\n// Joint 1\n#define E1_STEP_PIN 36\n#define E1_DIR_PIN 34\n#define E1_ENABLE_PIN 30\n\n// Joint 2\n#define Z_STEP_PIN         46\n#define Z_DIR_PIN          48\n#define Z_ENABLE_PIN       62\n#define Z_MIN_PIN          18\n#define Z_MAX_PIN          19\n\n// Joint 3\n#define Y_STEP_PIN         60\n#define Y_DIR_PIN          61\n#define Y_ENABLE_PIN       56\n#define Y_MIN_PIN          14\n#define Y_MAX_PIN          15\n\n// Joint 4\n#define X_STEP_PIN 54\n#define X_DIR_PIN 55\n#define X_ENABLE_PIN 38\n\n// Joint 5 \n#define E0_STEP_PIN 26\n#define E0_DIR_PIN 28\n#define E0_ENABLE_PIN 24\n\n\n// EG X-Y position bed driven by 2 steppers\n// Alas its not possible to build an array of these with different pins for each :-(\nAccelStepper joint1(1,E1_STEP_PIN, E1_DIR_PIN);\nAccelStepper joint2(1,Z_STEP_PIN, Z_DIR_PIN);\nAccelStepper joint3(1,Y_STEP_PIN, Y_DIR_PIN);\nAccelStepper joint4(1,X_STEP_PIN, X_DIR_PIN);\nAccelStepper joint5(1, E0_STEP_PIN, E0_DIR_PIN);\n\n// Up to 10 steppers can be handled as a group by MultiStepper\nMultiStepper steppers;\n\n//test with uint8 converted to long\nunsigned int x = 1000;\n\nvoid setup() {\n  Serial.begin(250000);\n\n  // Configure each stepper\n  joint1.setMaxSpeed(1500);\n  joint2.setMaxSpeed(750);\n  joint3.setMaxSpeed(2000);\n  joint4.setMaxSpeed(500);\n  joint5.setMaxSpeed(1000);\n\n  // Then give them to MultiStepper to manage\n  steppers.addStepper(joint1);\n  steppers.addStepper(joint2);\n  steppers.addStepper(joint3);\n  steppers.addStepper(joint4);\n  steppers.addStepper(joint5);\n}\n\nvoid loop() {\n  long positions[5]; // Array of desired stepper positions\n\n  // Back of the envelope calculation for microsteps/revolution, where positions[i] is the number of steps (or microsteps).\n  positions[0] = 0; //4100 microsteps is 1/8 revolutions ----> 32800 microsteps/rev\n  positions[1] = 0; //2000 is 40/360 revolutions ---> 18000 microsteps/rev\n  positions[2] = 0; //4000 is 20/360 revolutions ---> 72000 microsteps/rev\n  positions[3] = 0; //820 is 1/4 revolution (200steps/revolution * 16microsteps/step (since microstepping) ~= 32800 microsteps/rev)\n  positions[4] = 0; //2000 is 50/360 revolution ---> 14400\n  \n  steppers.moveTo(positions);\n  steppers.runSpeedToPosition(); // Blocks until all are in position\n  delay(1);\n  \n  // Move to a different coordinate\n  positions[0] = 0;\n  positions[1] = 0;\n  positions[2] = 0;\n  positions[3] = 0;\n  positions[4] = 0;\n  steppers.moveTo(positions);\n  steppers.runSpeedToPosition(); // Blocks until all are in position\n  delay(1);\n}\n"
  },
  {
    "path": "moveo_moveit/moveo_moveit_arduino/moveo_moveit_arduino.ino",
    "content": "/* Purpose: This sketch uses ROS as well as MultiStepper, AccelStepper, and Servo libraries to control the \n * BCN3D Moveo robotic arm. In this setup, a Ramps 1.4 shield is used on top of an Arduino Mega 2560.  \n * Subscribing to the following ROS topics: 1) joint_steps, 2) gripper_angle\n *    1) joint_steps is computed from the simulation in PC and sent Arduino via rosserial.  It contains\n *       the steps (relative to the starting position) necessary for each motor to move to reach the goal position.\n *    2) gripper_angle contains the necessary gripper angle to grasp the object when the goal state is reached \n * \n * Publishing to the following ROS topics: joint_steps_feedback\n *    1) joint_steps_feedback is a topic used for debugging to make sure the Arduino is receiving the joint_steps data\n *       accurately\n *       \n * Author: Jesse Weisberg\n */\n#if (ARDUINO >= 100)\n  #include <Arduino.h>\n#else\n  #include <WProgram.h>\n#endif\n#include <ros.h>\n\n#include <moveo_moveit/ArmJointState.h>\n#include <Servo.h> \n#include <std_msgs/Bool.h>\n#include <std_msgs/String.h>\n#include <math.h>\n#include <std_msgs/Int16.h>\n#include <std_msgs/UInt16.h>\n#include <AccelStepper.h>\n#include <MultiStepper.h>\n\n// Joint 1\n#define E1_STEP_PIN        36\n#define E1_DIR_PIN         34\n#define E1_ENABLE_PIN      30\n\n// Joint 2\n#define Z_STEP_PIN         46\n#define Z_DIR_PIN          48\n#define Z_ENABLE_PIN       62\n#define Z_MIN_PIN          18\n#define Z_MAX_PIN          19\n\n// Joint 3\n#define Y_STEP_PIN         60\n#define Y_DIR_PIN          61\n#define Y_ENABLE_PIN       56\n#define Y_MIN_PIN          14\n#define Y_MAX_PIN          15\n\n// Joint 4\n#define X_STEP_PIN         54\n#define X_DIR_PIN          55\n#define X_ENABLE_PIN       38\n\n// Joint 5 \n#define E0_STEP_PIN        26\n#define E0_DIR_PIN         28\n#define E0_ENABLE_PIN      24\n\nAccelStepper joint1(1,E1_STEP_PIN, E1_DIR_PIN);\nAccelStepper joint2(1,Z_STEP_PIN, Z_DIR_PIN);\nAccelStepper joint3(1,Y_STEP_PIN, Y_DIR_PIN);\nAccelStepper joint4(1,X_STEP_PIN, X_DIR_PIN);\nAccelStepper joint5(1, E0_STEP_PIN, E0_DIR_PIN);\n\nServo gripper;\nMultiStepper steppers;\n\nint joint_step[6];\nint joint_status = 0;\n\nros::NodeHandle nh;\nstd_msgs::Int16 msg;\n\n//instantiate publisher (for debugging purposes)\n//ros::Publisher steps(\"joint_steps_feedback\",&msg);\n\nvoid arm_cb(const moveo_moveit::ArmJointState& arm_steps){\n  joint_status = 1;\n  joint_step[0] = arm_steps.position1;\n  joint_step[1] = arm_steps.position2;\n  joint_step[2] = arm_steps.position3;\n  joint_step[3] = arm_steps.position4;\n  joint_step[4] = arm_steps.position5;\n  joint_step[5] = arm_steps.position6; //gripper position <0-180>\n}\n\nvoid gripper_cb( const std_msgs::UInt16& cmd_msg){\n  gripper.write(cmd_msg.data); // Set servo angle, should be from 0-180  \n  digitalWrite(13, HIGH-digitalRead(13));  // Toggle led  \n}\n\n//instantiate subscribers\nros::Subscriber<moveo_moveit::ArmJointState> arm_sub(\"joint_steps\",arm_cb); //subscribes to joint_steps on arm\nros::Subscriber<std_msgs::UInt16> gripper_sub(\"gripper_angle\", gripper_cb); //subscribes to gripper position\n//to publish from terminal: rostopic pub gripper_angle std_msgs/UInt16 <0-180>\n\nvoid setup() {\n  //put your setup code here, to run once:\n  //Serial.begin(57600);\n  pinMode(13,OUTPUT);\n  joint_status = 1;\n\n  nh.initNode();\n  nh.subscribe(arm_sub);\n  nh.subscribe(gripper_sub);\n  //nh.advertise(steps);\n\n  // Configure each stepper\n  joint1.setMaxSpeed(1500);\n  joint2.setMaxSpeed(750);\n  joint3.setMaxSpeed(2000);\n  joint4.setMaxSpeed(500);\n  joint5.setMaxSpeed(1000);\n\n  // Then give them to MultiStepper to manage\n  steppers.addStepper(joint1);\n  steppers.addStepper(joint2);\n  steppers.addStepper(joint3);\n  steppers.addStepper(joint4);\n  steppers.addStepper(joint5);\n\n  // Configure gripper servo\n  gripper.attach(11);\n  \n  digitalWrite(13, 1); //toggle led\n}\n\nvoid loop() {\n  if (joint_status == 1) // If command callback (arm_cb) is being called, execute stepper command\n  { \n    long positions[5];  // Array of desired stepper positions must be long\n    positions[0] = joint_step[0]; // negated since the real robot rotates in the opposite direction as ROS\n    positions[1] = -joint_step[1]; \n    positions[2] = joint_step[2]; \n    positions[3] = joint_step[3]; \n    positions[4] = -joint_step[4]; \n\n    // Publish back to ros to check if everything's correct\n    //msg.data=positions[4];\n    //steps.publish(&msg);\n\n    steppers.moveTo(positions);\n    nh.spinOnce();\n    steppers.runSpeedToPosition(); // Blocks until all are in position\n    gripper.write(joint_step[5]);  // move gripper after manipulator reaches goal   \n  }\n  digitalWrite(13, HIGH-digitalRead(13)); //toggle led\n  joint_status = 0;\n  \n  nh.spinOnce();\n  delay(1);\n  \n}\n"
  },
  {
    "path": "moveo_moveit/msg/ArmJointState.msg",
    "content": "int16 position1\nint16 position2\nint16 position3\nint16 position4\nint16 position5\nint16 position6\n"
  },
  {
    "path": "moveo_moveit/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package>\n  <name>moveo_moveit</name>\n  <version>0.0.0</version>\n  <description>The moveo_moveit package</description>\n\n  <maintainer email=\"jesse.weisberg@gmail.com\">Jesse Weisberg</maintainer>\n\n\n  <!-- One license tag required, multiple allowed, one license per tag -->\n  <!-- Commonly used license strings: -->\n  <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->\n  <license>TODO</license>\n\n\n  <!-- <url type=\"website\">http://wiki.ros.org/carmen_move</url> -->\n  <!-- <author email=\"jane.doe@example.com\">Jane Doe</author> -->\n\n\n  <!-- The *_depend tags are used to specify dependencies -->\n  <!-- Dependencies can be catkin packages or system dependencies -->\n  <!-- Examples: -->\n  \n  <!-- Use buildtool_depend for build tool packages: -->\n  <!--   <buildtool_depend>catkin</buildtool_depend> -->\n\n  <!-- Use test_depend for packages you need only for testing: -->\n  <!--   <test_depend>gtest</test_depend> -->\n  <buildtool_depend>catkin</buildtool_depend>\n  \n  <build_depend>message_generation</build_depend>\n  <build_depend>pluginlib</build_depend>\n  <build_depend>eigen</build_depend>\n  <build_depend>moveit_core</build_depend>\n  <build_depend>moveit_ros_planning_interface</build_depend>\n  <build_depend>moveit_ros_perception</build_depend>\n  <build_depend>interactive_markers</build_depend>\n  <build_depend>geometric_shapes</build_depend>\n  <build_depend>moveit_visual_tools</build_depend>\n\n  <run_depend>pluginlib</run_depend>\n  <run_depend>moveit_core</run_depend>\n  <run_depend>moveit_fake_controller_manager</run_depend>\n  <run_depend>moveit_ros_planning_interface</run_depend>\n  <run_depend>moveit_ros_perception</run_depend>\n  <run_depend>interactive_markers</run_depend>\n  <run_depend>moveit_visual_tools</run_depend>\n\n\n<!--  <build_depend>roscpp</build_depend>\n  <build_depend>rospy</build_depend>\n  <build_depend>sensor_msgs</build_depend>\n  <build_depend>std_msgs</build_depend>\n  <build_depend>moveit_ros_planning_interface</build_depend>\n  <build_depend>moveit_core</build_depend>\n\n  <run_depend>message_generation</run_depend>\n  <run_depend>message_runtime</run_depend>\n  <run_depend>roscpp</run_depend>\n  <run_depend>rospy</run_depend>\n  <run_depend>sensor_msgs</run_depend>\n  <run_depend>std_msgs</run_depend>\n  <run_depend>moveit_core</run_depend>\n  <run_depend>moveit_ros_planning_interface</run_depend>\n  <run_depend>interactive_markers</run_depend>\n-->\n\n\n\n  <!-- The export tag contains other, unspecified, tags -->\n  <export>\n    <!-- Other tools can request additional information be placed here -->\n\n  </export>\n</package>\n"
  },
  {
    "path": "moveo_moveit/scripts/README.md",
    "content": "# Object-Specific Pick and Place\nThis script uses real-time object recognition in a monocular image to perform predefined 'pick and place' movements.  In this example, apples are moved to the left, and bananas to the right (though many object-specific grasps and trajectories can be made).\n\n- [Video Demo](https://youtu.be/kkUbyFa2MWc)\n\n## How to Use\n1. Connect your webcam via USB to your laptop, with the other USB port connected to the Arduino\n2. Upload Arduino firmware (moveo_moveit/moveo_moveit_arduino/moveo_moveit_arduino.ino)\n3. Create a virtualenv that has Python 3, OpenCV 3, and Tensorflow 1.2+\n4. Within that virtualenv (in moveo_ros/object_detector_app), in terminal run: ```python object_detection_multithreading.py```\n5. In another terminal (no virtualenv), run: ``` roscore ```\n5. In another terminal (no virtualenv), run: ``` rosrun rosserial_python serial_node.py /dev/ttyUSB0 ``` (establishes rosserial node that communicates with Arduino)\n6. Tweak your predefined object-specific trajectories (for now, this is not so robust, but I'm working on it!)\n7. In another terminal (no virtualenv), run: ``` rosrun moveo_moveit moveo_objrec_publisher.py ```\n8. Now, when object is placed in the FOV of the camera, a trajectory will be performed based on what object is detected! In this example, I've set up the framework to perform a sequence of trajectories that together form different 'pick and place' trajectories for each object.\n\n## How it Works\n### Real-Time Object Recognition\nHere, we use Python 3, Tensorflow's Object Detection API, OpenCV, and an ordinary webcam to create this application.  For more information about how this works, see [here](https://github.com/jesseweisberg/moveo_ros/tree/master/object_detector_app).  While real-time object recognition is going on, the label of the recognized object is sent via ZMQ to a node in ROS.  Then, the node in ROS publishes to a rostopic.  The intermedicary step of sending via ZMQ is necessary because ROS only supports Python 2, whereas the object recognition app uses Python 3.  Thus, ZMQ really is just used to send the detected object info from a Python 3 (non-ROS friendly) environment to a Python 2 (ROS friendly) environment.\n\n### Using Real-Time Object Recognition to Perform Object-Specific Pick and Place\nThe node, **moveo_objrec_publisher.py** (in moveo_ros/moveo_moveit/scripts), receives the label of the recognized object from the object_detection_multithreading.py script, and publishes a sequence of trajectories (on the /joint_steps topic) to perform a 'pick and place' motion for that specific object.  The Arduino subscribes to the /joint_steps topic and performs the trajectories.\n"
  },
  {
    "path": "moveo_moveit/scripts/moveo_objrec_publisher.py",
    "content": "#!/usr/bin/env python\n#!/usr/bin/env python3\n\n'''\nSubscribes to a zmq socket and publishes that information to a ros topic.  This is one workaround for using\nPython 2 and Python 3 in the same ROS application.\n\nIn my case, this receives real-time object detection info from a script in Python 3 and publishes to a rostopic.\n\nAuthor: Jesse Weisberg\n'''\nimport rospy\nfrom std_msgs.msg import String\nimport sys\nimport zmq\nfrom msgpack import loads\nimport time\nimport pyttsx\nfrom datetime import datetime \nfrom espeak import espeak\nfrom moveo_moveit.msg import ArmJointState\n\nfixated_object_label = None\ngripper = {'open': 0, 'banana': 70, 'apple': 50}\nupright = [0, 0, 0, 0, 0, 0]\n\n#predefined movements for pick and place of an apple and banana\napple_pick = [0, -2243, -23410, 14, -800, gripper['apple']]\napple_move = [0, -1113, -17410, 14, -3300, gripper['apple']]\napple_place = [-4600, -2400, -18410, 91, -800, gripper['open']]\n\nbanana_pick = [0, -2243, -24410, 14, -400, gripper['banana']]\nbanana_move = [0, -1043, -17410, 14, -3300, gripper['banana']]\nbanana_place = [4600, -2400, -20410, -91, -400, gripper['open']]\n\n\nobject_trajectories = {\"apple\": [upright, apple_pick, apple_move, apple_place, upright],\n                       \"banana\": [upright, banana_pick, banana_move, banana_place, upright]}\n\n\n#subscribe to detected object from object_detection_pupil.py (Pupil object detection plugin) via zmq\ndef subscribe_detected_object():\n    context = zmq.Context()\n    socket = context.socket(zmq.SUB)\n    addr = '127.0.0.1'  # remote ip or localhost\n    port = \"5556\"  # same as in the pupil remote gui\n    print('retrieving objects...')\n    socket.connect(\"tcp://{}:{}\".format(addr, port))\n\n    #subscribe to detected_objects topic\n    while True:\n        try:\n            socket.setsockopt_string(zmq.SUBSCRIBE, 'detected_object')\n        except TypeError:\n            socket.setsockopt(zmq.SUBSCRIBE, 'detected_object')\n        #process object\n        detected_object = socket.recv_string() \n        if len(detected_object.split())==3:\n            fixated_object_label = detected_object.split()[1]\n            confidence = detected_object.split()[2]\n        if len(detected_object.split())==4:\n            fixated_object_label = detected_object.split()[1] + ' ' + detected_object.split()[2]\n            confidence = detected_object.split()[3]\n\n        # Potential improvement idea with emg sensory feedback\n        # activate grasp for robotic manipulator: turn on \"ready to execute switch\"\n        # time.sleep(3), during this time wait for emg sensory input\n        # set up another rostopic that with emg sensory input, \n        # arduino reads that if higher than thresh, execute predetermined motion planning/grasp  \n        return fixated_object_label\n\n\n# publish detected object to a ros topic\ndef publish_detected_object():\n    pub = rospy.Publisher('joint_steps', ArmJointState, queue_size=4)\n    rospy.init_node('pick_and_place_object_detection', anonymous=True)\n    rate = rospy.Rate(.1) # 20hz\n\n    while not rospy.is_shutdown():\n        fixated_object_label = subscribe_detected_object()\n        rospy.loginfo(fixated_object_label)\n        \n        # check if fixated object label is a key in object_trajectories\n        # if so, publish each trajectory in object_trajectories[key] to ArmJointState\n        if fixated_object_label in object_trajectories:\n            for i in object_trajectories[fixated_object_label]:\n                goal = ArmJointState()\n                goal.position1 = i[0]\n                goal.position2 = i[1]\n                goal.position3 = i[2]\n                goal.position4 = i[3]\n                goal.position5 = i[4]\n                goal.position6 = i[5]\n                pub.publish(goal)\n                rospy.sleep(10)\n                \n        espeak.synth(fixated_object_label)\n        while espeak.is_playing():\n             pass\n\n        #rate.sleep()\n    \n\nif __name__ == '__main__':\n    try:\n        publish_detected_object()\n    except rospy.ROSInterruptException:\n        pass\n"
  },
  {
    "path": "moveo_moveit/src/move_group_interface_coor_1.cpp",
    "content": "#include <moveit/move_group_interface/move_group_interface.h>\n#include <moveit/planning_scene_interface/planning_scene_interface.h>\n\n#include <moveit_msgs/DisplayRobotState.h>\n#include <moveit_msgs/DisplayTrajectory.h>\n\n#include <moveit_msgs/AttachedCollisionObject.h>\n#include <moveit_msgs/CollisionObject.h>\n\n#include <moveit_visual_tools/moveit_visual_tools.h>\n\nint main(int argc, char **argv)\n{\t\n  ros::init(argc, argv, \"move_group_1\");\n  ros::NodeHandle node_handle;\n  ros::AsyncSpinner spinner(1);\n  spinner.start();\n\n  //----------------------------\n  //Setup\n  //----------------------------\n\n  static const std::string PLANNING_GROUP = \"arm\";\n\n  // The :move_group_interface:`MoveGroup` class can be easily\n  // setup using just the name of the planning group you would like to control and plan for\n  moveit::planning_interface::MoveGroupInterface move_group(PLANNING_GROUP);\n\n  //Using :planning_scene_interface:'PlanningSceneInterface' class to deal directly with the world\n  moveit::planning_interface::PlanningSceneInterface planning_scene_interface;\n\n  // Raw pointers are frequently used to refer to the planning group for improved performance.\n  const robot_state::JointModelGroup *joint_model_group =\n    move_group.getCurrentState()->getJointModelGroup(PLANNING_GROUP);\n  \n  move_group.setEndEffectorLink(\"Link_5\");\n  geometry_msgs::PoseStamped current_pose = move_group.getCurrentPose();\n  // We can print the name of the reference frame for this robot.\n  // also printing the current position and orientation of the robot.\n  ros::Publisher pose_pub = node_handle.advertise<geometry_msgs::PoseStamped>(\"robot_pose\", 10);\n  ROS_INFO_NAMED(\"moveo\", \"x position: %f\", current_pose.pose.position.x);\n  ROS_INFO_NAMED(\"moveo\", \"y position: %f\", current_pose.pose.position.y);\n  ROS_INFO_NAMED(\"moveo\", \"z position: %f\", current_pose.pose.position.z);\n  ROS_INFO_NAMED(\"moveo\", \"x orientation: %f\", current_pose.pose.orientation.x);\n  ROS_INFO_NAMED(\"moveo\", \"y orientation: %f\", current_pose.pose.orientation.y);\n  ROS_INFO_NAMED(\"moveo\", \"z orientation: %f\", current_pose.pose.orientation.z);\n  ROS_INFO_NAMED(\"moveo\", \"w orientation: %f\", current_pose.pose.orientation.w);\n \n  // Visualization\n  // ^^^^^^^^^^^^^\n  //\n  // The package MoveItVisualTools provides many capabilties for visualizing objects, robots,\n  // and trajectories in Rviz as well as debugging tools such as step-by-step introspection of a script\n  namespace rvt = rviz_visual_tools;\n  moveit_visual_tools::MoveItVisualTools visual_tools(\"odom\");\n  visual_tools.deleteAllMarkers();\n\n  // Remote control is an introspection tool that allows users to step through a high level script\n  // via buttons and keyboard shortcuts in Rviz\n  visual_tools.loadRemoteControl();\n\n  // Rviz provides many types of markers, in this demo we will use text, cylinders, and spheres\n  Eigen::Affine3d text_pose = Eigen::Affine3d::Identity();\n  text_pose.translation().z() = 1.0; // above head of PR2\n  visual_tools.publishText(text_pose, \"MoveGroupInterface Moveo Demo\", rvt::WHITE, rvt::XLARGE);\n\n  // Batch publishing is used to reduce the number of messages being sent to Rviz for large visualizations\n  visual_tools.trigger();\n\n\n  //-----------------------------\n  //Getting Basic Information\n  //-----------------------------\n\n  // We can print the name of the reference frame for this robot.\n  ROS_INFO_NAMED(\"moveo\", \"Reference frame: %s\", move_group.getPlanningFrame().c_str());\n\n  // We can also print the name of the end-effector link for this group.\n  ROS_INFO_NAMED(\"moveo\", \"End effector link: %s\", move_group.getEndEffectorLink().c_str());\n\n  //-----------------------------\n  //Planning to a Pose Goal\n  //-----------------------------\n\n  //Plan a motion for this group to a desired pose for end-effector\n  // hardcode desired position here before running node in a separate terminal\n  geometry_msgs::Pose target_pose1;\n  //default pose\n  target_pose1.position.x = 0.120679;\n  target_pose1.position.y = 0.072992;\n  target_pose1.position.z = 0.569166;\n  target_pose1.orientation.x = -0.386473;\n  target_pose1.orientation.y =  -0.418023;\n  target_pose1.orientation.z = -0.760978;\n  target_pose1.orientation.w = 0.311139;\n\n  //upright pose\n  // target_pose1.position.x = 0.000130;\n  // target_pose1.position.y = -0.240464;\n  // target_pose1.position.z = 0.756570;\n  // target_pose1.orientation.x = 0.359602;\n  // target_pose1.orientation.y =  0.240924;\n  // target_pose1.orientation.z = -0.747187;\n  // target_pose1.orientation.w = 0.504335;\n\n\n//upright pose using robot_pose_publisher\n// position: \n//   x: 0.450865569212\n//   y: -0.0923533864181\n//   z: -0.646847372618\n// orientation: \n//   x: -0.359579060437\n//   y: -0.240936531262\n//   z: 0.747165791213\n//   w: 0.5043766129\n\n\n  move_group.setPoseTarget(target_pose1);\n\n  // Now, we call the planner to compute the plan and visualize it.\n  // Note that we are just planning, not asking move_group\n  // to actually move the robot.\n  moveit::planning_interface::MoveGroupInterface::Plan my_plan;\n\n  moveit::planning_interface::MoveItErrorCode success = move_group.plan(my_plan);\n\n  ROS_INFO_NAMED(\"moveo\", \"Visualizing plan 1 (pose goal) %s\", success ? \"\" : \"FAILED\");\n\n  // Visualizing plans\n  // ^^^^^^^^^^^^^^^^^\n  // We can also visualize the plan as a line with markers in Rviz.\n  ROS_INFO_NAMED(\"moveo\", \"Visualizing plan 1 as trajectory line\");\n  visual_tools.publishAxisLabeled(target_pose1, \"pose1\");\n  visual_tools.publishText(text_pose, \"Pose Goal\", rvt::WHITE, rvt::XLARGE);\n  visual_tools.publishTrajectoryLine(my_plan.trajectory_, joint_model_group);\n  visual_tools.trigger();\n  visual_tools.prompt(\"Execute trajectory\");\n  move_group.move();\n\n  ros::shutdown();  \n  return 0;\n}\n"
  },
  {
    "path": "moveo_moveit/src/moveit_convert.cpp",
    "content": "#include \"ros/ros.h\"\n#include \"sensor_msgs/JointState.h\"\n#include \"moveo_moveit/ArmJointState.h\"\n#include \"math.h\"\n\nmoveo_moveit::ArmJointState arm_steps;\nmoveo_moveit::ArmJointState total;\nint stepsPerRevolution[6] = {32800,18000,72000,3280,14400,0};  // microsteps/revolution (using 16ths) from observation, for each motor\nint joint_status = 0;\ndouble cur_angle[6];\nint joint_step[6];\ndouble prev_angle[6] = {0,0,0,0,0,0}; \ndouble init_angle[6] = {0,0,0,0,0,0};\ndouble total_steps[6] = {0,0,0,0,0,0};\nint count = 0;\n\n\n//keep a running sum of all the step counts and use that as the final step to send to arduino accelstepper\n\n// int angle_to_steps(double x)\n// {\n//   float steps;\n//   steps=((x / M_PI)*stepsPerRevolution)+0.5; // (radians)*(1 revolution/PI radians)*(200 steps/revolution)\n//   return steps;\n// }\n\n//command callback (for position) function \nvoid cmd_cb(const sensor_msgs::JointState& cmd_arm)\n{\n  if (count==0){\n    prev_angle[0] = cmd_arm.position[0];\n    prev_angle[1] = cmd_arm.position[1];\n    prev_angle[2] = cmd_arm.position[2];\n    prev_angle[3] = cmd_arm.position[3];\n    prev_angle[4] = cmd_arm.position[4];\n    prev_angle[5] = cmd_arm.position[5];\n\n    init_angle[0] = cmd_arm.position[0];\n    init_angle[1] = cmd_arm.position[1];\n    init_angle[2] = cmd_arm.position[2];\n    init_angle[3] = cmd_arm.position[3];\n    init_angle[4] = cmd_arm.position[4];\n    init_angle[5] = cmd_arm.position[5];\n  }\n\n  // ros::NodeHandle nh;\n  // ros::Subscriber sub = nh.subscribe(\"/move_group/fake_controller_joint_states\",1000,cmd_cb);\n  // ros::Publisher pub = nh.advertise<moveo_moveit::ArmJointState>(\"joint_steps\",50);\n  ROS_INFO_STREAM(\"Received /move_group/fake_controller_joint_states\");\n    \n  // arm_steps.position1 = (cmd_arm.position[0]*stepsPerRevolution[0]/M_PI+0.5)-prev_angle[0];\n  // arm_steps.position2 = (cmd_arm.position[1]*stepsPerRevolution[1]/M_PI+0.5)-prev_angle[1];\n  // arm_steps.position3 = (cmd_arm.position[2]*stepsPerRevolution[2]/M_PI+0.5)-prev_angle[2];\n  // arm_steps.position4 = (cmd_arm.position[3]*stepsPerRevolution[3]/M_PI+0.5)-prev_angle[3];\n  // arm_steps.position5 = (cmd_arm.position[4]*stepsPerRevolution[4]/M_PI+0.5)-prev_angle[4];\n  // arm_steps.position6 = (cmd_arm.position[5]*stepsPerRevolution[5]/M_PI+0.5)-prev_angle[5];\n\n  //compute relative step count to move each joint-- only works if all joint_angles start at 0\n  //otherwise, we need to set the current command to the initial joint_angles\n  //ROS_INFO_NAMED(\"test\", \"cmd_arm.position[4]: %f, prev_angle[4]: %f, init_angle[4]: %f\", cmd_arm.position[4], prev_angle[4], init_angle[4]);\n  //ROS_INFO_NAMED(\"test\", \"arm_steps.position5 #1: %f\", (cmd_arm.position[4]-prev_angle[4])*stepsPerRevolution[4]/M_PI);\n\n  arm_steps.position1 = (int)((cmd_arm.position[0]-prev_angle[0])*stepsPerRevolution[0]/(2*M_PI));\n  arm_steps.position2 = (int)((cmd_arm.position[1]-prev_angle[1])*stepsPerRevolution[1]/(2*M_PI));\n  arm_steps.position3 = (int)((cmd_arm.position[2]-prev_angle[2])*stepsPerRevolution[2]/(2*M_PI));\n  arm_steps.position4 = (int)((cmd_arm.position[3]-prev_angle[3])*stepsPerRevolution[3]/(2*M_PI));\n  arm_steps.position5 = (int)((cmd_arm.position[4]-prev_angle[4])*stepsPerRevolution[4]/(2*M_PI));\n  arm_steps.position6 = (int)((cmd_arm.position[5]-prev_angle[5])*stepsPerRevolution[5]/(2*M_PI));\n\n  ROS_INFO_NAMED(\"test\", \"arm_steps.position5 #2: %d\", arm_steps.position5);\n\n  if (count!=0){\n    prev_angle[0] = cmd_arm.position[0];\n    prev_angle[1] = cmd_arm.position[1];\n    prev_angle[2] = cmd_arm.position[2];\n    prev_angle[3] = cmd_arm.position[3];\n    prev_angle[4] = cmd_arm.position[4];\n    prev_angle[5] = cmd_arm.position[5];\n  }\n\n  //total steps taken to get to goal\n  // total_steps[0]+=arm_steps.position1;\n  // total_steps[1]+=arm_steps.position2;\n  // total_steps[2]+=arm_steps.position3;\n  // total_steps[3]+=arm_steps.position4;\n  // total_steps[4]+=arm_steps.position5;\n\n  total.position1 += arm_steps.position1;\n  total.position2 += arm_steps.position2;\n  total.position3 += arm_steps.position3;\n  total.position4 += arm_steps.position4;\n  total.position5 += arm_steps.position5;\n\n  ROS_INFO_NAMED(\"test\", \"total_steps[4]: %f, total: %d\", total_steps[4], total.position5);\n  ROS_INFO_NAMED(\"test\", \"arm_steps.position5 #3: %d\", arm_steps.position5);\n\n  ROS_INFO_STREAM(\"Done conversion to /joint_steps\");\n  joint_status = 1;\n  count=1;\n}\n\nint main(int argc, char **argv)\n{\n  ros::init(argc, argv, \"moveo_moveit\");\n  ros::NodeHandle nh;\n  ROS_INFO_STREAM(\"In main function\");\n  ros::Subscriber sub = nh.subscribe(\"/move_group/fake_controller_joint_states\",1000,cmd_cb);\n  ros::Publisher pub = nh.advertise<moveo_moveit::ArmJointState>(\"joint_steps\",50);\n  \n  ros::Rate loop_rate(20);\n\n  while (ros::ok())\n  {\n    if(joint_status==1)\n    {\n      joint_status = 0;\n      //pub.publish(arm_steps);\n      pub.publish(total);\n      ROS_INFO_STREAM(\"Published to /joint_steps\");\n    }\n    ros::spinOnce();\n    loop_rate.sleep();  \n  }\n\n  //ros::spin();\n  return 0;\n}\n"
  },
  {
    "path": "moveo_moveit_config/.setup_assistant",
    "content": "moveit_setup_assistant_config:\n  URDF:\n    package: moveo_urdf\n    relative_path: urdf/moveo_urdf.urdf\n  SRDF:\n    relative_path: config/moveo_urdf.srdf\n  CONFIG:\n    author_name: Jesse Weisberg\n    author_email: jesse.weisberg@gmail.com\n    generated_timestamp: 1510359526"
  },
  {
    "path": "moveo_moveit_config/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 2.8.3)\nproject(moveo_moveit_config)\n\nfind_package(catkin REQUIRED)\n\ncatkin_package()\n\ninstall(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n  PATTERN \"setup_assistant.launch\" EXCLUDE)\ninstall(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})\n"
  },
  {
    "path": "moveo_moveit_config/config/fake_controllers.yaml",
    "content": "controller_list:\n  - name: fake_arm_controller\n    joints:\n      - Joint_1\n      - Joint_2\n      - Joint_3\n      - Joint_4\n      - Joint_5\n  - name: fake_gripper_controller\n    joints:\n      - Gripper_Idol_Gear_Joint\n      - Gripper_Servo_Gear_Joint"
  },
  {
    "path": "moveo_moveit_config/config/joint_limits.yaml",
    "content": "# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed\n# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]\n# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]\njoint_limits:\n  Gripper_Idol_Gear_Joint:\n    has_velocity_limits: true\n    max_velocity: 1\n    has_acceleration_limits: false\n    max_acceleration: 0\n  Gripper_Servo_Gear_Joint:\n    has_velocity_limits: true\n    max_velocity: 1\n    has_acceleration_limits: false\n    max_acceleration: 0\n  Joint_1:\n    has_velocity_limits: true\n    max_velocity: 1\n    has_acceleration_limits: false\n    max_acceleration: 0\n  Joint_2:\n    has_velocity_limits: true\n    max_velocity: 1\n    has_acceleration_limits: false\n    max_acceleration: 0\n  Joint_3:\n    has_velocity_limits: true\n    max_velocity: 1\n    has_acceleration_limits: false\n    max_acceleration: 0\n  Joint_4:\n    has_velocity_limits: true\n    max_velocity: 1\n    has_acceleration_limits: false\n    max_acceleration: 0\n  Joint_5:\n    has_velocity_limits: true\n    max_velocity: 1\n    has_acceleration_limits: false\n    max_acceleration: 0\n  Pivot_Arm_Gripper_Idol_Joint:\n    has_velocity_limits: true\n    max_velocity: 1\n    has_acceleration_limits: false\n    max_acceleration: 0\n  Pivot_Arm_Gripper_Servo_Joint:\n    has_velocity_limits: true\n    max_velocity: 1\n    has_acceleration_limits: false\n    max_acceleration: 0\n  Tip_Gripper_Idol_Joint:\n    has_velocity_limits: true\n    max_velocity: 1\n    has_acceleration_limits: false\n    max_acceleration: 0\n  Tip_Gripper_Servo_Joint:\n    has_velocity_limits: true\n    max_velocity: 1\n    has_acceleration_limits: false\n    max_acceleration: 0"
  },
  {
    "path": "moveo_moveit_config/config/kinematics.yaml",
    "content": "arm:\n  kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin\n  kinematics_solver_search_resolution: 0.005\n  kinematics_solver_timeout: 0.005\n  kinematics_solver_attempts: 3"
  },
  {
    "path": "moveo_moveit_config/config/moveo_urdf.srdf",
    "content": "<?xml version=\"1.0\" ?>\n<!--This does not replace URDF, and is not an extension of URDF.\n    This is a format for representing semantic information about the robot structure.\n    A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined\n-->\n<robot name=\"moveo_urdf\">\n    <!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->\n    <!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->\n    <!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->\n    <!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->\n    <!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->\n    <group name=\"arm\">\n        <chain base_link=\"base_link\" tip_link=\"Link_5\" />\n    </group>\n    <group name=\"gripper\">\n        <link name=\"Gripper_Idol_Gear\" />\n        <link name=\"Tip_Gripper_Idol\" />\n        <link name=\"Gripper_Servo_Gear\" />\n        <link name=\"Tip_Gripper_Servo\" />\n        <link name=\"Pivot_Arm_Gripper_Idol\" />\n        <link name=\"Pivot_Arm_Gripper_Servo\" />\n    </group>\n    <!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->\n    <group_state name=\"Upright\" group=\"arm\">\n        <joint name=\"Joint_1\" value=\"0\" />\n        <joint name=\"Joint_2\" value=\"0.6386\" />\n        <joint name=\"Joint_3\" value=\"0.5523\" />\n        <joint name=\"Joint_4\" value=\"-0.4143\" />\n        <joint name=\"Joint_5\" value=\"0.9148\" />\n    </group_state>\n    <!--END EFFECTOR: Purpose: Represent information about an end effector.-->\n    <end_effector name=\"gripper_ee\" parent_link=\"Link_5\" group=\"gripper\" />\n    <!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->\n    <virtual_joint name=\"base_odom\" type=\"planar\" parent_frame=\"odom\" child_link=\"base_link\" />\n    <!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->\n    <disable_collisions link1=\"Gripper_Idol_Gear\" link2=\"Gripper_Servo_Gear\" reason=\"Never\" />\n    <disable_collisions link1=\"Gripper_Idol_Gear\" link2=\"Link_2\" reason=\"Never\" />\n    <disable_collisions link1=\"Gripper_Idol_Gear\" link2=\"Link_3\" reason=\"Never\" />\n    <disable_collisions link1=\"Gripper_Idol_Gear\" link2=\"Link_4\" reason=\"Never\" />\n    <disable_collisions link1=\"Gripper_Idol_Gear\" link2=\"Link_5\" reason=\"Adjacent\" />\n    <disable_collisions link1=\"Gripper_Idol_Gear\" link2=\"Pivot_Arm_Gripper_Servo\" reason=\"Never\" />\n    <disable_collisions link1=\"Gripper_Idol_Gear\" link2=\"Tip_Gripper_Idol\" reason=\"Adjacent\" />\n    <disable_collisions link1=\"Gripper_Idol_Gear\" link2=\"Tip_Gripper_Servo\" reason=\"Never\" />\n    <disable_collisions link1=\"Gripper_Servo_Gear\" link2=\"Link_2\" reason=\"Never\" />\n    <disable_collisions link1=\"Gripper_Servo_Gear\" link2=\"Link_3\" reason=\"Never\" />\n    <disable_collisions link1=\"Gripper_Servo_Gear\" link2=\"Link_4\" reason=\"Never\" />\n    <disable_collisions link1=\"Gripper_Servo_Gear\" link2=\"Link_5\" reason=\"Adjacent\" />\n    <disable_collisions link1=\"Gripper_Servo_Gear\" link2=\"Pivot_Arm_Gripper_Idol\" reason=\"Never\" />\n    <disable_collisions link1=\"Gripper_Servo_Gear\" link2=\"Tip_Gripper_Idol\" reason=\"Never\" />\n    <disable_collisions link1=\"Gripper_Servo_Gear\" link2=\"Tip_Gripper_Servo\" reason=\"Adjacent\" />\n    <disable_collisions link1=\"Link_1\" link2=\"Link_2\" reason=\"Adjacent\" />\n    <disable_collisions link1=\"Link_1\" link2=\"base_link\" reason=\"Adjacent\" />\n    <disable_collisions link1=\"Link_2\" link2=\"Link_3\" reason=\"Adjacent\" />\n    <disable_collisions link1=\"Link_2\" link2=\"Link_4\" reason=\"Never\" />\n    <disable_collisions link1=\"Link_2\" link2=\"Link_5\" reason=\"Never\" />\n    <disable_collisions link1=\"Link_2\" link2=\"Pivot_Arm_Gripper_Idol\" reason=\"Never\" />\n    <disable_collisions link1=\"Link_2\" link2=\"Pivot_Arm_Gripper_Servo\" reason=\"Never\" />\n    <disable_collisions link1=\"Link_3\" link2=\"Link_4\" reason=\"Adjacent\" />\n    <disable_collisions link1=\"Link_3\" link2=\"Link_5\" reason=\"Never\" />\n    <disable_collisions link1=\"Link_3\" link2=\"Pivot_Arm_Gripper_Idol\" reason=\"Never\" />\n    <disable_collisions link1=\"Link_3\" link2=\"Pivot_Arm_Gripper_Servo\" reason=\"Never\" />\n    <disable_collisions link1=\"Link_3\" link2=\"Tip_Gripper_Idol\" reason=\"Never\" />\n    <disable_collisions link1=\"Link_3\" link2=\"Tip_Gripper_Servo\" reason=\"Never\" />\n    <disable_collisions link1=\"Link_4\" link2=\"Link_5\" reason=\"Adjacent\" />\n    <disable_collisions link1=\"Link_4\" link2=\"Pivot_Arm_Gripper_Idol\" reason=\"Never\" />\n    <disable_collisions link1=\"Link_4\" link2=\"Pivot_Arm_Gripper_Servo\" reason=\"Never\" />\n    <disable_collisions link1=\"Link_4\" link2=\"Tip_Gripper_Idol\" reason=\"Never\" />\n    <disable_collisions link1=\"Link_4\" link2=\"Tip_Gripper_Servo\" reason=\"Never\" />\n    <disable_collisions link1=\"Link_5\" link2=\"Pivot_Arm_Gripper_Idol\" reason=\"Adjacent\" />\n    <disable_collisions link1=\"Link_5\" link2=\"Pivot_Arm_Gripper_Servo\" reason=\"Adjacent\" />\n    <disable_collisions link1=\"Link_5\" link2=\"Tip_Gripper_Idol\" reason=\"Never\" />\n    <disable_collisions link1=\"Link_5\" link2=\"Tip_Gripper_Servo\" reason=\"Never\" />\n    <disable_collisions link1=\"Pivot_Arm_Gripper_Idol\" link2=\"Pivot_Arm_Gripper_Servo\" reason=\"Never\" />\n    <disable_collisions link1=\"Pivot_Arm_Gripper_Idol\" link2=\"Tip_Gripper_Idol\" reason=\"Default\" />\n    <disable_collisions link1=\"Pivot_Arm_Gripper_Idol\" link2=\"Tip_Gripper_Servo\" reason=\"Never\" />\n    <disable_collisions link1=\"Pivot_Arm_Gripper_Servo\" link2=\"Tip_Gripper_Idol\" reason=\"Never\" />\n    <disable_collisions link1=\"Pivot_Arm_Gripper_Servo\" link2=\"Tip_Gripper_Servo\" reason=\"Default\" />\n    <disable_collisions link1=\"Tip_Gripper_Idol\" link2=\"Tip_Gripper_Servo\" reason=\"Never\" />\n</robot>\n"
  },
  {
    "path": "moveo_moveit_config/config/ompl_planning.yaml",
    "content": "planner_configs:\n  SBLkConfigDefault:\n    type: geometric::SBL\n    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()\n  ESTkConfigDefault:\n    type: geometric::EST\n    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup()\n    goal_bias: 0.05  # When close to goal select goal, with this probability. default: 0.05\n  LBKPIECEkConfigDefault:\n    type: geometric::LBKPIECE\n    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()\n    border_fraction: 0.9  # Fraction of time focused on boarder default: 0.9\n    min_valid_path_fraction: 0.5  # Accept partially valid moves above fraction. default: 0.5\n  BKPIECEkConfigDefault:\n    type: geometric::BKPIECE\n    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()\n    border_fraction: 0.9  # Fraction of time focused on boarder default: 0.9\n    failed_expansion_score_factor: 0.5  # When extending motion fails, scale score by factor. default: 0.5\n    min_valid_path_fraction: 0.5  # Accept partially valid moves above fraction. default: 0.5\n  KPIECEkConfigDefault:\n    type: geometric::KPIECE\n    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()\n    goal_bias: 0.05  # When close to goal select goal, with this probability. default: 0.05 \n    border_fraction: 0.9  # Fraction of time focused on boarder default: 0.9 (0.0,1.]\n    failed_expansion_score_factor: 0.5  # When extending motion fails, scale score by factor. default: 0.5\n    min_valid_path_fraction: 0.5  # Accept partially valid moves above fraction. default: 0.5\n  RRTkConfigDefault:\n    type: geometric::RRT\n    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()\n    goal_bias: 0.05  # When close to goal select goal, with this probability? default: 0.05\n  RRTConnectkConfigDefault:\n    type: geometric::RRTConnect\n    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()\n  RRTstarkConfigDefault:\n    type: geometric::RRTstar\n    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()\n    goal_bias: 0.05  # When close to goal select goal, with this probability? default: 0.05\n    delay_collision_checking: 1  # Stop collision checking as soon as C-free parent found. default 1\n  TRRTkConfigDefault:\n    type: geometric::TRRT\n    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()\n    goal_bias: 0.05  # When close to goal select goal, with this probability? default: 0.05\n    max_states_failed: 10  # when to start increasing temp. default: 10\n    temp_change_factor: 2.0  # how much to increase or decrease temp. default: 2.0\n    min_temperature: 10e-10  # lower limit of temp change. default: 10e-10\n    init_temperature: 10e-6  # initial temperature. default: 10e-6\n    frountier_threshold: 0.0  # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() \n    frountierNodeRatio: 0.1  # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1\n    k_constant: 0.0  # value used to normalize expresssion. default: 0.0 set in setup()\n  PRMkConfigDefault:\n    type: geometric::PRM\n    max_nearest_neighbors: 10  # use k nearest neighbors. default: 10\n  PRMstarkConfigDefault:\n    type: geometric::PRMstar\n  FMTkConfigDefault:\n    type: geometric::FMT\n    num_samples: 1000  # number of states that the planner should sample. default: 1000\n    radius_multiplier: 1.1  # multiplier used for the nearest neighbors search radius. default: 1.1\n    nearest_k: 1  # use Knearest strategy. default: 1\n    cache_cc: 1  # use collision checking cache. default: 1\n    heuristics: 0  # activate cost to go heuristics. default: 0\n    extended_fmt: 1  # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1\n  BFMTkConfigDefault:\n    type: geometric::BFMT\n    num_samples: 1000  # number of states that the planner should sample. default: 1000\n    radius_multiplier: 1.0  # multiplier used for the nearest neighbors search radius. default: 1.0\n    nearest_k: 1  # use the Knearest strategy. default: 1\n    balanced: 0  # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1\n    optimality: 1  # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1\n    heuristics: 1  # activates cost to go heuristics. default: 1\n    cache_cc: 1  # use the collision checking cache. default: 1\n    extended_fmt: 1  # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1\n  PDSTkConfigDefault:\n    type: geometric::PDST\n  STRIDEkConfigDefault:\n    type: geometric::STRIDE\n    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()\n    goal_bias: 0.05  # When close to goal select goal, with this probability. default: 0.05 \n    use_projected_distance: 0  # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0\n    degree: 16  # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 \n    max_degree: 18  # max degree of a node in the GNAT. default: 12\n    min_degree: 12  # min degree of a node in the GNAT. default: 12\n    max_pts_per_leaf: 6  # max points per leaf in the GNAT. default: 6\n    estimated_dimension: 0.0  # estimated dimension of the free space. default: 0.0\n    min_valid_path_fraction: 0.2  # Accept partially valid moves above fraction. default: 0.2\n  BiTRRTkConfigDefault:\n    type: geometric::BiTRRT\n    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()\n    temp_change_factor: 0.1  # how much to increase or decrease temp. default: 0.1\n    init_temperature: 100  # initial temperature. default: 100\n    frountier_threshold: 0.0  # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() \n    frountier_node_ratio: 0.1  # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1\n    cost_threshold: 1e300  # the cost threshold. Any motion cost that is not better will not be expanded. default: inf\n  LBTRRTkConfigDefault:\n    type: geometric::LBTRRT\n    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()\n    goal_bias: 0.05  # When close to goal select goal, with this probability. default: 0.05 \n    epsilon: 0.4  # optimality approximation factor. default: 0.4\n  BiESTkConfigDefault:\n    type: geometric::BiEST\n    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()\n  ProjESTkConfigDefault:\n    type: geometric::ProjEST\n    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()\n    goal_bias: 0.05  # When close to goal select goal, with this probability. default: 0.05 \n  LazyPRMkConfigDefault:\n    type: geometric::LazyPRM\n    range: 0.0  # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()\n  LazyPRMstarkConfigDefault:\n    type: geometric::LazyPRMstar\n  SPARSkConfigDefault:\n    type: geometric::SPARS\n    stretch_factor: 3.0  # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0\n    sparse_delta_fraction: 0.25  # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25\n    dense_delta_fraction: 0.001  # delta fraction for interface detection. default: 0.001\n    max_failures: 1000  # maximum consecutive failure limit. default: 1000\n  SPARStwokConfigDefault:\n    type: geometric::SPARStwo\n    stretch_factor: 3.0  # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0\n    sparse_delta_fraction: 0.25  # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25\n    dense_delta_fraction: 0.001  # delta fraction for interface detection. default: 0.001\n    max_failures: 5000  # maximum consecutive failure limit. default: 5000\narm:\n  planner_configs:\n    - SBLkConfigDefault\n    - ESTkConfigDefault\n    - LBKPIECEkConfigDefault\n    - BKPIECEkConfigDefault\n    - KPIECEkConfigDefault\n    - RRTkConfigDefault\n    - RRTConnectkConfigDefault\n    - RRTstarkConfigDefault\n    - TRRTkConfigDefault\n    - PRMkConfigDefault\n    - PRMstarkConfigDefault\n    - FMTkConfigDefault\n    - BFMTkConfigDefault\n    - PDSTkConfigDefault\n    - STRIDEkConfigDefault\n    - BiTRRTkConfigDefault\n    - LBTRRTkConfigDefault\n    - BiESTkConfigDefault\n    - ProjESTkConfigDefault\n    - LazyPRMkConfigDefault\n    - LazyPRMstarkConfigDefault\n    - SPARSkConfigDefault\n    - SPARStwokConfigDefault\n  projection_evaluator: joints(Joint_1,Joint_2)\n  longest_valid_segment_fraction: 0.005\ngripper:\n  planner_configs:\n    - SBLkConfigDefault\n    - ESTkConfigDefault\n    - LBKPIECEkConfigDefault\n    - BKPIECEkConfigDefault\n    - KPIECEkConfigDefault\n    - RRTkConfigDefault\n    - RRTConnectkConfigDefault\n    - RRTstarkConfigDefault\n    - TRRTkConfigDefault\n    - PRMkConfigDefault\n    - PRMstarkConfigDefault\n    - FMTkConfigDefault\n    - BFMTkConfigDefault\n    - PDSTkConfigDefault\n    - STRIDEkConfigDefault\n    - BiTRRTkConfigDefault\n    - LBTRRTkConfigDefault\n    - BiESTkConfigDefault\n    - ProjESTkConfigDefault\n    - LazyPRMkConfigDefault\n    - LazyPRMstarkConfigDefault\n    - SPARSkConfigDefault\n    - SPARStwokConfigDefault\n  projection_evaluator: joints(Gripper_Idol_Gear_Joint,Tip_Gripper_Idol_Joint)\n  longest_valid_segment_fraction: 0.005"
  },
  {
    "path": "moveo_moveit_config/launch/default_warehouse_db.launch",
    "content": "<launch>\n\n  <arg name=\"reset\" default=\"false\"/>\n  <!-- If not specified, we'll use a default database location -->\n  <arg name=\"moveit_warehouse_database_path\" default=\"$(find moveo_moveit_config)/default_warehouse_mongo_db\" />\n\n  <!-- Launch the warehouse with the configured database location -->\n  <include file=\"$(find moveo_moveit_config)/launch/warehouse.launch\">\n    <arg name=\"moveit_warehouse_database_path\" value=\"$(arg moveit_warehouse_database_path)\" />\n  </include>\n\n  <!-- If we want to reset the database, run this node -->\n  <node if=\"$(arg reset)\" name=\"$(anon moveit_default_db_reset)\" type=\"moveit_init_demo_warehouse\" pkg=\"moveit_ros_warehouse\" respawn=\"false\" output=\"screen\" />\n\n</launch>\n"
  },
  {
    "path": "moveo_moveit_config/launch/demo.launch",
    "content": "<launch>\n\n  <!-- By default, we do not start a database (it can be large) -->\n  <arg name=\"db\" default=\"false\" />\n  <!-- Allow user to specify database location -->\n  <arg name=\"db_path\" default=\"$(find moveo_moveit_config)/default_warehouse_mongo_db\" />\n\n  <!-- By default, we are not in debug mode -->\n  <arg name=\"debug\" default=\"false\" />\n\n  <!--\n  By default, hide joint_state_publisher's GUI\n\n  MoveIt!'s \"demo\" mode replaces the real robot driver with the joint_state_publisher.\n  The latter one maintains and publishes the current joint configuration of the simulated robot.\n  It also provides a GUI to move the simulated robot around \"manually\".\n  This corresponds to moving around the real robot without the use of MoveIt.\n  -->\n  <arg name=\"use_gui\" default=\"false\" />\n\n  <!-- Load the URDF, SRDF and other .yaml configuration files on the param server -->\n  <include file=\"$(find moveo_moveit_config)/launch/planning_context.launch\">\n    <arg name=\"load_robot_description\" value=\"true\"/>\n  </include>\n\n  <!-- If needed, broadcast static tf for robot root -->\n    <node pkg=\"tf\" type=\"static_transform_publisher\" name=\"virtual_joint_broadcaster_0\" args=\"0 0 0 0 0 0 odom base_link 100\" />\n\n\n  <!-- We do not have a robot connected, so publish fake joint states -->\n  <node name=\"joint_state_publisher\" pkg=\"joint_state_publisher\" type=\"joint_state_publisher\">\n    <param name=\"/use_gui\" value=\"$(arg use_gui)\"/>\n    <rosparam param=\"/source_list\">[/move_group/fake_controller_joint_states]</rosparam>\n  </node>\n\n  <!-- Given the published joint states, publish tf for the robot links -->\n  <node name=\"robot_state_publisher\" pkg=\"robot_state_publisher\" type=\"robot_state_publisher\" respawn=\"true\" output=\"screen\" />\n\n  <!-- Run the main MoveIt executable without trajectory execution (we do not have controllers configured by default) -->\n  <include file=\"$(find moveo_moveit_config)/launch/move_group.launch\">\n    <arg name=\"allow_trajectory_execution\" value=\"true\"/>\n    <arg name=\"fake_execution\" value=\"true\"/>\n    <arg name=\"info\" value=\"true\"/>\n    <arg name=\"debug\" value=\"$(arg debug)\"/>\n  </include>\n\n  <!-- Run Rviz and load the default config to see the state of the move_group node -->\n  <include file=\"$(find moveo_moveit_config)/launch/moveit_rviz.launch\">\n    <arg name=\"config\" value=\"true\"/>\n    <arg name=\"debug\" value=\"$(arg debug)\"/>\n  </include>\n\n  <!-- If database loading was enabled, start mongodb as well -->\n  <include file=\"$(find moveo_moveit_config)/launch/default_warehouse_db.launch\" if=\"$(arg db)\">\n    <arg name=\"moveit_warehouse_database_path\" value=\"$(arg db_path)\"/>\n  </include>\n\n</launch>\n"
  },
  {
    "path": "moveo_moveit_config/launch/fake_moveit_controller_manager.launch.xml",
    "content": "<launch>\n\n  <!-- Set the param that trajectory_execution_manager needs to find the controller plugin -->\n  <param name=\"moveit_controller_manager\" value=\"moveit_fake_controller_manager/MoveItFakeControllerManager\"/>\n\n  <!-- The rest of the params are specific to this plugin -->\n  <rosparam file=\"$(find moveo_moveit_config)/config/fake_controllers.yaml\"/>\n\n</launch>\n"
  },
  {
    "path": "moveo_moveit_config/launch/joystick_control.launch",
    "content": "<launch>\n  <!-- See moveit_ros/visualization/doc/joystick.rst for documentation -->\n\n  <arg name=\"dev\" default=\"/dev/input/js0\" />\n\n  <!-- Launch joy node -->\n  <node pkg=\"joy\" type=\"joy_node\" name=\"joy\">\n    <param name=\"dev\" value=\"$(arg dev)\" /> <!-- Customize this to match the location your joystick is plugged in on-->\n    <param name=\"deadzone\" value=\"0.2\" />\n    <param name=\"autorepeat_rate\" value=\"40\" />\n    <param name=\"coalesce_interval\" value=\"0.025\" />\n  </node>\n\n  <!-- Launch python interface -->\n  <node pkg=\"moveit_ros_visualization\" type=\"moveit_joy.py\" output=\"screen\" name=\"moveit_joy\"/>\n        \n</launch>\n"
  },
  {
    "path": "moveo_moveit_config/launch/move_group.launch",
    "content": "<launch>\n\n  <include file=\"$(find moveo_moveit_config)/launch/planning_context.launch\" />\n\n  <!-- GDB Debug Option -->\n  <arg name=\"debug\" default=\"false\" />\n  <arg unless=\"$(arg debug)\" name=\"launch_prefix\" value=\"\" />\n  <arg     if=\"$(arg debug)\" name=\"launch_prefix\"\n\t   value=\"gdb -x $(find moveo_moveit_config)/launch/gdb_settings.gdb --ex run --args\" />\n\n  <!-- Verbose Mode Option -->\n  <arg name=\"info\" default=\"$(arg debug)\" />\n  <arg unless=\"$(arg info)\" name=\"command_args\" value=\"\" />\n  <arg     if=\"$(arg info)\" name=\"command_args\" value=\"--debug\" />\n\n  <!-- move_group settings -->\n  <arg name=\"allow_trajectory_execution\" default=\"true\"/>\n  <arg name=\"fake_execution\" default=\"false\"/>\n  <arg name=\"max_safe_path_cost\" default=\"1\"/>\n  <arg name=\"jiggle_fraction\" default=\"0.05\" />\n  <arg name=\"publish_monitored_planning_scene\" default=\"true\"/>\n\n  <!-- Planning Functionality -->\n  <include ns=\"move_group\" file=\"$(find moveo_moveit_config)/launch/planning_pipeline.launch.xml\">\n    <arg name=\"pipeline\" value=\"ompl\" />\n  </include>\n\n  <!-- Trajectory Execution Functionality -->\n  <include ns=\"move_group\" file=\"$(find moveo_moveit_config)/launch/trajectory_execution.launch.xml\" if=\"$(arg allow_trajectory_execution)\">\n    <arg name=\"moveit_manage_controllers\" value=\"true\" />\n    <arg name=\"moveit_controller_manager\" value=\"moveo_urdf\" unless=\"$(arg fake_execution)\"/>\n    <arg name=\"moveit_controller_manager\" value=\"fake\" if=\"$(arg fake_execution)\"/>\n  </include>\n\n  <!-- Sensors Functionality -->\n  <include ns=\"move_group\" file=\"$(find moveo_moveit_config)/launch/sensor_manager.launch.xml\" if=\"$(arg allow_trajectory_execution)\">\n    <arg name=\"moveit_sensor_manager\" value=\"moveo_urdf\" />\n  </include>\n\n  <!-- Start the actual move_group node/action server -->\n  <node name=\"move_group\" launch-prefix=\"$(arg launch_prefix)\" pkg=\"moveit_ros_move_group\" type=\"move_group\" respawn=\"false\" output=\"screen\" args=\"$(arg command_args)\">\n    <!-- Set the display variable, in case OpenGL code is used internally -->\n    <env name=\"DISPLAY\" value=\"$(optenv DISPLAY :0)\" />\n\n    <param name=\"allow_trajectory_execution\" value=\"$(arg allow_trajectory_execution)\"/>\n    <param name=\"max_safe_path_cost\" value=\"$(arg max_safe_path_cost)\"/>\n    <param name=\"jiggle_fraction\" value=\"$(arg jiggle_fraction)\" />\n\n    <!-- load these non-default MoveGroup capabilities -->\n    <!--\n    <param name=\"capabilities\" value=\"\n                  a_package/AwsomeMotionPlanningCapability\n                  another_package/GraspPlanningPipeline\n                  \" />\n    -->\n\n    <!-- inhibit these default MoveGroup capabilities -->\n    <!--\n    <param name=\"disable_capabilities\" value=\"\n                  move_group/MoveGroupKinematicsService\n                  move_group/ClearOctomapService\n                  \" />\n    -->\n\n    <!-- Publish the planning scene of the physical robot so that rviz plugin can know actual robot -->\n    <param name=\"planning_scene_monitor/publish_planning_scene\" value=\"$(arg publish_monitored_planning_scene)\" />\n    <param name=\"planning_scene_monitor/publish_geometry_updates\" value=\"$(arg publish_monitored_planning_scene)\" />\n    <param name=\"planning_scene_monitor/publish_state_updates\" value=\"$(arg publish_monitored_planning_scene)\" />\n    <param name=\"planning_scene_monitor/publish_transforms_updates\" value=\"$(arg publish_monitored_planning_scene)\" />\n  </node>\n\n</launch>\n"
  },
  {
    "path": "moveo_moveit_config/launch/moveit.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 0\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /MotionPlanning1/Scene Robot1\n        - /MarkerArray1\n        - /Axes1\n      Splitter Ratio: 0.742560029\n    Tree Height: 294\n  - Class: rviz/Help\n    Name: Help\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz_visual_tools/RvizVisualToolsGui\n    Name: RvizVisualToolsGui\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 0.200000003\n      Class: rviz/Grid\n      Color: 160; 160; 164\n      Enabled: true\n      Line Style:\n        Line Width: 0.0299999993\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 10\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Class: moveit_rviz_plugin/MotionPlanning\n      Enabled: true\n      Move Group Namespace: \"\"\n      MoveIt_Goal_Tolerance: 0\n      MoveIt_Planning_Attempts: 10\n      MoveIt_Planning_Time: 5\n      MoveIt_Use_Constraint_Aware_IK: true\n      MoveIt_Warehouse_Host: 127.0.0.1\n      MoveIt_Warehouse_Port: 33829\n      MoveIt_Workspace:\n        Center:\n          X: 0\n          Y: 0\n          Z: 0\n        Size:\n          X: 2\n          Y: 2\n          Z: 2\n      Name: MotionPlanning\n      Planned Path:\n        Color Enabled: false\n        Interrupt Display: false\n        Links:\n          All Links Enabled: true\n          Expand Joint Details: false\n          Expand Link Details: false\n          Expand Tree: false\n          Gripper_Idol_Gear:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Gripper_Servo_Gear:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Link Tree Style: Links in Alphabetic Order\n          Link_1:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Link_2:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Link_3:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Link_4:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Link_5:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Pivot_Arm_Gripper_Idol:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Pivot_Arm_Gripper_Servo:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Tip_Gripper_Idol:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Tip_Gripper_Servo:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          base_link:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          odom:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n        Loop Animation: true\n        Robot Alpha: 0.5\n        Robot Color: 150; 50; 150\n        Show Robot Collision: false\n        Show Robot Visual: true\n        Show Trail: false\n        State Display Time: 0.05 s\n        Trail Step Size: 1\n        Trajectory Topic: move_group/display_planned_path\n      Planning Metrics:\n        Payload: 1\n        Show Joint Torques: false\n        Show Manipulability: false\n        Show Manipulability Index: false\n        Show Weight Limit: false\n        TextHeight: 0.0799999982\n      Planning Request:\n        Colliding Link Color: 255; 0; 0\n        Goal State Alpha: 1\n        Goal State Color: 250; 128; 0\n        Interactive Marker Size: 0.200000003\n        Joint Violation Color: 255; 0; 255\n        Planning Group: arm\n        Query Goal State: true\n        Query Start State: false\n        Show Workspace: false\n        Start State Alpha: 1\n        Start State Color: 0; 255; 0\n      Planning Scene Topic: move_group/monitored_planning_scene\n      Robot Description: robot_description\n      Scene Geometry:\n        Scene Alpha: 1\n        Scene Color: 50; 230; 50\n        Scene Display Time: 0.200000003\n        Show Scene Geometry: true\n        Voxel Coloring: Z-Axis\n        Voxel Rendering: Occupied Voxels\n      Scene Robot:\n        Attached Body Color: 150; 50; 150\n        Links:\n          All Links Enabled: true\n          Expand Joint Details: false\n          Expand Link Details: false\n          Expand Tree: false\n          Gripper_Idol_Gear:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Gripper_Servo_Gear:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Link Tree Style: Links in Alphabetic Order\n          Link_1:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Link_2:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Link_3:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Link_4:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Link_5:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Pivot_Arm_Gripper_Idol:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Pivot_Arm_Gripper_Servo:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Tip_Gripper_Idol:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          Tip_Gripper_Servo:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          base_link:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n            Value: true\n          odom:\n            Alpha: 1\n            Show Axes: false\n            Show Trail: false\n        Robot Alpha: 0.5\n        Show Robot Collision: false\n        Show Robot Visual: true\n      Value: true\n    - Class: rviz/MarkerArray\n      Enabled: true\n      Marker Topic: rviz_visual_tools\n      Name: MarkerArray\n      Namespaces:\n        {}\n      Queue Size: 100\n      Value: true\n    - Class: rviz/Axes\n      Enabled: true\n      Length: 0.100000001\n      Name: Axes\n      Radius: 0.0199999996\n      Reference Frame: <Fixed Frame>\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Fixed Frame: base_link\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/MoveCamera\n    - Class: rviz/Select\n  Value: true\n  Views:\n    Current:\n      Class: rviz/XYOrbit\n      Distance: 1.85478854\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.0599999987\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Focal Point:\n        X: 0.138867736\n        Y: -0.210714757\n        Z: 2.23518001e-07\n      Focal Shape Fixed Size: true\n      Focal Shape Size: 0.0500000007\n      Invert Z Axis: false\n      Name: Current View\n      Near Clip Distance: 0.00999999978\n      Pitch: 0.205203816\n      Target Frame: base_link\n      Value: XYOrbit (rviz)\n      Yaw: 2.23356652\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 1148\n  Help:\n    collapsed: false\n  Hide Left Dock: false\n  Hide Right Dock: true\n  MotionPlanning:\n    collapsed: false\n  MotionPlanning - Slider:\n    collapsed: false\n  QMainWindow State: 000000ff00000000fd0000000100000000000002b800000441fc0200000009fb000000100044006900730070006c006100790073010000002200000165000000db00fffffffb00000024005200760069007a00560069007300750061006c0054006f006f006c0073004700750069010000018b0000005a0000003d00fffffffb0000002e004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d00200053006c0069006400650072000000016f000000590000004400fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e006701000001e90000027a0000018700fffffffb0000000800480065006c00700000000342000000bb0000007000fffffffb0000000a005600690065007700730000000365000000b0000000ac00fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb000000120020002d00200053006c00690064006500720000000000ffffffff0000000000000000000003450000044100000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  RvizVisualToolsGui:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1537\n  X: 388\n  Y: 24\n"
  },
  {
    "path": "moveo_moveit_config/launch/moveit_rviz.launch",
    "content": "<launch>\n\n  <arg name=\"debug\" default=\"false\" />\n  <arg unless=\"$(arg debug)\" name=\"launch_prefix\" value=\"\" />\n  <arg     if=\"$(arg debug)\" name=\"launch_prefix\" value=\"gdb --ex run --args\" />\n\n  <arg name=\"config\" default=\"false\" />\n  <arg unless=\"$(arg config)\" name=\"command_args\" value=\"\" />\n  <arg     if=\"$(arg config)\" name=\"command_args\" value=\"-d $(find moveo_moveit_config)/launch/moveit.rviz\" />\n  \n  <node name=\"$(anon rviz)\" launch-prefix=\"$(arg launch_prefix)\" pkg=\"rviz\" type=\"rviz\" respawn=\"false\"\n\targs=\"$(arg command_args)\" output=\"screen\">\n    <rosparam command=\"load\" file=\"$(find moveo_moveit_config)/config/kinematics.yaml\"/>\n  </node>\n\n</launch>\n"
  },
  {
    "path": "moveo_moveit_config/launch/moveo_urdf_moveit_controller_manager.launch.xml",
    "content": "<launch>\n\n</launch>\n"
  },
  {
    "path": "moveo_moveit_config/launch/moveo_urdf_moveit_sensor_manager.launch.xml",
    "content": "<launch>\n\n</launch>\n"
  },
  {
    "path": "moveo_moveit_config/launch/ompl_planning_pipeline.launch.xml",
    "content": "<launch>\n\n  <!-- OMPL Plugin for MoveIt! -->\n  <arg name=\"planning_plugin\" value=\"ompl_interface/OMPLPlanner\" />\n\n  <!-- The request adapters (plugins) used when planning with OMPL. \n       ORDER MATTERS -->\n  <arg name=\"planning_adapters\" value=\"default_planner_request_adapters/AddTimeParameterization\n\t\t\t\t       default_planner_request_adapters/FixWorkspaceBounds\n\t\t\t\t       default_planner_request_adapters/FixStartStateBounds\n\t\t\t\t       default_planner_request_adapters/FixStartStateCollision\n\t\t\t\t       default_planner_request_adapters/FixStartStatePathConstraints\" />\n\n  <arg name=\"start_state_max_bounds_error\" value=\"0.1\" />\n\n  <param name=\"planning_plugin\" value=\"$(arg planning_plugin)\" />\n  <param name=\"request_adapters\" value=\"$(arg planning_adapters)\" />\n  <param name=\"start_state_max_bounds_error\" value=\"$(arg start_state_max_bounds_error)\" />\n\n  <rosparam command=\"load\" file=\"$(find moveo_moveit_config)/config/ompl_planning.yaml\"/>\n\n</launch>\n"
  },
  {
    "path": "moveo_moveit_config/launch/planning_context.launch",
    "content": "<launch>\n  <!-- By default we do not overwrite the URDF. Change the following to true to change the default behavior -->\n  <arg name=\"load_robot_description\" default=\"false\"/>\n\n  <!-- The name of the parameter under which the URDF is loaded -->\n  <arg name=\"robot_description\" default=\"robot_description\"/>\n\n  <!-- Load universal robot description format (URDF) -->\n  <param if=\"$(arg load_robot_description)\" name=\"$(arg robot_description)\" textfile=\"$(find moveo_urdf)/urdf/moveo_urdf.urdf\"/>\n\n  <!-- The semantic description that corresponds to the URDF -->\n  <param name=\"$(arg robot_description)_semantic\" textfile=\"$(find moveo_moveit_config)/config/moveo_urdf.srdf\" />\n  \n  <!-- Load updated joint limits (override information from URDF) -->\n  <group ns=\"$(arg robot_description)_planning\">\n    <rosparam command=\"load\" file=\"$(find moveo_moveit_config)/config/joint_limits.yaml\"/>\n  </group>\n\n  <!-- Load default settings for kinematics; these settings are overridden by settings in a node's namespace -->\n  <group ns=\"$(arg robot_description)_kinematics\">\n    <rosparam command=\"load\" file=\"$(find moveo_moveit_config)/config/kinematics.yaml\"/>\n  </group>\n  \n</launch>\n"
  },
  {
    "path": "moveo_moveit_config/launch/planning_pipeline.launch.xml",
    "content": "<launch>\n\n  <!-- This file makes it easy to include different planning pipelines; \n       It is assumed that all planning pipelines are named XXX_planning_pipeline.launch  -->  \n\n  <arg name=\"pipeline\" default=\"ompl\" />\n\n  <include file=\"$(find moveo_moveit_config)/launch/$(arg pipeline)_planning_pipeline.launch.xml\" />\n\n</launch>\n"
  },
  {
    "path": "moveo_moveit_config/launch/run_benchmark_ompl.launch",
    "content": "<launch>\n\n  <!-- This argument must specify the list of .cfg files to process for benchmarking -->\n  <arg name=\"cfg\" />\n\n  <!-- Load URDF -->\n  <include file=\"$(find moveo_moveit_config)/launch/planning_context.launch\">\n    <arg name=\"load_robot_description\" value=\"true\"/>\n  </include>\n\n  <!-- Start the database -->\n  <include file=\"$(find moveo_moveit_config)/launch/warehouse.launch\">\n    <arg name=\"moveit_warehouse_database_path\" value=\"moveit_ompl_benchmark_warehouse\"/>\n  </include>  \n\n  <!-- Start Benchmark Executable -->\n  <node name=\"$(anon moveit_benchmark)\" pkg=\"moveit_ros_benchmarks\" type=\"moveit_run_benchmark\" args=\"$(arg cfg) --benchmark-planners\" respawn=\"false\" output=\"screen\">\n    <rosparam command=\"load\" file=\"$(find moveo_moveit_config)/config/kinematics.yaml\"/>\n    <rosparam command=\"load\" file=\"$(find moveo_moveit_config)/config/ompl_planning.yaml\"/>\n  </node>\n\n</launch>\n"
  },
  {
    "path": "moveo_moveit_config/launch/sensor_manager.launch.xml",
    "content": "<launch>\n\n  <!-- This file makes it easy to include the settings for sensor managers -->  \n\n  <!-- Params for the octomap monitor -->\n  <!--  <param name=\"octomap_frame\" type=\"string\" value=\"some frame in which the robot moves\" /> -->\n  <param name=\"octomap_resolution\" type=\"double\" value=\"0.025\" />\n  <param name=\"max_range\" type=\"double\" value=\"5.0\" />\n\n  <!-- Load the robot specific sensor manager; this sets the moveit_sensor_manager ROS parameter -->\n  <arg name=\"moveit_sensor_manager\" default=\"moveo_urdf\" />\n  <include file=\"$(find moveo_moveit_config)/launch/$(arg moveit_sensor_manager)_moveit_sensor_manager.launch.xml\" />\n  \n</launch>\n"
  },
  {
    "path": "moveo_moveit_config/launch/setup_assistant.launch",
    "content": "<!-- Re-launch the MoveIt Setup Assistant with this configuration package already loaded -->\n<launch>\n\n  <!-- Debug Info -->\n  <arg name=\"debug\" default=\"false\" />\n  <arg unless=\"$(arg debug)\" name=\"launch_prefix\" value=\"\" />\n  <arg     if=\"$(arg debug)\" name=\"launch_prefix\" value=\"gdb --ex run --args\" />\n\n  <!-- Run -->\n  <node pkg=\"moveit_setup_assistant\" type=\"moveit_setup_assistant\" name=\"moveit_setup_assistant\" \n\targs=\"--config_pkg=moveo_moveit_config\"\n\tlaunch-prefix=\"$(arg launch_prefix)\"\n        output=\"screen\" />\n\n</launch>\n"
  },
  {
    "path": "moveo_moveit_config/launch/trajectory_execution.launch.xml",
    "content": "<launch>\n\n  <!-- This file makes it easy to include the settings for trajectory execution  -->  \n\n  <!-- Flag indicating whether MoveIt! is allowed to load/unload  or switch controllers -->\n  <arg name=\"moveit_manage_controllers\" default=\"true\"/>\n  <param name=\"moveit_manage_controllers\" value=\"$(arg moveit_manage_controllers)\"/>\n\n  <!-- When determining the expected duration of a trajectory, this multiplicative factor is applied to get the allowed duration of execution -->\n  <param name=\"trajectory_execution/allowed_execution_duration_scaling\" value=\"1.2\"/> <!-- default 1.2 -->\n  <!-- Allow more than the expected execution time before triggering a trajectory cancel (applied after scaling) -->\n  <param name=\"trajectory_execution/allowed_goal_duration_margin\" value=\"0.5\"/> <!-- default 0.5 -->\n  <!-- Allowed joint-value tolerance for validation that trajectory's first point matches current robot state -->\n  <param name=\"trajectory_execution/allowed_start_tolerance\" value=\"0.01\"/> <!-- default 0.01 -->\n  \n  <!-- Load the robot specific controller manager; this sets the moveit_controller_manager ROS parameter -->\n  <arg name=\"moveit_controller_manager\" default=\"moveo_urdf\" />\n  <include file=\"$(find moveo_moveit_config)/launch/$(arg moveit_controller_manager)_moveit_controller_manager.launch.xml\" />\n  \n</launch>\n"
  },
  {
    "path": "moveo_moveit_config/launch/warehouse.launch",
    "content": "<launch>\n  \n  <!-- The path to the database must be specified -->\n  <arg name=\"moveit_warehouse_database_path\" />\n\n  <!-- Load warehouse parameters -->  \n  <include file=\"$(find moveo_moveit_config)/launch/warehouse_settings.launch.xml\" />\n\n  <!-- Run the DB server -->\n  <node name=\"$(anon mongo_wrapper_ros)\" cwd=\"ROS_HOME\" type=\"mongo_wrapper_ros.py\" pkg=\"warehouse_ros_mongo\">\n    <param name=\"overwrite\" value=\"false\"/>\n    <param name=\"database_path\" value=\"$(arg moveit_warehouse_database_path)\" />\n  </node>\n\n</launch>\n"
  },
  {
    "path": "moveo_moveit_config/launch/warehouse_settings.launch.xml",
    "content": "<launch>\n  <!-- Set the parameters for the warehouse and run the mongodb server. -->\n\n  <!-- The default DB port for moveit (not default MongoDB port to avoid potential conflicts) -->  \n  <arg name=\"moveit_warehouse_port\" default=\"33829\" /> \n\n  <!-- The default DB host for moveit -->\n  <arg name=\"moveit_warehouse_host\" default=\"localhost\" /> \n  \n  <!-- Set parameters for the warehouse -->\n  <param name=\"warehouse_port\" value=\"$(arg moveit_warehouse_port)\"/>\n  <param name=\"warehouse_host\" value=\"$(arg moveit_warehouse_host)\"/>\n  <param name=\"warehouse_exec\" value=\"mongod\" />\n  <param name=\"warehouse_plugin\" value=\"warehouse_ros_mongo::MongoDatabaseConnection\" />\n\n</launch>\n"
  },
  {
    "path": "moveo_moveit_config/package.xml",
    "content": "<package>\n\n  <name>moveo_moveit_config</name>\n  <version>0.3.0</version>\n  <description>\n     An automatically generated package with all the configuration and launch files for using the moveo_urdf with the MoveIt! Motion Planning Framework\n  </description>\n  <author email=\"jesse.weisberg@gmail.com\">Jesse Weisberg</author>\n  <maintainer email=\"jesse.weisberg@gmail.com\">Jesse Weisberg</maintainer>\n\n  <license>BSD</license>\n\n  <url type=\"website\">http://moveit.ros.org/</url>\n  <url type=\"bugtracker\">https://github.com/ros-planning/moveit/issues</url>\n  <url type=\"repository\">https://github.com/ros-planning/moveit</url>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <run_depend>moveit_ros_move_group</run_depend>\n  <run_depend>moveit_kinematics</run_depend>\n  <run_depend>moveit_planners_ompl</run_depend>\n  <run_depend>moveit_ros_visualization</run_depend>\n  <run_depend>joint_state_publisher</run_depend>\n  <run_depend>robot_state_publisher</run_depend>\n  <run_depend>xacro</run_depend>\n  <!-- This package is referenced in the warehouse launch files, but does not build out of the box at the moment. Commented the dependency until this works. -->\n  <!-- <run_depend>warehouse_ros_mongo</run_depend> -->\n  <build_depend>moveo_urdf</build_depend>\n  <run_depend>moveo_urdf</run_depend>\n\n\n</package>\n"
  },
  {
    "path": "moveo_urdf/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 2.8.3)\r\n\r\nproject(moveo_urdf)\r\n\r\nfind_package(catkin REQUIRED)\r\n\r\ncatkin_package()\r\n\r\nfind_package(roslaunch)\r\n\r\nforeach(dir config launch meshes urdf)\r\n\tinstall(DIRECTORY ${dir}/\r\n\t\tDESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir})\r\nendforeach(dir)\r\n"
  },
  {
    "path": "moveo_urdf/config/joint_names_move_urdf.yaml",
    "content": "controller_joint_names: ['Joint_1', 'Joint_2', 'Joint_3', 'Joint_4', 'Joint_5', 'Gripper_Servo_Gear_Joint', 'Gripper_Idol_Gear_Joint', 'Pivot_Arm_Gripper_Servo_Joint', 'Pivot_Arm_Gripper_Idol_Joint', ]\r\n"
  },
  {
    "path": "moveo_urdf/launch/display.launch",
    "content": "<launch>\r\n  <arg\r\n    name=\"model\" />\r\n  <arg\r\n    name=\"gui\"\r\n    default=\"true\" />\r\n  <param\r\n    name=\"robot_description\"\r\n    textfile=\"$(find moveo_urdf)/urdf/moveo_urdf.urdf\" />\r\n  <param\r\n    name=\"use_gui\"\r\n    value=\"$(arg gui)\" />\r\n  <node\r\n    name=\"joint_state_publisher\"\r\n    pkg=\"joint_state_publisher\"\r\n    type=\"joint_state_publisher\" />\r\n  <node\r\n    name=\"robot_state_publisher\"\r\n    pkg=\"robot_state_publisher\"\r\n    type=\"state_publisher\" />\r\n  <node\r\n    name=\"rviz\"\r\n    pkg=\"rviz\"\r\n    type=\"rviz\"\r\n    args=\"-d $(find moveo_urdf)/urdf.rviz\" />\r\n</launch>\r\n"
  },
  {
    "path": "moveo_urdf/launch/gazebo.launch",
    "content": "<launch>\r\n\r\n  <!-- these are the arguments you can pass this launch file, for example paused:=true -->\r\n  <arg name=\"paused\" default=\"true\"/>\r\n  <arg name=\"use_sim_time\" default=\"true\"/>\r\n  <arg name=\"gui\" default=\"true\"/>\r\n  <arg name=\"headless\" default=\"false\"/>\r\n  <arg name=\"debug\" default=\"false\"/>\r\n  <arg name=\"model\" default=\"$(find moveo_urdf)/urdf/moveo_urdf.urdf\"/>\r\n\r\n  <!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->\r\n  <include file=\"$(find gazebo_ros)/launch/empty_world.launch\">\r\n    <arg name=\"debug\" value=\"$(arg debug)\" />\r\n    <arg name=\"gui\" value=\"$(arg gui)\" />\r\n    <arg name=\"paused\" value=\"$(arg paused)\"/>\r\n    <arg name=\"use_sim_time\" value=\"$(arg use_sim_time)\"/>\r\n    <arg name=\"headless\" value=\"$(arg headless)\"/>\r\n  </include>\r\n\r\n  <param name=\"robot_description\" command=\"$(find xacro)/xacro.py $(arg model)\" />\r\n\r\n  <!-- push robot_description to factory and spawn robot in gazebo -->\r\n  <node name=\"urdf_spawner\" pkg=\"gazebo_ros\" type=\"spawn_model\"\r\n        args=\"-z 1.0 -unpause -urdf -model robot -param robot_description\" respawn=\"false\" output=\"screen\" />\r\n\r\n  <node pkg=\"robot_state_publisher\" type=\"robot_state_publisher\"  name=\"robot_state_publisher\">\r\n    <param name=\"publish_frequency\" type=\"double\" value=\"30.0\" />\r\n  </node>\r\n\r\n</launch>\r\n"
  },
  {
    "path": "moveo_urdf/launch/gazebo_old.launch",
    "content": "<launch>\n  <include\n    file=\"$(find gazebo_ros)/launch/empty_world.launch\" />\n  <node\n    name=\"tf_footprint_base\"\n    pkg=\"tf\"\n    type=\"static_transform_publisher\"\n    args=\"0 0 0 0 0 0 base_link base_footprint 40\" />\n  <node\n    name=\"spawn_model\"\n    pkg=\"gazebo_ros\"\n    type=\"spawn_model\"\n    args=\"-file $(find moveo_urdf_5)/urdf/moveo_urdf_5.urdf -urdf -model moveo_urdf_5\"\n    output=\"screen\" />\n  <node\n    name=\"fake_joint_calibration\"\n    pkg=\"rostopic\"\n    type=\"rostopic\"\n    args=\"pub /calibrated std_msgs/Bool true\" />\n</launch>\n"
  },
  {
    "path": "moveo_urdf/launch/gazebo_sdf.launch",
    "content": "<launch>\n  <include\n    file=\"$(find gazebo_ros)/launch/empty_world.launch\" />\n  <node\n    name=\"tf_footprint_base\"\n    pkg=\"tf\"\n    type=\"static_transform_publisher\"\n    args=\"0 0 0 0 0 0 base_link base_footprint 40\" />\n  <node\n    name=\"spawn_model\"\n    pkg=\"gazebo_ros\"\n    type=\"spawn_model\"\n    args=\"-file $(find model_editor_models)/robot5/model.sdf -sdf -model robot5\"\n    output=\"screen\" />\n  <node\n    name=\"fake_joint_calibration\"\n    pkg=\"rostopic\"\n    type=\"rostopic\"\n    args=\"pub /calibrated std_msgs/Bool true\" />\n</launch>\n"
  },
  {
    "path": "moveo_urdf/package.xml",
    "content": "<package>\r\n  <name>moveo_urdf</name>\r\n  <version>1.0.0</version>\r\n  <description>\r\n    <p>URDF Description package for moveo_urdf</p>\r\n    <p>This package contains configuration data, 3D models and launch files\r\nfor moveo_urdf robot</p>\r\n  </description>\r\n  <author>Jesse Weisberg</author>\r\n  <maintainer email=\"jesse.weisberg@gmail.com\" />\r\n  <license>BSD</license>\r\n  <buildtool_depend>catkin</buildtool_depend>\r\n  <build_depend>roslaunch</build_depend>\r\n  <run_depend>robot_state_publisher</run_depend>\r\n  <run_depend>rviz</run_depend>\r\n  <run_depend>joint_state_publisher</run_depend>\r\n  <run_depend>gazebo</run_depend>\r\n  <export>\r\n    <architecture_independent />\r\n  </export>\r\n</package>\r\n"
  },
  {
    "path": "moveo_urdf/urdf/moveo_urdf.urdf",
    "content": "<?xml version='1.0'?>\n<robot\n  name=\"moveo_urdf\">\t\n\n  <link\n    name=\"base_link\">\n    <visual>\n      <origin\n        xyz=\"0 0 .13\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/base_link.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.75294 0.75294 0.75294 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 .13\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/base_link_col.STL\" />\n      </geometry>\n    </collision>\n  </link>\n\n  <!-- dummy link -->\n  <link\n    name=\"odom\">\n    <inertial>\n      <origin\n        xyz=\"0.034155 -0.20591 -0.049641\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"8.0643\" />\n      <inertia\n        ixx=\"0.11291\"\n        ixy=\"0.00066071\"\n        ixz=\"-0.00030472\"\n        iyy=\"0.089946\"\n        iyz=\"0.011461\"\n        izz=\"0.19187\" />\n    </inertial>\n   </link>\n\n  <joint\n    name=\"odom_joint\"\n    type=\"fixed\">\n    <origin\n      xyz=\"0 0 0\"\n      rpy=\"0 0 0\" />\n    <parent\n      link=\"base_link\" />\n    <child\n      link=\"odom\" />\n  </joint>\n\n\n\n\n\n  <link\n    name=\"Link_1\">\n    <inertial>\n      <origin\n        xyz=\"4.0186E-05 0.090634 0.00010221\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"4.2526\" />\n      <inertia\n        ixx=\"0.0034071\"\n        ixy=\"8.9041E-06\"\n        ixz=\"1.179E-07\"\n        iyy=\"0.018642\"\n        iyz=\"-3.6544E-06\"\n        izz=\"0.021987\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Link_1.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.75294 0.75294 0.75294 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Link_1_col.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Joint_1\"\n    type=\"revolute\">\n    <origin\n      xyz=\"0 -0.2425 .13\"\n      rpy=\"1.5708 9.5417E-17 2.7766\" />\n    <parent\n      link=\"base_link\" />\n    <child\n      link=\"Link_1\" />\n    <axis\n      xyz=\"0 1 0\" />\n    <limit\n      lower=\"-1.5707\"\n      upper=\"1.5707\"\n      effort=\"5\"\n      velocity=\"1\" />\n  </joint>\n  <link\n    name=\"Link_2\">\n    <inertial>\n      <origin\n        xyz=\"2.2815E-05 0.0017616 -0.080002\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"1.9323\" />\n      <inertia\n        ixx=\"0.012138\"\n        ixy=\"-3.5576E-06\"\n        ixz=\"-9.0632E-06\"\n        iyy=\"0.011445\"\n        iyz=\"0.00014273\"\n        izz=\"0.00070271\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Link_2.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.75294 0.75294 0.75294 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Link_2_col.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Joint_2\"\n    type=\"revolute\">\n    <origin\n      xyz=\"0 0.18264 0\"\n      rpy=\"-3.1416 0.95134 1.5708\" />\n    <parent\n      link=\"Link_1\" />\n    <child\n      link=\"Link_2\" />\n    <axis\n      xyz=\"0 -1 0\" />\n    <limit\n      lower=\"-1.5707\"\n      upper=\"1.5707\"\n      effort=\"5\"\n      velocity=\"1\" />\n  </joint>\n  <link\n    name=\"Link_3\">\n    <inertial>\n      <origin\n        xyz=\"0.05095 -0.00039084 -0.00045591\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"1.1381\" />\n      <inertia\n        ixx=\"0.00023572\"\n        ixy=\"-3.8425E-06\"\n        ixz=\"4.1286E-06\"\n        iyy=\"0.00029123\"\n        iyz=\"-1.0387E-07\"\n        izz=\"0.00052457\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Link_3.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.75294 0.75294 0.75294 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Link_3_col.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Joint_3\"\n    type=\"revolute\">\n    <origin\n      xyz=\"0 0 -0.22112\"\n      rpy=\"-3.1416 0.98126 -3.1416\" />\n    <parent\n      link=\"Link_2\" />\n    <child\n      link=\"Link_3\" />\n    <axis\n      xyz=\"0 -1 0\" />\n    <limit\n      lower=\"-1.5707\"\n      upper=\"1.5707\"\n      effort=\"5\"\n      velocity=\"1\" />\n  </joint>\n  <link\n    name=\"Link_4\">\n    <inertial>\n      <origin\n        xyz=\"-0.0027417 0.0025097 0.012864\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"0.62964\" />\n      <inertia\n        ixx=\"0.0001717\"\n        ixy=\"1.3446E-06\"\n        ixz=\"8.5164E-06\"\n        iyy=\"0.00010506\"\n        iyz=\"5.1412E-05\"\n        izz=\"7.8944E-05\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Link_4.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.29412 0.29412 0.29412 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Link_4_col.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Joint_4\"\n    type=\"revolute\">\n    <origin\n      xyz=\"0.16988 -0.00099213 0\"\n      rpy=\"3.1416 -1.2279 1.5708\" />\n    <parent\n      link=\"Link_3\" />\n    <child\n      link=\"Link_4\" />\n    <axis\n      xyz=\"0.010353 -0.99993 -0.0059382\" />\n    <limit\n      lower=\"-1.5707\"\n      upper=\"1.5707\"\n      effort=\"5\"\n      velocity=\"1\" />\n  </joint>\n  <link\n    name=\"Link_5\">\n    <inertial>\n      <origin\n        xyz=\"-0.011366 0.00012239 0.0078967\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"0.19875\" />\n      <inertia\n        ixx=\"6.2676E-05\"\n        ixy=\"4.2551E-06\"\n        ixz=\"4.0215E-05\"\n        iyy=\"9.7792E-05\"\n        iyz=\"8.5888E-07\"\n        izz=\"9.5807E-05\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Link_5.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.79216 0.81961 0.93333 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Link_5_col.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Joint_5\"\n    type=\"revolute\">\n    <origin\n      xyz=\"-0.0021346 0.053041 0.0016936\"\n      rpy=\"-1.5639 -0.091135 -0.00062919\" />\n    <parent\n      link=\"Link_4\" />\n    <child\n      link=\"Link_5\" />\n    <axis\n      xyz=\"0 1 0\" />\n    <limit\n      lower=\"-1.5707\"\n      upper=\"1.5707\"\n      effort=\"5\"\n      velocity=\"1\" />\n  </joint>\n  <link\n    name=\"Gripper_Servo_Gear\">\n    <inertial>\n      <origin\n        xyz=\"-0.0063957 -0.0033021 -0.00082714\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"0.0048997\" />\n      <inertia\n        ixx=\"2.0097E-09\"\n        ixy=\"-3.0673E-09\"\n        ixz=\"-6.3297E-10\"\n        iyy=\"4.9761E-09\"\n        iyz=\"-3.9668E-10\"\n        izz=\"6.8221E-09\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Gripper_Servo_Gear.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.9098 0.44314 0.031373 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Gripper_Servo_Gear_col.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Gripper_Servo_Gear_Joint\"\n    type=\"revolute\">\n    <origin\n      xyz=\"-0.05013 0.01413 0.041516\"\n      rpy=\"0.9321 0.032705 -1.5268\" />\n    <parent\n      link=\"Link_5\" />\n    <child\n      link=\"Gripper_Servo_Gear\" />\n    <axis\n      xyz=\"0 1 0\" />\n    <limit\n      lower=\"0\"\n      upper=\"1.5707\"\n      effort=\"5\"\n      velocity=\"1\" />\n  </joint>\n  <link\n    name=\"Tip_Gripper_Servo\">\n    <inertial>\n      <origin\n        xyz=\"0.028047 -0.000564 0.0049632\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"0.010676\" />\n      <inertia\n        ixx=\"8.9609E-09\"\n        ixy=\"6.3808E-09\"\n        ixz=\"-2.6788E-08\"\n        iyy=\"1.7457E-07\"\n        iyz=\"7.7239E-10\"\n        izz=\"1.7361E-07\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Tip_Gripper_Servo.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.6 1 0.27843 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Tip_Gripper_Servo_col.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Tip_Gripper_Servo_Joint\"\n    type=\"continuous\">\n    <origin\n      xyz=\"-0.039906 -0.004 -0.0027473\"\n      rpy=\"-3.1416 -1.5569 -2.0392E-12\" />\n    <parent\n      link=\"Gripper_Servo_Gear\" />\n    <child\n      link=\"Tip_Gripper_Servo\" />\n    <axis\n      xyz=\"0 1 0\" />\n    <limit\n      lower=\"0\"\n      upper=\"1.3\"\n      effort=\"5\"\n      velocity=\"1\" />\n    <mimic joint=\"Gripper_Servo_Gear_Joint\" multiplier=\"1\" offset=\"0\"/> \n  </joint>\n  <link\n    name=\"Gripper_Idol_Gear\">\n    <inertial>\n      <origin\n        xyz=\"-0.0061853 0.00086502 -3.5867E-05\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"0.0051273\" />\n      <inertia\n        ixx=\"2.3312E-09\"\n        ixy=\"1.1098E-09\"\n        ixz=\"-5.1524E-11\"\n        iyy=\"8.8855E-09\"\n        iyz=\"6.4357E-12\"\n        izz=\"1.1216E-08\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Gripper_Idol_Gear.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.058824 0.64706 1 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Gripper_Idol_Gear_col.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Gripper_Idol_Gear_Joint\"\n    type=\"revolute\">\n    <origin\n      xyz=\"-0.052696 -0.01387 0.038065\"\n      rpy=\"2.2091 -0.040996 1.626\" />\n    <parent\n      link=\"Link_5\" />\n    <child\n      link=\"Gripper_Idol_Gear\" />\n    <axis\n      xyz=\"0 1 0\" />\n    <limit\n      lower=\"-1.5707\"\n      upper=\"0\"\n      effort=\"5\"\n      velocity=\"1\" />\n  </joint>\n  <link\n    name=\"Tip_Gripper_Idol\">\n    <inertial>\n      <origin\n        xyz=\"0.0059646 0.00098916 0.027851\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"0.010676\" />\n      <inertia\n        ixx=\"1.6895E-07\"\n        ixy=\"-1.6878E-09\"\n        ixz=\"-3.8254E-08\"\n        iyy=\"1.7457E-07\"\n        iyz=\"-6.203E-09\"\n        izz=\"1.3622E-08\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Tip_Gripper_Idol.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.79216 0.81961 0.93333 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Tip_Gripper_Idol_col.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Tip_Gripper_Idol_Joint\"\n    type=\"revolute\">\n    <origin\n      xyz=\"-0.039906 -0.000125 -0.0027473\"\n      rpy=\"3.1416 0.5236 3.1416\" />\n    <parent\n      link=\"Gripper_Idol_Gear\" />\n    <child\n      link=\"Tip_Gripper_Idol\" />\n    <axis\n      xyz=\"0 1 0\" />\n    <limit\n      lower=\"-1.5\"\n      upper=\"0\"\n      effort=\"5\"\n      velocity=\"1\" />\n    <mimic joint=\"Gripper_Idol_Gear_Joint\" multiplier=\"-1\" offset=\"0\"/>\n  </joint>\n  <link\n    name=\"Pivot_Arm_Gripper_Servo\">\n    <inertial>\n      <origin\n        xyz=\"-0.017611 0.00080352 -1.2115E-11\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"0.0018597\" />\n      <inertia\n        ixx=\"2.3199E-09\"\n        ixy=\"3.1597E-09\"\n        ixz=\"3.9677E-16\"\n        iyy=\"7.8256E-08\"\n        iyz=\"-2.0327E-16\"\n        izz=\"8.0576E-08\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Pivot_Arm_Gripper_Servo.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.79216 0.81961 0.93333 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Pivot_Arm_Gripper_Servo_col.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Pivot_Arm_Gripper_Servo_Joint\"\n    type=\"revolute\">\n    <origin\n      xyz=\"-0.068745 0.00713 0.05\"\n      rpy=\"0.93142 -0.0083007 -1.582\" />\n    <parent\n      link=\"Link_5\" />\n    <child\n      link=\"Pivot_Arm_Gripper_Servo\" />\n    <axis\n      xyz=\"0 1 0\" />\n    <limit\n      lower=\"-1.5707\"\n      upper=\"1.5707\"\n      effort=\"5\"\n      velocity=\"1\" />\n    <mimic joint=\"Gripper_Servo_Gear_Joint\" multiplier=\"1\" offset=\"0\"/> \n  </joint>\n  <link\n    name=\"Pivot_Arm_Gripper_Idol\">\n    <inertial>\n      <origin\n        xyz=\"0.017611 0.00067852 -1.3978E-11\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"0.0018597\" />\n      <inertia\n        ixx=\"2.3199E-09\"\n        ixy=\"-3.1597E-09\"\n        ixz=\"-4.5779E-16\"\n        iyy=\"7.8256E-08\"\n        iyz=\"-2.26E-16\"\n        izz=\"8.0576E-08\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Pivot_Arm_Gripper_Idol.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.79216 0.81961 0.93333 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf/meshes/Pivot_Arm_Gripper_Idol_col.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Pivot_Arm_Gripper_Idol_Joint\"\n    type=\"revolute\">\n    <origin\n      xyz=\"-0.06867 -0.00687 0.0501\"\n      rpy=\"0.93138 1.7645E-12 -1.5708\" />\n    <parent\n      link=\"Link_5\" />\n    <child\n      link=\"Pivot_Arm_Gripper_Idol\" />\n    <axis\n      xyz=\"0 1 0\" />\n    <limit\n      lower=\"-1.5707\"\n      upper=\"1.5707\"\n      effort=\"5\"\n      velocity=\"1\" />\n    <mimic joint=\"Gripper_Idol_Gear_Joint\" multiplier=\"1\" offset=\"0\"/> \n  </joint>\n  <!--\n  <gazebo>\n    <plugin name=\"MimicJointPlugin\" filename=\"libroboticsgroup_gazebo_mimic_joint_plugin.so\">\n      joint=\"Gripper_Idol_Gear_Joint\"\n      mimicJoint=\"Pivot_Arm_Gripper_Idol_Joint\"\n      multiplier=\"1\"\n      offset=\"0\"\n    </plugin>\n    <plugin name=\"MimicJointPlugin\" filename=\"libroboticsgroup_gazebo_mimic_joint_plugin.so\">\n      joint=\"Gripper_Servo_Gear_Joint\"\n      mimicJoint=\"Pivot_Arm_Gripper_Servo_Joint\"\n      multiplier=\"1\"\n      offset=\"0\"\n    </plugin>\n    <plugin name=\"MimicJointPlugin\" filename=\"libroboticsgroup_gazebo_mimic_joint_plugin.so\">\n      joint=\"Gripper_Servo_Gear_Joint\"\n      mimicJoint=\"Tip_Gripper_Servo_Joint\n      multiplier=\"1\"\n      offset=\"0\"\n    </plugin>\n    <plugin name=\"MimicJointPlugin\" filename=\"libroboticsgroup_gazebo_mimic_joint_plugin.so\">\n      joint=\"Gripper_Idol_Gear_Joint\"\n      mimicJoint=\"Tip_Gripper_Idol_Joint\n      multiplier=\"-1\"\n      offset=\"0\"\n    </plugin>\n  </gazebo>\n  -->\n</robot>\n\n\n  \n\n"
  },
  {
    "path": "moveo_urdf/urdf/moveo_urdf_new.urdf",
    "content": "<robot\r\n  name=\"moveo_urdf_5\">\r\n    <link\r\n    name=\"base_link\">\r\n    <inertial>\r\n      <origin\r\n        xyz=\"0.034155 -0.20591 -0.049641\"\r\n        rpy=\"0 0 0\" />\r\n      <mass\r\n        value=\"8.0643\" />\r\n      <inertia\r\n        ixx=\"0.11291\"\r\n        ixy=\"0.00066071\"\r\n        ixz=\"-0.00030472\"\r\n        iyy=\"0.089946\"\r\n        iyz=\"0.011461\"\r\n        izz=\"0.19187\" />\r\n    </inertial>\r\n    <visual>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_4/meshes/base_link.STL\" />\r\n      </geometry>\r\n      <material\r\n        name=\"\">\r\n        <color\r\n          rgba=\"0.75294 0.75294 0.75294 1\" />\r\n      </material>\r\n    </visual>\r\n    <collision>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_4/meshes/base_link.STL\" />\r\n      </geometry>\r\n    </collision>\r\n  </link>\r\n  <link\r\n    name=\"Link_1\">\r\n    <inertial>\r\n      <origin\r\n        xyz=\"4.0186E-05 0.090634 0.00010221\"\r\n        rpy=\"0 0 0\" />\r\n      <mass\r\n        value=\"4.2526\" />\r\n      <inertia\r\n        ixx=\"0.0034071\"\r\n        ixy=\"8.9041E-06\"\r\n        ixz=\"1.179E-07\"\r\n        iyy=\"0.018642\"\r\n        iyz=\"-3.6544E-06\"\r\n        izz=\"0.021987\" />\r\n    </inertial>\r\n    <visual>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_4/meshes/Link_1.STL\" />\r\n      </geometry>\r\n      <material\r\n        name=\"\">\r\n        <color\r\n          rgba=\"0.75294 0.75294 0.75294 1\" />\r\n      </material>\r\n    </visual>\r\n    <collision>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_4/meshes/Link_1.STL\" />\r\n      </geometry>\r\n    </collision>\r\n  </link>\r\n  <joint\r\n    name=\"Joint_1\"\r\n    type=\"revolute\">\r\n    <origin\r\n      xyz=\"0 -0.2425 0\"\r\n      rpy=\"1.5708 9.5417E-17 2.7766\" />\r\n    <parent\r\n      link=\"base_link\" />\r\n    <child\r\n      link=\"Link_1\" />\r\n    <axis\r\n      xyz=\"0 1 0\" />\r\n    <limit\r\n      lower=\"-1\"\r\n      upper=\"1\"\r\n      effort=\"5\"\r\n      velocity=\"1\" />\r\n  </joint>\r\n  <link\r\n    name=\"Link_2\">\r\n    <inertial>\r\n      <origin\r\n        xyz=\"2.2815E-05 0.0017616 -0.080002\"\r\n        rpy=\"0 0 0\" />\r\n      <mass\r\n        value=\"1.9323\" />\r\n      <inertia\r\n        ixx=\"0.012138\"\r\n        ixy=\"-3.5576E-06\"\r\n        ixz=\"-9.0632E-06\"\r\n        iyy=\"0.011445\"\r\n        iyz=\"0.00014273\"\r\n        izz=\"0.00070271\" />\r\n    </inertial>\r\n    <visual>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_5/meshes/Link_2.STL\" />\r\n      </geometry>\r\n      <material\r\n        name=\"\">\r\n        <color\r\n          rgba=\"0.75294 0.75294 0.75294 1\" />\r\n      </material>\r\n    </visual>\r\n    <collision>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_5/meshes/Link_2.STL\" />\r\n      </geometry>\r\n    </collision>\r\n  </link>\r\n  <joint\r\n    name=\"Joint_2\"\r\n    type=\"revolute\">\r\n    <origin\r\n      xyz=\"0 0.18264 0\"\r\n      rpy=\"-3.1416 0.95134 1.5708\" />\r\n    <parent\r\n      link=\"Link_1\" />\r\n    <child\r\n      link=\"Link_2\" />\r\n    <axis\r\n      xyz=\"0 -1 0\" />\r\n    <limit\r\n      lower=\"-1\"\r\n      upper=\"1\"\r\n      effort=\"5\"\r\n      velocity=\"1\" />\r\n  </joint>\r\n  <link\r\n    name=\"Link_3\">\r\n    <inertial>\r\n      <origin\r\n        xyz=\"0.05095 -0.00039084 -0.00045591\"\r\n        rpy=\"0 0 0\" />\r\n      <mass\r\n        value=\"1.1381\" />\r\n      <inertia\r\n        ixx=\"0.00023572\"\r\n        ixy=\"-3.8425E-06\"\r\n        ixz=\"4.1286E-06\"\r\n        iyy=\"0.00029123\"\r\n        iyz=\"-1.0387E-07\"\r\n        izz=\"0.00052457\" />\r\n    </inertial>\r\n    <visual>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_5/meshes/Link_3.STL\" />\r\n      </geometry>\r\n      <material\r\n        name=\"\">\r\n        <color\r\n          rgba=\"0.75294 0.75294 0.75294 1\" />\r\n      </material>\r\n    </visual>\r\n    <collision>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_5/meshes/Link_3.STL\" />\r\n      </geometry>\r\n    </collision>\r\n  </link>\r\n  <joint\r\n    name=\"Joint_3\"\r\n    type=\"revolute\">\r\n    <origin\r\n      xyz=\"0 0 -0.22112\"\r\n      rpy=\"-3.1416 0.98126 -3.1416\" />\r\n    <parent\r\n      link=\"Link_2\" />\r\n    <child\r\n      link=\"Link_3\" />\r\n    <axis\r\n      xyz=\"0 -1 0\" />\r\n    <limit\r\n      lower=\"-1\"\r\n      upper=\"1\"\r\n      effort=\"5\"\r\n      velocity=\"1\" />\r\n  </joint>\r\n  <link\r\n    name=\"Link_4\">\r\n    <inertial>\r\n      <origin\r\n        xyz=\"-0.0027417 0.0025097 0.012864\"\r\n        rpy=\"0 0 0\" />\r\n      <mass\r\n        value=\"0.62964\" />\r\n      <inertia\r\n        ixx=\"0.0001717\"\r\n        ixy=\"1.3446E-06\"\r\n        ixz=\"8.5164E-06\"\r\n        iyy=\"0.00010506\"\r\n        iyz=\"5.1412E-05\"\r\n        izz=\"7.8944E-05\" />\r\n    </inertial>\r\n    <visual>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_5/meshes/Link_4.STL\" />\r\n      </geometry>\r\n      <material\r\n        name=\"\">\r\n        <color\r\n          rgba=\"0.29412 0.29412 0.29412 1\" />\r\n      </material>\r\n    </visual>\r\n    <collision>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_5/meshes/Link_4.STL\" />\r\n      </geometry>\r\n    </collision>\r\n  </link>\r\n  <joint\r\n    name=\"Joint_4\"\r\n    type=\"revolute\">\r\n    <origin\r\n      xyz=\"0.16988 -0.00099213 0\"\r\n      rpy=\"3.1416 -1.2279 1.5708\" />\r\n    <parent\r\n      link=\"Link_3\" />\r\n    <child\r\n      link=\"Link_4\" />\r\n    <axis\r\n      xyz=\"0.010353 -0.99993 -0.0059382\" />\r\n    <limit\r\n      lower=\"-1\"\r\n      upper=\"1\"\r\n      effort=\"5\"\r\n      velocity=\"1\" />\r\n  </joint>\r\n  <link\r\n    name=\"Link_5\">\r\n    <inertial>\r\n      <origin\r\n        xyz=\"-0.011366 0.00012239 0.0078967\"\r\n        rpy=\"0 0 0\" />\r\n      <mass\r\n        value=\"0.19875\" />\r\n      <inertia\r\n        ixx=\"6.2676E-05\"\r\n        ixy=\"4.2551E-06\"\r\n        ixz=\"4.0215E-05\"\r\n        iyy=\"9.7792E-05\"\r\n        iyz=\"8.5888E-07\"\r\n        izz=\"9.5807E-05\" />\r\n    </inertial>\r\n    <visual>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_5/meshes/Link_5.STL\" />\r\n      </geometry>\r\n      <material\r\n        name=\"\">\r\n        <color\r\n          rgba=\"0.79216 0.81961 0.93333 1\" />\r\n      </material>\r\n    </visual>\r\n    <collision>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_5/meshes/Link_5.STL\" />\r\n      </geometry>\r\n    </collision>\r\n  </link>\r\n  <joint\r\n    name=\"Joint_5\"\r\n    type=\"revolute\">\r\n    <origin\r\n      xyz=\"-0.0021346 0.053041 0.0016936\"\r\n      rpy=\"-1.5639 -0.091135 -0.00062919\" />\r\n    <parent\r\n      link=\"Link_4\" />\r\n    <child\r\n      link=\"Link_5\" />\r\n    <axis\r\n      xyz=\"0 1 0\" />\r\n    <limit\r\n      lower=\"-1\"\r\n      upper=\"1\"\r\n      effort=\"5\"\r\n      velocity=\"1\" />\r\n  </joint>\r\n    <link\r\n    name=\"Gripper_Servo_Gear\">\r\n    <inertial>\r\n      <origin\r\n        xyz=\"-0.0063957 -0.0033021 -0.00082714\"\r\n        rpy=\"0 0 0\" />\r\n      <mass\r\n        value=\"0.0048997\" />\r\n      <inertia\r\n        ixx=\"2.0097E-09\"\r\n        ixy=\"-3.0673E-09\"\r\n        ixz=\"-6.3297E-10\"\r\n        iyy=\"4.9761E-09\"\r\n        iyz=\"-3.9668E-10\"\r\n        izz=\"6.8221E-09\" />\r\n    </inertial>\r\n    <visual>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_5/meshes/Gripper_Servo_Gear.STL\" />\r\n      </geometry>\r\n      <material\r\n        name=\"\">\r\n        <color\r\n          rgba=\"0.9098 0.44314 0.031373 1\" />\r\n      </material>\r\n    </visual>\r\n    <collision>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_5/meshes/Gripper_Servo_Gear.STL\" />\r\n      </geometry>\r\n    </collision>\r\n  </link>\r\n  <joint\r\n    name=\"Gripper_Servo_Gear_Joint\"\r\n    type=\"revolute\">\r\n    <origin\r\n      xyz=\"-0.05013 0.01413 0.041516\"\r\n      rpy=\"0.9321 0.032705 -1.5268\" />\r\n    <parent\r\n      link=\"Link_5\" />\r\n    <child\r\n      link=\"Gripper_Servo_Gear\" />\r\n    <axis\r\n      xyz=\"0 1 0\" />\r\n    <limit\r\n      lower=\"0\"\r\n      upper=\"1.5707\"\r\n      effort=\"5\"\r\n      velocity=\"1\" />\r\n  </joint>\r\n  <link\r\n    name=\"Tip_Gripper_Servo\">\r\n    <inertial>\r\n      <origin\r\n        xyz=\"0.028047 -0.000564 0.0049632\"\r\n        rpy=\"0 0 0\" />\r\n      <mass\r\n        value=\"0.010676\" />\r\n      <inertia\r\n        ixx=\"8.9609E-09\"\r\n        ixy=\"6.3808E-09\"\r\n        ixz=\"-2.6788E-08\"\r\n        iyy=\"1.7457E-07\"\r\n        iyz=\"7.7239E-10\"\r\n        izz=\"1.7361E-07\" />\r\n    </inertial>\r\n    <visual>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_5/meshes/Tip_Gripper_Servo.STL\" />\r\n      </geometry>\r\n      <material\r\n        name=\"\">\r\n        <color\r\n          rgba=\"0.6 1 0.27843 1\" />\r\n      </material>\r\n    </visual>\r\n    <collision>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_5/meshes/Tip_Gripper_Servo.STL\" />\r\n      </geometry>\r\n    </collision>\r\n  </link>\r\n  <joint\r\n    name=\"Tip_Gripper_Servo_Joint\"\r\n    type=\"revolute\">\r\n    <origin\r\n      xyz=\"-0.039906 -0.004 -0.0027473\"\r\n      rpy=\"-3.1416 -1.5569 -2.0392E-12\" />\r\n    <parent\r\n      link=\"Gripper_Servo_Gear\" />\r\n    <child\r\n      link=\"Tip_Gripper_Servo\" />\r\n    <axis\r\n      xyz=\"0 1 0\" />\r\n    <limit\r\n      lower=\"0\"\r\n      upper=\"1.3\"\r\n      effort=\"5\"\r\n      velocity=\"1\" /> \r\n  </joint>\r\n  <link\r\n    name=\"Gripper_Idol_Gear\">\r\n    <inertial>\r\n      <origin\r\n        xyz=\"-0.020173 -0.027941 -0.043405\"\r\n        rpy=\"0 0 0\" />\r\n      <mass\r\n        value=\"0.0051273\" />\r\n      <inertia\r\n        ixx=\"2.3661E-09\"\r\n        ixy=\"1.1076E-09\"\r\n        ixz=\"5.5775E-10\"\r\n        iyy=\"8.8855E-09\"\r\n        iyz=\"-6.98E-11\"\r\n        izz=\"1.1181E-08\" />\r\n    </inertial>\r\n    <visual>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_4/meshes/Gripper_Idol_Gear.STL\" />\r\n      </geometry>\r\n      <material\r\n        name=\"\">\r\n        <color\r\n          rgba=\"0.058824 0.64706 1 1\" />\r\n      </material>\r\n    </visual>\r\n    <collision>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_4/meshes/Gripper_Idol_Gear.STL\" />\r\n      </geometry>\r\n    </collision>\r\n  </link>\r\n  <joint\r\n    name=\"Gripper_Idol_Gear_Joint\"\r\n    type=\"revolute\">\r\n    <origin\r\n      xyz=\"0 0 0.088169\"\r\n      rpy=\"2.2206 -1.7526E-12 1.5708\" />\r\n    <parent\r\n      link=\"Link_5\" />\r\n    <child\r\n      link=\"Gripper_Idol_Gear\" />\r\n    <axis\r\n      xyz=\"0 1 0\" />\r\n    <limit\r\n      lower=\"-1\"\r\n      upper=\"1\"\r\n      effort=\"5\"\r\n      velocity=\"1\" />\r\n  </joint>\r\n  <link\r\n    name=\"Tip_Gripper_Idol\">\r\n    <inertial>\r\n      <origin\r\n        xyz=\"0.07316 -0.036799 0.032473\"\r\n        rpy=\"0 0 0\" />\r\n      <mass\r\n        value=\"0.010676\" />\r\n      <inertia\r\n        ixx=\"1.6298E-07\"\r\n        ixy=\"-2.1098E-09\"\r\n        ixz=\"-4.8536E-08\"\r\n        iyy=\"1.7457E-07\"\r\n        iyz=\"-6.0724E-09\"\r\n        izz=\"1.9597E-08\" />\r\n    </inertial>\r\n    <visual>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_4/meshes/Tip_Gripper_Idol.STL\" />\r\n      </geometry>\r\n      <material\r\n        name=\"\">\r\n        <color\r\n          rgba=\"0.79216 0.81961 0.93333 1\" />\r\n      </material>\r\n    </visual>\r\n    <collision>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_4/meshes/Tip_Gripper_Idol.STL\" />\r\n      </geometry>\r\n    </collision>\r\n  </link>\r\n  <joint\r\n    name=\"Tip_Gripper_Idol_Joint\"\r\n    type=\"fixed\">\r\n    <origin\r\n      xyz=\"0 0.0088579 -0.0067312\"\r\n      rpy=\"-3.1416 0.5236 -3.1416\" />\r\n    <parent\r\n      link=\"Gripper_Idol_Gear\" />\r\n    <child\r\n      link=\"Tip_Gripper_Idol\" />\r\n    <axis\r\n      xyz=\"0 0 0\" />\r\n  </joint>\r\n  <link\r\n    name=\"Pivot_Arm_Gripper_Servo\">\r\n    <inertial>\r\n      <origin\r\n        xyz=\"-0.0246088378758516 -0.039491188677419 0.0548184657290344\"\r\n        rpy=\"0 0 0\" />\r\n      <mass\r\n        value=\"0.00185970821819588\" />\r\n      <inertia\r\n        ixx=\"2.3350521316943E-09\"\r\n        ixy=\"3.15938078443685E-09\"\r\n        ixz=\"-1.08844692176622E-09\"\r\n        iyy=\"7.82558758772591E-08\"\r\n        iyz=\"4.39516056818752E-11\"\r\n        izz=\"8.05606441237718E-08\" />\r\n    </inertial>\r\n    <visual>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_4/meshes/Pivot_Arm_Gripper_Servo.STL\" />\r\n      </geometry>\r\n      <material\r\n        name=\"\">\r\n        <color\r\n          rgba=\"0.792156862745098 0.819607843137255 0.933333333333333 1\" />\r\n      </material>\r\n    </visual>\r\n    <collision>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_4/meshes/Pivot_Arm_Gripper_Servo.STL\" />\r\n      </geometry>\r\n    </collision>\r\n  </link>\r\n  <joint\r\n    name=\"Pivot_Arm_Gripper_Servo_Joint\"\r\n    type=\"revolute\">\r\n    <origin\r\n      xyz=\"0 0 0.1026\"\r\n      rpy=\"0.92098 1.754E-12 -1.5708\" />\r\n    <parent\r\n      link=\"Link_5\" />\r\n    <child\r\n      link=\"Pivot_Arm_Gripper_Servo\" />\r\n    <axis\r\n      xyz=\"0 1 0\" />\r\n    <limit\r\n      lower=\"-1\"\r\n      upper=\"1\"\r\n      effort=\"5\"\r\n      velocity=\"1\" />\r\n  </joint>\r\n  <link\r\n    name=\"Pivot_Arm_Gripper_Idol\">\r\n    <inertial>\r\n      <origin\r\n        xyz=\"0.024736 -0.038928 0.055435\"\r\n        rpy=\"0 0 0\" />\r\n      <mass\r\n        value=\"0.0018597\" />\r\n      <inertia\r\n        ixx=\"2.3203E-09\"\r\n        ixy=\"-3.1597E-09\"\r\n        ixz=\"1.7754E-10\"\r\n        iyy=\"7.8256E-08\"\r\n        iyz=\"7.1682E-12\"\r\n        izz=\"8.0575E-08\" />\r\n    </inertial>\r\n    <visual>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_4/meshes/Pivot_Arm_Gripper_Idol.STL\" />\r\n      </geometry>\r\n      <material\r\n        name=\"\">\r\n        <color\r\n          rgba=\"0.79216 0.81961 0.93333 1\" />\r\n      </material>\r\n    </visual>\r\n    <collision>\r\n      <origin\r\n        xyz=\"0 0 0\"\r\n        rpy=\"0 0 0\" />\r\n      <geometry>\r\n        <mesh\r\n          filename=\"package://moveo_urdf_4/meshes/Pivot_Arm_Gripper_Idol.STL\" />\r\n      </geometry>\r\n    </collision>\r\n  </link>\r\n  <joint\r\n    name=\"Pivot_Arm_Gripper_Idol_Joint\"\r\n    type=\"revolute\">\r\n    <origin\r\n      xyz=\"0 0 0.10189\"\r\n      rpy=\"0.92098 -0.0013727 -1.5726\" />\r\n    <parent\r\n      link=\"Link_5\" />\r\n    <child\r\n      link=\"Pivot_Arm_Gripper_Idol\" />\r\n    <axis\r\n      xyz=\"0 1 0\" />\r\n    <limit\r\n      lower=\"-1\"\r\n      upper=\"1\"\r\n      effort=\"5\"\r\n      velocity=\"1\" />\r\n  </joint>\r\n\r\n</robot>\r\n"
  },
  {
    "path": "moveo_urdf/urdf/moveo_urdf_og.urdf",
    "content": "<robot\n  name=\"moveo_urdf_5\">\n    <link\n    name=\"base_link\">\n    <inertial>\n      <origin\n        xyz=\"0.034155 -0.20591 -0.049641\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"8.0643\" />\n      <inertia\n        ixx=\"0.11291\"\n        ixy=\"0.00066071\"\n        ixz=\"-0.00030472\"\n        iyy=\"0.089946\"\n        iyz=\"0.011461\"\n        izz=\"0.19187\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_4/meshes/base_link.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.75294 0.75294 0.75294 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_4/meshes/base_link.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <link\n    name=\"Link_1\">\n    <inertial>\n      <origin\n        xyz=\"4.0186E-05 0.090634 0.00010221\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"4.2526\" />\n      <inertia\n        ixx=\"0.0034071\"\n        ixy=\"8.9041E-06\"\n        ixz=\"1.179E-07\"\n        iyy=\"0.018642\"\n        iyz=\"-3.6544E-06\"\n        izz=\"0.021987\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_4/meshes/Link_1.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.75294 0.75294 0.75294 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_4/meshes/Link_1.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Joint_1\"\n    type=\"revolute\">\n    <origin\n      xyz=\"0 -0.2425 0\"\n      rpy=\"1.5708 9.5417E-17 2.7766\" />\n    <parent\n      link=\"base_link\" />\n    <child\n      link=\"Link_1\" />\n    <axis\n      xyz=\"0 1 0\" />\n    <limit\n      lower=\"-1\"\n      upper=\"1\"\n      effort=\"5\"\n      velocity=\"1\" />\n  </joint>\n  <link\n    name=\"Link_2\">\n    <inertial>\n      <origin\n        xyz=\"2.2815E-05 0.0017616 -0.080002\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"1.9323\" />\n      <inertia\n        ixx=\"0.012138\"\n        ixy=\"-3.5576E-06\"\n        ixz=\"-9.0632E-06\"\n        iyy=\"0.011445\"\n        iyz=\"0.00014273\"\n        izz=\"0.00070271\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Link_2.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.75294 0.75294 0.75294 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Link_2.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Joint_2\"\n    type=\"revolute\">\n    <origin\n      xyz=\"0 0.18264 0\"\n      rpy=\"-3.1416 0.95134 1.5708\" />\n    <parent\n      link=\"Link_1\" />\n    <child\n      link=\"Link_2\" />\n    <axis\n      xyz=\"0 -1 0\" />\n    <limit\n      lower=\"-1\"\n      upper=\"1\"\n      effort=\"5\"\n      velocity=\"1\" />\n  </joint>\n  <link\n    name=\"Link_3\">\n    <inertial>\n      <origin\n        xyz=\"0.05095 -0.00039084 -0.00045591\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"1.1381\" />\n      <inertia\n        ixx=\"0.00023572\"\n        ixy=\"-3.8425E-06\"\n        ixz=\"4.1286E-06\"\n        iyy=\"0.00029123\"\n        iyz=\"-1.0387E-07\"\n        izz=\"0.00052457\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Link_3.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.75294 0.75294 0.75294 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Link_3.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Joint_3\"\n    type=\"revolute\">\n    <origin\n      xyz=\"0 0 -0.22112\"\n      rpy=\"-3.1416 0.98126 -3.1416\" />\n    <parent\n      link=\"Link_2\" />\n    <child\n      link=\"Link_3\" />\n    <axis\n      xyz=\"0 -1 0\" />\n    <limit\n      lower=\"-1\"\n      upper=\"1\"\n      effort=\"5\"\n      velocity=\"1\" />\n  </joint>\n  <link\n    name=\"Link_4\">\n    <inertial>\n      <origin\n        xyz=\"-0.0027417 0.0025097 0.012864\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"0.62964\" />\n      <inertia\n        ixx=\"0.0001717\"\n        ixy=\"1.3446E-06\"\n        ixz=\"8.5164E-06\"\n        iyy=\"0.00010506\"\n        iyz=\"5.1412E-05\"\n        izz=\"7.8944E-05\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Link_4.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.29412 0.29412 0.29412 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Link_4.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Joint_4\"\n    type=\"revolute\">\n    <origin\n      xyz=\"0.16988 -0.00099213 0\"\n      rpy=\"3.1416 -1.2279 1.5708\" />\n    <parent\n      link=\"Link_3\" />\n    <child\n      link=\"Link_4\" />\n    <axis\n      xyz=\"0.010353 -0.99993 -0.0059382\" />\n    <limit\n      lower=\"-1\"\n      upper=\"1\"\n      effort=\"5\"\n      velocity=\"1\" />\n  </joint>\n  <link\n    name=\"Link_5\">\n    <inertial>\n      <origin\n        xyz=\"-0.011366 0.00012239 0.0078967\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"0.19875\" />\n      <inertia\n        ixx=\"6.2676E-05\"\n        ixy=\"4.2551E-06\"\n        ixz=\"4.0215E-05\"\n        iyy=\"9.7792E-05\"\n        iyz=\"8.5888E-07\"\n        izz=\"9.5807E-05\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Link_5.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.79216 0.81961 0.93333 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Link_5.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Joint_5\"\n    type=\"revolute\">\n    <origin\n      xyz=\"-0.0021346 0.053041 0.0016936\"\n      rpy=\"-1.5639 -0.091135 -0.00062919\" />\n    <parent\n      link=\"Link_4\" />\n    <child\n      link=\"Link_5\" />\n    <axis\n      xyz=\"0 1 0\" />\n    <limit\n      lower=\"-1\"\n      upper=\"1\"\n      effort=\"5\"\n      velocity=\"1\" />\n  </joint>\n  <link\n    name=\"Gripper_Servo_Gear\">\n    <inertial>\n      <origin\n        xyz=\"-0.0063957 -0.0033021 -0.00082714\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"0.0048997\" />\n      <inertia\n        ixx=\"2.0097E-09\"\n        ixy=\"-3.0673E-09\"\n        ixz=\"-6.3297E-10\"\n        iyy=\"4.9761E-09\"\n        iyz=\"-3.9668E-10\"\n        izz=\"6.8221E-09\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Gripper_Servo_Gear.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.9098 0.44314 0.031373 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Gripper_Servo_Gear.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Gripper_Servo_Gear_Joint\"\n    type=\"revolute\">\n    <origin\n      xyz=\"-0.05013 0.01413 0.041516\"\n      rpy=\"0.9321 0.032705 -1.5268\" />\n    <parent\n      link=\"Link_5\" />\n    <child\n      link=\"Gripper_Servo_Gear\" />\n    <axis\n      xyz=\"0 1 0\" />\n    <limit\n      lower=\"0\"\n      upper=\"1.5707\"\n      effort=\"5\"\n      velocity=\"1\" />\n  </joint>\n  <link\n    name=\"Tip_Gripper_Servo\">\n    <inertial>\n      <origin\n        xyz=\"0.028047 -0.000564 0.0049632\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"0.010676\" />\n      <inertia\n        ixx=\"8.9609E-09\"\n        ixy=\"6.3808E-09\"\n        ixz=\"-2.6788E-08\"\n        iyy=\"1.7457E-07\"\n        iyz=\"7.7239E-10\"\n        izz=\"1.7361E-07\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Tip_Gripper_Servo.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.6 1 0.27843 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Tip_Gripper_Servo.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Tip_Gripper_Servo_Joint\"\n    type=\"revolute\">\n    <origin\n      xyz=\"-0.039906 -0.004 -0.0027473\"\n      rpy=\"-3.1416 -1.5569 -2.0392E-12\" />\n    <parent\n      link=\"Gripper_Servo_Gear\" />\n    <child\n      link=\"Tip_Gripper_Servo\" />\n    <axis\n      xyz=\"0 1 0\" />\n    <limit\n      lower=\"0\"\n      upper=\"1.3\"\n      effort=\"5\"\n      velocity=\"1\" />\n    <mimic joint=\"Gripper_Servo_Gear_Joint\" multiplier=\"1\" offset=\"0\"/> \n  </joint>\n  <link\n    name=\"Gripper_Idol_Gear\">\n    <inertial>\n      <origin\n        xyz=\"-0.0061853 0.00086502 -3.5867E-05\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"0.0051273\" />\n      <inertia\n        ixx=\"2.3312E-09\"\n        ixy=\"1.1098E-09\"\n        ixz=\"-5.1524E-11\"\n        iyy=\"8.8855E-09\"\n        iyz=\"6.4357E-12\"\n        izz=\"1.1216E-08\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Gripper_Idol_Gear.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.058824 0.64706 1 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Gripper_Idol_Gear.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Gripper_Idol_Gear_Joint\"\n    type=\"revolute\">\n    <origin\n      xyz=\"-0.052696 -0.01387 0.038065\"\n      rpy=\"2.2091 -0.040996 1.626\" />\n    <parent\n      link=\"Link_5\" />\n    <child\n      link=\"Gripper_Idol_Gear\" />\n    <axis\n      xyz=\"0 1 0\" />\n    <limit\n      lower=\"-1.5707\"\n      upper=\"0\"\n      effort=\"5\"\n      velocity=\"1\" />\n  </joint>\n  <link\n    name=\"Tip_Gripper_Idol\">\n    <inertial>\n      <origin\n        xyz=\"0.0059646 0.00098916 0.027851\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"0.010676\" />\n      <inertia\n        ixx=\"1.6895E-07\"\n        ixy=\"-1.6878E-09\"\n        ixz=\"-3.8254E-08\"\n        iyy=\"1.7457E-07\"\n        iyz=\"-6.203E-09\"\n        izz=\"1.3622E-08\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Tip_Gripper_Idol.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.79216 0.81961 0.93333 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Tip_Gripper_Idol.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Tip_Gripper_Idol_Joint\"\n    type=\"revolute\">\n    <origin\n      xyz=\"-0.039906 -0.000125 -0.0027473\"\n      rpy=\"3.1416 0.5236 3.1416\" />\n    <parent\n      link=\"Gripper_Idol_Gear\" />\n    <child\n      link=\"Tip_Gripper_Idol\" />\n    <axis\n      xyz=\"0 1 0\" />\n    <limit\n      lower=\"-1.5\"\n      upper=\"0\"\n      effort=\"5\"\n      velocity=\"1\" />\n    <mimic joint=\"Gripper_Idol_Gear_Joint\" multiplier=\"-1\" offset=\"0\"/>\n  </joint>\n  <link\n    name=\"Pivot_Arm_Gripper_Servo\">\n    <inertial>\n      <origin\n        xyz=\"-0.017611 0.00080352 -1.2115E-11\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"0.0018597\" />\n      <inertia\n        ixx=\"2.3199E-09\"\n        ixy=\"3.1597E-09\"\n        ixz=\"3.9677E-16\"\n        iyy=\"7.8256E-08\"\n        iyz=\"-2.0327E-16\"\n        izz=\"8.0576E-08\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Pivot_Arm_Gripper_Servo.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.79216 0.81961 0.93333 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Pivot_Arm_Gripper_Servo.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Pivot_Arm_Gripper_Servo_Joint\"\n    type=\"revolute\">\n    <origin\n      xyz=\"-0.068745 0.00713 0.05\"\n      rpy=\"0.93142 -0.0083007 -1.582\" />\n    <parent\n      link=\"Link_5\" />\n    <child\n      link=\"Pivot_Arm_Gripper_Servo\" />\n    <axis\n      xyz=\"0 1 0\" />\n    <limit\n      lower=\"-1\"\n      upper=\"1\"\n      effort=\"5\"\n      velocity=\"1\" />\n    <mimic joint=\"Gripper_Servo_Gear_Joint\" multiplier=\"1\" offset=\"0\"/> \n  </joint>\n  <link\n    name=\"Pivot_Arm_Gripper_Idol\">\n    <inertial>\n      <origin\n        xyz=\"0.017611 0.00067852 -1.3978E-11\"\n        rpy=\"0 0 0\" />\n      <mass\n        value=\"0.0018597\" />\n      <inertia\n        ixx=\"2.3199E-09\"\n        ixy=\"-3.1597E-09\"\n        ixz=\"-4.5779E-16\"\n        iyy=\"7.8256E-08\"\n        iyz=\"-2.26E-16\"\n        izz=\"8.0576E-08\" />\n    </inertial>\n    <visual>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Pivot_Arm_Gripper_Idol.STL\" />\n      </geometry>\n      <material\n        name=\"\">\n        <color\n          rgba=\"0.79216 0.81961 0.93333 1\" />\n      </material>\n    </visual>\n    <collision>\n      <origin\n        xyz=\"0 0 0\"\n        rpy=\"0 0 0\" />\n      <geometry>\n        <mesh\n          filename=\"package://moveo_urdf_5/meshes/Pivot_Arm_Gripper_Idol.STL\" />\n      </geometry>\n    </collision>\n  </link>\n  <joint\n    name=\"Pivot_Arm_Gripper_Idol_Joint\"\n    type=\"revolute\">\n    <origin\n      xyz=\"-0.06867 -0.00687 0.0501\"\n      rpy=\"0.93138 1.7645E-12 -1.5708\" />\n    <parent\n      link=\"Link_5\" />\n    <child\n      link=\"Pivot_Arm_Gripper_Idol\" />\n    <axis\n      xyz=\"0 1 0\" />\n    <limit\n      lower=\"-1\"\n      upper=\"1\"\n      effort=\"5\"\n      velocity=\"1\" />\n    <mimic joint=\"Gripper_Idol_Gear_Joint\" multiplier=\"1\" offset=\"0\"/> \n  </joint>\n\n  <gazebo>\n    <plugin name=\"MimicJointPlugin\" filename=\"libroboticsgroup_gazebo_mimic_joint_plugin.so\">\n      joint=\"Gripper_Idol_Gear_Joint\"\n      mimicJoint=\"Pivot_Arm_Gripper_Idol_Joint\"\n      multiplier=\"1\"\n      offset=\"0\"\n    </plugin>\n    <plugin name=\"MimicJointPlugin\" filename=\"libroboticsgroup_gazebo_mimic_joint_plugin.so\">\n      joint=\"Gripper_Servo_Gear_Joint\"\n      mimicJoint=\"Pivot_Arm_Gripper_Servo_Joint\"\n      multiplier=\"1\"\n      offset=\"0\"\n    </plugin>\n    <plugin name=\"MimicJointPlugin\" filename=\"libroboticsgroup_gazebo_mimic_joint_plugin.so\">\n      joint=\"Gripper_Servo_Gear_Joint\"\n      mimicJoint=\"Tip_Gripper_Servo_Joint\n      multiplier=\"1\"\n      offset=\"0\"\n    </plugin>\n    <plugin name=\"MimicJointPlugin\" filename=\"libroboticsgroup_gazebo_mimic_joint_plugin.so\">\n      joint=\"Gripper_Idol_Gear_Joint\"\n      mimicJoint=\"Tip_Gripper_Idol_Joint\n      multiplier=\"-1\"\n      offset=\"0\"\n    </plugin>\n  </gazebo>\n</robot>\n\n\n  \n\n"
  },
  {
    "path": "object_detector_app/LICENSE",
    "content": "MIT License\n\nCopyright (c) 2017 Dat Tran\n\nPermission is hereby granted, free of charge, to any person obtaining a copy\nof this software and associated documentation files (the \"Software\"), to deal\nin the Software without restriction, including without limitation the rights\nto use, copy, modify, merge, publish, distribute, sublicense, and/or sell\ncopies of the Software, and to permit persons to whom the Software is\nfurnished to do so, subject to the following conditions:\n\nThe above copyright notice and this permission notice shall be included in all\ncopies or substantial portions of the Software.\n\nTHE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\nIMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\nFITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE\nAUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER\nLIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,\nOUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE\nSOFTWARE."
  },
  {
    "path": "object_detector_app/README.md",
    "content": "# Object-Detector-App\n\nA real-time object recognition application using [Google's TensorFlow Object Detection API](https://github.com/tensorflow/models/tree/master/research/object_detection) and [OpenCV](http://opencv.org/).\n\n## Getting Started\n1. `conda env create -f environment.yml`\n2. `python object_detection_app.py`\n    Optional arguments (default value):\n    * Device index of the camera `--source=0`\n    * Width of the frames in the video stream `--width=480`\n    * Height of the frames in the video stream `--height=360`\n    * Number of workers `--num-workers=2`\n    * Size of the queue `--queue-size=5`\n\n## Tests\n```\npytest -vs utils/\n```\n\n## Requirements\n- [Anaconda / Python 3.5](https://www.continuum.io/downloads)\n- [TensorFlow 1.2](https://www.tensorflow.org/)\n- [OpenCV 3.0](http://opencv.org/)\n\n## Notes\n- OpenCV 3.1 might crash on OSX after a while, so that's why I had to switch to version 3.0. See open issue and solution [here](https://github.com/opencv/opencv/issues/5874).\n- Moving the `.read()` part of the video stream in a multiple child processes did not work. However, it was possible to move it to a separate thread.\n\n## Copyright\n\nSee [LICENSE](LICENSE) for details.\nCopyright (c) 2017 [Dat Tran](http://www.dat-tran.com/).\n"
  },
  {
    "path": "object_detector_app/__init__.py",
    "content": "from . utils import *\nfrom . object_detection import *\nfrom . object_detection_multithreading import *\n"
  },
  {
    "path": "object_detector_app/environment.yml",
    "content": "name: object-detection\nchannels: !!python/tuple\n- menpo\n- defaults\ndependencies:\n- cycler=0.10.0=py35_0\n- freetype=2.5.5=2\n- icu=54.1=0\n- jbig=2.1=0\n- jlaura::opencv3=3.0.0=py35_0\n- jpeg=9b=0\n- libpng=1.6.27=0\n- libtiff=4.0.6=3\n- matplotlib=2.0.2=np113py35_0\n- menpo::tbb=4.3_20141023=0\n- mkl=2017.0.1=0\n- numpy=1.13.0=py35_0\n- olefile=0.44=py35_0\n- openssl=1.0.2l=0\n- pillow=4.1.1=py35_0\n- pip=9.0.1=py35_1\n- py=1.4.34=py35_0\n- pyparsing=2.2.0=py35_0\n- pyqt=5.6.0=py35_2\n- pytest=3.2.1=py35_0\n- python=3.5.3=1\n- python-dateutil=2.6.1=py35_0\n- pytz=2017.2=py35_0\n- qt=5.6.2=2\n- readline=6.2=2\n- setuptools=27.2.0=py35_0\n- sip=4.18=py35_0\n- six=1.10.0=py35_0\n- sqlite=3.13.0=0\n- tk=8.5.18=0\n- wheel=0.29.0=py35_0\n- xz=5.2.2=1\n- zlib=1.2.8=3\n- pip:\n  - backports.weakref==1.0rc1\n  - bleach==1.5.0\n  - html5lib==0.9999999\n  - markdown==2.2.0\n  - protobuf==3.3.0\n  - tensorflow==1.2.0\n  - werkzeug==0.12.2\nprefix: /Users/datitran/anaconda/envs/object-detection\n\n"
  },
  {
    "path": "object_detector_app/object_detection/BUILD",
    "content": "# Tensorflow Object Detection API: main runnables.\n\npackage(\n    default_visibility = [\"//visibility:public\"],\n)\n\nlicenses([\"notice\"])\n\n# Apache 2.0\n\npy_binary(\n    name = \"train\",\n    srcs = [\n        \"train.py\",\n    ],\n    deps = [\n        \":trainer\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/builders:input_reader_builder\",\n        \"//tensorflow_models/object_detection/builders:model_builder\",\n        \"//tensorflow_models/object_detection/protos:input_reader_py_pb2\",\n        \"//tensorflow_models/object_detection/protos:model_py_pb2\",\n        \"//tensorflow_models/object_detection/protos:pipeline_py_pb2\",\n        \"//tensorflow_models/object_detection/protos:train_py_pb2\",\n    ],\n)\n\npy_library(\n    name = \"trainer\",\n    srcs = [\"trainer.py\"],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/builders:optimizer_builder\",\n        \"//tensorflow_models/object_detection/builders:preprocessor_builder\",\n        \"//tensorflow_models/object_detection/core:batcher\",\n        \"//tensorflow_models/object_detection/core:standard_fields\",\n        \"//tensorflow_models/object_detection/utils:ops\",\n        \"//tensorflow_models/object_detection/utils:variables_helper\",\n        \"//tensorflow_models/slim:model_deploy\",\n    ],\n)\n\npy_test(\n    name = \"trainer_test\",\n    srcs = [\"trainer_test.py\"],\n    deps = [\n        \":trainer\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:losses\",\n        \"//tensorflow_models/object_detection/core:model\",\n        \"//tensorflow_models/object_detection/core:standard_fields\",\n        \"//tensorflow_models/object_detection/protos:train_py_pb2\",\n    ],\n)\n\npy_library(\n    name = \"eval_util\",\n    srcs = [\n        \"eval_util.py\",\n    ],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/utils:label_map_util\",\n        \"//tensorflow_models/object_detection/utils:object_detection_evaluation\",\n        \"//tensorflow_models/object_detection/utils:visualization_utils\",\n    ],\n)\n\npy_library(\n    name = \"evaluator\",\n    srcs = [\"evaluator.py\"],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection:eval_util\",\n        \"//tensorflow_models/object_detection/core:box_list\",\n        \"//tensorflow_models/object_detection/core:box_list_ops\",\n        \"//tensorflow_models/object_detection/core:prefetcher\",\n        \"//tensorflow_models/object_detection/core:standard_fields\",\n        \"//tensorflow_models/object_detection/protos:eval_py_pb2\",\n    ],\n)\n\npy_binary(\n    name = \"eval\",\n    srcs = [\n        \"eval.py\",\n    ],\n    deps = [\n        \":evaluator\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/builders:input_reader_builder\",\n        \"//tensorflow_models/object_detection/builders:model_builder\",\n        \"//tensorflow_models/object_detection/protos:eval_py_pb2\",\n        \"//tensorflow_models/object_detection/protos:input_reader_py_pb2\",\n        \"//tensorflow_models/object_detection/protos:model_py_pb2\",\n        \"//tensorflow_models/object_detection/protos:pipeline_py_pb2\",\n        \"//tensorflow_models/object_detection/utils:label_map_util\",\n    ],\n)\n\npy_library(\n    name = \"exporter\",\n    srcs = [\n        \"exporter.py\",\n    ],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow/python/tools:freeze_graph_lib\",\n        \"//tensorflow_models/object_detection/builders:model_builder\",\n        \"//tensorflow_models/object_detection/core:standard_fields\",\n        \"//tensorflow_models/object_detection/data_decoders:tf_example_decoder\",\n    ],\n)\n\npy_test(\n    name = \"exporter_test\",\n    srcs = [\n        \"exporter_test.py\",\n    ],\n    deps = [\n        \":exporter\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/builders:model_builder\",\n        \"//tensorflow_models/object_detection/core:model\",\n        \"//tensorflow_models/object_detection/protos:pipeline_py_pb2\",\n    ],\n)\n\npy_binary(\n    name = \"export_inference_graph\",\n    srcs = [\n        \"export_inference_graph.py\",\n    ],\n    deps = [\n        \":exporter\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/protos:pipeline_py_pb2\",\n    ],\n)\n\npy_binary(\n    name = \"create_pascal_tf_record\",\n    srcs = [\n        \"create_pascal_tf_record.py\",\n    ],\n    deps = [\n        \"//third_party/py/PIL:pil\",\n        \"//third_party/py/lxml\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/utils:dataset_util\",\n        \"//tensorflow_models/object_detection/utils:label_map_util\",\n    ],\n)\n\npy_test(\n    name = \"create_pascal_tf_record_test\",\n    srcs = [\n        \"create_pascal_tf_record_test.py\",\n    ],\n    deps = [\n        \":create_pascal_tf_record\",\n        \"//tensorflow\",\n    ],\n)\n\npy_binary(\n    name = \"create_pet_tf_record\",\n    srcs = [\n        \"create_pet_tf_record.py\",\n    ],\n    deps = [\n        \"//third_party/py/PIL:pil\",\n        \"//third_party/py/lxml\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/utils:dataset_util\",\n        \"//tensorflow_models/object_detection/utils:label_map_util\",\n    ],\n)\n"
  },
  {
    "path": "object_detector_app/object_detection/CONTRIBUTING.md",
    "content": "# Contributing to the Tensorflow Object Detection API\n\nPatches to Tensorflow Object Detection API are welcome!\n\nWe require contributors to fill out either the individual or corporate\nContributor License Agreement (CLA).\n\n  * If you are an individual writing original source code and you're sure you own the intellectual property, then you'll need to sign an [individual CLA](http://code.google.com/legal/individual-cla-v1.0.html).\n  * If you work for a company that wants to allow you to contribute your work, then you'll need to sign a [corporate CLA](http://code.google.com/legal/corporate-cla-v1.0.html).\n\nPlease follow the\n[Tensorflow contributing guidelines](https://github.com/tensorflow/tensorflow/blob/master/CONTRIBUTING.md)\nwhen submitting pull requests.\n"
  },
  {
    "path": "object_detector_app/object_detection/README.md",
    "content": "# Tensorflow Object Detection API\nCreating accurate machine learning models capable of localizing and identifying\nmultiple objects in a single image remains a core challenge in computer vision.\nThe TensorFlow Object Detection API is an open source framework built on top of\nTensorFlow that makes it easy to construct, train and deploy object detection\nmodels.  At Google we’ve certainly found this codebase to be useful for our\ncomputer vision needs, and we hope that you will as well.\n<p align=\"center\">\n  <img src=\"g3doc/img/kites_detections_output.jpg\" width=676 height=450>\n</p>\nContributions to the codebase are welcome and we would love to hear back from\nyou if you find this API useful.  Finally if you use the Tensorflow Object\nDetection API for a research publication, please consider citing:\n\n```\n\"Speed/accuracy trade-offs for modern convolutional object detectors.\"\nHuang J, Rathod V, Sun C, Zhu M, Korattikara A, Fathi A, Fischer I, Wojna Z,\nSong Y, Guadarrama S, Murphy K, CVPR 2017\n```\n\\[[link](https://arxiv.org/abs/1611.10012)\\]\\[[bibtex](\nhttps://scholar.googleusercontent.com/scholar.bib?q=info:l291WsrB-hQJ:scholar.google.com/&output=citation&scisig=AAGBfm0AAAAAWUIIlnPZ_L9jxvPwcC49kDlELtaeIyU-&scisf=4&ct=citation&cd=-1&hl=en&scfhb=1)\\]\n\n## Maintainers\n\n* Jonathan Huang, github: [jch1](https://github.com/jch1)\n* Vivek Rathod, github: [tombstone](https://github.com/tombstone)\n* Derek Chow, github: [derekjchow](https://github.com/derekjchow)\n* Chen Sun, github: [jesu9](https://github.com/jesu9)\n* Menglong Zhu, github: [dreamdragon](https://github.com/dreamdragon)\n\n\n## Table of contents\n\nQuick Start:\n* <a href='object_detection_tutorial.ipynb'>\n      Quick Start: Jupyter notebook for off-the-shelf inference</a><br>\n* <a href=\"g3doc/running_pets.md\">Quick Start: Training a pet detector</a><br>\n\nSetup:\n* <a href='g3doc/installation.md'>Installation</a><br>\n* <a href='g3doc/configuring_jobs.md'>\n      Configuring an object detection pipeline</a><br>\n* <a href='g3doc/preparing_inputs.md'>Preparing inputs</a><br>\n\nRunning:\n* <a href='g3doc/running_locally.md'>Running locally</a><br>\n* <a href='g3doc/running_on_cloud.md'>Running on the cloud</a><br>\n\nExtras:\n* <a href='g3doc/detection_model_zoo.md'>Tensorflow detection model zoo</a><br>\n* <a href='g3doc/exporting_models.md'>\n      Exporting a trained model for inference</a><br>\n* <a href='g3doc/defining_your_own_model.md'>\n      Defining your own model architecture</a><br>\n\n## Release information\n\n### June 15, 2017\n\nIn addition to our base Tensorflow detection model definitions, this\nrelease includes:\n\n* A selection of trainable detection models, including:\n  * Single Shot Multibox Detector (SSD) with MobileNet,\n  * SSD with Inception V2,\n  * Region-Based Fully Convolutional Networks (R-FCN) with Resnet 101,\n  * Faster RCNN with Resnet 101,\n  * Faster RCNN with Inception Resnet v2\n* Frozen weights (trained on the COCO dataset) for each of the above models to\n  be used for out-of-the-box inference purposes.\n* A [Jupyter notebook](object_detection_tutorial.ipynb) for performing\n  out-of-the-box inference with one of our released models\n* Convenient [local training](g3doc/running_locally.md) scripts as well as\n  distributed training and evaluation pipelines via\n  [Google Cloud](g3doc/running_on_cloud.md).\n\n\n<b>Thanks to contributors</b>: Jonathan Huang, Vivek Rathod, Derek Chow,\nChen Sun, Menglong Zhu, Matthew Tang, Anoop Korattikara, Alireza Fathi, Ian Fischer, Zbigniew Wojna, Yang Song, Sergio Guadarrama, Jasper Uijlings,\nViacheslav Kovalevskyi, Kevin Murphy\n"
  },
  {
    "path": "object_detector_app/object_detection/__init__.py",
    "content": "from . import *\n\n"
  },
  {
    "path": "object_detector_app/object_detection/anchor_generators/BUILD",
    "content": "# Tensorflow Object Detection API: Anchor Generator implementations.\n\npackage(\n    default_visibility = [\"//visibility:public\"],\n)\n\nlicenses([\"notice\"])\n\n# Apache 2.0\npy_library(\n    name = \"grid_anchor_generator\",\n    srcs = [\n        \"grid_anchor_generator.py\",\n    ],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:anchor_generator\",\n        \"//tensorflow_models/object_detection/core:box_list\",\n        \"//tensorflow_models/object_detection/utils:ops\",\n    ],\n)\n\npy_test(\n    name = \"grid_anchor_generator_test\",\n    srcs = [\n        \"grid_anchor_generator_test.py\",\n    ],\n    deps = [\n        \":grid_anchor_generator\",\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"multiple_grid_anchor_generator\",\n    srcs = [\n        \"multiple_grid_anchor_generator.py\",\n    ],\n    deps = [\n        \":grid_anchor_generator\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:anchor_generator\",\n        \"//tensorflow_models/object_detection/core:box_list_ops\",\n    ],\n)\n\npy_test(\n    name = \"multiple_grid_anchor_generator_test\",\n    srcs = [\n        \"multiple_grid_anchor_generator_test.py\",\n    ],\n    deps = [\n        \":multiple_grid_anchor_generator\",\n        \"//third_party/py/numpy\",\n    ],\n)\n"
  },
  {
    "path": "object_detector_app/object_detection/anchor_generators/__init__.py",
    "content": ""
  },
  {
    "path": "object_detector_app/object_detection/anchor_generators/grid_anchor_generator.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Generates grid anchors on the fly as used in Faster RCNN.\n\nGenerates grid anchors on the fly as described in:\n\"Faster R-CNN: Towards Real-Time Object Detection with Region Proposal Networks\"\nShaoqing Ren, Kaiming He, Ross Girshick, and Jian Sun.\n\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.core import anchor_generator\nfrom object_detection.core import box_list\nfrom object_detection.utils import ops\n\n\nclass GridAnchorGenerator(anchor_generator.AnchorGenerator):\n  \"\"\"Generates a grid of anchors at given scales and aspect ratios.\"\"\"\n\n  def __init__(self,\n               scales=(0.5, 1.0, 2.0),\n               aspect_ratios=(0.5, 1.0, 2.0),\n               base_anchor_size=None,\n               anchor_stride=None,\n               anchor_offset=None):\n    \"\"\"Constructs a GridAnchorGenerator.\n\n    Args:\n      scales: a list of (float) scales, default=(0.5, 1.0, 2.0)\n      aspect_ratios: a list of (float) aspect ratios, default=(0.5, 1.0, 2.0)\n      base_anchor_size: base anchor size as height, width (\n                        (length-2 float32 list, default=[256, 256])\n      anchor_stride: difference in centers between base anchors for adjacent\n                     grid positions (length-2 float32 list, default=[16, 16])\n      anchor_offset: center of the anchor with scale and aspect ratio 1 for the\n                     upper left element of the grid, this should be zero for\n                     feature networks with only VALID padding and even receptive\n                     field size, but may need additional calculation if other\n                     padding is used (length-2 float32 tensor, default=[0, 0])\n    \"\"\"\n    # Handle argument defaults\n    if base_anchor_size is None:\n      base_anchor_size = [256, 256]\n    base_anchor_size = tf.constant(base_anchor_size, tf.float32)\n    if anchor_stride is None:\n      anchor_stride = [16, 16]\n    anchor_stride = tf.constant(anchor_stride, dtype=tf.float32)\n    if anchor_offset is None:\n      anchor_offset = [0, 0]\n    anchor_offset = tf.constant(anchor_offset, dtype=tf.float32)\n\n    self._scales = scales\n    self._aspect_ratios = aspect_ratios\n    self._base_anchor_size = base_anchor_size\n    self._anchor_stride = anchor_stride\n    self._anchor_offset = anchor_offset\n\n  def name_scope(self):\n    return 'GridAnchorGenerator'\n\n  def num_anchors_per_location(self):\n    \"\"\"Returns the number of anchors per spatial location.\n\n    Returns:\n      a list of integers, one for each expected feature map to be passed to\n      the `generate` function.\n    \"\"\"\n    return [len(self._scales) * len(self._aspect_ratios)]\n\n  def _generate(self, feature_map_shape_list):\n    \"\"\"Generates a collection of bounding boxes to be used as anchors.\n\n    Args:\n      feature_map_shape_list: list of pairs of convnet layer resolutions in the\n        format [(height_0, width_0)].  For example, setting\n        feature_map_shape_list=[(8, 8)] asks for anchors that correspond\n        to an 8x8 layer.  For this anchor generator, only lists of length 1 are\n        allowed.\n\n    Returns:\n      boxes: a BoxList holding a collection of N anchor boxes\n    Raises:\n      ValueError: if feature_map_shape_list, box_specs_list do not have the same\n        length.\n      ValueError: if feature_map_shape_list does not consist of pairs of\n        integers\n    \"\"\"\n    if not (isinstance(feature_map_shape_list, list)\n            and len(feature_map_shape_list) == 1):\n      raise ValueError('feature_map_shape_list must be a list of length 1.')\n    if not all([isinstance(list_item, tuple) and len(list_item) == 2\n                for list_item in feature_map_shape_list]):\n      raise ValueError('feature_map_shape_list must be a list of pairs.')\n    grid_height, grid_width = feature_map_shape_list[0]\n    scales_grid, aspect_ratios_grid = ops.meshgrid(self._scales,\n                                                   self._aspect_ratios)\n    scales_grid = tf.reshape(scales_grid, [-1])\n    aspect_ratios_grid = tf.reshape(aspect_ratios_grid, [-1])\n    return tile_anchors(grid_height,\n                        grid_width,\n                        scales_grid,\n                        aspect_ratios_grid,\n                        self._base_anchor_size,\n                        self._anchor_stride,\n                        self._anchor_offset)\n\n\ndef tile_anchors(grid_height,\n                 grid_width,\n                 scales,\n                 aspect_ratios,\n                 base_anchor_size,\n                 anchor_stride,\n                 anchor_offset):\n  \"\"\"Create a tiled set of anchors strided along a grid in image space.\n\n  This op creates a set of anchor boxes by placing a \"basis\" collection of\n  boxes with user-specified scales and aspect ratios centered at evenly\n  distributed points along a grid.  The basis collection is specified via the\n  scale and aspect_ratios arguments.  For example, setting scales=[.1, .2, .2]\n  and aspect ratios = [2,2,1/2] means that we create three boxes: one with scale\n  .1, aspect ratio 2, one with scale .2, aspect ratio 2, and one with scale .2\n  and aspect ratio 1/2.  Each box is multiplied by \"base_anchor_size\" before\n  placing it over its respective center.\n\n  Grid points are specified via grid_height, grid_width parameters as well as\n  the anchor_stride and anchor_offset parameters.\n\n  Args:\n    grid_height: size of the grid in the y direction (int or int scalar tensor)\n    grid_width: size of the grid in the x direction (int or int scalar tensor)\n    scales: a 1-d  (float) tensor representing the scale of each box in the\n      basis set.\n    aspect_ratios: a 1-d (float) tensor representing the aspect ratio of each\n      box in the basis set.  The length of the scales and aspect_ratios tensors\n      must be equal.\n    base_anchor_size: base anchor size as [height, width]\n      (float tensor of shape [2])\n    anchor_stride: difference in centers between base anchors for adjacent grid\n                   positions (float tensor of shape [2])\n    anchor_offset: center of the anchor with scale and aspect ratio 1 for the\n                   upper left element of the grid, this should be zero for\n                   feature networks with only VALID padding and even receptive\n                   field size, but may need some additional calculation if other\n                   padding is used (float tensor of shape [2])\n  Returns:\n    a BoxList holding a collection of N anchor boxes\n  \"\"\"\n  ratio_sqrts = tf.sqrt(aspect_ratios)\n  heights = scales / ratio_sqrts * base_anchor_size[0]\n  widths = scales * ratio_sqrts * base_anchor_size[1]\n\n  # Get a grid of box centers\n  y_centers = tf.to_float(tf.range(grid_height))\n  y_centers = y_centers * anchor_stride[0] + anchor_offset[0]\n  x_centers = tf.to_float(tf.range(grid_width))\n  x_centers = x_centers * anchor_stride[1] + anchor_offset[1]\n  x_centers, y_centers = ops.meshgrid(x_centers, y_centers)\n\n  widths_grid, x_centers_grid = ops.meshgrid(widths, x_centers)\n  heights_grid, y_centers_grid = ops.meshgrid(heights, y_centers)\n  bbox_centers = tf.stack([y_centers_grid, x_centers_grid], axis=3)\n  bbox_sizes = tf.stack([heights_grid, widths_grid], axis=3)\n  bbox_centers = tf.reshape(bbox_centers, [-1, 2])\n  bbox_sizes = tf.reshape(bbox_sizes, [-1, 2])\n  bbox_corners = _center_size_bbox_to_corners_bbox(bbox_centers, bbox_sizes)\n  return box_list.BoxList(bbox_corners)\n\n\ndef _center_size_bbox_to_corners_bbox(centers, sizes):\n  \"\"\"Converts bbox center-size representation to corners representation.\n\n  Args:\n    centers: a tensor with shape [N, 2] representing bounding box centers\n    sizes: a tensor with shape [N, 2] representing bounding boxes\n\n  Returns:\n    corners: tensor with shape [N, 4] representing bounding boxes in corners\n      representation\n  \"\"\"\n  return tf.concat([centers - .5 * sizes, centers + .5 * sizes], 1)\n"
  },
  {
    "path": "object_detector_app/object_detection/anchor_generators/grid_anchor_generator_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.grid_anchor_generator.\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.anchor_generators import grid_anchor_generator\n\n\nclass GridAnchorGeneratorTest(tf.test.TestCase):\n\n  def test_construct_single_anchor(self):\n    \"\"\"Builds a 1x1 anchor grid to test the size of the output boxes.\"\"\"\n    scales = [0.5, 1.0, 2.0]\n    aspect_ratios = [0.25, 1.0, 4.0]\n    anchor_offset = [7, -3]\n    exp_anchor_corners = [[-121, -35, 135, 29], [-249, -67, 263, 61],\n                          [-505, -131, 519, 125], [-57, -67, 71, 61],\n                          [-121, -131, 135, 125], [-249, -259, 263, 253],\n                          [-25, -131, 39, 125], [-57, -259, 71, 253],\n                          [-121, -515, 135, 509]]\n\n    anchor_generator = grid_anchor_generator.GridAnchorGenerator(\n        scales, aspect_ratios,\n        anchor_offset=anchor_offset)\n    anchors = anchor_generator.generate(feature_map_shape_list=[(1, 1)])\n    anchor_corners = anchors.get()\n\n    with self.test_session():\n      anchor_corners_out = anchor_corners.eval()\n      self.assertAllClose(anchor_corners_out, exp_anchor_corners)\n\n  def test_construct_anchor_grid(self):\n    base_anchor_size = [10, 10]\n    anchor_stride = [19, 19]\n    anchor_offset = [0, 0]\n    scales = [0.5, 1.0, 2.0]\n    aspect_ratios = [1.0]\n\n    exp_anchor_corners = [[-2.5, -2.5, 2.5, 2.5], [-5., -5., 5., 5.],\n                          [-10., -10., 10., 10.], [-2.5, 16.5, 2.5, 21.5],\n                          [-5., 14., 5, 24], [-10., 9., 10, 29],\n                          [16.5, -2.5, 21.5, 2.5], [14., -5., 24, 5],\n                          [9., -10., 29, 10], [16.5, 16.5, 21.5, 21.5],\n                          [14., 14., 24, 24], [9., 9., 29, 29]]\n\n    anchor_generator = grid_anchor_generator.GridAnchorGenerator(\n        scales,\n        aspect_ratios,\n        base_anchor_size=base_anchor_size,\n        anchor_stride=anchor_stride,\n        anchor_offset=anchor_offset)\n\n    anchors = anchor_generator.generate(feature_map_shape_list=[(2, 2)])\n    anchor_corners = anchors.get()\n\n    with self.test_session():\n      anchor_corners_out = anchor_corners.eval()\n      self.assertAllClose(anchor_corners_out, exp_anchor_corners)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/anchor_generators/multiple_grid_anchor_generator.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Generates grid anchors on the fly corresponding to multiple CNN layers.\n\nGenerates grid anchors on the fly corresponding to multiple CNN layers as\ndescribed in:\n\"SSD: Single Shot MultiBox Detector\"\nWei Liu, Dragomir Anguelov, Dumitru Erhan, Christian Szegedy, Scott Reed,\nCheng-Yang Fu, Alexander C. Berg\n(see Section 2.2: Choosing scales and aspect ratios for default boxes)\n\"\"\"\n\nimport numpy as np\n\nimport tensorflow as tf\n\nfrom object_detection.anchor_generators import grid_anchor_generator\nfrom object_detection.core import anchor_generator\nfrom object_detection.core import box_list_ops\n\n\nclass MultipleGridAnchorGenerator(anchor_generator.AnchorGenerator):\n  \"\"\"Generate a grid of anchors for multiple CNN layers.\"\"\"\n\n  def __init__(self,\n               box_specs_list,\n               base_anchor_size=None,\n               clip_window=None):\n    \"\"\"Constructs a MultipleGridAnchorGenerator.\n\n    To construct anchors, at multiple grid resolutions, one must provide a\n    list of feature_map_shape_list (e.g., [(8, 8), (4, 4)]), and for each grid\n    size, a corresponding list of (scale, aspect ratio) box specifications.\n\n    For example:\n    box_specs_list = [[(.1, 1.0), (.1, 2.0)],  # for 8x8 grid\n                      [(.2, 1.0), (.3, 1.0), (.2, 2.0)]]  # for 4x4 grid\n\n    To support the fully convolutional setting, we pass grid sizes in at\n    generation time, while scale and aspect ratios are fixed at construction\n    time.\n\n    Args:\n      box_specs_list: list of list of (scale, aspect ratio) pairs with the\n        outside list having the same number of entries as feature_map_shape_list\n        (which is passed in at generation time).\n      base_anchor_size: base anchor size as [height, width]\n                        (length-2 float tensor, default=[256, 256]).\n      clip_window: a tensor of shape [4] specifying a window to which all\n        anchors should be clipped. If clip_window is None, then no clipping\n        is performed.\n\n    Raises:\n      ValueError: if box_specs_list is not a list of list of pairs\n      ValueError: if clip_window is not either None or a tensor of shape [4]\n    \"\"\"\n    if isinstance(box_specs_list, list) and all(\n        [isinstance(list_item, list) for list_item in box_specs_list]):\n      self._box_specs = box_specs_list\n    else:\n      raise ValueError('box_specs_list is expected to be a '\n                       'list of lists of pairs')\n    if base_anchor_size is None:\n      base_anchor_size = tf.constant([256, 256], dtype=tf.float32)\n    self._base_anchor_size = base_anchor_size\n    if clip_window is not None and clip_window.get_shape().as_list() != [4]:\n      raise ValueError('clip_window must either be None or a shape [4] tensor')\n    self._clip_window = clip_window\n    self._scales = []\n    self._aspect_ratios = []\n    for box_spec in self._box_specs:\n      if not all([isinstance(entry, tuple) and len(entry) == 2\n                  for entry in box_spec]):\n        raise ValueError('box_specs_list is expected to be a '\n                         'list of lists of pairs')\n      scales, aspect_ratios = zip(*box_spec)\n      self._scales.append(scales)\n      self._aspect_ratios.append(aspect_ratios)\n\n  def name_scope(self):\n    return 'MultipleGridAnchorGenerator'\n\n  def num_anchors_per_location(self):\n    \"\"\"Returns the number of anchors per spatial location.\n\n    Returns:\n      a list of integers, one for each expected feature map to be passed to\n      the Generate function.\n    \"\"\"\n    return [len(box_specs) for box_specs in self._box_specs]\n\n  def _generate(self,\n                feature_map_shape_list,\n                im_height=1,\n                im_width=1,\n                anchor_strides=None,\n                anchor_offsets=None):\n    \"\"\"Generates a collection of bounding boxes to be used as anchors.\n\n    The number of anchors generated for a single grid with shape MxM where we\n    place k boxes over each grid center is k*M^2 and thus the total number of\n    anchors is the sum over all grids. In our box_specs_list example\n    (see the constructor docstring), we would place two boxes over each grid\n    point on an 8x8 grid and three boxes over each grid point on a 4x4 grid and\n    thus end up with 2*8^2 + 3*4^2 = 176 anchors in total. The layout of the\n    output anchors follows the order of how the grid sizes and box_specs are\n    specified (with box_spec index varying the fastest, followed by width\n    index, then height index, then grid index).\n\n    Args:\n      feature_map_shape_list: list of pairs of convnet layer resolutions in the\n        format [(height_0, width_0), (height_1, width_1), ...]. For example,\n        setting feature_map_shape_list=[(8, 8), (7, 7)] asks for anchors that\n        correspond to an 8x8 layer followed by a 7x7 layer.\n      im_height: the height of the image to generate the grid for. If both\n        im_height and im_width are 1, the generated anchors default to\n        normalized coordinates, otherwise absolute coordinates are used for the\n        grid.\n      im_width: the width of the image to generate the grid for. If both\n        im_height and im_width are 1, the generated anchors default to\n        normalized coordinates, otherwise absolute coordinates are used for the\n        grid.\n      anchor_strides: list of pairs of strides (in y and x directions\n        respectively). For example, setting\n        anchor_strides=[(.25, .25), (.5, .5)] means that we want the anchors\n        corresponding to the first layer to be strided by .25 and those in the\n        second layer to be strided by .5 in both y and x directions. By\n        default, if anchor_strides=None, then they are set to be the reciprocal\n        of the corresponding grid sizes. The pairs can also be specified as\n        dynamic tf.int or tf.float numbers, e.g. for variable shape input\n        images.\n      anchor_offsets: list of pairs of offsets (in y and x directions\n        respectively). The offset specifies where we want the center of the\n        (0, 0)-th anchor to lie for each layer. For example, setting\n        anchor_offsets=[(.125, .125), (.25, .25)]) means that we want the\n        (0, 0)-th anchor of the first layer to lie at (.125, .125) in image\n        space and likewise that we want the (0, 0)-th anchor of the second\n        layer to lie at (.25, .25) in image space. By default, if\n        anchor_offsets=None, then they are set to be half of the corresponding\n        anchor stride. The pairs can also be specified as dynamic tf.int or\n        tf.float numbers, e.g. for variable shape input images.\n\n    Returns:\n      boxes: a BoxList holding a collection of N anchor boxes\n    Raises:\n      ValueError: if feature_map_shape_list, box_specs_list do not have the same\n        length.\n      ValueError: if feature_map_shape_list does not consist of pairs of\n        integers\n    \"\"\"\n    if not (isinstance(feature_map_shape_list, list)\n            and len(feature_map_shape_list) == len(self._box_specs)):\n      raise ValueError('feature_map_shape_list must be a list with the same '\n                       'length as self._box_specs')\n    if not all([isinstance(list_item, tuple) and len(list_item) == 2\n                for list_item in feature_map_shape_list]):\n      raise ValueError('feature_map_shape_list must be a list of pairs.')\n    if not anchor_strides:\n      anchor_strides = [(tf.to_float(im_height) / tf.to_float(pair[0]),\n                         tf.to_float(im_width) / tf.to_float(pair[1]))\n                        for pair in feature_map_shape_list]\n    if not anchor_offsets:\n      anchor_offsets = [(0.5 * stride[0], 0.5 * stride[1])\n                        for stride in anchor_strides]\n    for arg, arg_name in zip([anchor_strides, anchor_offsets],\n                             ['anchor_strides', 'anchor_offsets']):\n      if not (isinstance(arg, list) and len(arg) == len(self._box_specs)):\n        raise ValueError('%s must be a list with the same length '\n                         'as self._box_specs' % arg_name)\n      if not all([isinstance(list_item, tuple) and len(list_item) == 2\n                  for list_item in arg]):\n        raise ValueError('%s must be a list of pairs.' % arg_name)\n\n    anchor_grid_list = []\n    min_im_shape = tf.to_float(tf.minimum(im_height, im_width))\n    base_anchor_size = min_im_shape * self._base_anchor_size\n    for grid_size, scales, aspect_ratios, stride, offset in zip(\n        feature_map_shape_list, self._scales, self._aspect_ratios,\n        anchor_strides, anchor_offsets):\n      anchor_grid_list.append(\n          grid_anchor_generator.tile_anchors(\n              grid_height=grid_size[0],\n              grid_width=grid_size[1],\n              scales=scales,\n              aspect_ratios=aspect_ratios,\n              base_anchor_size=base_anchor_size,\n              anchor_stride=stride,\n              anchor_offset=offset))\n    concatenated_anchors = box_list_ops.concatenate(anchor_grid_list)\n    num_anchors = concatenated_anchors.num_boxes_static()\n    if num_anchors is None:\n      num_anchors = concatenated_anchors.num_boxes()\n    if self._clip_window is not None:\n      clip_window = tf.multiply(\n          tf.to_float([im_height, im_width, im_height, im_width]),\n          self._clip_window)\n      concatenated_anchors = box_list_ops.clip_to_window(\n          concatenated_anchors, clip_window, filter_nonoverlapping=False)\n      # TODO: make reshape an option for the clip_to_window op\n      concatenated_anchors.set(\n          tf.reshape(concatenated_anchors.get(), [num_anchors, 4]))\n\n    stddevs_tensor = 0.01 * tf.ones(\n        [num_anchors, 4], dtype=tf.float32, name='stddevs')\n    concatenated_anchors.add_field('stddev', stddevs_tensor)\n\n    return concatenated_anchors\n\n\ndef create_ssd_anchors(num_layers=6,\n                       min_scale=0.2,\n                       max_scale=0.95,\n                       aspect_ratios=(1.0, 2.0, 3.0, 1.0/2, 1.0/3),\n                       base_anchor_size=None,\n                       reduce_boxes_in_lowest_layer=True):\n  \"\"\"Creates MultipleGridAnchorGenerator for SSD anchors.\n\n  This function instantiates a MultipleGridAnchorGenerator that reproduces\n  ``default box`` construction proposed by Liu et al in the SSD paper.\n  See Section 2.2 for details. Grid sizes are assumed to be passed in\n  at generation time from finest resolution to coarsest resolution --- this is\n  used to (linearly) interpolate scales of anchor boxes corresponding to the\n  intermediate grid sizes.\n\n  Anchors that are returned by calling the `generate` method on the returned\n  MultipleGridAnchorGenerator object are always in normalized coordinates\n  and clipped to the unit square: (i.e. all coordinates lie in [0, 1]x[0, 1]).\n\n  Args:\n    num_layers: integer number of grid layers to create anchors for (actual\n      grid sizes passed in at generation time)\n    min_scale: scale of anchors corresponding to finest resolution (float)\n    max_scale: scale of anchors corresponding to coarsest resolution (float)\n    aspect_ratios: list or tuple of (float) aspect ratios to place on each\n      grid point.\n    base_anchor_size: base anchor size as [height, width].\n    reduce_boxes_in_lowest_layer: a boolean to indicate whether the fixed 3\n      boxes per location is used in the lowest layer.\n\n  Returns:\n    a MultipleGridAnchorGenerator\n  \"\"\"\n  if base_anchor_size is None:\n    base_anchor_size = [1.0, 1.0]\n  base_anchor_size = tf.constant(base_anchor_size, dtype=tf.float32)\n  box_specs_list = []\n  scales = [min_scale + (max_scale - min_scale) * i / (num_layers - 1)\n            for i in range(num_layers)] + [1.0]\n  for layer, scale, scale_next in zip(\n      range(num_layers), scales[:-1], scales[1:]):\n    layer_box_specs = []\n    if layer == 0 and reduce_boxes_in_lowest_layer:\n      layer_box_specs = [(0.1, 1.0), (scale, 2.0), (scale, 0.5)]\n    else:\n      for aspect_ratio in aspect_ratios:\n        layer_box_specs.append((scale, aspect_ratio))\n        if aspect_ratio == 1.0:\n          layer_box_specs.append((np.sqrt(scale*scale_next), 1.0))\n    box_specs_list.append(layer_box_specs)\n  return MultipleGridAnchorGenerator(box_specs_list, base_anchor_size)\n"
  },
  {
    "path": "object_detector_app/object_detection/anchor_generators/multiple_grid_anchor_generator_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for anchor_generators.multiple_grid_anchor_generator_test.py.\"\"\"\n\nimport numpy as np\n\nimport tensorflow as tf\n\nfrom object_detection.anchor_generators import multiple_grid_anchor_generator as ag\n\n\nclass MultipleGridAnchorGeneratorTest(tf.test.TestCase):\n\n  def test_construct_single_anchor_grid(self):\n    \"\"\"Builds a 1x1 anchor grid to test the size of the output boxes.\"\"\"\n    exp_anchor_corners = [[-121, -35, 135, 29], [-249, -67, 263, 61],\n                          [-505, -131, 519, 125], [-57, -67, 71, 61],\n                          [-121, -131, 135, 125], [-249, -259, 263, 253],\n                          [-25, -131, 39, 125], [-57, -259, 71, 253],\n                          [-121, -515, 135, 509]]\n\n    base_anchor_size = tf.constant([256, 256], dtype=tf.float32)\n    box_specs_list = [[(.5, .25), (1.0, .25), (2.0, .25),\n                       (.5, 1.0), (1.0, 1.0), (2.0, 1.0),\n                       (.5, 4.0), (1.0, 4.0), (2.0, 4.0)]]\n    anchor_generator = ag.MultipleGridAnchorGenerator(\n        box_specs_list, base_anchor_size)\n    anchors = anchor_generator.generate(feature_map_shape_list=[(1, 1)],\n                                        anchor_strides=[(16, 16)],\n                                        anchor_offsets=[(7, -3)])\n    anchor_corners = anchors.get()\n    with self.test_session():\n      anchor_corners_out = anchor_corners.eval()\n      self.assertAllClose(anchor_corners_out, exp_anchor_corners)\n\n  def test_construct_anchor_grid(self):\n    base_anchor_size = tf.constant([10, 10], dtype=tf.float32)\n    box_specs_list = [[(0.5, 1.0), (1.0, 1.0), (2.0, 1.0)]]\n\n    exp_anchor_corners = [[-2.5, -2.5, 2.5, 2.5], [-5., -5., 5., 5.],\n                          [-10., -10., 10., 10.], [-2.5, 16.5, 2.5, 21.5],\n                          [-5., 14., 5, 24], [-10., 9., 10, 29],\n                          [16.5, -2.5, 21.5, 2.5], [14., -5., 24, 5],\n                          [9., -10., 29, 10], [16.5, 16.5, 21.5, 21.5],\n                          [14., 14., 24, 24], [9., 9., 29, 29]]\n\n    anchor_generator = ag.MultipleGridAnchorGenerator(\n        box_specs_list, base_anchor_size)\n    anchors = anchor_generator.generate(feature_map_shape_list=[(2, 2)],\n                                        anchor_strides=[(19, 19)],\n                                        anchor_offsets=[(0, 0)])\n    anchor_corners = anchors.get()\n\n    with self.test_session():\n      anchor_corners_out = anchor_corners.eval()\n      self.assertAllClose(anchor_corners_out, exp_anchor_corners)\n\n  def test_construct_anchor_grid_non_square(self):\n    base_anchor_size = tf.constant([1, 1], dtype=tf.float32)\n    box_specs_list = [[(1.0, 1.0)]]\n\n    exp_anchor_corners = [[0., -0.25, 1., 0.75], [0., 0.25, 1., 1.25]]\n\n    anchor_generator = ag.MultipleGridAnchorGenerator(box_specs_list,\n                                                      base_anchor_size)\n    anchors = anchor_generator.generate(feature_map_shape_list=[(tf.constant(\n        1, dtype=tf.int32), tf.constant(2, dtype=tf.int32))])\n    anchor_corners = anchors.get()\n\n    with self.test_session():\n      anchor_corners_out = anchor_corners.eval()\n      self.assertAllClose(anchor_corners_out, exp_anchor_corners)\n\n  def test_construct_anchor_grid_unnormalized(self):\n    base_anchor_size = tf.constant([1, 1], dtype=tf.float32)\n    box_specs_list = [[(1.0, 1.0)]]\n\n    exp_anchor_corners = [[0., 0., 320., 320.], [0., 320., 320., 640.]]\n\n    anchor_generator = ag.MultipleGridAnchorGenerator(box_specs_list,\n                                                      base_anchor_size)\n    anchors = anchor_generator.generate(\n        feature_map_shape_list=[(tf.constant(1, dtype=tf.int32), tf.constant(\n            2, dtype=tf.int32))],\n        im_height=320,\n        im_width=640)\n    anchor_corners = anchors.get()\n\n    with self.test_session():\n      anchor_corners_out = anchor_corners.eval()\n      self.assertAllClose(anchor_corners_out, exp_anchor_corners)\n\n  def test_construct_multiple_grids(self):\n    base_anchor_size = tf.constant([1.0, 1.0], dtype=tf.float32)\n    box_specs_list = [[(1.0, 1.0), (2.0, 1.0), (1.0, 0.5)],\n                      [(1.0, 1.0), (1.0, 0.5)]]\n\n    # height and width of box with .5 aspect ratio\n    h = np.sqrt(2)\n    w = 1.0/np.sqrt(2)\n    exp_small_grid_corners = [[-.25, -.25, .75, .75],\n                              [.25-.5*h, .25-.5*w, .25+.5*h, .25+.5*w],\n                              [-.25, .25, .75, 1.25],\n                              [.25-.5*h, .75-.5*w, .25+.5*h, .75+.5*w],\n                              [.25, -.25, 1.25, .75],\n                              [.75-.5*h, .25-.5*w, .75+.5*h, .25+.5*w],\n                              [.25, .25, 1.25, 1.25],\n                              [.75-.5*h, .75-.5*w, .75+.5*h, .75+.5*w]]\n    # only test first entry of larger set of anchors\n    exp_big_grid_corners = [[.125-.5, .125-.5, .125+.5, .125+.5],\n                            [.125-1.0, .125-1.0, .125+1.0, .125+1.0],\n                            [.125-.5*h, .125-.5*w, .125+.5*h, .125+.5*w],]\n\n    anchor_generator = ag.MultipleGridAnchorGenerator(\n        box_specs_list, base_anchor_size)\n    anchors = anchor_generator.generate(feature_map_shape_list=[(4, 4), (2, 2)],\n                                        anchor_strides=[(.25, .25), (.5, .5)],\n                                        anchor_offsets=[(.125, .125),\n                                                        (.25, .25)])\n    anchor_corners = anchors.get()\n\n    with self.test_session():\n      anchor_corners_out = anchor_corners.eval()\n      self.assertEquals(anchor_corners_out.shape, (56, 4))\n      big_grid_corners = anchor_corners_out[0:3, :]\n      small_grid_corners = anchor_corners_out[48:, :]\n      self.assertAllClose(small_grid_corners, exp_small_grid_corners)\n      self.assertAllClose(big_grid_corners, exp_big_grid_corners)\n\n  def test_construct_multiple_grids_with_clipping(self):\n    base_anchor_size = tf.constant([1.0, 1.0], dtype=tf.float32)\n    box_specs_list = [[(1.0, 1.0), (2.0, 1.0), (1.0, 0.5)],\n                      [(1.0, 1.0), (1.0, 0.5)]]\n\n    # height and width of box with .5 aspect ratio\n    h = np.sqrt(2)\n    w = 1.0/np.sqrt(2)\n    exp_small_grid_corners = [[0, 0, .75, .75],\n                              [0, 0, .25+.5*h, .25+.5*w],\n                              [0, .25, .75, 1],\n                              [0, .75-.5*w, .25+.5*h, 1],\n                              [.25, 0, 1, .75],\n                              [.75-.5*h, 0, 1, .25+.5*w],\n                              [.25, .25, 1, 1],\n                              [.75-.5*h, .75-.5*w, 1, 1]]\n\n    clip_window = tf.constant([0, 0, 1, 1], dtype=tf.float32)\n    anchor_generator = ag.MultipleGridAnchorGenerator(\n        box_specs_list, base_anchor_size, clip_window=clip_window)\n    anchors = anchor_generator.generate(feature_map_shape_list=[(4, 4), (2, 2)])\n    anchor_corners = anchors.get()\n\n    with self.test_session():\n      anchor_corners_out = anchor_corners.eval()\n      small_grid_corners = anchor_corners_out[48:, :]\n      self.assertAllClose(small_grid_corners, exp_small_grid_corners)\n\n  def test_invalid_box_specs(self):\n    # not all box specs are pairs\n    box_specs_list = [[(1.0, 1.0), (2.0, 1.0), (1.0, 0.5)],\n                      [(1.0, 1.0), (1.0, 0.5, .3)]]\n    with self.assertRaises(ValueError):\n      ag.MultipleGridAnchorGenerator(box_specs_list)\n\n    # box_specs_list is not a list of lists\n    box_specs_list = [(1.0, 1.0), (2.0, 1.0), (1.0, 0.5)]\n    with self.assertRaises(ValueError):\n      ag.MultipleGridAnchorGenerator(box_specs_list)\n\n  def test_invalid_generate_arguments(self):\n    base_anchor_size = tf.constant([1.0, 1.0], dtype=tf.float32)\n    box_specs_list = [[(1.0, 1.0), (2.0, 1.0), (1.0, 0.5)],\n                      [(1.0, 1.0), (1.0, 0.5)]]\n    anchor_generator = ag.MultipleGridAnchorGenerator(\n        box_specs_list, base_anchor_size)\n\n    # incompatible lengths with box_specs_list\n    with self.assertRaises(ValueError):\n      anchor_generator.generate(feature_map_shape_list=[(4, 4), (2, 2)],\n                                anchor_strides=[(.25, .25)],\n                                anchor_offsets=[(.125, .125), (.25, .25)])\n    with self.assertRaises(ValueError):\n      anchor_generator.generate(feature_map_shape_list=[(4, 4), (2, 2), (1, 1)],\n                                anchor_strides=[(.25, .25), (.5, .5)],\n                                anchor_offsets=[(.125, .125), (.25, .25)])\n    with self.assertRaises(ValueError):\n      anchor_generator.generate(feature_map_shape_list=[(4, 4), (2, 2)],\n                                anchor_strides=[(.5, .5)],\n                                anchor_offsets=[(.25, .25)])\n\n    # not pairs\n    with self.assertRaises(ValueError):\n      anchor_generator.generate(feature_map_shape_list=[(4, 4, 4), (2, 2)],\n                                anchor_strides=[(.25, .25), (.5, .5)],\n                                anchor_offsets=[(.125, .125), (.25, .25)])\n    with self.assertRaises(ValueError):\n      anchor_generator.generate(feature_map_shape_list=[(4, 4), (2, 2)],\n                                anchor_strides=[(.25, .25, .1), (.5, .5)],\n                                anchor_offsets=[(.125, .125),\n                                                (.25, .25)])\n    with self.assertRaises(ValueError):\n      anchor_generator.generate(feature_map_shape_list=[(4), (2, 2)],\n                                anchor_strides=[(.25, .25), (.5, .5)],\n                                anchor_offsets=[(.125), (.25)])\n\n\nclass CreateSSDAnchorsTest(tf.test.TestCase):\n\n  def test_create_ssd_anchors_returns_correct_shape(self):\n    anchor_generator = ag.create_ssd_anchors(\n        num_layers=6, min_scale=0.2, max_scale=0.95,\n        aspect_ratios=(1.0, 2.0, 3.0, 1.0/2, 1.0/3),\n        reduce_boxes_in_lowest_layer=True)\n\n    feature_map_shape_list = [(38, 38), (19, 19), (10, 10),\n                              (5, 5), (3, 3), (1, 1)]\n    anchors = anchor_generator.generate(\n        feature_map_shape_list=feature_map_shape_list)\n    anchor_corners = anchors.get()\n    with self.test_session():\n      anchor_corners_out = anchor_corners.eval()\n      self.assertEquals(anchor_corners_out.shape, (7308, 4))\n\n    anchor_generator = ag.create_ssd_anchors(\n        num_layers=6, min_scale=0.2, max_scale=0.95,\n        aspect_ratios=(1.0, 2.0, 3.0, 1.0/2, 1.0/3),\n        reduce_boxes_in_lowest_layer=False)\n\n    feature_map_shape_list = [(38, 38), (19, 19), (10, 10),\n                              (5, 5), (3, 3), (1, 1)]\n    anchors = anchor_generator.generate(\n        feature_map_shape_list=feature_map_shape_list)\n    anchor_corners = anchors.get()\n    with self.test_session():\n      anchor_corners_out = anchor_corners.eval()\n      self.assertEquals(anchor_corners_out.shape, (11640, 4))\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/box_coders/BUILD",
    "content": "# Tensorflow Object Detection API: Box Coder implementations.\n\npackage(\n    default_visibility = [\"//visibility:public\"],\n)\n\nlicenses([\"notice\"])\n\n# Apache 2.0\npy_library(\n    name = \"faster_rcnn_box_coder\",\n    srcs = [\n        \"faster_rcnn_box_coder.py\",\n    ],\n    deps = [\n        \"//tensorflow_models/object_detection/core:box_coder\",\n        \"//tensorflow_models/object_detection/core:box_list\",\n    ],\n)\n\npy_test(\n    name = \"faster_rcnn_box_coder_test\",\n    srcs = [\n        \"faster_rcnn_box_coder_test.py\",\n    ],\n    deps = [\n        \":faster_rcnn_box_coder\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:box_list\",\n    ],\n)\n\npy_library(\n    name = \"keypoint_box_coder\",\n    srcs = [\n        \"keypoint_box_coder.py\",\n    ],\n    deps = [\n        \"//tensorflow_models/object_detection/core:box_coder\",\n        \"//tensorflow_models/object_detection/core:box_list\",\n        \"//tensorflow_models/object_detection/core:standard_fields\",\n    ],\n)\n\npy_test(\n    name = \"keypoint_box_coder_test\",\n    srcs = [\n        \"keypoint_box_coder_test.py\",\n    ],\n    deps = [\n        \":keypoint_box_coder\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:box_list\",\n        \"//tensorflow_models/object_detection/core:standard_fields\",\n    ],\n)\n\npy_library(\n    name = \"mean_stddev_box_coder\",\n    srcs = [\n        \"mean_stddev_box_coder.py\",\n    ],\n    deps = [\n        \"//tensorflow_models/object_detection/core:box_coder\",\n        \"//tensorflow_models/object_detection/core:box_list\",\n    ],\n)\n\npy_test(\n    name = \"mean_stddev_box_coder_test\",\n    srcs = [\n        \"mean_stddev_box_coder_test.py\",\n    ],\n    deps = [\n        \":mean_stddev_box_coder\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:box_list\",\n    ],\n)\n\npy_library(\n    name = \"square_box_coder\",\n    srcs = [\n        \"square_box_coder.py\",\n    ],\n    deps = [\n        \"//tensorflow_models/object_detection/core:box_coder\",\n        \"//tensorflow_models/object_detection/core:box_list\",\n    ],\n)\n\npy_test(\n    name = \"square_box_coder_test\",\n    srcs = [\n        \"square_box_coder_test.py\",\n    ],\n    deps = [\n        \":square_box_coder\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:box_list\",\n    ],\n)\n"
  },
  {
    "path": "object_detector_app/object_detection/box_coders/__init__.py",
    "content": ""
  },
  {
    "path": "object_detector_app/object_detection/box_coders/faster_rcnn_box_coder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Faster RCNN box coder.\n\nFaster RCNN box coder follows the coding schema described below:\n  ty = (y - ya) / ha\n  tx = (x - xa) / wa\n  th = log(h / ha)\n  tw = log(w / wa)\n  where x, y, w, h denote the box's center coordinates, width and height\n  respectively. Similarly, xa, ya, wa, ha denote the anchor's center\n  coordinates, width and height. tx, ty, tw and th denote the anchor-encoded\n  center, width and height respectively.\n\n  See http://arxiv.org/abs/1506.01497 for details.\n\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.core import box_coder\nfrom object_detection.core import box_list\n\nEPSILON = 1e-8\n\n\nclass FasterRcnnBoxCoder(box_coder.BoxCoder):\n  \"\"\"Faster RCNN box coder.\"\"\"\n\n  def __init__(self, scale_factors=None):\n    \"\"\"Constructor for FasterRcnnBoxCoder.\n\n    Args:\n      scale_factors: List of 4 positive scalars to scale ty, tx, th and tw.\n        If set to None, does not perform scaling. For Faster RCNN,\n        the open-source implementation recommends using [10.0, 10.0, 5.0, 5.0].\n    \"\"\"\n    if scale_factors:\n      assert len(scale_factors) == 4\n      for scalar in scale_factors:\n        assert scalar > 0\n    self._scale_factors = scale_factors\n\n  @property\n  def code_size(self):\n    return 4\n\n  def _encode(self, boxes, anchors):\n    \"\"\"Encode a box collection with respect to anchor collection.\n\n    Args:\n      boxes: BoxList holding N boxes to be encoded.\n      anchors: BoxList of anchors.\n\n    Returns:\n      a tensor representing N anchor-encoded boxes of the format\n      [ty, tx, th, tw].\n    \"\"\"\n    # Convert anchors to the center coordinate representation.\n    ycenter_a, xcenter_a, ha, wa = anchors.get_center_coordinates_and_sizes()\n    ycenter, xcenter, h, w = boxes.get_center_coordinates_and_sizes()\n    # Avoid NaN in division and log below.\n    ha += EPSILON\n    wa += EPSILON\n    h += EPSILON\n    w += EPSILON\n\n    tx = (xcenter - xcenter_a) / wa\n    ty = (ycenter - ycenter_a) / ha\n    tw = tf.log(w / wa)\n    th = tf.log(h / ha)\n    # Scales location targets as used in paper for joint training.\n    if self._scale_factors:\n      ty *= self._scale_factors[0]\n      tx *= self._scale_factors[1]\n      th *= self._scale_factors[2]\n      tw *= self._scale_factors[3]\n    return tf.transpose(tf.stack([ty, tx, th, tw]))\n\n  def _decode(self, rel_codes, anchors):\n    \"\"\"Decode relative codes to boxes.\n\n    Args:\n      rel_codes: a tensor representing N anchor-encoded boxes.\n      anchors: BoxList of anchors.\n\n    Returns:\n      boxes: BoxList holding N bounding boxes.\n    \"\"\"\n    ycenter_a, xcenter_a, ha, wa = anchors.get_center_coordinates_and_sizes()\n\n    ty, tx, th, tw = tf.unstack(tf.transpose(rel_codes))\n    if self._scale_factors:\n      ty /= self._scale_factors[0]\n      tx /= self._scale_factors[1]\n      th /= self._scale_factors[2]\n      tw /= self._scale_factors[3]\n    w = tf.exp(tw) * wa\n    h = tf.exp(th) * ha\n    ycenter = ty * ha + ycenter_a\n    xcenter = tx * wa + xcenter_a\n    ymin = ycenter - h / 2.\n    xmin = xcenter - w / 2.\n    ymax = ycenter + h / 2.\n    xmax = xcenter + w / 2.\n    return box_list.BoxList(tf.transpose(tf.stack([ymin, xmin, ymax, xmax])))\n"
  },
  {
    "path": "object_detector_app/object_detection/box_coders/faster_rcnn_box_coder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.box_coder.faster_rcnn_box_coder.\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.box_coders import faster_rcnn_box_coder\nfrom object_detection.core import box_list\n\n\nclass FasterRcnnBoxCoderTest(tf.test.TestCase):\n\n  def test_get_correct_relative_codes_after_encoding(self):\n    boxes = [[10.0, 10.0, 20.0, 15.0], [0.2, 0.1, 0.5, 0.4]]\n    anchors = [[15.0, 12.0, 30.0, 18.0], [0.1, 0.0, 0.7, 0.9]]\n    expected_rel_codes = [[-0.5, -0.416666, -0.405465, -0.182321],\n                          [-0.083333, -0.222222, -0.693147, -1.098612]]\n    boxes = box_list.BoxList(tf.constant(boxes))\n    anchors = box_list.BoxList(tf.constant(anchors))\n    coder = faster_rcnn_box_coder.FasterRcnnBoxCoder()\n    rel_codes = coder.encode(boxes, anchors)\n    with self.test_session() as sess:\n      rel_codes_out, = sess.run([rel_codes])\n      self.assertAllClose(rel_codes_out, expected_rel_codes)\n\n  def test_get_correct_relative_codes_after_encoding_with_scaling(self):\n    boxes = [[10.0, 10.0, 20.0, 15.0], [0.2, 0.1, 0.5, 0.4]]\n    anchors = [[15.0, 12.0, 30.0, 18.0], [0.1, 0.0, 0.7, 0.9]]\n    scale_factors = [2, 3, 4, 5]\n    expected_rel_codes = [[-1., -1.25, -1.62186, -0.911608],\n                          [-0.166667, -0.666667, -2.772588, -5.493062]]\n    boxes = box_list.BoxList(tf.constant(boxes))\n    anchors = box_list.BoxList(tf.constant(anchors))\n    coder = faster_rcnn_box_coder.FasterRcnnBoxCoder(\n        scale_factors=scale_factors)\n    rel_codes = coder.encode(boxes, anchors)\n    with self.test_session() as sess:\n      rel_codes_out, = sess.run([rel_codes])\n      self.assertAllClose(rel_codes_out, expected_rel_codes)\n\n  def test_get_correct_boxes_after_decoding(self):\n    anchors = [[15.0, 12.0, 30.0, 18.0], [0.1, 0.0, 0.7, 0.9]]\n    rel_codes = [[-0.5, -0.416666, -0.405465, -0.182321],\n                 [-0.083333, -0.222222, -0.693147, -1.098612]]\n    expected_boxes = [[10.0, 10.0, 20.0, 15.0], [0.2, 0.1, 0.5, 0.4]]\n    anchors = box_list.BoxList(tf.constant(anchors))\n    coder = faster_rcnn_box_coder.FasterRcnnBoxCoder()\n    boxes = coder.decode(rel_codes, anchors)\n    with self.test_session() as sess:\n      boxes_out, = sess.run([boxes.get()])\n      self.assertAllClose(boxes_out, expected_boxes)\n\n  def test_get_correct_boxes_after_decoding_with_scaling(self):\n    anchors = [[15.0, 12.0, 30.0, 18.0], [0.1, 0.0, 0.7, 0.9]]\n    rel_codes = [[-1., -1.25, -1.62186, -0.911608],\n                 [-0.166667, -0.666667, -2.772588, -5.493062]]\n    scale_factors = [2, 3, 4, 5]\n    expected_boxes = [[10.0, 10.0, 20.0, 15.0], [0.2, 0.1, 0.5, 0.4]]\n    anchors = box_list.BoxList(tf.constant(anchors))\n    coder = faster_rcnn_box_coder.FasterRcnnBoxCoder(\n        scale_factors=scale_factors)\n    boxes = coder.decode(rel_codes, anchors)\n    with self.test_session() as sess:\n      boxes_out, = sess.run([boxes.get()])\n      self.assertAllClose(boxes_out, expected_boxes)\n\n  def test_very_small_Width_nan_after_encoding(self):\n    boxes = [[10.0, 10.0, 10.0000001, 20.0]]\n    anchors = [[15.0, 12.0, 30.0, 18.0]]\n    expected_rel_codes = [[-0.833333, 0., -21.128731, 0.510826]]\n    boxes = box_list.BoxList(tf.constant(boxes))\n    anchors = box_list.BoxList(tf.constant(anchors))\n    coder = faster_rcnn_box_coder.FasterRcnnBoxCoder()\n    rel_codes = coder.encode(boxes, anchors)\n    with self.test_session() as sess:\n      rel_codes_out, = sess.run([rel_codes])\n      self.assertAllClose(rel_codes_out, expected_rel_codes)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/box_coders/keypoint_box_coder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Keypoint box coder.\n\nThe keypoint box coder follows the coding schema described below (this is\nsimilar to the FasterRcnnBoxCoder, except that it encodes keypoints in addition\nto box coordinates):\n  ty = (y - ya) / ha\n  tx = (x - xa) / wa\n  th = log(h / ha)\n  tw = log(w / wa)\n  tky0 = (ky0 - ya) / ha\n  tkx0 = (kx0 - xa) / ha\n  tky1 = (ky1 - ya) / ha\n  tkx1 = (kx1 - xa) / ha\n  ...\n  where x, y, w, h denote the box's center coordinates, width and height\n  respectively. Similarly, xa, ya, wa, ha denote the anchor's center\n  coordinates, width and height. tx, ty, tw and th denote the anchor-encoded\n  center, width and height respectively. ky0, kx0, ky1, kx1, ... denote the\n  keypoints' coordinates, and tky0, tkx0, tky1, tkx1, ... denote the\n  anchor-encoded keypoint coordinates.\n\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.core import box_coder\nfrom object_detection.core import box_list\nfrom object_detection.core import standard_fields as fields\n\nEPSILON = 1e-8\n\n\nclass KeypointBoxCoder(box_coder.BoxCoder):\n  \"\"\"Keypoint box coder.\"\"\"\n\n  def __init__(self, num_keypoints, scale_factors=None):\n    \"\"\"Constructor for KeypointBoxCoder.\n\n    Args:\n      num_keypoints: Number of keypoints to encode/decode.\n      scale_factors: List of 4 positive scalars to scale ty, tx, th and tw.\n        In addition to scaling ty and tx, the first 2 scalars are used to scale\n        the y and x coordinates of the keypoints as well. If set to None, does\n        not perform scaling.\n    \"\"\"\n    self._num_keypoints = num_keypoints\n\n    if scale_factors:\n      assert len(scale_factors) == 4\n      for scalar in scale_factors:\n        assert scalar > 0\n    self._scale_factors = scale_factors\n    self._keypoint_scale_factors = None\n    if scale_factors is not None:\n      self._keypoint_scale_factors = tf.expand_dims(tf.tile(\n          [tf.to_float(scale_factors[0]), tf.to_float(scale_factors[1])],\n          [num_keypoints]), 1)\n\n  @property\n  def code_size(self):\n    return 4 + self._num_keypoints * 2\n\n  def _encode(self, boxes, anchors):\n    \"\"\"Encode a box and keypoint collection with respect to anchor collection.\n\n    Args:\n      boxes: BoxList holding N boxes and keypoints to be encoded. Boxes are\n        tensors with the shape [N, 4], and keypoints are tensors with the shape\n        [N, num_keypoints, 2].\n      anchors: BoxList of anchors.\n\n    Returns:\n      a tensor representing N anchor-encoded boxes of the format\n      [ty, tx, th, tw, tky0, tkx0, tky1, tkx1, ...] where tky0 and tkx0\n      represent the y and x coordinates of the first keypoint, tky1 and tkx1\n      represent the y and x coordinates of the second keypoint, and so on.\n    \"\"\"\n    # Convert anchors to the center coordinate representation.\n    ycenter_a, xcenter_a, ha, wa = anchors.get_center_coordinates_and_sizes()\n    ycenter, xcenter, h, w = boxes.get_center_coordinates_and_sizes()\n    keypoints = boxes.get_field(fields.BoxListFields.keypoints)\n    keypoints = tf.transpose(tf.reshape(keypoints,\n                                        [-1, self._num_keypoints * 2]))\n    num_boxes = boxes.num_boxes()\n\n    # Avoid NaN in division and log below.\n    ha += EPSILON\n    wa += EPSILON\n    h += EPSILON\n    w += EPSILON\n\n    tx = (xcenter - xcenter_a) / wa\n    ty = (ycenter - ycenter_a) / ha\n    tw = tf.log(w / wa)\n    th = tf.log(h / ha)\n\n    tiled_anchor_centers = tf.tile(\n        tf.stack([ycenter_a, xcenter_a]), [self._num_keypoints, 1])\n    tiled_anchor_sizes = tf.tile(\n        tf.stack([ha, wa]), [self._num_keypoints, 1])\n    tkeypoints = (keypoints - tiled_anchor_centers) / tiled_anchor_sizes\n\n    # Scales location targets as used in paper for joint training.\n    if self._scale_factors:\n      ty *= self._scale_factors[0]\n      tx *= self._scale_factors[1]\n      th *= self._scale_factors[2]\n      tw *= self._scale_factors[3]\n      tkeypoints *= tf.tile(self._keypoint_scale_factors, [1, num_boxes])\n\n    tboxes = tf.stack([ty, tx, th, tw])\n    return tf.transpose(tf.concat([tboxes, tkeypoints], 0))\n\n  def _decode(self, rel_codes, anchors):\n    \"\"\"Decode relative codes to boxes and keypoints.\n\n    Args:\n      rel_codes: a tensor with shape [N, 4 + 2 * num_keypoints] representing N\n        anchor-encoded boxes and keypoints\n      anchors: BoxList of anchors.\n\n    Returns:\n      boxes: BoxList holding N bounding boxes and keypoints.\n    \"\"\"\n    ycenter_a, xcenter_a, ha, wa = anchors.get_center_coordinates_and_sizes()\n\n    num_codes = tf.shape(rel_codes)[0]\n    result = tf.unstack(tf.transpose(rel_codes))\n    ty, tx, th, tw = result[:4]\n    tkeypoints = result[4:]\n    if self._scale_factors:\n      ty /= self._scale_factors[0]\n      tx /= self._scale_factors[1]\n      th /= self._scale_factors[2]\n      tw /= self._scale_factors[3]\n      tkeypoints /= tf.tile(self._keypoint_scale_factors, [1, num_codes])\n\n    w = tf.exp(tw) * wa\n    h = tf.exp(th) * ha\n    ycenter = ty * ha + ycenter_a\n    xcenter = tx * wa + xcenter_a\n    ymin = ycenter - h / 2.\n    xmin = xcenter - w / 2.\n    ymax = ycenter + h / 2.\n    xmax = xcenter + w / 2.\n    decoded_boxes_keypoints = box_list.BoxList(\n        tf.transpose(tf.stack([ymin, xmin, ymax, xmax])))\n\n    tiled_anchor_centers = tf.tile(\n        tf.stack([ycenter_a, xcenter_a]), [self._num_keypoints, 1])\n    tiled_anchor_sizes = tf.tile(\n        tf.stack([ha, wa]), [self._num_keypoints, 1])\n    keypoints = tkeypoints * tiled_anchor_sizes + tiled_anchor_centers\n    keypoints = tf.reshape(tf.transpose(keypoints),\n                           [-1, self._num_keypoints, 2])\n    decoded_boxes_keypoints.add_field(fields.BoxListFields.keypoints, keypoints)\n    return decoded_boxes_keypoints\n"
  },
  {
    "path": "object_detector_app/object_detection/box_coders/keypoint_box_coder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.box_coder.keypoint_box_coder.\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.box_coders import keypoint_box_coder\nfrom object_detection.core import box_list\nfrom object_detection.core import standard_fields as fields\n\n\nclass KeypointBoxCoderTest(tf.test.TestCase):\n\n  def test_get_correct_relative_codes_after_encoding(self):\n    boxes = [[10., 10., 20., 15.],\n             [0.2, 0.1, 0.5, 0.4]]\n    keypoints = [[[15., 12.], [10., 15.]],\n                 [[0.5, 0.3], [0.2, 0.4]]]\n    num_keypoints = len(keypoints[0])\n    anchors = [[15., 12., 30., 18.],\n               [0.1, 0.0, 0.7, 0.9]]\n    expected_rel_codes = [\n        [-0.5, -0.416666, -0.405465, -0.182321,\n         -0.5, -0.5, -0.833333, 0.],\n        [-0.083333, -0.222222, -0.693147, -1.098612,\n         0.166667, -0.166667, -0.333333, -0.055556]\n    ]\n    boxes = box_list.BoxList(tf.constant(boxes))\n    boxes.add_field(fields.BoxListFields.keypoints, tf.constant(keypoints))\n    anchors = box_list.BoxList(tf.constant(anchors))\n    coder = keypoint_box_coder.KeypointBoxCoder(num_keypoints)\n    rel_codes = coder.encode(boxes, anchors)\n    with self.test_session() as sess:\n      rel_codes_out, = sess.run([rel_codes])\n      self.assertAllClose(rel_codes_out, expected_rel_codes)\n\n  def test_get_correct_relative_codes_after_encoding_with_scaling(self):\n    boxes = [[10., 10., 20., 15.],\n             [0.2, 0.1, 0.5, 0.4]]\n    keypoints = [[[15., 12.], [10., 15.]],\n                 [[0.5, 0.3], [0.2, 0.4]]]\n    num_keypoints = len(keypoints[0])\n    anchors = [[15., 12., 30., 18.],\n               [0.1, 0.0, 0.7, 0.9]]\n    scale_factors = [2, 3, 4, 5]\n    expected_rel_codes = [\n        [-1., -1.25, -1.62186, -0.911608,\n         -1.0, -1.5, -1.666667, 0.],\n        [-0.166667, -0.666667, -2.772588, -5.493062,\n         0.333333, -0.5, -0.666667, -0.166667]\n    ]\n    boxes = box_list.BoxList(tf.constant(boxes))\n    boxes.add_field(fields.BoxListFields.keypoints, tf.constant(keypoints))\n    anchors = box_list.BoxList(tf.constant(anchors))\n    coder = keypoint_box_coder.KeypointBoxCoder(\n        num_keypoints, scale_factors=scale_factors)\n    rel_codes = coder.encode(boxes, anchors)\n    with self.test_session() as sess:\n      rel_codes_out, = sess.run([rel_codes])\n      self.assertAllClose(rel_codes_out, expected_rel_codes)\n\n  def test_get_correct_boxes_after_decoding(self):\n    anchors = [[15., 12., 30., 18.],\n               [0.1, 0.0, 0.7, 0.9]]\n    rel_codes = [\n        [-0.5, -0.416666, -0.405465, -0.182321,\n         -0.5, -0.5, -0.833333, 0.],\n        [-0.083333, -0.222222, -0.693147, -1.098612,\n         0.166667, -0.166667, -0.333333, -0.055556]\n    ]\n    expected_boxes = [[10., 10., 20., 15.],\n                      [0.2, 0.1, 0.5, 0.4]]\n    expected_keypoints = [[[15., 12.], [10., 15.]],\n                          [[0.5, 0.3], [0.2, 0.4]]]\n    num_keypoints = len(expected_keypoints[0])\n    anchors = box_list.BoxList(tf.constant(anchors))\n    coder = keypoint_box_coder.KeypointBoxCoder(num_keypoints)\n    boxes = coder.decode(rel_codes, anchors)\n    with self.test_session() as sess:\n      boxes_out, keypoints_out = sess.run(\n          [boxes.get(), boxes.get_field(fields.BoxListFields.keypoints)])\n      self.assertAllClose(boxes_out, expected_boxes)\n      self.assertAllClose(keypoints_out, expected_keypoints)\n\n  def test_get_correct_boxes_after_decoding_with_scaling(self):\n    anchors = [[15., 12., 30., 18.],\n               [0.1, 0.0, 0.7, 0.9]]\n    rel_codes = [\n        [-1., -1.25, -1.62186, -0.911608,\n         -1.0, -1.5, -1.666667, 0.],\n        [-0.166667, -0.666667, -2.772588, -5.493062,\n         0.333333, -0.5, -0.666667, -0.166667]\n    ]\n    scale_factors = [2, 3, 4, 5]\n    expected_boxes = [[10., 10., 20., 15.],\n                      [0.2, 0.1, 0.5, 0.4]]\n    expected_keypoints = [[[15., 12.], [10., 15.]],\n                          [[0.5, 0.3], [0.2, 0.4]]]\n    num_keypoints = len(expected_keypoints[0])\n    anchors = box_list.BoxList(tf.constant(anchors))\n    coder = keypoint_box_coder.KeypointBoxCoder(\n        num_keypoints, scale_factors=scale_factors)\n    boxes = coder.decode(rel_codes, anchors)\n    with self.test_session() as sess:\n      boxes_out, keypoints_out = sess.run(\n          [boxes.get(), boxes.get_field(fields.BoxListFields.keypoints)])\n      self.assertAllClose(boxes_out, expected_boxes)\n      self.assertAllClose(keypoints_out, expected_keypoints)\n\n  def test_very_small_width_nan_after_encoding(self):\n    boxes = [[10., 10., 10.0000001, 20.]]\n    keypoints = [[[10., 10.], [10.0000001, 20.]]]\n    anchors = [[15., 12., 30., 18.]]\n    expected_rel_codes = [[-0.833333, 0., -21.128731, 0.510826,\n                           -0.833333, -0.833333, -0.833333, 0.833333]]\n    boxes = box_list.BoxList(tf.constant(boxes))\n    boxes.add_field(fields.BoxListFields.keypoints, tf.constant(keypoints))\n    anchors = box_list.BoxList(tf.constant(anchors))\n    coder = keypoint_box_coder.KeypointBoxCoder(2)\n    rel_codes = coder.encode(boxes, anchors)\n    with self.test_session() as sess:\n      rel_codes_out, = sess.run([rel_codes])\n      self.assertAllClose(rel_codes_out, expected_rel_codes)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/box_coders/mean_stddev_box_coder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Mean stddev box coder.\n\nThis box coder use the following coding schema to encode boxes:\nrel_code = (box_corner - anchor_corner_mean) / anchor_corner_stddev.\n\"\"\"\nfrom object_detection.core import box_coder\nfrom object_detection.core import box_list\n\n\nclass MeanStddevBoxCoder(box_coder.BoxCoder):\n  \"\"\"Mean stddev box coder.\"\"\"\n\n  @property\n  def code_size(self):\n    return 4\n\n  def _encode(self, boxes, anchors):\n    \"\"\"Encode a box collection with respect to anchor collection.\n\n    Args:\n      boxes: BoxList holding N boxes to be encoded.\n      anchors: BoxList of N anchors.  We assume that anchors has an associated\n        stddev field.\n\n    Returns:\n      a tensor representing N anchor-encoded boxes\n    Raises:\n      ValueError: if the anchors BoxList does not have a stddev field\n    \"\"\"\n    if not anchors.has_field('stddev'):\n      raise ValueError('anchors must have a stddev field')\n    box_corners = boxes.get()\n    means = anchors.get()\n    stddev = anchors.get_field('stddev')\n    return (box_corners - means) / stddev\n\n  def _decode(self, rel_codes, anchors):\n    \"\"\"Decode.\n\n    Args:\n      rel_codes: a tensor representing N anchor-encoded boxes.\n      anchors: BoxList of anchors.  We assume that anchors has an associated\n        stddev field.\n\n    Returns:\n      boxes: BoxList holding N bounding boxes\n    Raises:\n      ValueError: if the anchors BoxList does not have a stddev field\n    \"\"\"\n    if not anchors.has_field('stddev'):\n      raise ValueError('anchors must have a stddev field')\n    means = anchors.get()\n    stddevs = anchors.get_field('stddev')\n    box_corners = rel_codes * stddevs + means\n    return box_list.BoxList(box_corners)\n"
  },
  {
    "path": "object_detector_app/object_detection/box_coders/mean_stddev_box_coder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.box_coder.mean_stddev_boxcoder.\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.box_coders import mean_stddev_box_coder\nfrom object_detection.core import box_list\n\n\nclass MeanStddevBoxCoderTest(tf.test.TestCase):\n\n  def testGetCorrectRelativeCodesAfterEncoding(self):\n    box_corners = [[0.0, 0.0, 0.5, 0.5], [0.0, 0.0, 0.5, 0.5]]\n    boxes = box_list.BoxList(tf.constant(box_corners))\n    expected_rel_codes = [[0.0, 0.0, 0.0, 0.0], [-5.0, -5.0, -5.0, -3.0]]\n    prior_means = tf.constant([[0.0, 0.0, 0.5, 0.5], [0.5, 0.5, 1.0, 0.8]])\n    prior_stddevs = tf.constant(2 * [4 * [.1]])\n    priors = box_list.BoxList(prior_means)\n    priors.add_field('stddev', prior_stddevs)\n\n    coder = mean_stddev_box_coder.MeanStddevBoxCoder()\n    rel_codes = coder.encode(boxes, priors)\n    with self.test_session() as sess:\n      rel_codes_out = sess.run(rel_codes)\n      self.assertAllClose(rel_codes_out, expected_rel_codes)\n\n  def testGetCorrectBoxesAfterDecoding(self):\n    rel_codes = tf.constant([[0.0, 0.0, 0.0, 0.0], [-5.0, -5.0, -5.0, -3.0]])\n    expected_box_corners = [[0.0, 0.0, 0.5, 0.5], [0.0, 0.0, 0.5, 0.5]]\n    prior_means = tf.constant([[0.0, 0.0, 0.5, 0.5], [0.5, 0.5, 1.0, 0.8]])\n    prior_stddevs = tf.constant(2 * [4 * [.1]])\n    priors = box_list.BoxList(prior_means)\n    priors.add_field('stddev', prior_stddevs)\n\n    coder = mean_stddev_box_coder.MeanStddevBoxCoder()\n    decoded_boxes = coder.decode(rel_codes, priors)\n    decoded_box_corners = decoded_boxes.get()\n    with self.test_session() as sess:\n      decoded_out = sess.run(decoded_box_corners)\n      self.assertAllClose(decoded_out, expected_box_corners)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/box_coders/square_box_coder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Square box coder.\n\nSquare box coder follows the coding schema described below:\nl = sqrt(h * w)\nla = sqrt(ha * wa)\nty = (y - ya) / la\ntx = (x - xa) / la\ntl = log(l / la)\nwhere x, y, w, h denote the box's center coordinates, width, and height,\nrespectively. Similarly, xa, ya, wa, ha denote the anchor's center\ncoordinates, width and height. tx, ty, tl denote the anchor-encoded\ncenter, and length, respectively. Because the encoded box is a square, only\none length is encoded.\n\nThis has shown to provide performance improvements over the Faster RCNN box\ncoder when the objects being detected tend to be square (e.g. faces) and when\nthe input images are not distorted via resizing.\n\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.core import box_coder\nfrom object_detection.core import box_list\n\nEPSILON = 1e-8\n\n\nclass SquareBoxCoder(box_coder.BoxCoder):\n  \"\"\"Encodes a 3-scalar representation of a square box.\"\"\"\n\n  def __init__(self, scale_factors=None):\n    \"\"\"Constructor for SquareBoxCoder.\n\n    Args:\n      scale_factors: List of 3 positive scalars to scale ty, tx, and tl.\n        If set to None, does not perform scaling. For faster RCNN,\n        the open-source implementation recommends using [10.0, 10.0, 5.0].\n\n    Raises:\n      ValueError: If scale_factors is not length 3 or contains values less than\n        or equal to 0.\n    \"\"\"\n    if scale_factors:\n      if len(scale_factors) != 3:\n        raise ValueError('The argument scale_factors must be a list of length '\n                         '3.')\n      if any(scalar <= 0 for scalar in scale_factors):\n        raise ValueError('The values in scale_factors must all be greater '\n                         'than 0.')\n    self._scale_factors = scale_factors\n\n  @property\n  def code_size(self):\n    return 3\n\n  def _encode(self, boxes, anchors):\n    \"\"\"Encodes a box collection with respect to an anchor collection.\n\n    Args:\n      boxes: BoxList holding N boxes to be encoded.\n      anchors: BoxList of anchors.\n\n    Returns:\n      a tensor representing N anchor-encoded boxes of the format\n      [ty, tx, tl].\n    \"\"\"\n    # Convert anchors to the center coordinate representation.\n    ycenter_a, xcenter_a, ha, wa = anchors.get_center_coordinates_and_sizes()\n    la = tf.sqrt(ha * wa)\n    ycenter, xcenter, h, w = boxes.get_center_coordinates_and_sizes()\n    l = tf.sqrt(h * w)\n    # Avoid NaN in division and log below.\n    la += EPSILON\n    l += EPSILON\n\n    tx = (xcenter - xcenter_a) / la\n    ty = (ycenter - ycenter_a) / la\n    tl = tf.log(l / la)\n    # Scales location targets for joint training.\n    if self._scale_factors:\n      ty *= self._scale_factors[0]\n      tx *= self._scale_factors[1]\n      tl *= self._scale_factors[2]\n    return tf.transpose(tf.stack([ty, tx, tl]))\n\n  def _decode(self, rel_codes, anchors):\n    \"\"\"Decodes relative codes to boxes.\n\n    Args:\n      rel_codes: a tensor representing N anchor-encoded boxes.\n      anchors: BoxList of anchors.\n\n    Returns:\n      boxes: BoxList holding N bounding boxes.\n    \"\"\"\n    ycenter_a, xcenter_a, ha, wa = anchors.get_center_coordinates_and_sizes()\n    la = tf.sqrt(ha * wa)\n\n    ty, tx, tl = tf.unstack(tf.transpose(rel_codes))\n    if self._scale_factors:\n      ty /= self._scale_factors[0]\n      tx /= self._scale_factors[1]\n      tl /= self._scale_factors[2]\n    l = tf.exp(tl) * la\n    ycenter = ty * la + ycenter_a\n    xcenter = tx * la + xcenter_a\n    ymin = ycenter - l / 2.\n    xmin = xcenter - l / 2.\n    ymax = ycenter + l / 2.\n    xmax = xcenter + l / 2.\n    return box_list.BoxList(tf.transpose(tf.stack([ymin, xmin, ymax, xmax])))\n"
  },
  {
    "path": "object_detector_app/object_detection/box_coders/square_box_coder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.box_coder.square_box_coder.\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.box_coders import square_box_coder\nfrom object_detection.core import box_list\n\n\nclass SquareBoxCoderTest(tf.test.TestCase):\n\n  def test_correct_relative_codes_with_default_scale(self):\n    boxes = [[10.0, 10.0, 20.0, 15.0], [0.2, 0.1, 0.5, 0.4]]\n    anchors = [[15.0, 12.0, 30.0, 18.0], [0.1, 0.0, 0.7, 0.9]]\n    scale_factors = None\n    expected_rel_codes = [[-0.790569, -0.263523, -0.293893],\n                          [-0.068041, -0.272166, -0.89588]]\n\n    boxes = box_list.BoxList(tf.constant(boxes))\n    anchors = box_list.BoxList(tf.constant(anchors))\n    coder = square_box_coder.SquareBoxCoder(scale_factors=scale_factors)\n    rel_codes = coder.encode(boxes, anchors)\n    with self.test_session() as sess:\n      (rel_codes_out,) = sess.run([rel_codes])\n      self.assertAllClose(rel_codes_out, expected_rel_codes)\n\n  def test_correct_relative_codes_with_non_default_scale(self):\n    boxes = [[10.0, 10.0, 20.0, 15.0], [0.2, 0.1, 0.5, 0.4]]\n    anchors = [[15.0, 12.0, 30.0, 18.0], [0.1, 0.0, 0.7, 0.9]]\n    scale_factors = [2, 3, 4]\n    expected_rel_codes = [[-1.581139, -0.790569, -1.175573],\n                          [-0.136083, -0.816497, -3.583519]]\n    boxes = box_list.BoxList(tf.constant(boxes))\n    anchors = box_list.BoxList(tf.constant(anchors))\n    coder = square_box_coder.SquareBoxCoder(scale_factors=scale_factors)\n    rel_codes = coder.encode(boxes, anchors)\n    with self.test_session() as sess:\n      (rel_codes_out,) = sess.run([rel_codes])\n      self.assertAllClose(rel_codes_out, expected_rel_codes)\n\n  def test_correct_relative_codes_with_small_width(self):\n    boxes = [[10.0, 10.0, 10.0000001, 20.0]]\n    anchors = [[15.0, 12.0, 30.0, 18.0]]\n    scale_factors = None\n    expected_rel_codes = [[-1.317616, 0., -20.670586]]\n    boxes = box_list.BoxList(tf.constant(boxes))\n    anchors = box_list.BoxList(tf.constant(anchors))\n    coder = square_box_coder.SquareBoxCoder(scale_factors=scale_factors)\n    rel_codes = coder.encode(boxes, anchors)\n    with self.test_session() as sess:\n      (rel_codes_out,) = sess.run([rel_codes])\n      self.assertAllClose(rel_codes_out, expected_rel_codes)\n\n  def test_correct_boxes_with_default_scale(self):\n    anchors = [[15.0, 12.0, 30.0, 18.0], [0.1, 0.0, 0.7, 0.9]]\n    rel_codes = [[-0.5, -0.416666, -0.405465],\n                 [-0.083333, -0.222222, -0.693147]]\n    scale_factors = None\n    expected_boxes = [[14.594306, 7.884875, 20.918861, 14.209432],\n                      [0.155051, 0.102989, 0.522474, 0.470412]]\n    anchors = box_list.BoxList(tf.constant(anchors))\n    coder = square_box_coder.SquareBoxCoder(scale_factors=scale_factors)\n    boxes = coder.decode(rel_codes, anchors)\n    with self.test_session() as sess:\n      (boxes_out,) = sess.run([boxes.get()])\n      self.assertAllClose(boxes_out, expected_boxes)\n\n  def test_correct_boxes_with_non_default_scale(self):\n    anchors = [[15.0, 12.0, 30.0, 18.0], [0.1, 0.0, 0.7, 0.9]]\n    rel_codes = [[-1., -1.25, -1.62186], [-0.166667, -0.666667, -2.772588]]\n    scale_factors = [2, 3, 4]\n    expected_boxes = [[14.594306, 7.884875, 20.918861, 14.209432],\n                      [0.155051, 0.102989, 0.522474, 0.470412]]\n    anchors = box_list.BoxList(tf.constant(anchors))\n    coder = square_box_coder.SquareBoxCoder(scale_factors=scale_factors)\n    boxes = coder.decode(rel_codes, anchors)\n    with self.test_session() as sess:\n      (boxes_out,) = sess.run([boxes.get()])\n      self.assertAllClose(boxes_out, expected_boxes)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/BUILD",
    "content": "# Tensorflow Object Detection API: component builders.\n\npackage(\n    default_visibility = [\"//visibility:public\"],\n)\n\nlicenses([\"notice\"])\n\n# Apache 2.0\npy_library(\n    name = \"model_builder\",\n    srcs = [\"model_builder.py\"],\n    deps = [\n        \":anchor_generator_builder\",\n        \":box_coder_builder\",\n        \":box_predictor_builder\",\n        \":hyperparams_builder\",\n        \":image_resizer_builder\",\n        \":losses_builder\",\n        \":matcher_builder\",\n        \":post_processing_builder\",\n        \":region_similarity_calculator_builder\",\n        \"//tensorflow_models/object_detection/core:box_predictor\",\n        \"//tensorflow_models/object_detection/meta_architectures:faster_rcnn_meta_arch\",\n        \"//tensorflow_models/object_detection/meta_architectures:rfcn_meta_arch\",\n        \"//tensorflow_models/object_detection/meta_architectures:ssd_meta_arch\",\n        \"//tensorflow_models/object_detection/models:faster_rcnn_inception_resnet_v2_feature_extractor\",\n        \"//tensorflow_models/object_detection/models:faster_rcnn_resnet_v1_feature_extractor\",\n        \"//tensorflow_models/object_detection/models:ssd_inception_v2_feature_extractor\",\n        \"//tensorflow_models/object_detection/models:ssd_mobilenet_v1_feature_extractor\",\n        \"//tensorflow_models/object_detection/protos:model_py_pb2\",\n    ],\n)\n\npy_test(\n    name = \"model_builder_test\",\n    srcs = [\"model_builder_test.py\"],\n    deps = [\n        \":model_builder\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/meta_architectures:faster_rcnn_meta_arch\",\n        \"//tensorflow_models/object_detection/meta_architectures:ssd_meta_arch\",\n        \"//tensorflow_models/object_detection/models:ssd_inception_v2_feature_extractor\",\n        \"//tensorflow_models/object_detection/models:ssd_mobilenet_v1_feature_extractor\",\n        \"//tensorflow_models/object_detection/protos:model_py_pb2\",\n    ],\n)\n\npy_library(\n    name = \"matcher_builder\",\n    srcs = [\"matcher_builder.py\"],\n    deps = [\n        \"//tensorflow_models/object_detection/matchers:argmax_matcher\",\n        \"//tensorflow_models/object_detection/matchers:bipartite_matcher\",\n        \"//tensorflow_models/object_detection/protos:matcher_py_pb2\",\n    ],\n)\n\npy_test(\n    name = \"matcher_builder_test\",\n    srcs = [\"matcher_builder_test.py\"],\n    deps = [\n        \":matcher_builder\",\n        \"//tensorflow_models/object_detection/matchers:argmax_matcher\",\n        \"//tensorflow_models/object_detection/matchers:bipartite_matcher\",\n        \"//tensorflow_models/object_detection/protos:matcher_py_pb2\",\n    ],\n)\n\npy_library(\n    name = \"box_coder_builder\",\n    srcs = [\"box_coder_builder.py\"],\n    deps = [\n        \"//tensorflow_models/object_detection/box_coders:faster_rcnn_box_coder\",\n        \"//tensorflow_models/object_detection/box_coders:mean_stddev_box_coder\",\n        \"//tensorflow_models/object_detection/box_coders:square_box_coder\",\n        \"//tensorflow_models/object_detection/protos:box_coder_py_pb2\",\n    ],\n)\n\npy_test(\n    name = \"box_coder_builder_test\",\n    srcs = [\"box_coder_builder_test.py\"],\n    deps = [\n        \":box_coder_builder\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/box_coders:faster_rcnn_box_coder\",\n        \"//tensorflow_models/object_detection/box_coders:mean_stddev_box_coder\",\n        \"//tensorflow_models/object_detection/box_coders:square_box_coder\",\n        \"//tensorflow_models/object_detection/protos:box_coder_py_pb2\",\n    ],\n)\n\npy_library(\n    name = \"anchor_generator_builder\",\n    srcs = [\"anchor_generator_builder.py\"],\n    deps = [\n        \"//tensorflow_models/object_detection/anchor_generators:grid_anchor_generator\",\n        \"//tensorflow_models/object_detection/anchor_generators:multiple_grid_anchor_generator\",\n        \"//tensorflow_models/object_detection/protos:anchor_generator_py_pb2\",\n    ],\n)\n\npy_test(\n    name = \"anchor_generator_builder_test\",\n    srcs = [\"anchor_generator_builder_test.py\"],\n    deps = [\n        \":anchor_generator_builder\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/anchor_generators:grid_anchor_generator\",\n        \"//tensorflow_models/object_detection/anchor_generators:multiple_grid_anchor_generator\",\n        \"//tensorflow_models/object_detection/protos:anchor_generator_py_pb2\",\n    ],\n)\n\npy_library(\n    name = \"input_reader_builder\",\n    srcs = [\"input_reader_builder.py\"],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/data_decoders:tf_example_decoder\",\n        \"//tensorflow_models/object_detection/protos:input_reader_py_pb2\",\n    ],\n)\n\npy_test(\n    name = \"input_reader_builder_test\",\n    srcs = [\n        \"input_reader_builder_test.py\",\n    ],\n    deps = [\n        \":input_reader_builder\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:standard_fields\",\n        \"//tensorflow_models/object_detection/protos:input_reader_py_pb2\",\n    ],\n)\n\npy_library(\n    name = \"losses_builder\",\n    srcs = [\"losses_builder.py\"],\n    deps = [\n        \"//tensorflow_models/object_detection/core:losses\",\n        \"//tensorflow_models/object_detection/protos:losses_py_pb2\",\n    ],\n)\n\npy_test(\n    name = \"losses_builder_test\",\n    srcs = [\"losses_builder_test.py\"],\n    deps = [\n        \":losses_builder\",\n        \"//tensorflow_models/object_detection/core:losses\",\n        \"//tensorflow_models/object_detection/protos:losses_py_pb2\",\n    ],\n)\n\npy_library(\n    name = \"optimizer_builder\",\n    srcs = [\"optimizer_builder.py\"],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/utils:learning_schedules\",\n    ],\n)\n\npy_test(\n    name = \"optimizer_builder_test\",\n    srcs = [\"optimizer_builder_test.py\"],\n    deps = [\n        \":optimizer_builder\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/protos:optimizer_py_pb2\",\n    ],\n)\n\npy_library(\n    name = \"post_processing_builder\",\n    srcs = [\"post_processing_builder.py\"],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:post_processing\",\n        \"//tensorflow_models/object_detection/protos:post_processing_py_pb2\",\n    ],\n)\n\npy_test(\n    name = \"post_processing_builder_test\",\n    srcs = [\"post_processing_builder_test.py\"],\n    deps = [\n        \":post_processing_builder\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/protos:post_processing_py_pb2\",\n    ],\n)\n\npy_library(\n    name = \"hyperparams_builder\",\n    srcs = [\"hyperparams_builder.py\"],\n    deps = [\n        \"//tensorflow_models/object_detection/protos:hyperparams_py_pb2\",\n    ],\n)\n\npy_test(\n    name = \"hyperparams_builder_test\",\n    srcs = [\"hyperparams_builder_test.py\"],\n    deps = [\n        \":hyperparams_builder\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/protos:hyperparams_py_pb2\",\n    ],\n)\n\npy_library(\n    name = \"box_predictor_builder\",\n    srcs = [\"box_predictor_builder.py\"],\n    deps = [\n        \":hyperparams_builder\",\n        \"//tensorflow_models/object_detection/core:box_predictor\",\n        \"//tensorflow_models/object_detection/protos:box_predictor_py_pb2\",\n    ],\n)\n\npy_test(\n    name = \"box_predictor_builder_test\",\n    srcs = [\"box_predictor_builder_test.py\"],\n    deps = [\n        \":box_predictor_builder\",\n        \":hyperparams_builder\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/protos:box_predictor_py_pb2\",\n        \"//tensorflow_models/object_detection/protos:hyperparams_py_pb2\",\n    ],\n)\n\npy_library(\n    name = \"region_similarity_calculator_builder\",\n    srcs = [\"region_similarity_calculator_builder.py\"],\n    deps = [\n        \"//tensorflow_models/object_detection/core:region_similarity_calculator\",\n        \"//tensorflow_models/object_detection/protos:region_similarity_calculator_py_pb2\",\n    ],\n)\n\npy_test(\n    name = \"region_similarity_calculator_builder_test\",\n    srcs = [\"region_similarity_calculator_builder_test.py\"],\n    deps = [\n        \":region_similarity_calculator_builder\",\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"preprocessor_builder\",\n    srcs = [\"preprocessor_builder.py\"],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:preprocessor\",\n        \"//tensorflow_models/object_detection/protos:preprocessor_py_pb2\",\n    ],\n)\n\npy_test(\n    name = \"preprocessor_builder_test\",\n    srcs = [\n        \"preprocessor_builder_test.py\",\n    ],\n    deps = [\n        \":preprocessor_builder\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:preprocessor\",\n        \"//tensorflow_models/object_detection/protos:preprocessor_py_pb2\",\n    ],\n)\n\npy_library(\n    name = \"image_resizer_builder\",\n    srcs = [\"image_resizer_builder.py\"],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:preprocessor\",\n        \"//tensorflow_models/object_detection/protos:image_resizer_py_pb2\",\n    ],\n)\n\npy_test(\n    name = \"image_resizer_builder_test\",\n    srcs = [\"image_resizer_builder_test.py\"],\n    deps = [\n        \":image_resizer_builder\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/protos:image_resizer_py_pb2\",\n    ],\n)\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/__init__.py",
    "content": ""
  },
  {
    "path": "object_detector_app/object_detection/builders/anchor_generator_builder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"A function to build an object detection anchor generator from config.\"\"\"\n\nfrom object_detection.anchor_generators import grid_anchor_generator\nfrom object_detection.anchor_generators import multiple_grid_anchor_generator\nfrom object_detection.protos import anchor_generator_pb2\n\n\ndef build(anchor_generator_config):\n  \"\"\"Builds an anchor generator based on the config.\n\n  Args:\n    anchor_generator_config: An anchor_generator.proto object containing the\n      config for the desired anchor generator.\n\n  Returns:\n    Anchor generator based on the config.\n\n  Raises:\n    ValueError: On empty anchor generator proto.\n  \"\"\"\n  if not isinstance(anchor_generator_config,\n                    anchor_generator_pb2.AnchorGenerator):\n    raise ValueError('anchor_generator_config not of type '\n                     'anchor_generator_pb2.AnchorGenerator')\n  if anchor_generator_config.WhichOneof(\n      'anchor_generator_oneof') == 'grid_anchor_generator':\n    grid_anchor_generator_config = anchor_generator_config.grid_anchor_generator\n    return grid_anchor_generator.GridAnchorGenerator(\n        scales=[float(scale) for scale in grid_anchor_generator_config.scales],\n        aspect_ratios=[float(aspect_ratio)\n                       for aspect_ratio\n                       in grid_anchor_generator_config.aspect_ratios],\n        base_anchor_size=[grid_anchor_generator_config.height,\n                          grid_anchor_generator_config.width],\n        anchor_stride=[grid_anchor_generator_config.height_stride,\n                       grid_anchor_generator_config.width_stride],\n        anchor_offset=[grid_anchor_generator_config.height_offset,\n                       grid_anchor_generator_config.width_offset])\n  elif anchor_generator_config.WhichOneof(\n      'anchor_generator_oneof') == 'ssd_anchor_generator':\n    ssd_anchor_generator_config = anchor_generator_config.ssd_anchor_generator\n    return multiple_grid_anchor_generator.create_ssd_anchors(\n        num_layers=ssd_anchor_generator_config.num_layers,\n        min_scale=ssd_anchor_generator_config.min_scale,\n        max_scale=ssd_anchor_generator_config.max_scale,\n        aspect_ratios=ssd_anchor_generator_config.aspect_ratios,\n        reduce_boxes_in_lowest_layer=(ssd_anchor_generator_config\n                                      .reduce_boxes_in_lowest_layer))\n  else:\n    raise ValueError('Empty anchor generator.')\n\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/anchor_generator_builder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for anchor_generator_builder.\"\"\"\n\nimport tensorflow as tf\n\nfrom google.protobuf import text_format\nfrom object_detection.anchor_generators import grid_anchor_generator\nfrom object_detection.anchor_generators import multiple_grid_anchor_generator\nfrom object_detection.builders import anchor_generator_builder\nfrom object_detection.protos import anchor_generator_pb2\n\n\nclass AnchorGeneratorBuilderTest(tf.test.TestCase):\n\n  def assert_almost_list_equal(self, expected_list, actual_list, delta=None):\n    self.assertEqual(len(expected_list), len(actual_list))\n    for expected_item, actual_item in zip(expected_list, actual_list):\n      self.assertAlmostEqual(expected_item, actual_item, delta=delta)\n\n  def test_build_grid_anchor_generator_with_defaults(self):\n    anchor_generator_text_proto = \"\"\"\n      grid_anchor_generator {\n      }\n     \"\"\"\n    anchor_generator_proto = anchor_generator_pb2.AnchorGenerator()\n    text_format.Merge(anchor_generator_text_proto, anchor_generator_proto)\n    anchor_generator_object = anchor_generator_builder.build(\n        anchor_generator_proto)\n    self.assertTrue(isinstance(anchor_generator_object,\n                               grid_anchor_generator.GridAnchorGenerator))\n    self.assertListEqual(anchor_generator_object._scales, [])\n    self.assertListEqual(anchor_generator_object._aspect_ratios, [])\n    with self.test_session() as sess:\n      base_anchor_size, anchor_offset, anchor_stride = sess.run(\n          [anchor_generator_object._base_anchor_size,\n           anchor_generator_object._anchor_offset,\n           anchor_generator_object._anchor_stride])\n    self.assertAllEqual(anchor_offset, [0, 0])\n    self.assertAllEqual(anchor_stride, [16, 16])\n    self.assertAllEqual(base_anchor_size, [256, 256])\n\n  def test_build_grid_anchor_generator_with_non_default_parameters(self):\n    anchor_generator_text_proto = \"\"\"\n      grid_anchor_generator {\n        height: 128\n        width: 512\n        height_stride: 10\n        width_stride: 20\n        height_offset: 30\n        width_offset: 40\n        scales: [0.4, 2.2]\n        aspect_ratios: [0.3, 4.5]\n      }\n     \"\"\"\n    anchor_generator_proto = anchor_generator_pb2.AnchorGenerator()\n    text_format.Merge(anchor_generator_text_proto, anchor_generator_proto)\n    anchor_generator_object = anchor_generator_builder.build(\n        anchor_generator_proto)\n    self.assertTrue(isinstance(anchor_generator_object,\n                               grid_anchor_generator.GridAnchorGenerator))\n    self.assert_almost_list_equal(anchor_generator_object._scales,\n                                  [0.4, 2.2])\n    self.assert_almost_list_equal(anchor_generator_object._aspect_ratios,\n                                  [0.3, 4.5])\n    with self.test_session() as sess:\n      base_anchor_size, anchor_offset, anchor_stride = sess.run(\n          [anchor_generator_object._base_anchor_size,\n           anchor_generator_object._anchor_offset,\n           anchor_generator_object._anchor_stride])\n    self.assertAllEqual(anchor_offset, [30, 40])\n    self.assertAllEqual(anchor_stride, [10, 20])\n    self.assertAllEqual(base_anchor_size, [128, 512])\n\n  def test_build_ssd_anchor_generator_with_defaults(self):\n    anchor_generator_text_proto = \"\"\"\n      ssd_anchor_generator {\n        aspect_ratios: [1.0]\n      }\n    \"\"\"\n    anchor_generator_proto = anchor_generator_pb2.AnchorGenerator()\n    text_format.Merge(anchor_generator_text_proto, anchor_generator_proto)\n    anchor_generator_object = anchor_generator_builder.build(\n        anchor_generator_proto)\n    self.assertTrue(isinstance(anchor_generator_object,\n                               multiple_grid_anchor_generator.\n                               MultipleGridAnchorGenerator))\n    for actual_scales, expected_scales in zip(\n        list(anchor_generator_object._scales),\n        [(0.1, 0.2, 0.2),\n         (0.35, 0.418),\n         (0.499, 0.570),\n         (0.649, 0.721),\n         (0.799, 0.871),\n         (0.949, 0.974)]):\n      self.assert_almost_list_equal(expected_scales, actual_scales, delta=1e-2)\n    for actual_aspect_ratio, expected_aspect_ratio in zip(\n        list(anchor_generator_object._aspect_ratios),\n        [(1.0, 2.0, 0.5)] + 5 * [(1.0, 1.0)]):\n      self.assert_almost_list_equal(expected_aspect_ratio, actual_aspect_ratio)\n\n    with self.test_session() as sess:\n      base_anchor_size = sess.run(anchor_generator_object._base_anchor_size)\n    self.assertAllClose(base_anchor_size, [1.0, 1.0])\n\n  def test_build_ssd_anchor_generator_withoud_reduced_boxes(self):\n    anchor_generator_text_proto = \"\"\"\n      ssd_anchor_generator {\n        aspect_ratios: [1.0]\n        reduce_boxes_in_lowest_layer: false\n      }\n    \"\"\"\n    anchor_generator_proto = anchor_generator_pb2.AnchorGenerator()\n    text_format.Merge(anchor_generator_text_proto, anchor_generator_proto)\n    anchor_generator_object = anchor_generator_builder.build(\n        anchor_generator_proto)\n    self.assertTrue(isinstance(anchor_generator_object,\n                               multiple_grid_anchor_generator.\n                               MultipleGridAnchorGenerator))\n\n    for actual_scales, expected_scales in zip(\n        list(anchor_generator_object._scales),\n        [(0.2, 0.264),\n         (0.35, 0.418),\n         (0.499, 0.570),\n         (0.649, 0.721),\n         (0.799, 0.871),\n         (0.949, 0.974)]):\n      self.assert_almost_list_equal(expected_scales, actual_scales, delta=1e-2)\n\n    for actual_aspect_ratio, expected_aspect_ratio in zip(\n        list(anchor_generator_object._aspect_ratios),\n        6 * [(1.0, 1.0)]):\n      self.assert_almost_list_equal(expected_aspect_ratio, actual_aspect_ratio)\n\n    with self.test_session() as sess:\n      base_anchor_size = sess.run(anchor_generator_object._base_anchor_size)\n    self.assertAllClose(base_anchor_size, [1.0, 1.0])\n\n  def test_build_ssd_anchor_generator_with_non_default_parameters(self):\n    anchor_generator_text_proto = \"\"\"\n      ssd_anchor_generator {\n        num_layers: 2\n        min_scale: 0.3\n        max_scale: 0.8\n        aspect_ratios: [2.0]\n      }\n    \"\"\"\n    anchor_generator_proto = anchor_generator_pb2.AnchorGenerator()\n    text_format.Merge(anchor_generator_text_proto, anchor_generator_proto)\n    anchor_generator_object = anchor_generator_builder.build(\n        anchor_generator_proto)\n    self.assertTrue(isinstance(anchor_generator_object,\n                               multiple_grid_anchor_generator.\n                               MultipleGridAnchorGenerator))\n\n    for actual_scales, expected_scales in zip(\n        list(anchor_generator_object._scales),\n        [(0.1, 0.3, 0.3), (0.8,)]):\n      self.assert_almost_list_equal(expected_scales, actual_scales, delta=1e-2)\n\n    for actual_aspect_ratio, expected_aspect_ratio in zip(\n        list(anchor_generator_object._aspect_ratios),\n        [(1.0, 2.0, 0.5), (2.0,)]):\n      self.assert_almost_list_equal(expected_aspect_ratio, actual_aspect_ratio)\n\n    with self.test_session() as sess:\n      base_anchor_size = sess.run(anchor_generator_object._base_anchor_size)\n    self.assertAllClose(base_anchor_size, [1.0, 1.0])\n\n  def test_raise_value_error_on_empty_anchor_genertor(self):\n    anchor_generator_text_proto = \"\"\"\n    \"\"\"\n    anchor_generator_proto = anchor_generator_pb2.AnchorGenerator()\n    text_format.Merge(anchor_generator_text_proto, anchor_generator_proto)\n    with self.assertRaises(ValueError):\n      anchor_generator_builder.build(anchor_generator_proto)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/box_coder_builder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"A function to build an object detection box coder from configuration.\"\"\"\nfrom object_detection.box_coders import faster_rcnn_box_coder\nfrom object_detection.box_coders import mean_stddev_box_coder\nfrom object_detection.box_coders import square_box_coder\nfrom object_detection.protos import box_coder_pb2\n\n\ndef build(box_coder_config):\n  \"\"\"Builds a box coder object based on the box coder config.\n\n  Args:\n    box_coder_config: A box_coder.proto object containing the config for the\n      desired box coder.\n\n  Returns:\n    BoxCoder based on the config.\n\n  Raises:\n    ValueError: On empty box coder proto.\n  \"\"\"\n  if not isinstance(box_coder_config, box_coder_pb2.BoxCoder):\n    raise ValueError('box_coder_config not of type box_coder_pb2.BoxCoder.')\n\n  if box_coder_config.WhichOneof('box_coder_oneof') == 'faster_rcnn_box_coder':\n    return faster_rcnn_box_coder.FasterRcnnBoxCoder(scale_factors=[\n        box_coder_config.faster_rcnn_box_coder.y_scale,\n        box_coder_config.faster_rcnn_box_coder.x_scale,\n        box_coder_config.faster_rcnn_box_coder.height_scale,\n        box_coder_config.faster_rcnn_box_coder.width_scale\n    ])\n  if (box_coder_config.WhichOneof('box_coder_oneof') ==\n      'mean_stddev_box_coder'):\n    return mean_stddev_box_coder.MeanStddevBoxCoder()\n  if box_coder_config.WhichOneof('box_coder_oneof') == 'square_box_coder':\n    return square_box_coder.SquareBoxCoder(scale_factors=[\n        box_coder_config.square_box_coder.y_scale,\n        box_coder_config.square_box_coder.x_scale,\n        box_coder_config.square_box_coder.length_scale\n    ])\n  raise ValueError('Empty box coder.')\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/box_coder_builder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for box_coder_builder.\"\"\"\n\nimport tensorflow as tf\n\nfrom google.protobuf import text_format\nfrom object_detection.box_coders import faster_rcnn_box_coder\nfrom object_detection.box_coders import mean_stddev_box_coder\nfrom object_detection.box_coders import square_box_coder\nfrom object_detection.builders import box_coder_builder\nfrom object_detection.protos import box_coder_pb2\n\n\nclass BoxCoderBuilderTest(tf.test.TestCase):\n\n  def test_build_faster_rcnn_box_coder_with_defaults(self):\n    box_coder_text_proto = \"\"\"\n      faster_rcnn_box_coder {\n      }\n    \"\"\"\n    box_coder_proto = box_coder_pb2.BoxCoder()\n    text_format.Merge(box_coder_text_proto, box_coder_proto)\n    box_coder_object = box_coder_builder.build(box_coder_proto)\n    self.assertTrue(isinstance(box_coder_object,\n                               faster_rcnn_box_coder.FasterRcnnBoxCoder))\n    self.assertEqual(box_coder_object._scale_factors, [10.0, 10.0, 5.0, 5.0])\n\n  def test_build_faster_rcnn_box_coder_with_non_default_parameters(self):\n    box_coder_text_proto = \"\"\"\n      faster_rcnn_box_coder {\n        y_scale: 6.0\n        x_scale: 3.0\n        height_scale: 7.0\n        width_scale: 8.0\n      }\n    \"\"\"\n    box_coder_proto = box_coder_pb2.BoxCoder()\n    text_format.Merge(box_coder_text_proto, box_coder_proto)\n    box_coder_object = box_coder_builder.build(box_coder_proto)\n    self.assertTrue(isinstance(box_coder_object,\n                               faster_rcnn_box_coder.FasterRcnnBoxCoder))\n    self.assertEqual(box_coder_object._scale_factors, [6.0, 3.0, 7.0, 8.0])\n\n  def test_build_mean_stddev_box_coder(self):\n    box_coder_text_proto = \"\"\"\n      mean_stddev_box_coder {\n      }\n    \"\"\"\n    box_coder_proto = box_coder_pb2.BoxCoder()\n    text_format.Merge(box_coder_text_proto, box_coder_proto)\n    box_coder_object = box_coder_builder.build(box_coder_proto)\n    self.assertTrue(\n        isinstance(box_coder_object,\n                   mean_stddev_box_coder.MeanStddevBoxCoder))\n\n  def test_build_square_box_coder_with_defaults(self):\n    box_coder_text_proto = \"\"\"\n      square_box_coder {\n      }\n    \"\"\"\n    box_coder_proto = box_coder_pb2.BoxCoder()\n    text_format.Merge(box_coder_text_proto, box_coder_proto)\n    box_coder_object = box_coder_builder.build(box_coder_proto)\n    self.assertTrue(\n        isinstance(box_coder_object, square_box_coder.SquareBoxCoder))\n    self.assertEqual(box_coder_object._scale_factors, [10.0, 10.0, 5.0])\n\n  def test_build_square_box_coder_with_non_default_parameters(self):\n    box_coder_text_proto = \"\"\"\n      square_box_coder {\n        y_scale: 6.0\n        x_scale: 3.0\n        length_scale: 7.0\n      }\n    \"\"\"\n    box_coder_proto = box_coder_pb2.BoxCoder()\n    text_format.Merge(box_coder_text_proto, box_coder_proto)\n    box_coder_object = box_coder_builder.build(box_coder_proto)\n    self.assertTrue(\n        isinstance(box_coder_object, square_box_coder.SquareBoxCoder))\n    self.assertEqual(box_coder_object._scale_factors, [6.0, 3.0, 7.0])\n\n  def test_raise_error_on_empty_box_coder(self):\n    box_coder_text_proto = \"\"\"\n    \"\"\"\n    box_coder_proto = box_coder_pb2.BoxCoder()\n    text_format.Merge(box_coder_text_proto, box_coder_proto)\n    with self.assertRaises(ValueError):\n      box_coder_builder.build(box_coder_proto)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/box_predictor_builder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Function to build box predictor from configuration.\"\"\"\n\nfrom object_detection.core import box_predictor\nfrom object_detection.protos import box_predictor_pb2\n\n\ndef build(argscope_fn, box_predictor_config, is_training, num_classes):\n  \"\"\"Builds box predictor based on the configuration.\n\n  Builds box predictor based on the configuration. See box_predictor.proto for\n  configurable options. Also, see box_predictor.py for more details.\n\n  Args:\n    argscope_fn: A function that takes the following inputs:\n        * hyperparams_pb2.Hyperparams proto\n        * a boolean indicating if the model is in training mode.\n      and returns a tf slim argscope for Conv and FC hyperparameters.\n    box_predictor_config: box_predictor_pb2.BoxPredictor proto containing\n      configuration.\n    is_training: Whether the models is in training mode.\n    num_classes: Number of classes to predict.\n\n  Returns:\n    box_predictor: box_predictor.BoxPredictor object.\n\n  Raises:\n    ValueError: On unknown box predictor.\n  \"\"\"\n  if not isinstance(box_predictor_config, box_predictor_pb2.BoxPredictor):\n    raise ValueError('box_predictor_config not of type '\n                     'box_predictor_pb2.BoxPredictor.')\n\n  box_predictor_oneof = box_predictor_config.WhichOneof('box_predictor_oneof')\n\n  if  box_predictor_oneof == 'convolutional_box_predictor':\n    conv_box_predictor = box_predictor_config.convolutional_box_predictor\n    conv_hyperparams = argscope_fn(conv_box_predictor.conv_hyperparams,\n                                   is_training)\n    box_predictor_object = box_predictor.ConvolutionalBoxPredictor(\n        is_training=is_training,\n        num_classes=num_classes,\n        conv_hyperparams=conv_hyperparams,\n        min_depth=conv_box_predictor.min_depth,\n        max_depth=conv_box_predictor.max_depth,\n        num_layers_before_predictor=(conv_box_predictor.\n                                     num_layers_before_predictor),\n        use_dropout=conv_box_predictor.use_dropout,\n        dropout_keep_prob=conv_box_predictor.dropout_keep_probability,\n        kernel_size=conv_box_predictor.kernel_size,\n        box_code_size=conv_box_predictor.box_code_size,\n        apply_sigmoid_to_scores=conv_box_predictor.apply_sigmoid_to_scores)\n    return box_predictor_object\n\n  if box_predictor_oneof == 'mask_rcnn_box_predictor':\n    mask_rcnn_box_predictor = box_predictor_config.mask_rcnn_box_predictor\n    fc_hyperparams = argscope_fn(mask_rcnn_box_predictor.fc_hyperparams,\n                                 is_training)\n    conv_hyperparams = None\n    if mask_rcnn_box_predictor.HasField('conv_hyperparams'):\n      conv_hyperparams = argscope_fn(mask_rcnn_box_predictor.conv_hyperparams,\n                                     is_training)\n    box_predictor_object = box_predictor.MaskRCNNBoxPredictor(\n        is_training=is_training,\n        num_classes=num_classes,\n        fc_hyperparams=fc_hyperparams,\n        use_dropout=mask_rcnn_box_predictor.use_dropout,\n        dropout_keep_prob=mask_rcnn_box_predictor.dropout_keep_probability,\n        box_code_size=mask_rcnn_box_predictor.box_code_size,\n        conv_hyperparams=conv_hyperparams,\n        predict_instance_masks=mask_rcnn_box_predictor.predict_instance_masks,\n        mask_prediction_conv_depth=(mask_rcnn_box_predictor.\n                                    mask_prediction_conv_depth),\n        predict_keypoints=mask_rcnn_box_predictor.predict_keypoints)\n    return box_predictor_object\n\n  if box_predictor_oneof == 'rfcn_box_predictor':\n    rfcn_box_predictor = box_predictor_config.rfcn_box_predictor\n    conv_hyperparams = argscope_fn(rfcn_box_predictor.conv_hyperparams,\n                                   is_training)\n    box_predictor_object = box_predictor.RfcnBoxPredictor(\n        is_training=is_training,\n        num_classes=num_classes,\n        conv_hyperparams=conv_hyperparams,\n        crop_size=[rfcn_box_predictor.crop_height,\n                   rfcn_box_predictor.crop_width],\n        num_spatial_bins=[rfcn_box_predictor.num_spatial_bins_height,\n                          rfcn_box_predictor.num_spatial_bins_width],\n        depth=rfcn_box_predictor.depth,\n        box_code_size=rfcn_box_predictor.box_code_size)\n    return box_predictor_object\n  raise ValueError('Unknown box predictor: {}'.format(box_predictor_oneof))\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/box_predictor_builder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for box_predictor_builder.\"\"\"\nimport mock\nimport tensorflow as tf\n\nfrom google.protobuf import text_format\nfrom object_detection.builders import box_predictor_builder\nfrom object_detection.builders import hyperparams_builder\nfrom object_detection.protos import box_predictor_pb2\nfrom object_detection.protos import hyperparams_pb2\n\n\nclass ConvolutionalBoxPredictorBuilderTest(tf.test.TestCase):\n\n  def test_box_predictor_calls_conv_argscope_fn(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l1_regularizer {\n          weight: 0.0003\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n          mean: 0.0\n          stddev: 0.3\n        }\n      }\n      activation: RELU_6\n    \"\"\"\n    hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, hyperparams_proto)\n    def mock_conv_argscope_builder(conv_hyperparams_arg, is_training):\n      return (conv_hyperparams_arg, is_training)\n\n    box_predictor_proto = box_predictor_pb2.BoxPredictor()\n    box_predictor_proto.convolutional_box_predictor.conv_hyperparams.CopyFrom(\n        hyperparams_proto)\n    box_predictor = box_predictor_builder.build(\n        argscope_fn=mock_conv_argscope_builder,\n        box_predictor_config=box_predictor_proto,\n        is_training=False,\n        num_classes=10)\n    (conv_hyperparams_actual, is_training) = box_predictor._conv_hyperparams\n    self.assertAlmostEqual((hyperparams_proto.regularizer.\n                            l1_regularizer.weight),\n                           (conv_hyperparams_actual.regularizer.l1_regularizer.\n                            weight))\n    self.assertAlmostEqual((hyperparams_proto.initializer.\n                            truncated_normal_initializer.stddev),\n                           (conv_hyperparams_actual.initializer.\n                            truncated_normal_initializer.stddev))\n    self.assertAlmostEqual((hyperparams_proto.initializer.\n                            truncated_normal_initializer.mean),\n                           (conv_hyperparams_actual.initializer.\n                            truncated_normal_initializer.mean))\n    self.assertEqual(hyperparams_proto.activation,\n                     conv_hyperparams_actual.activation)\n    self.assertFalse(is_training)\n\n  def test_construct_non_default_conv_box_predictor(self):\n    box_predictor_text_proto = \"\"\"\n      convolutional_box_predictor {\n        min_depth: 2\n        max_depth: 16\n        num_layers_before_predictor: 2\n        use_dropout: false\n        dropout_keep_probability: 0.4\n        kernel_size: 3\n        box_code_size: 3\n        apply_sigmoid_to_scores: true\n      }\n    \"\"\"\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l1_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n    \"\"\"\n    hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, hyperparams_proto)\n    def mock_conv_argscope_builder(conv_hyperparams_arg, is_training):\n      return (conv_hyperparams_arg, is_training)\n\n    box_predictor_proto = box_predictor_pb2.BoxPredictor()\n    text_format.Merge(box_predictor_text_proto, box_predictor_proto)\n    box_predictor_proto.convolutional_box_predictor.conv_hyperparams.CopyFrom(\n        hyperparams_proto)\n    box_predictor = box_predictor_builder.build(\n        argscope_fn=mock_conv_argscope_builder,\n        box_predictor_config=box_predictor_proto,\n        is_training=False,\n        num_classes=10)\n    self.assertEqual(box_predictor._min_depth, 2)\n    self.assertEqual(box_predictor._max_depth, 16)\n    self.assertEqual(box_predictor._num_layers_before_predictor, 2)\n    self.assertFalse(box_predictor._use_dropout)\n    self.assertAlmostEqual(box_predictor._dropout_keep_prob, 0.4)\n    self.assertTrue(box_predictor._apply_sigmoid_to_scores)\n    self.assertEqual(box_predictor.num_classes, 10)\n    self.assertFalse(box_predictor._is_training)\n\n  def test_construct_default_conv_box_predictor(self):\n    box_predictor_text_proto = \"\"\"\n      convolutional_box_predictor {\n        conv_hyperparams {\n          regularizer {\n            l1_regularizer {\n            }\n          }\n          initializer {\n            truncated_normal_initializer {\n            }\n          }\n        }\n      }\"\"\"\n    box_predictor_proto = box_predictor_pb2.BoxPredictor()\n    text_format.Merge(box_predictor_text_proto, box_predictor_proto)\n    box_predictor = box_predictor_builder.build(\n        argscope_fn=hyperparams_builder.build,\n        box_predictor_config=box_predictor_proto,\n        is_training=True,\n        num_classes=90)\n    self.assertEqual(box_predictor._min_depth, 0)\n    self.assertEqual(box_predictor._max_depth, 0)\n    self.assertEqual(box_predictor._num_layers_before_predictor, 0)\n    self.assertTrue(box_predictor._use_dropout)\n    self.assertAlmostEqual(box_predictor._dropout_keep_prob, 0.8)\n    self.assertFalse(box_predictor._apply_sigmoid_to_scores)\n    self.assertEqual(box_predictor.num_classes, 90)\n    self.assertTrue(box_predictor._is_training)\n\n\nclass MaskRCNNBoxPredictorBuilderTest(tf.test.TestCase):\n\n  def test_box_predictor_builder_calls_fc_argscope_fn(self):\n    fc_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l1_regularizer {\n          weight: 0.0003\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n          mean: 0.0\n          stddev: 0.3\n        }\n      }\n      activation: RELU_6\n      op: FC\n    \"\"\"\n    hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(fc_hyperparams_text_proto, hyperparams_proto)\n    box_predictor_proto = box_predictor_pb2.BoxPredictor()\n    box_predictor_proto.mask_rcnn_box_predictor.fc_hyperparams.CopyFrom(\n        hyperparams_proto)\n    mock_argscope_fn = mock.Mock(return_value='arg_scope')\n    box_predictor = box_predictor_builder.build(\n        argscope_fn=mock_argscope_fn,\n        box_predictor_config=box_predictor_proto,\n        is_training=False,\n        num_classes=10)\n    mock_argscope_fn.assert_called_with(hyperparams_proto, False)\n    self.assertEqual(box_predictor._fc_hyperparams, 'arg_scope')\n\n  def test_non_default_mask_rcnn_box_predictor(self):\n    fc_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l1_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n      activation: RELU_6\n      op: FC\n    \"\"\"\n    box_predictor_text_proto = \"\"\"\n      mask_rcnn_box_predictor {\n        use_dropout: true\n        dropout_keep_probability: 0.8\n        box_code_size: 3\n      }\n    \"\"\"\n    hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(fc_hyperparams_text_proto, hyperparams_proto)\n    def mock_fc_argscope_builder(fc_hyperparams_arg, is_training):\n      return (fc_hyperparams_arg, is_training)\n\n    box_predictor_proto = box_predictor_pb2.BoxPredictor()\n    text_format.Merge(box_predictor_text_proto, box_predictor_proto)\n    box_predictor_proto.mask_rcnn_box_predictor.fc_hyperparams.CopyFrom(\n        hyperparams_proto)\n    box_predictor = box_predictor_builder.build(\n        argscope_fn=mock_fc_argscope_builder,\n        box_predictor_config=box_predictor_proto,\n        is_training=True,\n        num_classes=90)\n    self.assertTrue(box_predictor._use_dropout)\n    self.assertAlmostEqual(box_predictor._dropout_keep_prob, 0.8)\n    self.assertEqual(box_predictor.num_classes, 90)\n    self.assertTrue(box_predictor._is_training)\n    self.assertEqual(box_predictor._box_code_size, 3)\n\n  def test_build_default_mask_rcnn_box_predictor(self):\n    box_predictor_proto = box_predictor_pb2.BoxPredictor()\n    box_predictor_proto.mask_rcnn_box_predictor.fc_hyperparams.op = (\n        hyperparams_pb2.Hyperparams.FC)\n    box_predictor = box_predictor_builder.build(\n        argscope_fn=mock.Mock(return_value='arg_scope'),\n        box_predictor_config=box_predictor_proto,\n        is_training=True,\n        num_classes=90)\n    self.assertFalse(box_predictor._use_dropout)\n    self.assertAlmostEqual(box_predictor._dropout_keep_prob, 0.5)\n    self.assertEqual(box_predictor.num_classes, 90)\n    self.assertTrue(box_predictor._is_training)\n    self.assertEqual(box_predictor._box_code_size, 4)\n    self.assertFalse(box_predictor._predict_instance_masks)\n    self.assertFalse(box_predictor._predict_keypoints)\n\n  def test_build_box_predictor_with_mask_branch(self):\n    box_predictor_proto = box_predictor_pb2.BoxPredictor()\n    box_predictor_proto.mask_rcnn_box_predictor.fc_hyperparams.op = (\n        hyperparams_pb2.Hyperparams.FC)\n    box_predictor_proto.mask_rcnn_box_predictor.conv_hyperparams.op = (\n        hyperparams_pb2.Hyperparams.CONV)\n    box_predictor_proto.mask_rcnn_box_predictor.predict_instance_masks = True\n    box_predictor_proto.mask_rcnn_box_predictor.mask_prediction_conv_depth = 512\n    mock_argscope_fn = mock.Mock(return_value='arg_scope')\n    box_predictor = box_predictor_builder.build(\n        argscope_fn=mock_argscope_fn,\n        box_predictor_config=box_predictor_proto,\n        is_training=True,\n        num_classes=90)\n    mock_argscope_fn.assert_has_calls(\n        [mock.call(box_predictor_proto.mask_rcnn_box_predictor.fc_hyperparams,\n                   True),\n         mock.call(box_predictor_proto.mask_rcnn_box_predictor.conv_hyperparams,\n                   True)], any_order=True)\n    self.assertFalse(box_predictor._use_dropout)\n    self.assertAlmostEqual(box_predictor._dropout_keep_prob, 0.5)\n    self.assertEqual(box_predictor.num_classes, 90)\n    self.assertTrue(box_predictor._is_training)\n    self.assertEqual(box_predictor._box_code_size, 4)\n    self.assertTrue(box_predictor._predict_instance_masks)\n    self.assertEqual(box_predictor._mask_prediction_conv_depth, 512)\n    self.assertFalse(box_predictor._predict_keypoints)\n\n\nclass RfcnBoxPredictorBuilderTest(tf.test.TestCase):\n\n  def test_box_predictor_calls_fc_argscope_fn(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l1_regularizer {\n          weight: 0.0003\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n          mean: 0.0\n          stddev: 0.3\n        }\n      }\n      activation: RELU_6\n    \"\"\"\n    hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, hyperparams_proto)\n    def mock_conv_argscope_builder(conv_hyperparams_arg, is_training):\n      return (conv_hyperparams_arg, is_training)\n\n    box_predictor_proto = box_predictor_pb2.BoxPredictor()\n    box_predictor_proto.rfcn_box_predictor.conv_hyperparams.CopyFrom(\n        hyperparams_proto)\n    box_predictor = box_predictor_builder.build(\n        argscope_fn=mock_conv_argscope_builder,\n        box_predictor_config=box_predictor_proto,\n        is_training=False,\n        num_classes=10)\n    (conv_hyperparams_actual, is_training) = box_predictor._conv_hyperparams\n    self.assertAlmostEqual((hyperparams_proto.regularizer.\n                            l1_regularizer.weight),\n                           (conv_hyperparams_actual.regularizer.l1_regularizer.\n                            weight))\n    self.assertAlmostEqual((hyperparams_proto.initializer.\n                            truncated_normal_initializer.stddev),\n                           (conv_hyperparams_actual.initializer.\n                            truncated_normal_initializer.stddev))\n    self.assertAlmostEqual((hyperparams_proto.initializer.\n                            truncated_normal_initializer.mean),\n                           (conv_hyperparams_actual.initializer.\n                            truncated_normal_initializer.mean))\n    self.assertEqual(hyperparams_proto.activation,\n                     conv_hyperparams_actual.activation)\n    self.assertFalse(is_training)\n\n  def test_non_default_rfcn_box_predictor(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l1_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n      activation: RELU_6\n    \"\"\"\n    box_predictor_text_proto = \"\"\"\n      rfcn_box_predictor {\n        num_spatial_bins_height: 4\n        num_spatial_bins_width: 4\n        depth: 4\n        box_code_size: 3\n        crop_height: 16\n        crop_width: 16\n      }\n    \"\"\"\n    hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, hyperparams_proto)\n    def mock_conv_argscope_builder(conv_hyperparams_arg, is_training):\n      return (conv_hyperparams_arg, is_training)\n\n    box_predictor_proto = box_predictor_pb2.BoxPredictor()\n    text_format.Merge(box_predictor_text_proto, box_predictor_proto)\n    box_predictor_proto.rfcn_box_predictor.conv_hyperparams.CopyFrom(\n        hyperparams_proto)\n    box_predictor = box_predictor_builder.build(\n        argscope_fn=mock_conv_argscope_builder,\n        box_predictor_config=box_predictor_proto,\n        is_training=True,\n        num_classes=90)\n    self.assertEqual(box_predictor.num_classes, 90)\n    self.assertTrue(box_predictor._is_training)\n    self.assertEqual(box_predictor._box_code_size, 3)\n    self.assertEqual(box_predictor._num_spatial_bins, [4, 4])\n    self.assertEqual(box_predictor._crop_size, [16, 16])\n\n  def test_default_rfcn_box_predictor(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l1_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n      activation: RELU_6\n    \"\"\"\n    hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, hyperparams_proto)\n    def mock_conv_argscope_builder(conv_hyperparams_arg, is_training):\n      return (conv_hyperparams_arg, is_training)\n\n    box_predictor_proto = box_predictor_pb2.BoxPredictor()\n    box_predictor_proto.rfcn_box_predictor.conv_hyperparams.CopyFrom(\n        hyperparams_proto)\n    box_predictor = box_predictor_builder.build(\n        argscope_fn=mock_conv_argscope_builder,\n        box_predictor_config=box_predictor_proto,\n        is_training=True,\n        num_classes=90)\n    self.assertEqual(box_predictor.num_classes, 90)\n    self.assertTrue(box_predictor._is_training)\n    self.assertEqual(box_predictor._box_code_size, 4)\n    self.assertEqual(box_predictor._num_spatial_bins, [3, 3])\n    self.assertEqual(box_predictor._crop_size, [12, 12])\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/hyperparams_builder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Builder function to construct tf-slim arg_scope for convolution, fc ops.\"\"\"\nimport tensorflow as tf\n\nfrom object_detection.protos import hyperparams_pb2\n\nslim = tf.contrib.slim\n\n\ndef build(hyperparams_config, is_training):\n  \"\"\"Builds tf-slim arg_scope for convolution ops based on the config.\n\n  Returns an arg_scope to use for convolution ops containing weights\n  initializer, weights regularizer, activation function, batch norm function\n  and batch norm parameters based on the configuration.\n\n  Note that if the batch_norm parameteres are not specified in the config\n  (i.e. left to default) then batch norm is excluded from the arg_scope.\n\n  The batch norm parameters are set for updates based on `is_training` argument\n  and conv_hyperparams_config.batch_norm.train parameter. During training, they\n  are updated only if batch_norm.train parameter is true. However, during eval,\n  no updates are made to the batch norm variables. In both cases, their current\n  values are used during forward pass.\n\n  Args:\n    hyperparams_config: hyperparams.proto object containing\n      hyperparameters.\n    is_training: Whether the network is in training mode.\n\n  Returns:\n    arg_scope: tf-slim arg_scope containing hyperparameters for ops.\n\n  Raises:\n    ValueError: if hyperparams_config is not of type hyperparams.Hyperparams.\n  \"\"\"\n  if not isinstance(hyperparams_config,\n                    hyperparams_pb2.Hyperparams):\n    raise ValueError('hyperparams_config not of type '\n                     'hyperparams_pb.Hyperparams.')\n\n  batch_norm = None\n  batch_norm_params = None\n  if hyperparams_config.HasField('batch_norm'):\n    batch_norm = slim.batch_norm\n    batch_norm_params = _build_batch_norm_params(\n        hyperparams_config.batch_norm, is_training)\n\n  affected_ops = [slim.conv2d, slim.separable_conv2d, slim.conv2d_transpose]\n  if hyperparams_config.HasField('op') and (\n      hyperparams_config.op == hyperparams_pb2.Hyperparams.FC):\n    affected_ops = [slim.fully_connected]\n  with slim.arg_scope(\n      affected_ops,\n      weights_regularizer=_build_regularizer(\n          hyperparams_config.regularizer),\n      weights_initializer=_build_initializer(\n          hyperparams_config.initializer),\n      activation_fn=_build_activation_fn(hyperparams_config.activation),\n      normalizer_fn=batch_norm,\n      normalizer_params=batch_norm_params) as sc:\n    return sc\n\n\ndef _build_activation_fn(activation_fn):\n  \"\"\"Builds a callable activation from config.\n\n  Args:\n    activation_fn: hyperparams_pb2.Hyperparams.activation\n\n  Returns:\n    Callable activation function.\n\n  Raises:\n    ValueError: On unknown activation function.\n  \"\"\"\n  if activation_fn == hyperparams_pb2.Hyperparams.NONE:\n    return None\n  if activation_fn == hyperparams_pb2.Hyperparams.RELU:\n    return tf.nn.relu\n  if activation_fn == hyperparams_pb2.Hyperparams.RELU_6:\n    return tf.nn.relu6\n  raise ValueError('Unknown activation function: {}'.format(activation_fn))\n\n\ndef _build_regularizer(regularizer):\n  \"\"\"Builds a tf-slim regularizer from config.\n\n  Args:\n    regularizer: hyperparams_pb2.Hyperparams.regularizer proto.\n\n  Returns:\n    tf-slim regularizer.\n\n  Raises:\n    ValueError: On unknown regularizer.\n  \"\"\"\n  regularizer_oneof = regularizer.WhichOneof('regularizer_oneof')\n  if  regularizer_oneof == 'l1_regularizer':\n    return slim.l1_regularizer(scale=regularizer.l1_regularizer.weight)\n  if regularizer_oneof == 'l2_regularizer':\n    return slim.l2_regularizer(scale=regularizer.l2_regularizer.weight)\n  raise ValueError('Unknown regularizer function: {}'.format(regularizer_oneof))\n\n\ndef _build_initializer(initializer):\n  \"\"\"Build a tf initializer from config.\n\n  Args:\n    initializer: hyperparams_pb2.Hyperparams.regularizer proto.\n\n  Returns:\n    tf initializer.\n\n  Raises:\n    ValueError: On unknown initializer.\n  \"\"\"\n  initializer_oneof = initializer.WhichOneof('initializer_oneof')\n  if initializer_oneof == 'truncated_normal_initializer':\n    return tf.truncated_normal_initializer(\n        mean=initializer.truncated_normal_initializer.mean,\n        stddev=initializer.truncated_normal_initializer.stddev)\n  if initializer_oneof == 'variance_scaling_initializer':\n    enum_descriptor = (hyperparams_pb2.VarianceScalingInitializer.\n                       DESCRIPTOR.enum_types_by_name['Mode'])\n    mode = enum_descriptor.values_by_number[initializer.\n                                            variance_scaling_initializer.\n                                            mode].name\n    return slim.variance_scaling_initializer(\n        factor=initializer.variance_scaling_initializer.factor,\n        mode=mode,\n        uniform=initializer.variance_scaling_initializer.uniform)\n  raise ValueError('Unknown initializer function: {}'.format(\n      initializer_oneof))\n\n\ndef _build_batch_norm_params(batch_norm, is_training):\n  \"\"\"Build a dictionary of batch_norm params from config.\n\n  Args:\n    batch_norm: hyperparams_pb2.ConvHyperparams.batch_norm proto.\n    is_training: Whether the models is in training mode.\n\n  Returns:\n    A dictionary containing batch_norm parameters.\n  \"\"\"\n  batch_norm_params = {\n      'decay': batch_norm.decay,\n      'center': batch_norm.center,\n      'scale': batch_norm.scale,\n      'epsilon': batch_norm.epsilon,\n      'fused': True,\n      'is_training': is_training and batch_norm.train,\n  }\n  return batch_norm_params\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/hyperparams_builder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests object_detection.core.hyperparams_builder.\"\"\"\n\nimport numpy as np\nimport tensorflow as tf\n\nfrom google.protobuf import text_format\n\n# TODO: Rewrite third_party imports.\nfrom object_detection.builders import hyperparams_builder\nfrom object_detection.protos import hyperparams_pb2\n\nslim = tf.contrib.slim\n\n\nclass HyperparamsBuilderTest(tf.test.TestCase):\n\n  # TODO: Make this a public api in slim arg_scope.py.\n  def _get_scope_key(self, op):\n    return getattr(op, '_key_op', str(op))\n\n  def test_default_arg_scope_has_conv2d_op(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l1_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=True)\n    self.assertTrue(self._get_scope_key(slim.conv2d) in scope)\n\n  def test_default_arg_scope_has_separable_conv2d_op(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l1_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=True)\n    self.assertTrue(self._get_scope_key(slim.separable_conv2d) in scope)\n\n  def test_default_arg_scope_has_conv2d_transpose_op(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l1_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=True)\n    self.assertTrue(self._get_scope_key(slim.conv2d_transpose) in scope)\n\n  def test_explicit_fc_op_arg_scope_has_fully_connected_op(self):\n    conv_hyperparams_text_proto = \"\"\"\n      op: FC\n      regularizer {\n        l1_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=True)\n    self.assertTrue(self._get_scope_key(slim.fully_connected) in scope)\n\n  def test_separable_conv2d_and_conv2d_and_transpose_have_same_parameters(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l1_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=True)\n    kwargs_1, kwargs_2, kwargs_3 = scope.values()\n    self.assertDictEqual(kwargs_1, kwargs_2)\n    self.assertDictEqual(kwargs_1, kwargs_3)\n\n  def test_return_l1_regularized_weights(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l1_regularizer {\n          weight: 0.5\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=True)\n    conv_scope_arguments = scope.values()[0]\n    regularizer = conv_scope_arguments['weights_regularizer']\n    weights = np.array([1., -1, 4., 2.])\n    with self.test_session() as sess:\n      result = sess.run(regularizer(tf.constant(weights)))\n    self.assertAllClose(np.abs(weights).sum() * 0.5, result)\n\n  def test_return_l2_regularizer_weights(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l2_regularizer {\n          weight: 0.42\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=True)\n    conv_scope_arguments = scope.values()[0]\n\n    regularizer = conv_scope_arguments['weights_regularizer']\n    weights = np.array([1., -1, 4., 2.])\n    with self.test_session() as sess:\n      result = sess.run(regularizer(tf.constant(weights)))\n    self.assertAllClose(np.power(weights, 2).sum() / 2.0 * 0.42, result)\n\n  def test_return_non_default_batch_norm_params_with_train_during_train(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l2_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n      batch_norm {\n        decay: 0.7\n        center: false\n        scale: true\n        epsilon: 0.03\n        train: true\n      }\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=True)\n    conv_scope_arguments = scope.values()[0]\n    self.assertEqual(conv_scope_arguments['normalizer_fn'], slim.batch_norm)\n    batch_norm_params = conv_scope_arguments['normalizer_params']\n    self.assertAlmostEqual(batch_norm_params['decay'], 0.7)\n    self.assertAlmostEqual(batch_norm_params['epsilon'], 0.03)\n    self.assertFalse(batch_norm_params['center'])\n    self.assertTrue(batch_norm_params['scale'])\n    self.assertTrue(batch_norm_params['is_training'])\n\n  def test_return_batch_norm_params_with_notrain_during_eval(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l2_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n      batch_norm {\n        decay: 0.7\n        center: false\n        scale: true\n        epsilon: 0.03\n        train: true\n      }\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=False)\n    conv_scope_arguments = scope.values()[0]\n    self.assertEqual(conv_scope_arguments['normalizer_fn'], slim.batch_norm)\n    batch_norm_params = conv_scope_arguments['normalizer_params']\n    self.assertAlmostEqual(batch_norm_params['decay'], 0.7)\n    self.assertAlmostEqual(batch_norm_params['epsilon'], 0.03)\n    self.assertFalse(batch_norm_params['center'])\n    self.assertTrue(batch_norm_params['scale'])\n    self.assertFalse(batch_norm_params['is_training'])\n\n  def test_return_batch_norm_params_with_notrain_when_train_is_false(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l2_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n      batch_norm {\n        decay: 0.7\n        center: false\n        scale: true\n        epsilon: 0.03\n        train: false\n      }\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=True)\n    conv_scope_arguments = scope.values()[0]\n    self.assertEqual(conv_scope_arguments['normalizer_fn'], slim.batch_norm)\n    batch_norm_params = conv_scope_arguments['normalizer_params']\n    self.assertAlmostEqual(batch_norm_params['decay'], 0.7)\n    self.assertAlmostEqual(batch_norm_params['epsilon'], 0.03)\n    self.assertFalse(batch_norm_params['center'])\n    self.assertTrue(batch_norm_params['scale'])\n    self.assertFalse(batch_norm_params['is_training'])\n\n  def test_do_not_use_batch_norm_if_default(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l2_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=True)\n    conv_scope_arguments = scope.values()[0]\n    self.assertEqual(conv_scope_arguments['normalizer_fn'], None)\n    self.assertEqual(conv_scope_arguments['normalizer_params'], None)\n\n  def test_use_none_activation(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l2_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n      activation: NONE\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=True)\n    conv_scope_arguments = scope.values()[0]\n    self.assertEqual(conv_scope_arguments['activation_fn'], None)\n\n  def test_use_relu_activation(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l2_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n      activation: RELU\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=True)\n    conv_scope_arguments = scope.values()[0]\n    self.assertEqual(conv_scope_arguments['activation_fn'], tf.nn.relu)\n\n  def test_use_relu_6_activation(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l2_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n      activation: RELU_6\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=True)\n    conv_scope_arguments = scope.values()[0]\n    self.assertEqual(conv_scope_arguments['activation_fn'], tf.nn.relu6)\n\n  def _assert_variance_in_range(self, initializer, shape, variance,\n                                tol=1e-2):\n    with tf.Graph().as_default() as g:\n      with self.test_session(graph=g) as sess:\n        var = tf.get_variable(\n            name='test',\n            shape=shape,\n            dtype=tf.float32,\n            initializer=initializer)\n        sess.run(tf.global_variables_initializer())\n        values = sess.run(var)\n        self.assertAllClose(np.var(values), variance, tol, tol)\n\n  def test_variance_in_range_with_variance_scaling_initializer_fan_in(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l2_regularizer {\n        }\n      }\n      initializer {\n        variance_scaling_initializer {\n          factor: 2.0\n          mode: FAN_IN\n          uniform: false\n        }\n      }\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=True)\n    conv_scope_arguments = scope.values()[0]\n    initializer = conv_scope_arguments['weights_initializer']\n    self._assert_variance_in_range(initializer, shape=[100, 40],\n                                   variance=2. / 100.)\n\n  def test_variance_in_range_with_variance_scaling_initializer_fan_out(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l2_regularizer {\n        }\n      }\n      initializer {\n        variance_scaling_initializer {\n          factor: 2.0\n          mode: FAN_OUT\n          uniform: false\n        }\n      }\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=True)\n    conv_scope_arguments = scope.values()[0]\n    initializer = conv_scope_arguments['weights_initializer']\n    self._assert_variance_in_range(initializer, shape=[100, 40],\n                                   variance=2. / 40.)\n\n  def test_variance_in_range_with_variance_scaling_initializer_fan_avg(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l2_regularizer {\n        }\n      }\n      initializer {\n        variance_scaling_initializer {\n          factor: 2.0\n          mode: FAN_AVG\n          uniform: false\n        }\n      }\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=True)\n    conv_scope_arguments = scope.values()[0]\n    initializer = conv_scope_arguments['weights_initializer']\n    self._assert_variance_in_range(initializer, shape=[100, 40],\n                                   variance=4. / (100. + 40.))\n\n  def test_variance_in_range_with_variance_scaling_initializer_uniform(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l2_regularizer {\n        }\n      }\n      initializer {\n        variance_scaling_initializer {\n          factor: 2.0\n          mode: FAN_IN\n          uniform: true\n        }\n      }\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=True)\n    conv_scope_arguments = scope.values()[0]\n    initializer = conv_scope_arguments['weights_initializer']\n    self._assert_variance_in_range(initializer, shape=[100, 40],\n                                   variance=2. / 100.)\n\n  def test_variance_in_range_with_truncated_normal_initializer(self):\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l2_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n          mean: 0.0\n          stddev: 0.8\n        }\n      }\n    \"\"\"\n    conv_hyperparams_proto = hyperparams_pb2.Hyperparams()\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams_proto)\n    scope = hyperparams_builder.build(conv_hyperparams_proto, is_training=True)\n    conv_scope_arguments = scope.values()[0]\n    initializer = conv_scope_arguments['weights_initializer']\n    self._assert_variance_in_range(initializer, shape=[100, 40],\n                                   variance=0.49, tol=1e-1)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/image_resizer_builder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Builder function for image resizing operations.\"\"\"\nimport functools\n\nfrom object_detection.core import preprocessor\nfrom object_detection.protos import image_resizer_pb2\n\n\ndef build(image_resizer_config):\n  \"\"\"Builds callable for image resizing operations.\n\n  Args:\n    image_resizer_config: image_resizer.proto object containing parameters for\n      an image resizing operation.\n\n  Returns:\n    image_resizer_fn: Callable for image resizing.  This callable always takes\n      a rank-3 image tensor (corresponding to a single image) and returns a\n      rank-3 image tensor, possibly with new spatial dimensions.\n\n  Raises:\n    ValueError: if `image_resizer_config` is of incorrect type.\n    ValueError: if `image_resizer_config.image_resizer_oneof` is of expected\n      type.\n    ValueError: if min_dimension > max_dimension when keep_aspect_ratio_resizer\n      is used.\n  \"\"\"\n  if not isinstance(image_resizer_config, image_resizer_pb2.ImageResizer):\n    raise ValueError('image_resizer_config not of type '\n                     'image_resizer_pb2.ImageResizer.')\n\n  if image_resizer_config.WhichOneof(\n      'image_resizer_oneof') == 'keep_aspect_ratio_resizer':\n    keep_aspect_ratio_config = image_resizer_config.keep_aspect_ratio_resizer\n    if not (keep_aspect_ratio_config.min_dimension\n            <= keep_aspect_ratio_config.max_dimension):\n      raise ValueError('min_dimension > max_dimension')\n    return functools.partial(\n        preprocessor.resize_to_range,\n        min_dimension=keep_aspect_ratio_config.min_dimension,\n        max_dimension=keep_aspect_ratio_config.max_dimension)\n  if image_resizer_config.WhichOneof(\n      'image_resizer_oneof') == 'fixed_shape_resizer':\n    fixed_shape_resizer_config = image_resizer_config.fixed_shape_resizer\n    return functools.partial(preprocessor.resize_image,\n                             new_height=fixed_shape_resizer_config.height,\n                             new_width=fixed_shape_resizer_config.width)\n  raise ValueError('Invalid image resizer option.')\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/image_resizer_builder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.builders.image_resizer_builder.\"\"\"\nimport tensorflow as tf\nfrom google.protobuf import text_format\nfrom object_detection.builders import image_resizer_builder\nfrom object_detection.protos import image_resizer_pb2\n\n\nclass ImageResizerBuilderTest(tf.test.TestCase):\n\n  def _shape_of_resized_random_image_given_text_proto(\n      self, input_shape, text_proto):\n    image_resizer_config = image_resizer_pb2.ImageResizer()\n    text_format.Merge(text_proto, image_resizer_config)\n    image_resizer_fn = image_resizer_builder.build(image_resizer_config)\n    images = tf.to_float(tf.random_uniform(\n        input_shape, minval=0, maxval=255, dtype=tf.int32))\n    resized_images = image_resizer_fn(images)\n    with self.test_session() as sess:\n      return sess.run(resized_images).shape\n\n  def test_built_keep_aspect_ratio_resizer_returns_expected_shape(self):\n    image_resizer_text_proto = \"\"\"\n      keep_aspect_ratio_resizer {\n        min_dimension: 10\n        max_dimension: 20\n      }\n    \"\"\"\n    input_shape = (50, 25, 3)\n    expected_output_shape = (20, 10, 3)\n    output_shape = self._shape_of_resized_random_image_given_text_proto(\n        input_shape, image_resizer_text_proto)\n    self.assertEqual(output_shape, expected_output_shape)\n\n  def test_built_fixed_shape_resizer_returns_expected_shape(self):\n    image_resizer_text_proto = \"\"\"\n      fixed_shape_resizer {\n        height: 10\n        width: 20\n      }\n    \"\"\"\n    input_shape = (50, 25, 3)\n    expected_output_shape = (10, 20, 3)\n    output_shape = self._shape_of_resized_random_image_given_text_proto(\n        input_shape, image_resizer_text_proto)\n    self.assertEqual(output_shape, expected_output_shape)\n\n  def test_raises_error_on_invalid_input(self):\n    invalid_input = 'invalid_input'\n    with self.assertRaises(ValueError):\n      image_resizer_builder.build(invalid_input)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/input_reader_builder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Input reader builder.\n\nCreates data sources for DetectionModels from an InputReader config. See\ninput_reader.proto for options.\n\nNote: If users wishes to also use their own InputReaders with the Object\nDetection configuration framework, they should define their own builder function\nthat wraps the build function.\n\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.data_decoders import tf_example_decoder\nfrom object_detection.protos import input_reader_pb2\n\nparallel_reader = tf.contrib.slim.parallel_reader\n\n\ndef build(input_reader_config):\n  \"\"\"Builds a tensor dictionary based on the InputReader config.\n\n  Args:\n    input_reader_config: A input_reader_pb2.InputReader object.\n\n  Returns:\n    A tensor dict based on the input_reader_config.\n\n  Raises:\n    ValueError: On invalid input reader proto.\n  \"\"\"\n  if not isinstance(input_reader_config, input_reader_pb2.InputReader):\n    raise ValueError('input_reader_config not of type '\n                     'input_reader_pb2.InputReader.')\n\n  if input_reader_config.WhichOneof('input_reader') == 'tf_record_input_reader':\n    config = input_reader_config.tf_record_input_reader\n    _, string_tensor = parallel_reader.parallel_read(\n        config.input_path,\n        reader_class=tf.TFRecordReader,\n        num_epochs=(input_reader_config.num_epochs\n                    if input_reader_config.num_epochs else None),\n        num_readers=input_reader_config.num_readers,\n        shuffle=input_reader_config.shuffle,\n        dtypes=[tf.string, tf.string],\n        capacity=input_reader_config.queue_capacity,\n        min_after_dequeue=input_reader_config.min_after_dequeue)\n\n    return tf_example_decoder.TfExampleDecoder().Decode(string_tensor)\n\n  raise ValueError('Unsupported input_reader_config.')\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/input_reader_builder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for input_reader_builder.\"\"\"\n\nimport os\nimport numpy as np\nimport tensorflow as tf\n\nfrom google.protobuf import text_format\n\nfrom tensorflow.core.example import example_pb2\nfrom tensorflow.core.example import feature_pb2\nfrom object_detection.builders import input_reader_builder\nfrom object_detection.core import standard_fields as fields\nfrom object_detection.protos import input_reader_pb2\n\n\nclass InputReaderBuilderTest(tf.test.TestCase):\n\n  def create_tf_record(self):\n    path = os.path.join(self.get_temp_dir(), 'tfrecord')\n    writer = tf.python_io.TFRecordWriter(path)\n\n    image_tensor = np.random.randint(255, size=(4, 5, 3)).astype(np.uint8)\n    with self.test_session():\n      encoded_jpeg = tf.image.encode_jpeg(tf.constant(image_tensor)).eval()\n    example = example_pb2.Example(features=feature_pb2.Features(feature={\n        'image/encoded': feature_pb2.Feature(\n            bytes_list=feature_pb2.BytesList(value=[encoded_jpeg])),\n        'image/format': feature_pb2.Feature(\n            bytes_list=feature_pb2.BytesList(value=['jpeg'.encode('utf-8')])),\n        'image/object/bbox/xmin': feature_pb2.Feature(\n            float_list=feature_pb2.FloatList(value=[0.0])),\n        'image/object/bbox/xmax': feature_pb2.Feature(\n            float_list=feature_pb2.FloatList(value=[1.0])),\n        'image/object/bbox/ymin': feature_pb2.Feature(\n            float_list=feature_pb2.FloatList(value=[0.0])),\n        'image/object/bbox/ymax': feature_pb2.Feature(\n            float_list=feature_pb2.FloatList(value=[1.0])),\n        'image/object/class/label': feature_pb2.Feature(\n            int64_list=feature_pb2.Int64List(value=[2])),\n    }))\n    writer.write(example.SerializeToString())\n    writer.close()\n\n    return path\n\n  def test_build_tf_record_input_reader(self):\n    tf_record_path = self.create_tf_record()\n\n    input_reader_text_proto = \"\"\"\n      shuffle: false\n      num_readers: 1\n      tf_record_input_reader {{\n        input_path: '{0}'\n      }}\n    \"\"\".format(tf_record_path)\n    input_reader_proto = input_reader_pb2.InputReader()\n    text_format.Merge(input_reader_text_proto, input_reader_proto)\n    tensor_dict = input_reader_builder.build(input_reader_proto)\n\n    sv = tf.train.Supervisor(logdir=self.get_temp_dir())\n    with sv.prepare_or_wait_for_session() as sess:\n      sv.start_queue_runners(sess)\n      output_dict = sess.run(tensor_dict)\n\n    self.assertEquals(\n        (4, 5, 3), output_dict[fields.InputDataFields.image].shape)\n    self.assertEquals(\n        [2], output_dict[fields.InputDataFields.groundtruth_classes])\n    self.assertEquals(\n        (1, 4), output_dict[fields.InputDataFields.groundtruth_boxes].shape)\n    self.assertAllEqual(\n        [0.0, 0.0, 1.0, 1.0],\n        output_dict[fields.InputDataFields.groundtruth_boxes][0])\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/losses_builder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"A function to build localization and classification losses from config.\"\"\"\n\nfrom object_detection.core import losses\nfrom object_detection.protos import losses_pb2\n\n\ndef build(loss_config):\n  \"\"\"Build losses based on the config.\n\n  Builds classification, localization losses and optionally a hard example miner\n  based on the config.\n\n  Args:\n    loss_config: A losses_pb2.Loss object.\n\n  Returns:\n    classification_loss: Classification loss object.\n    localization_loss: Localization loss object.\n    classification_weight: Classification loss weight.\n    localization_weight: Localization loss weight.\n    hard_example_miner: Hard example miner object.\n  \"\"\"\n  classification_loss = _build_classification_loss(\n      loss_config.classification_loss)\n  localization_loss = _build_localization_loss(\n      loss_config.localization_loss)\n  classification_weight = loss_config.classification_weight\n  localization_weight = loss_config.localization_weight\n  hard_example_miner = None\n  if loss_config.HasField('hard_example_miner'):\n    hard_example_miner = build_hard_example_miner(\n        loss_config.hard_example_miner,\n        classification_weight,\n        localization_weight)\n  return (classification_loss, localization_loss,\n          classification_weight,\n          localization_weight, hard_example_miner)\n\n\ndef build_hard_example_miner(config,\n                             classification_weight,\n                             localization_weight):\n  \"\"\"Builds hard example miner based on the config.\n\n  Args:\n    config: A losses_pb2.HardExampleMiner object.\n    classification_weight: Classification loss weight.\n    localization_weight: Localization loss weight.\n\n  Returns:\n    Hard example miner.\n\n  \"\"\"\n  loss_type = None\n  if config.loss_type == losses_pb2.HardExampleMiner.BOTH:\n    loss_type = 'both'\n  if config.loss_type == losses_pb2.HardExampleMiner.CLASSIFICATION:\n    loss_type = 'cls'\n  if config.loss_type == losses_pb2.HardExampleMiner.LOCALIZATION:\n    loss_type = 'loc'\n\n  max_negatives_per_positive = None\n  num_hard_examples = None\n  if config.max_negatives_per_positive > 0:\n    max_negatives_per_positive = config.max_negatives_per_positive\n  if config.num_hard_examples > 0:\n    num_hard_examples = config.num_hard_examples\n  hard_example_miner = losses.HardExampleMiner(\n      num_hard_examples=num_hard_examples,\n      iou_threshold=config.iou_threshold,\n      loss_type=loss_type,\n      cls_loss_weight=classification_weight,\n      loc_loss_weight=localization_weight,\n      max_negatives_per_positive=max_negatives_per_positive,\n      min_negatives_per_image=config.min_negatives_per_image)\n  return hard_example_miner\n\n\ndef _build_localization_loss(loss_config):\n  \"\"\"Builds a localization loss based on the loss config.\n\n  Args:\n    loss_config: A losses_pb2.LocalizationLoss object.\n\n  Returns:\n    Loss based on the config.\n\n  Raises:\n    ValueError: On invalid loss_config.\n  \"\"\"\n  if not isinstance(loss_config, losses_pb2.LocalizationLoss):\n    raise ValueError('loss_config not of type losses_pb2.LocalizationLoss.')\n\n  loss_type = loss_config.WhichOneof('localization_loss')\n\n  if loss_type == 'weighted_l2':\n    config = loss_config.weighted_l2\n    return losses.WeightedL2LocalizationLoss(\n        anchorwise_output=config.anchorwise_output)\n\n  if loss_type == 'weighted_smooth_l1':\n    config = loss_config.weighted_smooth_l1\n    return losses.WeightedSmoothL1LocalizationLoss(\n        anchorwise_output=config.anchorwise_output)\n\n  if loss_type == 'weighted_iou':\n    return losses.WeightedIOULocalizationLoss()\n\n  raise ValueError('Empty loss config.')\n\n\ndef _build_classification_loss(loss_config):\n  \"\"\"Builds a classification loss based on the loss config.\n\n  Args:\n    loss_config: A losses_pb2.ClassificationLoss object.\n\n  Returns:\n    Loss based on the config.\n\n  Raises:\n    ValueError: On invalid loss_config.\n  \"\"\"\n  if not isinstance(loss_config, losses_pb2.ClassificationLoss):\n    raise ValueError('loss_config not of type losses_pb2.ClassificationLoss.')\n\n  loss_type = loss_config.WhichOneof('classification_loss')\n\n  if loss_type == 'weighted_sigmoid':\n    config = loss_config.weighted_sigmoid\n    return losses.WeightedSigmoidClassificationLoss(\n        anchorwise_output=config.anchorwise_output)\n\n  if loss_type == 'weighted_softmax':\n    config = loss_config.weighted_softmax\n    return losses.WeightedSoftmaxClassificationLoss(\n        anchorwise_output=config.anchorwise_output)\n\n  if loss_type == 'bootstrapped_sigmoid':\n    config = loss_config.bootstrapped_sigmoid\n    return losses.BootstrappedSigmoidClassificationLoss(\n        alpha=config.alpha,\n        bootstrap_type=('hard' if config.hard_bootstrap else 'soft'),\n        anchorwise_output=config.anchorwise_output)\n\n  raise ValueError('Empty loss config.')\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/losses_builder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for losses_builder.\"\"\"\n\nimport tensorflow as tf\n\nfrom google.protobuf import text_format\nfrom object_detection.builders import losses_builder\nfrom object_detection.core import losses\nfrom object_detection.protos import losses_pb2\n\n\nclass LocalizationLossBuilderTest(tf.test.TestCase):\n\n  def test_build_weighted_l2_localization_loss(self):\n    losses_text_proto = \"\"\"\n      localization_loss {\n        weighted_l2 {\n        }\n      }\n      classification_loss {\n        weighted_softmax {\n        }\n      }\n    \"\"\"\n    losses_proto = losses_pb2.Loss()\n    text_format.Merge(losses_text_proto, losses_proto)\n    _, localization_loss, _, _, _ = losses_builder.build(losses_proto)\n    self.assertTrue(isinstance(localization_loss,\n                               losses.WeightedL2LocalizationLoss))\n\n  def test_build_weighted_smooth_l1_localization_loss(self):\n    losses_text_proto = \"\"\"\n      localization_loss {\n        weighted_smooth_l1 {\n        }\n      }\n      classification_loss {\n        weighted_softmax {\n        }\n      }\n    \"\"\"\n    losses_proto = losses_pb2.Loss()\n    text_format.Merge(losses_text_proto, losses_proto)\n    _, localization_loss, _, _, _ = losses_builder.build(losses_proto)\n    self.assertTrue(isinstance(localization_loss,\n                               losses.WeightedSmoothL1LocalizationLoss))\n\n  def test_build_weighted_iou_localization_loss(self):\n    losses_text_proto = \"\"\"\n      localization_loss {\n        weighted_iou {\n        }\n      }\n      classification_loss {\n        weighted_softmax {\n        }\n      }\n    \"\"\"\n    losses_proto = losses_pb2.Loss()\n    text_format.Merge(losses_text_proto, losses_proto)\n    _, localization_loss, _, _, _ = losses_builder.build(losses_proto)\n    self.assertTrue(isinstance(localization_loss,\n                               losses.WeightedIOULocalizationLoss))\n\n  def test_anchorwise_output(self):\n    losses_text_proto = \"\"\"\n      localization_loss {\n        weighted_smooth_l1 {\n          anchorwise_output: true\n        }\n      }\n      classification_loss {\n        weighted_softmax {\n        }\n      }\n    \"\"\"\n    losses_proto = losses_pb2.Loss()\n    text_format.Merge(losses_text_proto, losses_proto)\n    _, localization_loss, _, _, _ = losses_builder.build(losses_proto)\n    self.assertTrue(isinstance(localization_loss,\n                               losses.WeightedSmoothL1LocalizationLoss))\n    predictions = tf.constant([[[0.0, 0.0, 1.0, 1.0], [0.0, 0.0, 1.0, 1.0]]])\n    targets = tf.constant([[[0.0, 0.0, 1.0, 1.0], [0.0, 0.0, 1.0, 1.0]]])\n    weights = tf.constant([[1.0, 1.0]])\n    loss = localization_loss(predictions, targets, weights=weights)\n    self.assertEqual(loss.shape, [1, 2])\n\n  def test_raise_error_on_empty_localization_config(self):\n    losses_text_proto = \"\"\"\n      classification_loss {\n        weighted_softmax {\n        }\n      }\n    \"\"\"\n    losses_proto = losses_pb2.Loss()\n    text_format.Merge(losses_text_proto, losses_proto)\n    with self.assertRaises(ValueError):\n      losses_builder._build_localization_loss(losses_proto)\n\n\nclass ClassificationLossBuilderTest(tf.test.TestCase):\n\n  def test_build_weighted_sigmoid_classification_loss(self):\n    losses_text_proto = \"\"\"\n      classification_loss {\n        weighted_sigmoid {\n        }\n      }\n      localization_loss {\n        weighted_l2 {\n        }\n      }\n    \"\"\"\n    losses_proto = losses_pb2.Loss()\n    text_format.Merge(losses_text_proto, losses_proto)\n    classification_loss, _, _, _, _ = losses_builder.build(losses_proto)\n    self.assertTrue(isinstance(classification_loss,\n                               losses.WeightedSigmoidClassificationLoss))\n\n  def test_build_weighted_softmax_classification_loss(self):\n    losses_text_proto = \"\"\"\n      classification_loss {\n        weighted_softmax {\n        }\n      }\n      localization_loss {\n        weighted_l2 {\n        }\n      }\n    \"\"\"\n    losses_proto = losses_pb2.Loss()\n    text_format.Merge(losses_text_proto, losses_proto)\n    classification_loss, _, _, _, _ = losses_builder.build(losses_proto)\n    self.assertTrue(isinstance(classification_loss,\n                               losses.WeightedSoftmaxClassificationLoss))\n\n  def test_build_bootstrapped_sigmoid_classification_loss(self):\n    losses_text_proto = \"\"\"\n      classification_loss {\n        bootstrapped_sigmoid {\n          alpha: 0.5\n        }\n      }\n      localization_loss {\n        weighted_l2 {\n        }\n      }\n    \"\"\"\n    losses_proto = losses_pb2.Loss()\n    text_format.Merge(losses_text_proto, losses_proto)\n    classification_loss, _, _, _, _ = losses_builder.build(losses_proto)\n    self.assertTrue(isinstance(classification_loss,\n                               losses.BootstrappedSigmoidClassificationLoss))\n\n  def test_anchorwise_output(self):\n    losses_text_proto = \"\"\"\n      classification_loss {\n        weighted_sigmoid {\n          anchorwise_output: true\n        }\n      }\n      localization_loss {\n        weighted_l2 {\n        }\n      }\n    \"\"\"\n    losses_proto = losses_pb2.Loss()\n    text_format.Merge(losses_text_proto, losses_proto)\n    classification_loss, _, _, _, _ = losses_builder.build(losses_proto)\n    self.assertTrue(isinstance(classification_loss,\n                               losses.WeightedSigmoidClassificationLoss))\n    predictions = tf.constant([[[0.0, 1.0, 0.0], [0.0, 0.5, 0.5]]])\n    targets = tf.constant([[[0.0, 1.0, 0.0], [0.0, 0.0, 1.0]]])\n    weights = tf.constant([[1.0, 1.0]])\n    loss = classification_loss(predictions, targets, weights=weights)\n    self.assertEqual(loss.shape, [1, 2])\n\n  def test_raise_error_on_empty_config(self):\n    losses_text_proto = \"\"\"\n      localization_loss {\n        weighted_l2 {\n        }\n      }\n    \"\"\"\n    losses_proto = losses_pb2.Loss()\n    text_format.Merge(losses_text_proto, losses_proto)\n    with self.assertRaises(ValueError):\n      losses_builder.build(losses_proto)\n\n\nclass HardExampleMinerBuilderTest(tf.test.TestCase):\n\n  def test_do_not_build_hard_example_miner_by_default(self):\n    losses_text_proto = \"\"\"\n      localization_loss {\n        weighted_l2 {\n        }\n      }\n      classification_loss {\n        weighted_softmax {\n        }\n      }\n    \"\"\"\n    losses_proto = losses_pb2.Loss()\n    text_format.Merge(losses_text_proto, losses_proto)\n    _, _, _, _, hard_example_miner = losses_builder.build(losses_proto)\n    self.assertEqual(hard_example_miner, None)\n\n  def test_build_hard_example_miner_for_classification_loss(self):\n    losses_text_proto = \"\"\"\n      localization_loss {\n        weighted_l2 {\n        }\n      }\n      classification_loss {\n        weighted_softmax {\n        }\n      }\n      hard_example_miner {\n        loss_type: CLASSIFICATION\n      }\n    \"\"\"\n    losses_proto = losses_pb2.Loss()\n    text_format.Merge(losses_text_proto, losses_proto)\n    _, _, _, _, hard_example_miner = losses_builder.build(losses_proto)\n    self.assertTrue(isinstance(hard_example_miner, losses.HardExampleMiner))\n    self.assertEqual(hard_example_miner._loss_type, 'cls')\n\n  def test_build_hard_example_miner_for_localization_loss(self):\n    losses_text_proto = \"\"\"\n      localization_loss {\n        weighted_l2 {\n        }\n      }\n      classification_loss {\n        weighted_softmax {\n        }\n      }\n      hard_example_miner {\n        loss_type: LOCALIZATION\n      }\n    \"\"\"\n    losses_proto = losses_pb2.Loss()\n    text_format.Merge(losses_text_proto, losses_proto)\n    _, _, _, _, hard_example_miner = losses_builder.build(losses_proto)\n    self.assertTrue(isinstance(hard_example_miner, losses.HardExampleMiner))\n    self.assertEqual(hard_example_miner._loss_type, 'loc')\n\n  def test_build_hard_example_miner_with_non_default_values(self):\n    losses_text_proto = \"\"\"\n      localization_loss {\n        weighted_l2 {\n        }\n      }\n      classification_loss {\n        weighted_softmax {\n        }\n      }\n      hard_example_miner {\n        num_hard_examples: 32\n        iou_threshold: 0.5\n        loss_type: LOCALIZATION\n        max_negatives_per_positive: 10\n        min_negatives_per_image: 3\n      }\n    \"\"\"\n    losses_proto = losses_pb2.Loss()\n    text_format.Merge(losses_text_proto, losses_proto)\n    _, _, _, _, hard_example_miner = losses_builder.build(losses_proto)\n    self.assertTrue(isinstance(hard_example_miner, losses.HardExampleMiner))\n    self.assertEqual(hard_example_miner._num_hard_examples, 32)\n    self.assertAlmostEqual(hard_example_miner._iou_threshold, 0.5)\n    self.assertEqual(hard_example_miner._max_negatives_per_positive, 10)\n    self.assertEqual(hard_example_miner._min_negatives_per_image, 3)\n\n\nclass LossBuilderTest(tf.test.TestCase):\n\n  def test_build_all_loss_parameters(self):\n    losses_text_proto = \"\"\"\n      localization_loss {\n        weighted_l2 {\n        }\n      }\n      classification_loss {\n        weighted_softmax {\n        }\n      }\n      hard_example_miner {\n      }\n      classification_weight: 0.8\n      localization_weight: 0.2\n    \"\"\"\n    losses_proto = losses_pb2.Loss()\n    text_format.Merge(losses_text_proto, losses_proto)\n    (classification_loss, localization_loss,\n     classification_weight, localization_weight,\n     hard_example_miner) = losses_builder.build(losses_proto)\n    self.assertTrue(isinstance(hard_example_miner, losses.HardExampleMiner))\n    self.assertTrue(isinstance(classification_loss,\n                               losses.WeightedSoftmaxClassificationLoss))\n    self.assertTrue(isinstance(localization_loss,\n                               losses.WeightedL2LocalizationLoss))\n    self.assertAlmostEqual(classification_weight, 0.8)\n    self.assertAlmostEqual(localization_weight, 0.2)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/matcher_builder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"A function to build an object detection matcher from configuration.\"\"\"\n\nfrom object_detection.matchers import argmax_matcher\nfrom object_detection.matchers import bipartite_matcher\nfrom object_detection.protos import matcher_pb2\n\n\ndef build(matcher_config):\n  \"\"\"Builds a matcher object based on the matcher config.\n\n  Args:\n    matcher_config: A matcher.proto object containing the config for the desired\n      Matcher.\n\n  Returns:\n    Matcher based on the config.\n\n  Raises:\n    ValueError: On empty matcher proto.\n  \"\"\"\n  if not isinstance(matcher_config, matcher_pb2.Matcher):\n    raise ValueError('matcher_config not of type matcher_pb2.Matcher.')\n  if matcher_config.WhichOneof('matcher_oneof') == 'argmax_matcher':\n    matcher = matcher_config.argmax_matcher\n    matched_threshold = unmatched_threshold = None\n    if not matcher.ignore_thresholds:\n      matched_threshold = matcher.matched_threshold\n      unmatched_threshold = matcher.unmatched_threshold\n    return argmax_matcher.ArgMaxMatcher(\n        matched_threshold=matched_threshold,\n        unmatched_threshold=unmatched_threshold,\n        negatives_lower_than_unmatched=matcher.negatives_lower_than_unmatched,\n        force_match_for_each_row=matcher.force_match_for_each_row)\n  if matcher_config.WhichOneof('matcher_oneof') == 'bipartite_matcher':\n    return bipartite_matcher.GreedyBipartiteMatcher()\n  raise ValueError('Empty matcher.')\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/matcher_builder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for matcher_builder.\"\"\"\n\nimport tensorflow as tf\n\nfrom google.protobuf import text_format\nfrom object_detection.builders import matcher_builder\nfrom object_detection.matchers import argmax_matcher\nfrom object_detection.matchers import bipartite_matcher\nfrom object_detection.protos import matcher_pb2\n\n\nclass MatcherBuilderTest(tf.test.TestCase):\n\n  def test_build_arg_max_matcher_with_defaults(self):\n    matcher_text_proto = \"\"\"\n      argmax_matcher {\n      }\n    \"\"\"\n    matcher_proto = matcher_pb2.Matcher()\n    text_format.Merge(matcher_text_proto, matcher_proto)\n    matcher_object = matcher_builder.build(matcher_proto)\n    self.assertTrue(isinstance(matcher_object, argmax_matcher.ArgMaxMatcher))\n    self.assertAlmostEqual(matcher_object._matched_threshold, 0.5)\n    self.assertAlmostEqual(matcher_object._unmatched_threshold, 0.5)\n    self.assertTrue(matcher_object._negatives_lower_than_unmatched)\n    self.assertFalse(matcher_object._force_match_for_each_row)\n\n  def test_build_arg_max_matcher_without_thresholds(self):\n    matcher_text_proto = \"\"\"\n      argmax_matcher {\n        ignore_thresholds: true\n      }\n    \"\"\"\n    matcher_proto = matcher_pb2.Matcher()\n    text_format.Merge(matcher_text_proto, matcher_proto)\n    matcher_object = matcher_builder.build(matcher_proto)\n    self.assertTrue(isinstance(matcher_object, argmax_matcher.ArgMaxMatcher))\n    self.assertEqual(matcher_object._matched_threshold, None)\n    self.assertEqual(matcher_object._unmatched_threshold, None)\n    self.assertTrue(matcher_object._negatives_lower_than_unmatched)\n    self.assertFalse(matcher_object._force_match_for_each_row)\n\n  def test_build_arg_max_matcher_with_non_default_parameters(self):\n    matcher_text_proto = \"\"\"\n      argmax_matcher {\n        matched_threshold: 0.7\n        unmatched_threshold: 0.3\n        negatives_lower_than_unmatched: false\n        force_match_for_each_row: true\n      }\n    \"\"\"\n    matcher_proto = matcher_pb2.Matcher()\n    text_format.Merge(matcher_text_proto, matcher_proto)\n    matcher_object = matcher_builder.build(matcher_proto)\n    self.assertTrue(isinstance(matcher_object, argmax_matcher.ArgMaxMatcher))\n    self.assertAlmostEqual(matcher_object._matched_threshold, 0.7)\n    self.assertAlmostEqual(matcher_object._unmatched_threshold, 0.3)\n    self.assertFalse(matcher_object._negatives_lower_than_unmatched)\n    self.assertTrue(matcher_object._force_match_for_each_row)\n\n  def test_build_bipartite_matcher(self):\n    matcher_text_proto = \"\"\"\n      bipartite_matcher {\n      }\n    \"\"\"\n    matcher_proto = matcher_pb2.Matcher()\n    text_format.Merge(matcher_text_proto, matcher_proto)\n    matcher_object = matcher_builder.build(matcher_proto)\n    self.assertTrue(\n        isinstance(matcher_object, bipartite_matcher.GreedyBipartiteMatcher))\n\n  def test_raise_error_on_empty_matcher(self):\n    matcher_text_proto = \"\"\"\n    \"\"\"\n    matcher_proto = matcher_pb2.Matcher()\n    text_format.Merge(matcher_text_proto, matcher_proto)\n    with self.assertRaises(ValueError):\n      matcher_builder.build(matcher_proto)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/model_builder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"A function to build a DetectionModel from configuration.\"\"\"\nfrom object_detection.builders import anchor_generator_builder\nfrom object_detection.builders import box_coder_builder\nfrom object_detection.builders import box_predictor_builder\nfrom object_detection.builders import hyperparams_builder\nfrom object_detection.builders import image_resizer_builder\nfrom object_detection.builders import losses_builder\nfrom object_detection.builders import matcher_builder\nfrom object_detection.builders import post_processing_builder\nfrom object_detection.builders import region_similarity_calculator_builder as sim_calc\nfrom object_detection.core import box_predictor\nfrom object_detection.meta_architectures import faster_rcnn_meta_arch\nfrom object_detection.meta_architectures import rfcn_meta_arch\nfrom object_detection.meta_architectures import ssd_meta_arch\nfrom object_detection.models import faster_rcnn_inception_resnet_v2_feature_extractor as frcnn_inc_res\nfrom object_detection.models import faster_rcnn_resnet_v1_feature_extractor as frcnn_resnet_v1\nfrom object_detection.models.ssd_inception_v2_feature_extractor import SSDInceptionV2FeatureExtractor\nfrom object_detection.models.ssd_mobilenet_v1_feature_extractor import SSDMobileNetV1FeatureExtractor\nfrom object_detection.protos import model_pb2\n\n# A map of names to SSD feature extractors.\nSSD_FEATURE_EXTRACTOR_CLASS_MAP = {\n    'ssd_inception_v2': SSDInceptionV2FeatureExtractor,\n    'ssd_mobilenet_v1': SSDMobileNetV1FeatureExtractor,\n}\n\n# A map of names to Faster R-CNN feature extractors.\nFASTER_RCNN_FEATURE_EXTRACTOR_CLASS_MAP = {\n    'faster_rcnn_resnet50':\n    frcnn_resnet_v1.FasterRCNNResnet50FeatureExtractor,\n    'faster_rcnn_resnet101':\n    frcnn_resnet_v1.FasterRCNNResnet101FeatureExtractor,\n    'faster_rcnn_resnet152':\n    frcnn_resnet_v1.FasterRCNNResnet152FeatureExtractor,\n    'faster_rcnn_inception_resnet_v2':\n    frcnn_inc_res.FasterRCNNInceptionResnetV2FeatureExtractor\n}\n\n\ndef build(model_config, is_training):\n  \"\"\"Builds a DetectionModel based on the model config.\n\n  Args:\n    model_config: A model.proto object containing the config for the desired\n      DetectionModel.\n    is_training: True if this model is being built for training purposes.\n\n  Returns:\n    DetectionModel based on the config.\n\n  Raises:\n    ValueError: On invalid meta architecture or model.\n  \"\"\"\n  if not isinstance(model_config, model_pb2.DetectionModel):\n    raise ValueError('model_config not of type model_pb2.DetectionModel.')\n  meta_architecture = model_config.WhichOneof('model')\n  if meta_architecture == 'ssd':\n    return _build_ssd_model(model_config.ssd, is_training)\n  if meta_architecture == 'faster_rcnn':\n    return _build_faster_rcnn_model(model_config.faster_rcnn, is_training)\n  raise ValueError('Unknown meta architecture: {}'.format(meta_architecture))\n\n\ndef _build_ssd_feature_extractor(feature_extractor_config, is_training,\n                                 reuse_weights=None):\n  \"\"\"Builds a ssd_meta_arch.SSDFeatureExtractor based on config.\n\n  Args:\n    feature_extractor_config: A SSDFeatureExtractor proto config from ssd.proto.\n    is_training: True if this feature extractor is being built for training.\n    reuse_weights: if the feature extractor should reuse weights.\n\n  Returns:\n    ssd_meta_arch.SSDFeatureExtractor based on config.\n\n  Raises:\n    ValueError: On invalid feature extractor type.\n  \"\"\"\n  feature_type = feature_extractor_config.type\n  depth_multiplier = feature_extractor_config.depth_multiplier\n  min_depth = feature_extractor_config.min_depth\n  conv_hyperparams = hyperparams_builder.build(\n      feature_extractor_config.conv_hyperparams, is_training)\n\n  if feature_type not in SSD_FEATURE_EXTRACTOR_CLASS_MAP:\n    raise ValueError('Unknown ssd feature_extractor: {}'.format(feature_type))\n\n  feature_extractor_class = SSD_FEATURE_EXTRACTOR_CLASS_MAP[feature_type]\n  return feature_extractor_class(depth_multiplier, min_depth, conv_hyperparams,\n                                 reuse_weights)\n\n\ndef _build_ssd_model(ssd_config, is_training):\n  \"\"\"Builds an SSD detection model based on the model config.\n\n  Args:\n    ssd_config: A ssd.proto object containing the config for the desired\n      SSDMetaArch.\n    is_training: True if this model is being built for training purposes.\n\n  Returns:\n    SSDMetaArch based on the config.\n  Raises:\n    ValueError: If ssd_config.type is not recognized (i.e. not registered in\n      model_class_map).\n  \"\"\"\n  num_classes = ssd_config.num_classes\n\n  # Feature extractor\n  feature_extractor = _build_ssd_feature_extractor(ssd_config.feature_extractor,\n                                                   is_training)\n\n  box_coder = box_coder_builder.build(ssd_config.box_coder)\n  matcher = matcher_builder.build(ssd_config.matcher)\n  region_similarity_calculator = sim_calc.build(\n      ssd_config.similarity_calculator)\n  ssd_box_predictor = box_predictor_builder.build(hyperparams_builder.build,\n                                                  ssd_config.box_predictor,\n                                                  is_training, num_classes)\n  anchor_generator = anchor_generator_builder.build(\n      ssd_config.anchor_generator)\n  image_resizer_fn = image_resizer_builder.build(ssd_config.image_resizer)\n  non_max_suppression_fn, score_conversion_fn = post_processing_builder.build(\n      ssd_config.post_processing)\n  (classification_loss, localization_loss, classification_weight,\n   localization_weight,\n   hard_example_miner) = losses_builder.build(ssd_config.loss)\n  normalize_loss_by_num_matches = ssd_config.normalize_loss_by_num_matches\n\n  return ssd_meta_arch.SSDMetaArch(\n      is_training,\n      anchor_generator,\n      ssd_box_predictor,\n      box_coder,\n      feature_extractor,\n      matcher,\n      region_similarity_calculator,\n      image_resizer_fn,\n      non_max_suppression_fn,\n      score_conversion_fn,\n      classification_loss,\n      localization_loss,\n      classification_weight,\n      localization_weight,\n      normalize_loss_by_num_matches,\n      hard_example_miner)\n\n\ndef _build_faster_rcnn_feature_extractor(\n    feature_extractor_config, is_training, reuse_weights=None):\n  \"\"\"Builds a faster_rcnn_meta_arch.FasterRCNNFeatureExtractor based on config.\n\n  Args:\n    feature_extractor_config: A FasterRcnnFeatureExtractor proto config from\n      faster_rcnn.proto.\n    is_training: True if this feature extractor is being built for training.\n    reuse_weights: if the feature extractor should reuse weights.\n\n  Returns:\n    faster_rcnn_meta_arch.FasterRCNNFeatureExtractor based on config.\n\n  Raises:\n    ValueError: On invalid feature extractor type.\n  \"\"\"\n  feature_type = feature_extractor_config.type\n  first_stage_features_stride = (\n      feature_extractor_config.first_stage_features_stride)\n\n  if feature_type not in FASTER_RCNN_FEATURE_EXTRACTOR_CLASS_MAP:\n    raise ValueError('Unknown Faster R-CNN feature_extractor: {}'.format(\n        feature_type))\n  feature_extractor_class = FASTER_RCNN_FEATURE_EXTRACTOR_CLASS_MAP[\n      feature_type]\n  return feature_extractor_class(\n      is_training, first_stage_features_stride, reuse_weights)\n\n\ndef _build_faster_rcnn_model(frcnn_config, is_training):\n  \"\"\"Builds a Faster R-CNN or R-FCN detection model based on the model config.\n\n  Builds R-FCN model if the second_stage_box_predictor in the config is of type\n  `rfcn_box_predictor` else builds a Faster R-CNN model.\n\n  Args:\n    frcnn_config: A faster_rcnn.proto object containing the config for the\n    desired FasterRCNNMetaArch or RFCNMetaArch.\n    is_training: True if this model is being built for training purposes.\n\n  Returns:\n    FasterRCNNMetaArch based on the config.\n  Raises:\n    ValueError: If frcnn_config.type is not recognized (i.e. not registered in\n      model_class_map).\n  \"\"\"\n  num_classes = frcnn_config.num_classes\n  image_resizer_fn = image_resizer_builder.build(frcnn_config.image_resizer)\n\n  feature_extractor = _build_faster_rcnn_feature_extractor(\n      frcnn_config.feature_extractor, is_training)\n\n  first_stage_only = frcnn_config.first_stage_only\n  first_stage_anchor_generator = anchor_generator_builder.build(\n      frcnn_config.first_stage_anchor_generator)\n\n  first_stage_atrous_rate = frcnn_config.first_stage_atrous_rate\n  first_stage_box_predictor_arg_scope = hyperparams_builder.build(\n      frcnn_config.first_stage_box_predictor_conv_hyperparams, is_training)\n  first_stage_box_predictor_kernel_size = (\n      frcnn_config.first_stage_box_predictor_kernel_size)\n  first_stage_box_predictor_depth = frcnn_config.first_stage_box_predictor_depth\n  first_stage_minibatch_size = frcnn_config.first_stage_minibatch_size\n  first_stage_positive_balance_fraction = (\n      frcnn_config.first_stage_positive_balance_fraction)\n  first_stage_nms_score_threshold = frcnn_config.first_stage_nms_score_threshold\n  first_stage_nms_iou_threshold = frcnn_config.first_stage_nms_iou_threshold\n  first_stage_max_proposals = frcnn_config.first_stage_max_proposals\n  first_stage_loc_loss_weight = (\n      frcnn_config.first_stage_localization_loss_weight)\n  first_stage_obj_loss_weight = frcnn_config.first_stage_objectness_loss_weight\n\n  initial_crop_size = frcnn_config.initial_crop_size\n  maxpool_kernel_size = frcnn_config.maxpool_kernel_size\n  maxpool_stride = frcnn_config.maxpool_stride\n\n  second_stage_box_predictor = box_predictor_builder.build(\n      hyperparams_builder.build,\n      frcnn_config.second_stage_box_predictor,\n      is_training=is_training,\n      num_classes=num_classes)\n  second_stage_batch_size = frcnn_config.second_stage_batch_size\n  second_stage_balance_fraction = frcnn_config.second_stage_balance_fraction\n  (second_stage_non_max_suppression_fn, second_stage_score_conversion_fn\n  ) = post_processing_builder.build(frcnn_config.second_stage_post_processing)\n  second_stage_localization_loss_weight = (\n      frcnn_config.second_stage_localization_loss_weight)\n  second_stage_classification_loss_weight = (\n      frcnn_config.second_stage_classification_loss_weight)\n\n  hard_example_miner = None\n  if frcnn_config.HasField('hard_example_miner'):\n    hard_example_miner = losses_builder.build_hard_example_miner(\n        frcnn_config.hard_example_miner,\n        second_stage_classification_loss_weight,\n        second_stage_localization_loss_weight)\n\n  common_kwargs = {\n      'is_training': is_training,\n      'num_classes': num_classes,\n      'image_resizer_fn': image_resizer_fn,\n      'feature_extractor': feature_extractor,\n      'first_stage_only': first_stage_only,\n      'first_stage_anchor_generator': first_stage_anchor_generator,\n      'first_stage_atrous_rate': first_stage_atrous_rate,\n      'first_stage_box_predictor_arg_scope':\n      first_stage_box_predictor_arg_scope,\n      'first_stage_box_predictor_kernel_size':\n      first_stage_box_predictor_kernel_size,\n      'first_stage_box_predictor_depth': first_stage_box_predictor_depth,\n      'first_stage_minibatch_size': first_stage_minibatch_size,\n      'first_stage_positive_balance_fraction':\n      first_stage_positive_balance_fraction,\n      'first_stage_nms_score_threshold': first_stage_nms_score_threshold,\n      'first_stage_nms_iou_threshold': first_stage_nms_iou_threshold,\n      'first_stage_max_proposals': first_stage_max_proposals,\n      'first_stage_localization_loss_weight': first_stage_loc_loss_weight,\n      'first_stage_objectness_loss_weight': first_stage_obj_loss_weight,\n      'second_stage_batch_size': second_stage_batch_size,\n      'second_stage_balance_fraction': second_stage_balance_fraction,\n      'second_stage_non_max_suppression_fn':\n      second_stage_non_max_suppression_fn,\n      'second_stage_score_conversion_fn': second_stage_score_conversion_fn,\n      'second_stage_localization_loss_weight':\n      second_stage_localization_loss_weight,\n      'second_stage_classification_loss_weight':\n      second_stage_classification_loss_weight,\n      'hard_example_miner': hard_example_miner}\n\n  if isinstance(second_stage_box_predictor, box_predictor.RfcnBoxPredictor):\n    return rfcn_meta_arch.RFCNMetaArch(\n        second_stage_rfcn_box_predictor=second_stage_box_predictor,\n        **common_kwargs)\n  else:\n    return faster_rcnn_meta_arch.FasterRCNNMetaArch(\n        initial_crop_size=initial_crop_size,\n        maxpool_kernel_size=maxpool_kernel_size,\n        maxpool_stride=maxpool_stride,\n        second_stage_mask_rcnn_box_predictor=second_stage_box_predictor,\n        **common_kwargs)\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/model_builder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.models.model_builder.\"\"\"\n\nimport tensorflow as tf\n\nfrom google.protobuf import text_format\nfrom object_detection.builders import model_builder\nfrom object_detection.meta_architectures import faster_rcnn_meta_arch\nfrom object_detection.meta_architectures import rfcn_meta_arch\nfrom object_detection.meta_architectures import ssd_meta_arch\nfrom object_detection.models import faster_rcnn_inception_resnet_v2_feature_extractor as frcnn_inc_res\nfrom object_detection.models import faster_rcnn_resnet_v1_feature_extractor as frcnn_resnet_v1\nfrom object_detection.models.ssd_inception_v2_feature_extractor import SSDInceptionV2FeatureExtractor\nfrom object_detection.models.ssd_mobilenet_v1_feature_extractor import SSDMobileNetV1FeatureExtractor\nfrom object_detection.protos import model_pb2\n\nFEATURE_EXTRACTOR_MAPS = {\n    'faster_rcnn_resnet50':\n    frcnn_resnet_v1.FasterRCNNResnet50FeatureExtractor,\n    'faster_rcnn_resnet101':\n    frcnn_resnet_v1.FasterRCNNResnet101FeatureExtractor,\n    'faster_rcnn_resnet152':\n    frcnn_resnet_v1.FasterRCNNResnet152FeatureExtractor\n}\n\n\nclass ModelBuilderTest(tf.test.TestCase):\n\n  def create_model(self, model_config):\n    \"\"\"Builds a DetectionModel based on the model config.\n\n    Args:\n      model_config: A model.proto object containing the config for the desired\n        DetectionModel.\n\n    Returns:\n      DetectionModel based on the config.\n    \"\"\"\n    return model_builder.build(model_config, is_training=True)\n\n  def test_create_ssd_inception_v2_model_from_config(self):\n    model_text_proto = \"\"\"\n      ssd {\n        feature_extractor {\n          type: 'ssd_inception_v2'\n          conv_hyperparams {\n            regularizer {\n                l2_regularizer {\n                }\n              }\n              initializer {\n                truncated_normal_initializer {\n                }\n              }\n          }\n        }\n        box_coder {\n          faster_rcnn_box_coder {\n          }\n        }\n        matcher {\n          argmax_matcher {\n          }\n        }\n        similarity_calculator {\n          iou_similarity {\n          }\n        }\n        anchor_generator {\n          ssd_anchor_generator {\n            aspect_ratios: 1.0\n          }\n        }\n        image_resizer {\n          fixed_shape_resizer {\n            height: 320\n            width: 320\n          }\n        }\n        box_predictor {\n          convolutional_box_predictor {\n            conv_hyperparams {\n              regularizer {\n                l2_regularizer {\n                }\n              }\n              initializer {\n                truncated_normal_initializer {\n                }\n              }\n            }\n          }\n        }\n        loss {\n          classification_loss {\n            weighted_softmax {\n            }\n          }\n          localization_loss {\n            weighted_smooth_l1 {\n            }\n          }\n        }\n      }\"\"\"\n    model_proto = model_pb2.DetectionModel()\n    text_format.Merge(model_text_proto, model_proto)\n    model = self.create_model(model_proto)\n    self.assertIsInstance(model, ssd_meta_arch.SSDMetaArch)\n    self.assertIsInstance(model._feature_extractor,\n                          SSDInceptionV2FeatureExtractor)\n\n  def test_create_ssd_mobilenet_v1_model_from_config(self):\n    model_text_proto = \"\"\"\n      ssd {\n        feature_extractor {\n          type: 'ssd_mobilenet_v1'\n          conv_hyperparams {\n            regularizer {\n                l2_regularizer {\n                }\n              }\n              initializer {\n                truncated_normal_initializer {\n                }\n              }\n          }\n        }\n        box_coder {\n          faster_rcnn_box_coder {\n          }\n        }\n        matcher {\n          argmax_matcher {\n          }\n        }\n        similarity_calculator {\n          iou_similarity {\n          }\n        }\n        anchor_generator {\n          ssd_anchor_generator {\n            aspect_ratios: 1.0\n          }\n        }\n        image_resizer {\n          fixed_shape_resizer {\n            height: 320\n            width: 320\n          }\n        }\n        box_predictor {\n          convolutional_box_predictor {\n            conv_hyperparams {\n              regularizer {\n                l2_regularizer {\n                }\n              }\n              initializer {\n                truncated_normal_initializer {\n                }\n              }\n            }\n          }\n        }\n        loss {\n          classification_loss {\n            weighted_softmax {\n            }\n          }\n          localization_loss {\n            weighted_smooth_l1 {\n            }\n          }\n        }\n      }\"\"\"\n    model_proto = model_pb2.DetectionModel()\n    text_format.Merge(model_text_proto, model_proto)\n    model = self.create_model(model_proto)\n    self.assertIsInstance(model, ssd_meta_arch.SSDMetaArch)\n    self.assertIsInstance(model._feature_extractor,\n                          SSDMobileNetV1FeatureExtractor)\n\n  def test_create_faster_rcnn_resnet_v1_models_from_config(self):\n    model_text_proto = \"\"\"\n      faster_rcnn {\n        num_classes: 3\n        image_resizer {\n          keep_aspect_ratio_resizer {\n            min_dimension: 600\n            max_dimension: 1024\n          }\n        }\n        feature_extractor {\n          type: 'faster_rcnn_resnet101'\n        }\n        first_stage_anchor_generator {\n          grid_anchor_generator {\n            scales: [0.25, 0.5, 1.0, 2.0]\n            aspect_ratios: [0.5, 1.0, 2.0]\n            height_stride: 16\n            width_stride: 16\n          }\n        }\n        first_stage_box_predictor_conv_hyperparams {\n          regularizer {\n            l2_regularizer {\n            }\n          }\n          initializer {\n            truncated_normal_initializer {\n            }\n          }\n        }\n        initial_crop_size: 14\n        maxpool_kernel_size: 2\n        maxpool_stride: 2\n        second_stage_box_predictor {\n          mask_rcnn_box_predictor {\n            fc_hyperparams {\n              op: FC\n              regularizer {\n                l2_regularizer {\n                }\n              }\n              initializer {\n                truncated_normal_initializer {\n                }\n              }\n            }\n          }\n        }\n        second_stage_post_processing {\n          batch_non_max_suppression {\n            score_threshold: 0.01\n            iou_threshold: 0.6\n            max_detections_per_class: 100\n            max_total_detections: 300\n          }\n          score_converter: SOFTMAX\n        }\n      }\"\"\"\n    model_proto = model_pb2.DetectionModel()\n    text_format.Merge(model_text_proto, model_proto)\n    for extractor_type, extractor_class in FEATURE_EXTRACTOR_MAPS.items():\n      model_proto.faster_rcnn.feature_extractor.type = extractor_type\n      model = model_builder.build(model_proto, is_training=True)\n      self.assertIsInstance(model, faster_rcnn_meta_arch.FasterRCNNMetaArch)\n      self.assertIsInstance(model._feature_extractor, extractor_class)\n\n  def test_create_faster_rcnn_inception_resnet_v2_model_from_config(self):\n    model_text_proto = \"\"\"\n      faster_rcnn {\n        num_classes: 3\n        image_resizer {\n          keep_aspect_ratio_resizer {\n            min_dimension: 600\n            max_dimension: 1024\n          }\n        }\n        feature_extractor {\n          type: 'faster_rcnn_inception_resnet_v2'\n        }\n        first_stage_anchor_generator {\n          grid_anchor_generator {\n            scales: [0.25, 0.5, 1.0, 2.0]\n            aspect_ratios: [0.5, 1.0, 2.0]\n            height_stride: 16\n            width_stride: 16\n          }\n        }\n        first_stage_box_predictor_conv_hyperparams {\n          regularizer {\n            l2_regularizer {\n            }\n          }\n          initializer {\n            truncated_normal_initializer {\n            }\n          }\n        }\n        initial_crop_size: 17\n        maxpool_kernel_size: 1\n        maxpool_stride: 1\n        second_stage_box_predictor {\n          mask_rcnn_box_predictor {\n            fc_hyperparams {\n              op: FC\n              regularizer {\n                l2_regularizer {\n                }\n              }\n              initializer {\n                truncated_normal_initializer {\n                }\n              }\n            }\n          }\n        }\n        second_stage_post_processing {\n          batch_non_max_suppression {\n            score_threshold: 0.01\n            iou_threshold: 0.6\n            max_detections_per_class: 100\n            max_total_detections: 300\n          }\n          score_converter: SOFTMAX\n        }\n      }\"\"\"\n    model_proto = model_pb2.DetectionModel()\n    text_format.Merge(model_text_proto, model_proto)\n    model = model_builder.build(model_proto, is_training=True)\n    self.assertIsInstance(model, faster_rcnn_meta_arch.FasterRCNNMetaArch)\n    self.assertIsInstance(\n        model._feature_extractor,\n        frcnn_inc_res.FasterRCNNInceptionResnetV2FeatureExtractor)\n\n  def test_create_faster_rcnn_model_from_config_with_example_miner(self):\n    model_text_proto = \"\"\"\n      faster_rcnn {\n        num_classes: 3\n        feature_extractor {\n          type: 'faster_rcnn_inception_resnet_v2'\n        }\n        image_resizer {\n          keep_aspect_ratio_resizer {\n            min_dimension: 600\n            max_dimension: 1024\n          }\n        }\n        first_stage_anchor_generator {\n          grid_anchor_generator {\n            scales: [0.25, 0.5, 1.0, 2.0]\n            aspect_ratios: [0.5, 1.0, 2.0]\n            height_stride: 16\n            width_stride: 16\n          }\n        }\n        first_stage_box_predictor_conv_hyperparams {\n          regularizer {\n            l2_regularizer {\n            }\n          }\n          initializer {\n            truncated_normal_initializer {\n            }\n          }\n        }\n        second_stage_box_predictor {\n          mask_rcnn_box_predictor {\n            fc_hyperparams {\n              op: FC\n              regularizer {\n                l2_regularizer {\n                }\n              }\n              initializer {\n                truncated_normal_initializer {\n                }\n              }\n            }\n          }\n        }\n        hard_example_miner {\n          num_hard_examples: 10\n          iou_threshold: 0.99\n        }\n      }\"\"\"\n    model_proto = model_pb2.DetectionModel()\n    text_format.Merge(model_text_proto, model_proto)\n    model = model_builder.build(model_proto, is_training=True)\n    self.assertIsNotNone(model._hard_example_miner)\n\n  def test_create_rfcn_resnet_v1_model_from_config(self):\n    model_text_proto = \"\"\"\n      faster_rcnn {\n        num_classes: 3\n        image_resizer {\n          keep_aspect_ratio_resizer {\n            min_dimension: 600\n            max_dimension: 1024\n          }\n        }\n        feature_extractor {\n          type: 'faster_rcnn_resnet101'\n        }\n        first_stage_anchor_generator {\n          grid_anchor_generator {\n            scales: [0.25, 0.5, 1.0, 2.0]\n            aspect_ratios: [0.5, 1.0, 2.0]\n            height_stride: 16\n            width_stride: 16\n          }\n        }\n        first_stage_box_predictor_conv_hyperparams {\n          regularizer {\n            l2_regularizer {\n            }\n          }\n          initializer {\n            truncated_normal_initializer {\n            }\n          }\n        }\n        initial_crop_size: 14\n        maxpool_kernel_size: 2\n        maxpool_stride: 2\n        second_stage_box_predictor {\n          rfcn_box_predictor {\n            conv_hyperparams {\n              op: CONV\n              regularizer {\n                l2_regularizer {\n                }\n              }\n              initializer {\n                truncated_normal_initializer {\n                }\n              }\n            }\n          }\n        }\n        second_stage_post_processing {\n          batch_non_max_suppression {\n            score_threshold: 0.01\n            iou_threshold: 0.6\n            max_detections_per_class: 100\n            max_total_detections: 300\n          }\n          score_converter: SOFTMAX\n        }\n      }\"\"\"\n    model_proto = model_pb2.DetectionModel()\n    text_format.Merge(model_text_proto, model_proto)\n    for extractor_type, extractor_class in FEATURE_EXTRACTOR_MAPS.items():\n      model_proto.faster_rcnn.feature_extractor.type = extractor_type\n      model = model_builder.build(model_proto, is_training=True)\n      self.assertIsInstance(model, rfcn_meta_arch.RFCNMetaArch)\n      self.assertIsInstance(model._feature_extractor, extractor_class)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/optimizer_builder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Functions to build DetectionModel training optimizers.\"\"\"\n\nimport tensorflow as tf\nfrom object_detection.utils import learning_schedules\n\nslim = tf.contrib.slim\n\n\ndef build(optimizer_config, global_summaries):\n  \"\"\"Create optimizer based on config.\n\n  Args:\n    optimizer_config: A Optimizer proto message.\n    global_summaries: A set to attach learning rate summary to.\n\n  Returns:\n    An optimizer.\n\n  Raises:\n    ValueError: when using an unsupported input data type.\n  \"\"\"\n  optimizer_type = optimizer_config.WhichOneof('optimizer')\n  optimizer = None\n\n  if optimizer_type == 'rms_prop_optimizer':\n    config = optimizer_config.rms_prop_optimizer\n    optimizer = tf.train.RMSPropOptimizer(\n        _create_learning_rate(config.learning_rate, global_summaries),\n        decay=config.decay,\n        momentum=config.momentum_optimizer_value,\n        epsilon=config.epsilon)\n\n  if optimizer_type == 'momentum_optimizer':\n    config = optimizer_config.momentum_optimizer\n    optimizer = tf.train.MomentumOptimizer(\n        _create_learning_rate(config.learning_rate, global_summaries),\n        momentum=config.momentum_optimizer_value)\n\n  if optimizer_type == 'adam_optimizer':\n    config = optimizer_config.adam_optimizer\n    optimizer = tf.train.AdamOptimizer(\n        _create_learning_rate(config.learning_rate, global_summaries))\n\n  if optimizer is None:\n    raise ValueError('Optimizer %s not supported.' % optimizer_type)\n\n  if optimizer_config.use_moving_average:\n    optimizer = tf.contrib.opt.MovingAverageOptimizer(\n        optimizer, average_decay=optimizer_config.moving_average_decay)\n\n  return optimizer\n\n\ndef _create_learning_rate(learning_rate_config, global_summaries):\n  \"\"\"Create optimizer learning rate based on config.\n\n  Args:\n    learning_rate_config: A LearningRate proto message.\n    global_summaries: A set to attach learning rate summary to.\n\n  Returns:\n    A learning rate.\n\n  Raises:\n    ValueError: when using an unsupported input data type.\n  \"\"\"\n  learning_rate = None\n  learning_rate_type = learning_rate_config.WhichOneof('learning_rate')\n  if learning_rate_type == 'constant_learning_rate':\n    config = learning_rate_config.constant_learning_rate\n    learning_rate = config.learning_rate\n\n  if learning_rate_type == 'exponential_decay_learning_rate':\n    config = learning_rate_config.exponential_decay_learning_rate\n    learning_rate = tf.train.exponential_decay(\n        config.initial_learning_rate,\n        slim.get_or_create_global_step(),\n        config.decay_steps,\n        config.decay_factor,\n        staircase=config.staircase)\n\n  if learning_rate_type == 'manual_step_learning_rate':\n    config = learning_rate_config.manual_step_learning_rate\n    if not config.schedule:\n      raise ValueError('Empty learning rate schedule.')\n    learning_rate_step_boundaries = [x.step for x in config.schedule]\n    learning_rate_sequence = [config.initial_learning_rate]\n    learning_rate_sequence += [x.learning_rate for x in config.schedule]\n    learning_rate = learning_schedules.manual_stepping(\n        slim.get_or_create_global_step(), learning_rate_step_boundaries,\n        learning_rate_sequence)\n\n  if learning_rate is None:\n    raise ValueError('Learning_rate %s not supported.' % learning_rate_type)\n\n  global_summaries.add(tf.summary.scalar('Learning Rate', learning_rate))\n  return learning_rate\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/optimizer_builder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for optimizer_builder.\"\"\"\n\nimport tensorflow as tf\n\nfrom google.protobuf import text_format\n\nfrom object_detection.builders import optimizer_builder\nfrom object_detection.protos import optimizer_pb2\n\n\nclass LearningRateBuilderTest(tf.test.TestCase):\n\n  def testBuildConstantLearningRate(self):\n    learning_rate_text_proto = \"\"\"\n      constant_learning_rate {\n        learning_rate: 0.004\n      }\n    \"\"\"\n    global_summaries = set([])\n    learning_rate_proto = optimizer_pb2.LearningRate()\n    text_format.Merge(learning_rate_text_proto, learning_rate_proto)\n    learning_rate = optimizer_builder._create_learning_rate(\n        learning_rate_proto, global_summaries)\n    self.assertAlmostEqual(learning_rate, 0.004)\n\n  def testBuildExponentialDecayLearningRate(self):\n    learning_rate_text_proto = \"\"\"\n      exponential_decay_learning_rate {\n        initial_learning_rate: 0.004\n        decay_steps: 99999\n        decay_factor: 0.85\n        staircase: false\n      }\n    \"\"\"\n    global_summaries = set([])\n    learning_rate_proto = optimizer_pb2.LearningRate()\n    text_format.Merge(learning_rate_text_proto, learning_rate_proto)\n    learning_rate = optimizer_builder._create_learning_rate(\n        learning_rate_proto, global_summaries)\n    self.assertTrue(isinstance(learning_rate, tf.Tensor))\n\n  def testBuildManualStepLearningRate(self):\n    learning_rate_text_proto = \"\"\"\n      manual_step_learning_rate {\n        schedule {\n          step: 0\n          learning_rate: 0.006\n        }\n        schedule {\n          step: 90000\n          learning_rate: 0.00006\n        }\n      }\n    \"\"\"\n    global_summaries = set([])\n    learning_rate_proto = optimizer_pb2.LearningRate()\n    text_format.Merge(learning_rate_text_proto, learning_rate_proto)\n    learning_rate = optimizer_builder._create_learning_rate(\n        learning_rate_proto, global_summaries)\n    self.assertTrue(isinstance(learning_rate, tf.Tensor))\n\n  def testRaiseErrorOnEmptyLearningRate(self):\n    learning_rate_text_proto = \"\"\"\n    \"\"\"\n    global_summaries = set([])\n    learning_rate_proto = optimizer_pb2.LearningRate()\n    text_format.Merge(learning_rate_text_proto, learning_rate_proto)\n    with self.assertRaises(ValueError):\n      optimizer_builder._create_learning_rate(\n          learning_rate_proto, global_summaries)\n\n\nclass OptimizerBuilderTest(tf.test.TestCase):\n\n  def testBuildRMSPropOptimizer(self):\n    optimizer_text_proto = \"\"\"\n      rms_prop_optimizer: {\n        learning_rate: {\n          exponential_decay_learning_rate {\n            initial_learning_rate: 0.004\n            decay_steps: 800720\n            decay_factor: 0.95\n          }\n        }\n        momentum_optimizer_value: 0.9\n        decay: 0.9\n        epsilon: 1.0\n      }\n      use_moving_average: false\n    \"\"\"\n    global_summaries = set([])\n    optimizer_proto = optimizer_pb2.Optimizer()\n    text_format.Merge(optimizer_text_proto, optimizer_proto)\n    optimizer = optimizer_builder.build(optimizer_proto, global_summaries)\n    self.assertTrue(isinstance(optimizer, tf.train.RMSPropOptimizer))\n\n  def testBuildMomentumOptimizer(self):\n    optimizer_text_proto = \"\"\"\n      momentum_optimizer: {\n        learning_rate: {\n          constant_learning_rate {\n            learning_rate: 0.001\n          }\n        }\n        momentum_optimizer_value: 0.99\n      }\n      use_moving_average: false\n    \"\"\"\n    global_summaries = set([])\n    optimizer_proto = optimizer_pb2.Optimizer()\n    text_format.Merge(optimizer_text_proto, optimizer_proto)\n    optimizer = optimizer_builder.build(optimizer_proto, global_summaries)\n    self.assertTrue(isinstance(optimizer, tf.train.MomentumOptimizer))\n\n  def testBuildAdamOptimizer(self):\n    optimizer_text_proto = \"\"\"\n      adam_optimizer: {\n        learning_rate: {\n          constant_learning_rate {\n            learning_rate: 0.002\n          }\n        }\n      }\n      use_moving_average: false\n    \"\"\"\n    global_summaries = set([])\n    optimizer_proto = optimizer_pb2.Optimizer()\n    text_format.Merge(optimizer_text_proto, optimizer_proto)\n    optimizer = optimizer_builder.build(optimizer_proto, global_summaries)\n    self.assertTrue(isinstance(optimizer, tf.train.AdamOptimizer))\n\n  def testBuildMovingAverageOptimizer(self):\n    optimizer_text_proto = \"\"\"\n      adam_optimizer: {\n        learning_rate: {\n          constant_learning_rate {\n            learning_rate: 0.002\n          }\n        }\n      }\n      use_moving_average: True\n    \"\"\"\n    global_summaries = set([])\n    optimizer_proto = optimizer_pb2.Optimizer()\n    text_format.Merge(optimizer_text_proto, optimizer_proto)\n    optimizer = optimizer_builder.build(optimizer_proto, global_summaries)\n    self.assertTrue(\n        isinstance(optimizer, tf.contrib.opt.MovingAverageOptimizer))\n\n  def testBuildMovingAverageOptimizerWithNonDefaultDecay(self):\n    optimizer_text_proto = \"\"\"\n      adam_optimizer: {\n        learning_rate: {\n          constant_learning_rate {\n            learning_rate: 0.002\n          }\n        }\n      }\n      use_moving_average: True\n      moving_average_decay: 0.2\n    \"\"\"\n    global_summaries = set([])\n    optimizer_proto = optimizer_pb2.Optimizer()\n    text_format.Merge(optimizer_text_proto, optimizer_proto)\n    optimizer = optimizer_builder.build(optimizer_proto, global_summaries)\n    self.assertTrue(\n        isinstance(optimizer, tf.contrib.opt.MovingAverageOptimizer))\n    # TODO: Find a way to not depend on the private members.\n    self.assertAlmostEqual(optimizer._ema._decay, 0.2)\n\n  def testBuildEmptyOptimizer(self):\n    optimizer_text_proto = \"\"\"\n    \"\"\"\n    global_summaries = set([])\n    optimizer_proto = optimizer_pb2.Optimizer()\n    text_format.Merge(optimizer_text_proto, optimizer_proto)\n    with self.assertRaises(ValueError):\n      optimizer_builder.build(optimizer_proto, global_summaries)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/post_processing_builder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Builder function for post processing operations.\"\"\"\nimport functools\n\nimport tensorflow as tf\nfrom object_detection.core import post_processing\nfrom object_detection.protos import post_processing_pb2\n\n\ndef build(post_processing_config):\n  \"\"\"Builds callables for post-processing operations.\n\n  Builds callables for non-max suppression and score conversion based on the\n  configuration.\n\n  Non-max suppression callable takes `boxes`, `scores`, and optionally\n  `clip_window`, `parallel_iterations` and `scope` as inputs. It returns\n  `nms_boxes`, `nms_scores`, `nms_nms_classes` and `num_detections`. See\n  post_processing.batch_multiclass_non_max_suppression for the type and shape\n  of these tensors.\n\n  Score converter callable should be called with `input` tensor. The callable\n  returns the output from one of 3 tf operations based on the configuration -\n  tf.identity, tf.sigmoid or tf.nn.softmax. See tensorflow documentation for\n  argument and return value descriptions.\n\n  Args:\n    post_processing_config: post_processing.proto object containing the\n      parameters for the post-processing operations.\n\n  Returns:\n    non_max_suppressor_fn: Callable for non-max suppression.\n    score_converter_fn: Callable for score conversion.\n\n  Raises:\n    ValueError: if the post_processing_config is of incorrect type.\n  \"\"\"\n  if not isinstance(post_processing_config, post_processing_pb2.PostProcessing):\n    raise ValueError('post_processing_config not of type '\n                     'post_processing_pb2.Postprocessing.')\n  non_max_suppressor_fn = _build_non_max_suppressor(\n      post_processing_config.batch_non_max_suppression)\n  score_converter_fn = _build_score_converter(\n      post_processing_config.score_converter)\n  return non_max_suppressor_fn, score_converter_fn\n\n\ndef _build_non_max_suppressor(nms_config):\n  \"\"\"Builds non-max suppresson based on the nms config.\n\n  Args:\n    nms_config: post_processing_pb2.PostProcessing.BatchNonMaxSuppression proto.\n\n  Returns:\n    non_max_suppressor_fn: Callable non-max suppressor.\n\n  Raises:\n    ValueError: On incorrect iou_threshold or on incompatible values of\n      max_total_detections and max_detections_per_class.\n  \"\"\"\n  if nms_config.iou_threshold < 0 or nms_config.iou_threshold > 1.0:\n    raise ValueError('iou_threshold not in [0, 1.0].')\n  if nms_config.max_detections_per_class > nms_config.max_total_detections:\n    raise ValueError('max_detections_per_class should be no greater than '\n                     'max_total_detections.')\n\n  non_max_suppressor_fn = functools.partial(\n      post_processing.batch_multiclass_non_max_suppression,\n      score_thresh=nms_config.score_threshold,\n      iou_thresh=nms_config.iou_threshold,\n      max_size_per_class=nms_config.max_detections_per_class,\n      max_total_size=nms_config.max_total_detections)\n  return non_max_suppressor_fn\n\n\ndef _build_score_converter(score_converter_config):\n  \"\"\"Builds score converter based on the config.\n\n  Builds one of [tf.identity, tf.sigmoid, tf.softmax] score converters based on\n  the config.\n\n  Args:\n    score_converter_config: post_processing_pb2.PostProcessing.score_converter.\n\n  Returns:\n    Callable score converter op.\n\n  Raises:\n    ValueError: On unknown score converter.\n  \"\"\"\n  if score_converter_config == post_processing_pb2.PostProcessing.IDENTITY:\n    return tf.identity\n  if score_converter_config == post_processing_pb2.PostProcessing.SIGMOID:\n    return tf.sigmoid\n  if score_converter_config == post_processing_pb2.PostProcessing.SOFTMAX:\n    return tf.nn.softmax\n  raise ValueError('Unknown score converter.')\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/post_processing_builder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for post_processing_builder.\"\"\"\n\nimport tensorflow as tf\nfrom google.protobuf import text_format\nfrom object_detection.builders import post_processing_builder\nfrom object_detection.protos import post_processing_pb2\n\n\nclass PostProcessingBuilderTest(tf.test.TestCase):\n\n  def test_build_non_max_suppressor_with_correct_parameters(self):\n    post_processing_text_proto = \"\"\"\n      batch_non_max_suppression {\n        score_threshold: 0.7\n        iou_threshold: 0.6\n        max_detections_per_class: 100\n        max_total_detections: 300\n      }\n    \"\"\"\n    post_processing_config = post_processing_pb2.PostProcessing()\n    text_format.Merge(post_processing_text_proto, post_processing_config)\n    non_max_suppressor, _ = post_processing_builder.build(\n        post_processing_config)\n    self.assertEqual(non_max_suppressor.keywords['max_size_per_class'], 100)\n    self.assertEqual(non_max_suppressor.keywords['max_total_size'], 300)\n    self.assertAlmostEqual(non_max_suppressor.keywords['score_thresh'], 0.7)\n    self.assertAlmostEqual(non_max_suppressor.keywords['iou_thresh'], 0.6)\n\n  def test_build_identity_score_converter(self):\n    post_processing_text_proto = \"\"\"\n      score_converter: IDENTITY\n    \"\"\"\n    post_processing_config = post_processing_pb2.PostProcessing()\n    text_format.Merge(post_processing_text_proto, post_processing_config)\n    _, score_converter = post_processing_builder.build(post_processing_config)\n    self.assertEqual(score_converter, tf.identity)\n\n  def test_build_sigmoid_score_converter(self):\n    post_processing_text_proto = \"\"\"\n      score_converter: SIGMOID\n    \"\"\"\n    post_processing_config = post_processing_pb2.PostProcessing()\n    text_format.Merge(post_processing_text_proto, post_processing_config)\n    _, score_converter = post_processing_builder.build(post_processing_config)\n    self.assertEqual(score_converter, tf.sigmoid)\n\n  def test_build_softmax_score_converter(self):\n    post_processing_text_proto = \"\"\"\n      score_converter: SOFTMAX\n    \"\"\"\n    post_processing_config = post_processing_pb2.PostProcessing()\n    text_format.Merge(post_processing_text_proto, post_processing_config)\n    _, score_converter = post_processing_builder.build(post_processing_config)\n    self.assertEqual(score_converter, tf.nn.softmax)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/preprocessor_builder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Builder for preprocessing steps.\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.core import preprocessor\nfrom object_detection.protos import preprocessor_pb2\n\n\ndef _get_step_config_from_proto(preprocessor_step_config, step_name):\n  \"\"\"Returns the value of a field named step_name from proto.\n\n  Args:\n    preprocessor_step_config: A preprocessor_pb2.PreprocessingStep object.\n    step_name: Name of the field to get value from.\n\n  Returns:\n    result_dict: a sub proto message from preprocessor_step_config which will be\n                 later converted to a dictionary.\n\n  Raises:\n    ValueError: If field does not exist in proto.\n  \"\"\"\n  for field, value in preprocessor_step_config.ListFields():\n    if field.name == step_name:\n      return value\n\n  raise ValueError('Could not get field %s from proto!', step_name)\n\n\ndef _get_dict_from_proto(config):\n  \"\"\"Helper function to put all proto fields into a dictionary.\n\n  For many preprocessing steps, there's an trivial 1-1 mapping from proto fields\n  to function arguments. This function automatically populates a dictionary with\n  the arguments from the proto.\n\n  Protos that CANNOT be trivially populated include:\n  * nested messages.\n  * steps that check if an optional field is set (ie. where None != 0).\n  * protos that don't map 1-1 to arguments (ie. list should be reshaped).\n  * fields requiring additional validation (ie. repeated field has n elements).\n\n  Args:\n    config: A protobuf object that does not violate the conditions above.\n\n  Returns:\n    result_dict: |config| converted into a python dictionary.\n  \"\"\"\n  result_dict = {}\n  for field, value in config.ListFields():\n    result_dict[field.name] = value\n  return result_dict\n\n\n# A map from a PreprocessingStep proto config field name to the preprocessing\n# function that should be used. The PreprocessingStep proto should be parsable\n# with _get_dict_from_proto.\nPREPROCESSING_FUNCTION_MAP = {\n    'normalize_image': preprocessor.normalize_image,\n    'random_horizontal_flip': preprocessor.random_horizontal_flip,\n    'random_pixel_value_scale': preprocessor.random_pixel_value_scale,\n    'random_image_scale': preprocessor.random_image_scale,\n    'random_rgb_to_gray': preprocessor.random_rgb_to_gray,\n    'random_adjust_brightness': preprocessor.random_adjust_brightness,\n    'random_adjust_contrast': preprocessor.random_adjust_contrast,\n    'random_adjust_hue': preprocessor.random_adjust_hue,\n    'random_adjust_saturation': preprocessor.random_adjust_saturation,\n    'random_distort_color': preprocessor.random_distort_color,\n    'random_jitter_boxes': preprocessor.random_jitter_boxes,\n    'random_crop_to_aspect_ratio': preprocessor.random_crop_to_aspect_ratio,\n    'random_black_patches': preprocessor.random_black_patches,\n    'scale_boxes_to_pixel_coordinates': (\n        preprocessor.scale_boxes_to_pixel_coordinates),\n    'subtract_channel_mean': preprocessor.subtract_channel_mean,\n}\n\n\n# A map to convert from preprocessor_pb2.ResizeImage.Method enum to\n# tf.image.ResizeMethod.\nRESIZE_METHOD_MAP = {\n    preprocessor_pb2.ResizeImage.AREA: tf.image.ResizeMethod.AREA,\n    preprocessor_pb2.ResizeImage.BICUBIC: tf.image.ResizeMethod.BICUBIC,\n    preprocessor_pb2.ResizeImage.BILINEAR: tf.image.ResizeMethod.BILINEAR,\n    preprocessor_pb2.ResizeImage.NEAREST_NEIGHBOR: (\n        tf.image.ResizeMethod.NEAREST_NEIGHBOR),\n}\n\n\ndef build(preprocessor_step_config):\n  \"\"\"Builds preprocessing step based on the configuration.\n\n  Args:\n    preprocessor_step_config: PreprocessingStep configuration proto.\n\n  Returns:\n    function, argmap: A callable function and an argument map to call function\n                      with.\n\n  Raises:\n    ValueError: On invalid configuration.\n  \"\"\"\n  step_type = preprocessor_step_config.WhichOneof('preprocessing_step')\n\n  if step_type in PREPROCESSING_FUNCTION_MAP:\n    preprocessing_function = PREPROCESSING_FUNCTION_MAP[step_type]\n    step_config = _get_step_config_from_proto(preprocessor_step_config,\n                                              step_type)\n    function_args = _get_dict_from_proto(step_config)\n    return (preprocessing_function, function_args)\n\n  if step_type == 'random_crop_image':\n    config = preprocessor_step_config.random_crop_image\n    return (preprocessor.random_crop_image,\n            {\n                'min_object_covered': config.min_object_covered,\n                'aspect_ratio_range': (config.min_aspect_ratio,\n                                       config.max_aspect_ratio),\n                'area_range': (config.min_area, config.max_area),\n                'overlap_thresh': config.overlap_thresh,\n                'random_coef': config.random_coef,\n            })\n\n  if step_type == 'random_pad_image':\n    config = preprocessor_step_config.random_pad_image\n    min_image_size = None\n    if (config.HasField('min_image_height') !=\n        config.HasField('min_image_width')):\n      raise ValueError('min_image_height and min_image_width should be either '\n                       'both set or both unset.')\n    if config.HasField('min_image_height'):\n      min_image_size = (config.min_image_height, config.min_image_width)\n\n    max_image_size = None\n    if (config.HasField('max_image_height') !=\n        config.HasField('max_image_width')):\n      raise ValueError('max_image_height and max_image_width should be either '\n                       'both set or both unset.')\n    if config.HasField('max_image_height'):\n      max_image_size = (config.max_image_height, config.max_image_width)\n\n    pad_color = config.pad_color\n    if pad_color and len(pad_color) != 3:\n      raise ValueError('pad_color should have 3 elements (RGB) if set!')\n    if not pad_color:\n      pad_color = None\n    return (preprocessor.random_pad_image,\n            {\n                'min_image_size': min_image_size,\n                'max_image_size': max_image_size,\n                'pad_color': pad_color,\n            })\n\n  if step_type == 'random_crop_pad_image':\n    config = preprocessor_step_config.random_crop_pad_image\n    min_padded_size_ratio = config.min_padded_size_ratio\n    if min_padded_size_ratio and len(min_padded_size_ratio) != 2:\n      raise ValueError('min_padded_size_ratio should have 3 elements if set!')\n    max_padded_size_ratio = config.max_padded_size_ratio\n    if max_padded_size_ratio and len(max_padded_size_ratio) != 2:\n      raise ValueError('max_padded_size_ratio should have 3 elements if set!')\n    pad_color = config.pad_color\n    if pad_color and len(pad_color) != 3:\n      raise ValueError('pad_color should have 3 elements if set!')\n    return (preprocessor.random_crop_pad_image,\n            {\n                'min_object_covered': config.min_object_covered,\n                'aspect_ratio_range': (config.min_aspect_ratio,\n                                       config.max_aspect_ratio),\n                'area_range': (config.min_area, config.max_area),\n                'overlap_thresh': config.overlap_thresh,\n                'random_coef': config.random_coef,\n                'min_padded_size_ratio': (min_padded_size_ratio if\n                                          min_padded_size_ratio else None),\n                'max_padded_size_ratio': (max_padded_size_ratio if\n                                          max_padded_size_ratio else None),\n                'pad_color': (pad_color if pad_color else None),\n            })\n\n  if step_type == 'random_resize_method':\n    config = preprocessor_step_config.random_resize_method\n    return (preprocessor.random_resize_method,\n            {\n                'target_size': [config.target_height, config.target_width],\n            })\n\n  if step_type == 'resize_image':\n    config = preprocessor_step_config.resize_image\n    method = RESIZE_METHOD_MAP[config.method]\n    return (preprocessor.resize_image,\n            {\n                'new_height': config.new_height,\n                'new_width': config.new_width,\n                'method': method\n            })\n\n  if step_type == 'ssd_random_crop':\n    config = preprocessor_step_config.ssd_random_crop\n    if config.operations:\n      min_object_covered = [op.min_object_covered for op in config.operations]\n      aspect_ratio_range = [(op.min_aspect_ratio, op.max_aspect_ratio)\n                            for op in config.operations]\n      area_range = [(op.min_area, op.max_area) for op in config.operations]\n      overlap_thresh = [op.overlap_thresh for op in config.operations]\n      random_coef = [op.random_coef for op in config.operations]\n      return (preprocessor.ssd_random_crop,\n              {\n                  'min_object_covered': min_object_covered,\n                  'aspect_ratio_range': aspect_ratio_range,\n                  'area_range': area_range,\n                  'overlap_thresh': overlap_thresh,\n                  'random_coef': random_coef,\n              })\n    return (preprocessor.ssd_random_crop, {})\n\n  if step_type == 'ssd_random_crop_pad':\n    config = preprocessor_step_config.ssd_random_crop_pad\n    if config.operations:\n      min_object_covered = [op.min_object_covered for op in config.operations]\n      aspect_ratio_range = [(op.min_aspect_ratio, op.max_aspect_ratio)\n                            for op in config.operations]\n      area_range = [(op.min_area, op.max_area) for op in config.operations]\n      overlap_thresh = [op.overlap_thresh for op in config.operations]\n      random_coef = [op.random_coef for op in config.operations]\n      min_padded_size_ratio = [\n          (op.min_padded_size_ratio[0], op.min_padded_size_ratio[1])\n          for op in config.operations]\n      max_padded_size_ratio = [\n          (op.max_padded_size_ratio[0], op.max_padded_size_ratio[1])\n          for op in config.operations]\n      pad_color = [(op.pad_color_r, op.pad_color_g, op.pad_color_b)\n                   for op in config.operations]\n      return (preprocessor.ssd_random_crop_pad,\n              {\n                  'min_object_covered': min_object_covered,\n                  'aspect_ratio_range': aspect_ratio_range,\n                  'area_range': area_range,\n                  'overlap_thresh': overlap_thresh,\n                  'random_coef': random_coef,\n                  'min_padded_size_ratio': min_padded_size_ratio,\n                  'max_padded_size_ratio': max_padded_size_ratio,\n                  'pad_color': pad_color,\n              })\n    return (preprocessor.ssd_random_crop_pad, {})\n\n  if step_type == 'ssd_random_crop_fixed_aspect_ratio':\n    config = preprocessor_step_config.ssd_random_crop_fixed_aspect_ratio\n    if config.operations:\n      min_object_covered = [op.min_object_covered for op in config.operations]\n      area_range = [(op.min_area, op.max_area) for op in config.operations]\n      overlap_thresh = [op.overlap_thresh for op in config.operations]\n      random_coef = [op.random_coef for op in config.operations]\n      return (preprocessor.ssd_random_crop_fixed_aspect_ratio,\n              {\n                  'min_object_covered': min_object_covered,\n                  'aspect_ratio': config.aspect_ratio,\n                  'area_range': area_range,\n                  'overlap_thresh': overlap_thresh,\n                  'random_coef': random_coef,\n              })\n    return (preprocessor.ssd_random_crop_fixed_aspect_ratio, {})\n\n  raise ValueError('Unknown preprocessing step.')\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/preprocessor_builder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for preprocessor_builder.\"\"\"\n\nimport tensorflow as tf\n\nfrom google.protobuf import text_format\n\nfrom object_detection.builders import preprocessor_builder\nfrom object_detection.core import preprocessor\nfrom object_detection.protos import preprocessor_pb2\n\n\nclass PreprocessorBuilderTest(tf.test.TestCase):\n\n  def assert_dictionary_close(self, dict1, dict2):\n    \"\"\"Helper to check if two dicts with floatst or integers are close.\"\"\"\n    self.assertEqual(sorted(dict1.keys()), sorted(dict2.keys()))\n    for key in dict1:\n      value = dict1[key]\n      if isinstance(value, float):\n        self.assertAlmostEqual(value, dict2[key])\n      else:\n        self.assertEqual(value, dict2[key])\n\n  def test_build_normalize_image(self):\n    preprocessor_text_proto = \"\"\"\n    normalize_image {\n      original_minval: 0.0\n      original_maxval: 255.0\n      target_minval: -1.0\n      target_maxval: 1.0\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.normalize_image)\n    self.assertEqual(args, {\n        'original_minval': 0.0,\n        'original_maxval': 255.0,\n        'target_minval': -1.0,\n        'target_maxval': 1.0,\n    })\n\n  def test_build_random_horizontal_flip(self):\n    preprocessor_text_proto = \"\"\"\n    random_horizontal_flip {\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.random_horizontal_flip)\n    self.assertEqual(args, {})\n\n  def test_build_random_pixel_value_scale(self):\n    preprocessor_text_proto = \"\"\"\n    random_pixel_value_scale {\n      minval: 0.8\n      maxval: 1.2\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.random_pixel_value_scale)\n    self.assert_dictionary_close(args, {'minval': 0.8, 'maxval': 1.2})\n\n  def test_build_random_image_scale(self):\n    preprocessor_text_proto = \"\"\"\n    random_image_scale {\n      min_scale_ratio: 0.8\n      max_scale_ratio: 2.2\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.random_image_scale)\n    self.assert_dictionary_close(args, {'min_scale_ratio': 0.8,\n                                        'max_scale_ratio': 2.2})\n\n  def test_build_random_rgb_to_gray(self):\n    preprocessor_text_proto = \"\"\"\n    random_rgb_to_gray {\n      probability: 0.8\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.random_rgb_to_gray)\n    self.assert_dictionary_close(args, {'probability': 0.8})\n\n  def test_build_random_adjust_brightness(self):\n    preprocessor_text_proto = \"\"\"\n    random_adjust_brightness {\n      max_delta: 0.2\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.random_adjust_brightness)\n    self.assert_dictionary_close(args, {'max_delta': 0.2})\n\n  def test_build_random_adjust_contrast(self):\n    preprocessor_text_proto = \"\"\"\n    random_adjust_contrast {\n      min_delta: 0.7\n      max_delta: 1.1\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.random_adjust_contrast)\n    self.assert_dictionary_close(args, {'min_delta': 0.7, 'max_delta': 1.1})\n\n  def test_build_random_adjust_hue(self):\n    preprocessor_text_proto = \"\"\"\n    random_adjust_hue {\n      max_delta: 0.01\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.random_adjust_hue)\n    self.assert_dictionary_close(args, {'max_delta': 0.01})\n\n  def test_build_random_adjust_saturation(self):\n    preprocessor_text_proto = \"\"\"\n    random_adjust_saturation {\n      min_delta: 0.75\n      max_delta: 1.15\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.random_adjust_saturation)\n    self.assert_dictionary_close(args, {'min_delta': 0.75, 'max_delta': 1.15})\n\n  def test_build_random_distort_color(self):\n    preprocessor_text_proto = \"\"\"\n    random_distort_color {\n      color_ordering: 1\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.random_distort_color)\n    self.assertEqual(args, {'color_ordering': 1})\n\n  def test_build_random_jitter_boxes(self):\n    preprocessor_text_proto = \"\"\"\n    random_jitter_boxes {\n      ratio: 0.1\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.random_jitter_boxes)\n    self.assert_dictionary_close(args, {'ratio': 0.1})\n\n  def test_build_random_crop_image(self):\n    preprocessor_text_proto = \"\"\"\n    random_crop_image {\n      min_object_covered: 0.75\n      min_aspect_ratio: 0.75\n      max_aspect_ratio: 1.5\n      min_area: 0.25\n      max_area: 0.875\n      overlap_thresh: 0.5\n      random_coef: 0.125\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.random_crop_image)\n    self.assertEqual(args, {\n        'min_object_covered': 0.75,\n        'aspect_ratio_range': (0.75, 1.5),\n        'area_range': (0.25, 0.875),\n        'overlap_thresh': 0.5,\n        'random_coef': 0.125,\n    })\n\n  def test_build_random_pad_image(self):\n    preprocessor_text_proto = \"\"\"\n    random_pad_image {\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.random_pad_image)\n    self.assertEqual(args, {\n        'min_image_size': None,\n        'max_image_size': None,\n        'pad_color': None,\n    })\n\n  def test_build_random_crop_pad_image(self):\n    preprocessor_text_proto = \"\"\"\n    random_crop_pad_image {\n      min_object_covered: 0.75\n      min_aspect_ratio: 0.75\n      max_aspect_ratio: 1.5\n      min_area: 0.25\n      max_area: 0.875\n      overlap_thresh: 0.5\n      random_coef: 0.125\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.random_crop_pad_image)\n    self.assertEqual(args, {\n        'min_object_covered': 0.75,\n        'aspect_ratio_range': (0.75, 1.5),\n        'area_range': (0.25, 0.875),\n        'overlap_thresh': 0.5,\n        'random_coef': 0.125,\n        'min_padded_size_ratio': None,\n        'max_padded_size_ratio': None,\n        'pad_color': None,\n    })\n\n  def test_build_random_crop_to_aspect_ratio(self):\n    preprocessor_text_proto = \"\"\"\n    random_crop_to_aspect_ratio {\n      aspect_ratio: 0.85\n      overlap_thresh: 0.35\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.random_crop_to_aspect_ratio)\n    self.assert_dictionary_close(args, {'aspect_ratio': 0.85,\n                                        'overlap_thresh': 0.35})\n\n  def test_build_random_black_patches(self):\n    preprocessor_text_proto = \"\"\"\n    random_black_patches {\n      max_black_patches: 20\n      probability: 0.95\n      size_to_image_ratio: 0.12\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.random_black_patches)\n    self.assert_dictionary_close(args, {'max_black_patches': 20,\n                                        'probability': 0.95,\n                                        'size_to_image_ratio': 0.12})\n\n  def test_build_random_resize_method(self):\n    preprocessor_text_proto = \"\"\"\n    random_resize_method {\n      target_height: 75\n      target_width: 100\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.random_resize_method)\n    self.assert_dictionary_close(args, {'target_size': [75, 100]})\n\n  def test_build_scale_boxes_to_pixel_coordinates(self):\n    preprocessor_text_proto = \"\"\"\n    scale_boxes_to_pixel_coordinates {}\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.scale_boxes_to_pixel_coordinates)\n    self.assertEqual(args, {})\n\n  def test_build_resize_image(self):\n    preprocessor_text_proto = \"\"\"\n    resize_image {\n      new_height: 75\n      new_width: 100\n      method: BICUBIC\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.resize_image)\n    self.assertEqual(args, {'new_height': 75,\n                            'new_width': 100,\n                            'method': tf.image.ResizeMethod.BICUBIC})\n\n  def test_build_subtract_channel_mean(self):\n    preprocessor_text_proto = \"\"\"\n    subtract_channel_mean {\n      means: [1.0, 2.0, 3.0]\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.subtract_channel_mean)\n    self.assertEqual(args, {'means': [1.0, 2.0, 3.0]})\n\n  def test_build_ssd_random_crop(self):\n    preprocessor_text_proto = \"\"\"\n    ssd_random_crop {\n      operations {\n        min_object_covered: 0.0\n        min_aspect_ratio: 0.875\n        max_aspect_ratio: 1.125\n        min_area: 0.5\n        max_area: 1.0\n        overlap_thresh: 0.0\n        random_coef: 0.375\n      }\n      operations {\n        min_object_covered: 0.25\n        min_aspect_ratio: 0.75\n        max_aspect_ratio: 1.5\n        min_area: 0.5\n        max_area: 1.0\n        overlap_thresh: 0.25\n        random_coef: 0.375\n      }\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.ssd_random_crop)\n    self.assertEqual(args, {'min_object_covered': [0.0, 0.25],\n                            'aspect_ratio_range': [(0.875, 1.125), (0.75, 1.5)],\n                            'area_range': [(0.5, 1.0), (0.5, 1.0)],\n                            'overlap_thresh': [0.0, 0.25],\n                            'random_coef': [0.375, 0.375]})\n\n  def test_build_ssd_random_crop_empty_operations(self):\n    preprocessor_text_proto = \"\"\"\n    ssd_random_crop {\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.ssd_random_crop)\n    self.assertEqual(args, {})\n\n  def test_build_ssd_random_crop_pad(self):\n    preprocessor_text_proto = \"\"\"\n    ssd_random_crop_pad {\n      operations {\n        min_object_covered: 0.0\n        min_aspect_ratio: 0.875\n        max_aspect_ratio: 1.125\n        min_area: 0.5\n        max_area: 1.0\n        overlap_thresh: 0.0\n        random_coef: 0.375\n        min_padded_size_ratio: [0.0, 0.0]\n        max_padded_size_ratio: [2.0, 2.0]\n        pad_color_r: 0.5\n        pad_color_g: 0.5\n        pad_color_b: 0.5\n      }\n      operations {\n        min_object_covered: 0.25\n        min_aspect_ratio: 0.75\n        max_aspect_ratio: 1.5\n        min_area: 0.5\n        max_area: 1.0\n        overlap_thresh: 0.25\n        random_coef: 0.375\n        min_padded_size_ratio: [0.0, 0.0]\n        max_padded_size_ratio: [2.0, 2.0]\n        pad_color_r: 0.5\n        pad_color_g: 0.5\n        pad_color_b: 0.5\n      }\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.ssd_random_crop_pad)\n    self.assertEqual(args, {'min_object_covered': [0.0, 0.25],\n                            'aspect_ratio_range': [(0.875, 1.125), (0.75, 1.5)],\n                            'area_range': [(0.5, 1.0), (0.5, 1.0)],\n                            'overlap_thresh': [0.0, 0.25],\n                            'random_coef': [0.375, 0.375],\n                            'min_padded_size_ratio': [(0.0, 0.0), (0.0, 0.0)],\n                            'max_padded_size_ratio': [(2.0, 2.0), (2.0, 2.0)],\n                            'pad_color': [(0.5, 0.5, 0.5), (0.5, 0.5, 0.5)]})\n\n  def test_build_ssd_random_crop_fixed_aspect_ratio(self):\n    preprocessor_text_proto = \"\"\"\n    ssd_random_crop_fixed_aspect_ratio {\n      operations {\n        min_object_covered: 0.0\n        min_area: 0.5\n        max_area: 1.0\n        overlap_thresh: 0.0\n        random_coef: 0.375\n      }\n      operations {\n        min_object_covered: 0.25\n        min_area: 0.5\n        max_area: 1.0\n        overlap_thresh: 0.25\n        random_coef: 0.375\n      }\n      aspect_ratio: 0.875\n    }\n    \"\"\"\n    preprocessor_proto = preprocessor_pb2.PreprocessingStep()\n    text_format.Merge(preprocessor_text_proto, preprocessor_proto)\n    function, args = preprocessor_builder.build(preprocessor_proto)\n    self.assertEqual(function, preprocessor.ssd_random_crop_fixed_aspect_ratio)\n    self.assertEqual(args, {'min_object_covered': [0.0, 0.25],\n                            'aspect_ratio': 0.875,\n                            'area_range': [(0.5, 1.0), (0.5, 1.0)],\n                            'overlap_thresh': [0.0, 0.25],\n                            'random_coef': [0.375, 0.375]})\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/region_similarity_calculator_builder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Builder for region similarity calculators.\"\"\"\n\nfrom object_detection.core import region_similarity_calculator\nfrom object_detection.protos import region_similarity_calculator_pb2\n\n\ndef build(region_similarity_calculator_config):\n  \"\"\"Builds region similarity calculator based on the configuration.\n\n  Builds one of [IouSimilarity, IoaSimilarity, NegSqDistSimilarity] objects. See\n  core/region_similarity_calculator.proto for details.\n\n  Args:\n    region_similarity_calculator_config: RegionSimilarityCalculator\n      configuration proto.\n\n  Returns:\n    region_similarity_calculator: RegionSimilarityCalculator object.\n\n  Raises:\n    ValueError: On unknown region similarity calculator.\n  \"\"\"\n\n  if not isinstance(\n      region_similarity_calculator_config,\n      region_similarity_calculator_pb2.RegionSimilarityCalculator):\n    raise ValueError(\n        'region_similarity_calculator_config not of type '\n        'region_similarity_calculator_pb2.RegionsSimilarityCalculator')\n\n  similarity_calculator = region_similarity_calculator_config.WhichOneof(\n      'region_similarity')\n  if similarity_calculator == 'iou_similarity':\n    return region_similarity_calculator.IouSimilarity()\n  if similarity_calculator == 'ioa_similarity':\n    return region_similarity_calculator.IoaSimilarity()\n  if similarity_calculator == 'neg_sq_dist_similarity':\n    return region_similarity_calculator.NegSqDistSimilarity()\n\n  raise ValueError('Unknown region similarity calculator.')\n\n"
  },
  {
    "path": "object_detector_app/object_detection/builders/region_similarity_calculator_builder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for region_similarity_calculator_builder.\"\"\"\n\nimport tensorflow as tf\n\nfrom google.protobuf import text_format\nfrom object_detection.builders import region_similarity_calculator_builder\nfrom object_detection.core import region_similarity_calculator\nfrom object_detection.protos import region_similarity_calculator_pb2 as sim_calc_pb2\n\n\nclass RegionSimilarityCalculatorBuilderTest(tf.test.TestCase):\n\n  def testBuildIoaSimilarityCalculator(self):\n    similarity_calc_text_proto = \"\"\"\n      ioa_similarity {\n      }\n    \"\"\"\n    similarity_calc_proto = sim_calc_pb2.RegionSimilarityCalculator()\n    text_format.Merge(similarity_calc_text_proto, similarity_calc_proto)\n    similarity_calc = region_similarity_calculator_builder.build(\n        similarity_calc_proto)\n    self.assertTrue(isinstance(similarity_calc,\n                               region_similarity_calculator.IoaSimilarity))\n\n  def testBuildIouSimilarityCalculator(self):\n    similarity_calc_text_proto = \"\"\"\n      iou_similarity {\n      }\n    \"\"\"\n    similarity_calc_proto = sim_calc_pb2.RegionSimilarityCalculator()\n    text_format.Merge(similarity_calc_text_proto, similarity_calc_proto)\n    similarity_calc = region_similarity_calculator_builder.build(\n        similarity_calc_proto)\n    self.assertTrue(isinstance(similarity_calc,\n                               region_similarity_calculator.IouSimilarity))\n\n  def testBuildNegSqDistSimilarityCalculator(self):\n    similarity_calc_text_proto = \"\"\"\n      neg_sq_dist_similarity {\n      }\n    \"\"\"\n    similarity_calc_proto = sim_calc_pb2.RegionSimilarityCalculator()\n    text_format.Merge(similarity_calc_text_proto, similarity_calc_proto)\n    similarity_calc = region_similarity_calculator_builder.build(\n        similarity_calc_proto)\n    self.assertTrue(isinstance(similarity_calc,\n                               region_similarity_calculator.\n                               NegSqDistSimilarity))\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/core/BUILD",
    "content": "# Tensorflow Object Detection API: Core.\n\npackage(\n    default_visibility = [\"//visibility:public\"],\n)\n\nlicenses([\"notice\"])\n# Apache 2.0\n\npy_library(\n    name = \"batcher\",\n    srcs = [\"batcher.py\"],\n    deps = [\n        \":prefetcher\",\n        \":preprocessor\",\n        \":standard_fields\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"batcher_test\",\n    srcs = [\"batcher_test.py\"],\n    deps = [\n        \":batcher\",\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"box_list\",\n    srcs = [\n        \"box_list.py\",\n    ],\n    deps = [\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"box_list_test\",\n    srcs = [\"box_list_test.py\"],\n    deps = [\n        \":box_list\",\n    ],\n)\n\npy_library(\n    name = \"box_list_ops\",\n    srcs = [\n        \"box_list_ops.py\",\n    ],\n    deps = [\n        \":box_list\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/utils:shape_utils\",\n    ],\n)\n\npy_test(\n    name = \"box_list_ops_test\",\n    srcs = [\"box_list_ops_test.py\"],\n    deps = [\n        \":box_list\",\n        \":box_list_ops\",\n    ],\n)\n\npy_library(\n    name = \"box_coder\",\n    srcs = [\n        \"box_coder.py\",\n    ],\n    deps = [\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"box_coder_test\",\n    srcs = [\n        \"box_coder_test.py\",\n    ],\n    deps = [\n        \":box_coder\",\n        \":box_list\",\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"keypoint_ops\",\n    srcs = [\n        \"keypoint_ops.py\",\n    ],\n    deps = [\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"keypoint_ops_test\",\n    srcs = [\"keypoint_ops_test.py\"],\n    deps = [\n        \":keypoint_ops\",\n    ],\n)\n\npy_library(\n    name = \"losses\",\n    srcs = [\"losses.py\"],\n    deps = [\n        \":box_list\",\n        \":box_list_ops\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/utils:ops\",\n    ],\n)\n\npy_library(\n    name = \"matcher\",\n    srcs = [\n        \"matcher.py\",\n    ],\n    deps = [\n    ],\n)\n\npy_library(\n    name = \"model\",\n    srcs = [\"model.py\"],\n    deps = [\n        \":standard_fields\",\n    ],\n)\n\npy_test(\n    name = \"matcher_test\",\n    srcs = [\n        \"matcher_test.py\",\n    ],\n    deps = [\n        \":matcher\",\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"prefetcher\",\n    srcs = [\"prefetcher.py\"],\n    deps = [\"//tensorflow\"],\n)\n\npy_library(\n    name = \"preprocessor\",\n    srcs = [\n        \"preprocessor.py\",\n    ],\n    deps = [\n        \":box_list\",\n        \":box_list_ops\",\n        \":keypoint_ops\",\n        \":standard_fields\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"preprocessor_test\",\n    srcs = [\n        \"preprocessor_test.py\",\n    ],\n    deps = [\n        \":preprocessor\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"losses_test\",\n    srcs = [\"losses_test.py\"],\n    deps = [\n        \":box_list\",\n        \":losses\",\n        \":matcher\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"prefetcher_test\",\n    srcs = [\"prefetcher_test.py\"],\n    deps = [\n        \":prefetcher\",\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"standard_fields\",\n    srcs = [\n        \"standard_fields.py\",\n    ],\n)\n\npy_library(\n    name = \"post_processing\",\n    srcs = [\"post_processing.py\"],\n    deps = [\n        \":box_list\",\n        \":box_list_ops\",\n        \":standard_fields\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"post_processing_test\",\n    srcs = [\"post_processing_test.py\"],\n    deps = [\n        \":box_list\",\n        \":box_list_ops\",\n        \":post_processing\",\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"target_assigner\",\n    srcs = [\n        \"target_assigner.py\",\n    ],\n    deps = [\n        \":box_list\",\n        \":box_list_ops\",\n        \":matcher\",\n        \":region_similarity_calculator\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/box_coders:faster_rcnn_box_coder\",\n        \"//tensorflow_models/object_detection/box_coders:mean_stddev_box_coder\",\n        \"//tensorflow_models/object_detection/core:box_coder\",\n        \"//tensorflow_models/object_detection/matchers:argmax_matcher\",\n        \"//tensorflow_models/object_detection/matchers:bipartite_matcher\",\n    ],\n)\n\npy_test(\n    name = \"target_assigner_test\",\n    size = \"large\",\n    timeout = \"long\",\n    srcs = [\"target_assigner_test.py\"],\n    deps = [\n        \":box_list\",\n        \":region_similarity_calculator\",\n        \":target_assigner\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/box_coders:mean_stddev_box_coder\",\n        \"//tensorflow_models/object_detection/matchers:bipartite_matcher\",\n    ],\n)\n\npy_library(\n    name = \"data_decoder\",\n    srcs = [\"data_decoder.py\"],\n)\n\npy_library(\n    name = \"box_predictor\",\n    srcs = [\"box_predictor.py\"],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/utils:ops\",\n        \"//tensorflow_models/object_detection/utils:static_shape\",\n    ],\n)\n\npy_test(\n    name = \"box_predictor_test\",\n    srcs = [\"box_predictor_test.py\"],\n    deps = [\n        \":box_predictor\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/builders:hyperparams_builder\",\n        \"//tensorflow_models/object_detection/protos:hyperparams_py_pb2\",\n    ],\n)\n\npy_library(\n    name = \"region_similarity_calculator\",\n    srcs = [\n        \"region_similarity_calculator.py\",\n    ],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:box_list_ops\",\n    ],\n)\n\npy_test(\n    name = \"region_similarity_calculator_test\",\n    srcs = [\n        \"region_similarity_calculator_test.py\",\n    ],\n    deps = [\n        \":region_similarity_calculator\",\n        \"//tensorflow_models/object_detection/core:box_list\",\n    ],\n)\n\npy_library(\n    name = \"anchor_generator\",\n    srcs = [\n        \"anchor_generator.py\",\n    ],\n    deps = [\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"minibatch_sampler\",\n    srcs = [\n        \"minibatch_sampler.py\",\n    ],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/utils:ops\",\n    ],\n)\n\npy_test(\n    name = \"minibatch_sampler_test\",\n    srcs = [\n        \"minibatch_sampler_test.py\",\n    ],\n    deps = [\n        \":minibatch_sampler\",\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"balanced_positive_negative_sampler\",\n    srcs = [\n        \"balanced_positive_negative_sampler.py\",\n    ],\n    deps = [\n        \":minibatch_sampler\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"balanced_positive_negative_sampler_test\",\n    srcs = [\n        \"balanced_positive_negative_sampler_test.py\",\n    ],\n    deps = [\n        \":balanced_positive_negative_sampler\",\n        \"//tensorflow\",\n    ],\n)\n"
  },
  {
    "path": "object_detector_app/object_detection/core/__init__.py",
    "content": ""
  },
  {
    "path": "object_detector_app/object_detection/core/anchor_generator.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Base anchor generator.\n\nThe job of the anchor generator is to create (or load) a collection\nof bounding boxes to be used as anchors.\n\nGenerated anchors are assumed to match some convolutional grid or list of grid\nshapes.  For example, we might want to generate anchors matching an 8x8\nfeature map and a 4x4 feature map.  If we place 3 anchors per grid location\non the first feature map and 6 anchors per grid location on the second feature\nmap, then 3*8*8 + 6*4*4 = 288 anchors are generated in total.\n\nTo support fully convolutional settings, feature map shapes are passed\ndynamically at generation time.  The number of anchors to place at each location\nis static --- implementations of AnchorGenerator must always be able return\nthe number of anchors that it uses per location for each feature map.\n\"\"\"\nfrom abc import ABCMeta\nfrom abc import abstractmethod\n\nimport tensorflow as tf\n\n\nclass AnchorGenerator(object):\n  \"\"\"Abstract base class for anchor generators.\"\"\"\n  __metaclass__ = ABCMeta\n\n  @abstractmethod\n  def name_scope(self):\n    \"\"\"Name scope.\n\n    Must be defined by implementations.\n\n    Returns:\n      a string representing the name scope of the anchor generation operation.\n    \"\"\"\n    pass\n\n  @property\n  def check_num_anchors(self):\n    \"\"\"Whether to dynamically check the number of anchors generated.\n\n    Can be overridden by implementations that would like to disable this\n    behavior.\n\n    Returns:\n      a boolean controlling whether the Generate function should dynamically\n      check the number of anchors generated against the mathematically\n      expected number of anchors.\n    \"\"\"\n    return True\n\n  @abstractmethod\n  def num_anchors_per_location(self):\n    \"\"\"Returns the number of anchors per spatial location.\n\n    Returns:\n      a list of integers, one for each expected feature map to be passed to\n      the `generate` function.\n    \"\"\"\n    pass\n\n  def generate(self, feature_map_shape_list, **params):\n    \"\"\"Generates a collection of bounding boxes to be used as anchors.\n\n    TODO: remove **params from argument list and make stride and offsets (for\n        multiple_grid_anchor_generator) constructor arguments.\n\n    Args:\n      feature_map_shape_list: list of (height, width) pairs in the format\n        [(height_0, width_0), (height_1, width_1), ...] that the generated\n        anchors must align with.  Pairs can be provided as 1-dimensional\n        integer tensors of length 2 or simply as tuples of integers.\n      **params: parameters for anchor generation op\n\n    Returns:\n      boxes: a BoxList holding a collection of N anchor boxes\n    Raises:\n      ValueError: if the number of feature map shapes does not match the length\n        of NumAnchorsPerLocation.\n    \"\"\"\n    if self.check_num_anchors and (\n        len(feature_map_shape_list) != len(self.num_anchors_per_location())):\n      raise ValueError('Number of feature maps is expected to equal the length '\n                       'of `num_anchors_per_location`.')\n    with tf.name_scope(self.name_scope()):\n      anchors = self._generate(feature_map_shape_list, **params)\n      if self.check_num_anchors:\n        with tf.control_dependencies([\n            self._assert_correct_number_of_anchors(\n                anchors, feature_map_shape_list)]):\n          anchors.set(tf.identity(anchors.get()))\n      return anchors\n\n  @abstractmethod\n  def _generate(self, feature_map_shape_list, **params):\n    \"\"\"To be overridden by implementations.\n\n    Args:\n      feature_map_shape_list: list of (height, width) pairs in the format\n        [(height_0, width_0), (height_1, width_1), ...] that the generated\n        anchors must align with.\n      **params: parameters for anchor generation op\n\n    Returns:\n      boxes: a BoxList holding a collection of N anchor boxes\n    \"\"\"\n    pass\n\n  def _assert_correct_number_of_anchors(self, anchors, feature_map_shape_list):\n    \"\"\"Assert that correct number of anchors was generated.\n\n    Args:\n      anchors: box_list.BoxList object holding anchors generated\n      feature_map_shape_list: list of (height, width) pairs in the format\n        [(height_0, width_0), (height_1, width_1), ...] that the generated\n        anchors must align with.\n    Returns:\n      Op that raises InvalidArgumentError if the number of anchors does not\n        match the number of expected anchors.\n    \"\"\"\n    expected_num_anchors = 0\n    for num_anchors_per_location, feature_map_shape in zip(\n        self.num_anchors_per_location(), feature_map_shape_list):\n      expected_num_anchors += (num_anchors_per_location\n                               * feature_map_shape[0]\n                               * feature_map_shape[1])\n    return tf.assert_equal(expected_num_anchors, anchors.num_boxes())\n"
  },
  {
    "path": "object_detector_app/object_detection/core/balanced_positive_negative_sampler.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Class to subsample minibatches by balancing positives and negatives.\n\nSubsamples minibatches based on a pre-specified positive fraction in range\n[0,1]. The class presumes there are many more negatives than positive examples:\nif the desired batch_size cannot be achieved with the pre-specified positive\nfraction, it fills the rest with negative examples. If this is not sufficient\nfor obtaining the desired batch_size, it returns fewer examples.\n\nThe main function to call is Subsample(self, indicator, labels). For convenience\none can also call SubsampleWeights(self, weights, labels) which is defined in\nthe minibatch_sampler base class.\n\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.core import minibatch_sampler\n\n\nclass BalancedPositiveNegativeSampler(minibatch_sampler.MinibatchSampler):\n  \"\"\"Subsamples minibatches to a desired balance of positives and negatives.\"\"\"\n\n  def __init__(self, positive_fraction=0.5):\n    \"\"\"Constructs a minibatch sampler.\n\n    Args:\n      positive_fraction: desired fraction of positive examples (scalar in [0,1])\n\n    Raises:\n      ValueError: if positive_fraction < 0, or positive_fraction > 1\n    \"\"\"\n    if positive_fraction < 0 or positive_fraction > 1:\n      raise ValueError('positive_fraction should be in range [0,1]. '\n                       'Received: %s.' % positive_fraction)\n    self._positive_fraction = positive_fraction\n\n  def subsample(self, indicator, batch_size, labels):\n    \"\"\"Returns subsampled minibatch.\n\n    Args:\n      indicator: boolean tensor of shape [N] whose True entries can be sampled.\n      batch_size: desired batch size.\n      labels: boolean tensor of shape [N] denoting positive(=True) and negative\n          (=False) examples.\n\n    Returns:\n      is_sampled: boolean tensor of shape [N], True for entries which are\n          sampled.\n\n    Raises:\n      ValueError: if labels and indicator are not 1D boolean tensors.\n    \"\"\"\n    if len(indicator.get_shape().as_list()) != 1:\n      raise ValueError('indicator must be 1 dimensional, got a tensor of '\n                       'shape %s' % indicator.get_shape())\n    if len(labels.get_shape().as_list()) != 1:\n      raise ValueError('labels must be 1 dimensional, got a tensor of '\n                       'shape %s' % labels.get_shape())\n    if labels.dtype != tf.bool:\n      raise ValueError('labels should be of type bool. Received: %s' %\n                       labels.dtype)\n    if indicator.dtype != tf.bool:\n      raise ValueError('indicator should be of type bool. Received: %s' %\n                       indicator.dtype)\n\n    # Only sample from indicated samples\n    negative_idx = tf.logical_not(labels)\n    positive_idx = tf.logical_and(labels, indicator)\n    negative_idx = tf.logical_and(negative_idx, indicator)\n\n    # Sample positive and negative samples separately\n    max_num_pos = int(self._positive_fraction * batch_size)\n    sampled_pos_idx = self.subsample_indicator(positive_idx, max_num_pos)\n    max_num_neg = batch_size - tf.reduce_sum(tf.cast(sampled_pos_idx, tf.int32))\n    sampled_neg_idx = self.subsample_indicator(negative_idx, max_num_neg)\n\n    sampled_idx = tf.logical_or(sampled_pos_idx, sampled_neg_idx)\n    return sampled_idx\n"
  },
  {
    "path": "object_detector_app/object_detection/core/balanced_positive_negative_sampler_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.core.balanced_positive_negative_sampler.\"\"\"\n\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.core import balanced_positive_negative_sampler\n\n\nclass BalancedPositiveNegativeSamplerTest(tf.test.TestCase):\n\n  def test_subsample_all_examples(self):\n    numpy_labels = np.random.permutation(300)\n    indicator = tf.constant(np.ones(300) == 1)\n    numpy_labels = (numpy_labels - 200) > 0\n\n    labels = tf.constant(numpy_labels)\n\n    sampler = (balanced_positive_negative_sampler.\n               BalancedPositiveNegativeSampler())\n    is_sampled = sampler.subsample(indicator, 64, labels)\n    with self.test_session() as sess:\n      is_sampled = sess.run(is_sampled)\n      self.assertTrue(sum(is_sampled) == 64)\n      self.assertTrue(sum(np.logical_and(numpy_labels, is_sampled)) == 32)\n      self.assertTrue(sum(np.logical_and(\n          np.logical_not(numpy_labels), is_sampled)) == 32)\n\n  def test_subsample_selection(self):\n    # Test random sampling when only some examples can be sampled:\n    # 100 samples, 20 positives, 10 positives cannot be sampled\n    numpy_labels = np.arange(100)\n    numpy_indicator = numpy_labels < 90\n    indicator = tf.constant(numpy_indicator)\n    numpy_labels = (numpy_labels - 80) >= 0\n\n    labels = tf.constant(numpy_labels)\n\n    sampler = (balanced_positive_negative_sampler.\n               BalancedPositiveNegativeSampler())\n    is_sampled = sampler.subsample(indicator, 64, labels)\n    with self.test_session() as sess:\n      is_sampled = sess.run(is_sampled)\n      self.assertTrue(sum(is_sampled) == 64)\n      self.assertTrue(sum(np.logical_and(numpy_labels, is_sampled)) == 10)\n      self.assertTrue(sum(np.logical_and(\n          np.logical_not(numpy_labels), is_sampled)) == 54)\n      self.assertAllEqual(is_sampled, np.logical_and(is_sampled,\n                                                     numpy_indicator))\n\n  def test_raises_error_with_incorrect_label_shape(self):\n    labels = tf.constant([[True, False, False]])\n    indicator = tf.constant([True, False, True])\n    sampler = (balanced_positive_negative_sampler.\n               BalancedPositiveNegativeSampler())\n    with self.assertRaises(ValueError):\n      sampler.subsample(indicator, 64, labels)\n\n  def test_raises_error_with_incorrect_indicator_shape(self):\n    labels = tf.constant([True, False, False])\n    indicator = tf.constant([[True, False, True]])\n    sampler = (balanced_positive_negative_sampler.\n               BalancedPositiveNegativeSampler())\n    with self.assertRaises(ValueError):\n      sampler.subsample(indicator, 64, labels)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/core/batcher.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Provides functions to batch a dictionary of input tensors.\"\"\"\nimport collections\n\nimport tensorflow as tf\n\nfrom object_detection.core import prefetcher\n\n\nclass BatchQueue(object):\n  \"\"\"BatchQueue class.\n\n  This class creates a batch queue to asynchronously enqueue tensors_dict.\n  It also adds a FIFO prefetcher so that the batches are readily available\n  for the consumers.  Dequeue ops for a BatchQueue object can be created via\n  the Dequeue method which evaluates to a batch of tensor_dict.\n\n  Example input pipeline with batching:\n  ------------------------------------\n  key, string_tensor = slim.parallel_reader.parallel_read(...)\n  tensor_dict = decoder.decode(string_tensor)\n  tensor_dict = preprocessor.preprocess(tensor_dict, ...)\n  batch_queue = batcher.BatchQueue(tensor_dict,\n                                   batch_size=32,\n                                   batch_queue_capacity=2000,\n                                   num_batch_queue_threads=8,\n                                   prefetch_queue_capacity=20)\n  tensor_dict = batch_queue.dequeue()\n  outputs = Model(tensor_dict)\n  ...\n  -----------------------------------\n\n  Notes:\n  -----\n  This class batches tensors of unequal sizes by zero padding and unpadding\n  them after generating a batch. This can be computationally expensive when\n  batching tensors (such as images) that are of vastly different sizes. So it is\n  recommended that the shapes of such tensors be fully defined in tensor_dict\n  while other lightweight tensors such as bounding box corners and class labels\n  can be of varying sizes. Use either crop or resize operations to fully define\n  the shape of an image in tensor_dict.\n\n  It is also recommended to perform any preprocessing operations on tensors\n  before passing to BatchQueue and subsequently calling the Dequeue method.\n\n  Another caveat is that this class does not read the last batch if it is not\n  full. The current implementation makes it hard to support that use case. So,\n  for evaluation, when it is critical to run all the examples through your\n  network use the input pipeline example mentioned in core/prefetcher.py.\n  \"\"\"\n\n  def __init__(self, tensor_dict, batch_size, batch_queue_capacity,\n               num_batch_queue_threads, prefetch_queue_capacity):\n    \"\"\"Constructs a batch queue holding tensor_dict.\n\n    Args:\n      tensor_dict: dictionary of tensors to batch.\n      batch_size: batch size.\n      batch_queue_capacity: max capacity of the queue from which the tensors are\n        batched.\n      num_batch_queue_threads: number of threads to use for batching.\n      prefetch_queue_capacity: max capacity of the queue used to prefetch\n        assembled batches.\n    \"\"\"\n    # Remember static shapes to set shapes of batched tensors.\n    static_shapes = collections.OrderedDict(\n        {key: tensor.get_shape() for key, tensor in tensor_dict.iteritems()})\n    # Remember runtime shapes to unpad tensors after batching.\n    runtime_shapes = collections.OrderedDict(\n        {(key, 'runtime_shapes'): tf.shape(tensor)\n         for key, tensor in tensor_dict.iteritems()})\n    all_tensors = tensor_dict\n    all_tensors.update(runtime_shapes)\n    batched_tensors = tf.train.batch(\n        all_tensors,\n        capacity=batch_queue_capacity,\n        batch_size=batch_size,\n        dynamic_pad=True,\n        num_threads=num_batch_queue_threads)\n\n    self._queue = prefetcher.prefetch(batched_tensors,\n                                      prefetch_queue_capacity)\n    self._static_shapes = static_shapes\n    self._batch_size = batch_size\n\n  def dequeue(self):\n    \"\"\"Dequeues a batch of tensor_dict from the BatchQueue.\n\n    TODO: use allow_smaller_final_batch to allow running over the whole eval set\n\n    Returns:\n      A list of tensor_dicts of the requested batch_size.\n    \"\"\"\n    batched_tensors = self._queue.dequeue()\n    # Separate input tensors from tensors containing their runtime shapes.\n    tensors = {}\n    shapes = {}\n    for key, batched_tensor in batched_tensors.iteritems():\n      unbatched_tensor_list = tf.unstack(batched_tensor)\n      for i, unbatched_tensor in enumerate(unbatched_tensor_list):\n        if isinstance(key, tuple) and key[1] == 'runtime_shapes':\n          shapes[(key[0], i)] = unbatched_tensor\n        else:\n          tensors[(key, i)] = unbatched_tensor\n\n    # Undo that padding using shapes and create a list of size `batch_size` that\n    # contains tensor dictionaries.\n    tensor_dict_list = []\n    batch_size = self._batch_size\n    for batch_id in range(batch_size):\n      tensor_dict = {}\n      for key in self._static_shapes:\n        tensor_dict[key] = tf.slice(tensors[(key, batch_id)],\n                                    tf.zeros_like(shapes[(key, batch_id)]),\n                                    shapes[(key, batch_id)])\n        tensor_dict[key].set_shape(self._static_shapes[key])\n      tensor_dict_list.append(tensor_dict)\n\n    return tensor_dict_list\n"
  },
  {
    "path": "object_detector_app/object_detection/core/batcher_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.core.batcher.\"\"\"\n\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.core import batcher\n\nslim = tf.contrib.slim\n\n\nclass BatcherTest(tf.test.TestCase):\n\n  def test_batch_and_unpad_2d_tensors_of_different_sizes_in_1st_dimension(self):\n    with self.test_session() as sess:\n      batch_size = 3\n      num_batches = 2\n      examples = tf.Variable(tf.constant(2, dtype=tf.int32))\n      counter = examples.count_up_to(num_batches * batch_size + 2)\n      boxes = tf.tile(\n          tf.reshape(tf.range(4), [1, 4]), tf.stack([counter, tf.constant(1)]))\n      batch_queue = batcher.BatchQueue(\n          tensor_dict={'boxes': boxes},\n          batch_size=batch_size,\n          batch_queue_capacity=100,\n          num_batch_queue_threads=1,\n          prefetch_queue_capacity=100)\n      batch = batch_queue.dequeue()\n\n      for tensor_dict in batch:\n        for tensor in tensor_dict.values():\n          self.assertAllEqual([None, 4], tensor.get_shape().as_list())\n\n      tf.initialize_all_variables().run()\n      with slim.queues.QueueRunners(sess):\n        i = 2\n        for _ in range(num_batches):\n          batch_np = sess.run(batch)\n          for tensor_dict in batch_np:\n            for tensor in tensor_dict.values():\n              self.assertAllEqual(tensor, np.tile(np.arange(4), (i, 1)))\n              i += 1\n        with self.assertRaises(tf.errors.OutOfRangeError):\n          sess.run(batch)\n\n  def test_batch_and_unpad_2d_tensors_of_different_sizes_in_all_dimensions(\n      self):\n    with self.test_session() as sess:\n      batch_size = 3\n      num_batches = 2\n      examples = tf.Variable(tf.constant(2, dtype=tf.int32))\n      counter = examples.count_up_to(num_batches * batch_size + 2)\n      image = tf.reshape(\n          tf.range(counter * counter), tf.stack([counter, counter]))\n      batch_queue = batcher.BatchQueue(\n          tensor_dict={'image': image},\n          batch_size=batch_size,\n          batch_queue_capacity=100,\n          num_batch_queue_threads=1,\n          prefetch_queue_capacity=100)\n      batch = batch_queue.dequeue()\n\n      for tensor_dict in batch:\n        for tensor in tensor_dict.values():\n          self.assertAllEqual([None, None], tensor.get_shape().as_list())\n\n      tf.initialize_all_variables().run()\n      with slim.queues.QueueRunners(sess):\n        i = 2\n        for _ in range(num_batches):\n          batch_np = sess.run(batch)\n          for tensor_dict in batch_np:\n            for tensor in tensor_dict.values():\n              self.assertAllEqual(tensor, np.arange(i * i).reshape((i, i)))\n              i += 1\n        with self.assertRaises(tf.errors.OutOfRangeError):\n          sess.run(batch)\n\n  def test_batch_and_unpad_2d_tensors_of_same_size_in_all_dimensions(self):\n    with self.test_session() as sess:\n      batch_size = 3\n      num_batches = 2\n      examples = tf.Variable(tf.constant(1, dtype=tf.int32))\n      counter = examples.count_up_to(num_batches * batch_size + 1)\n      image = tf.reshape(tf.range(1, 13), [4, 3]) * counter\n      batch_queue = batcher.BatchQueue(\n          tensor_dict={'image': image},\n          batch_size=batch_size,\n          batch_queue_capacity=100,\n          num_batch_queue_threads=1,\n          prefetch_queue_capacity=100)\n      batch = batch_queue.dequeue()\n\n      for tensor_dict in batch:\n        for tensor in tensor_dict.values():\n          self.assertAllEqual([4, 3], tensor.get_shape().as_list())\n\n      tf.initialize_all_variables().run()\n      with slim.queues.QueueRunners(sess):\n        i = 1\n        for _ in range(num_batches):\n          batch_np = sess.run(batch)\n          for tensor_dict in batch_np:\n            for tensor in tensor_dict.values():\n              self.assertAllEqual(tensor, np.arange(1, 13).reshape((4, 3)) * i)\n              i += 1\n        with self.assertRaises(tf.errors.OutOfRangeError):\n          sess.run(batch)\n\n  def test_batcher_when_batch_size_is_one(self):\n    with self.test_session() as sess:\n      batch_size = 1\n      num_batches = 2\n      examples = tf.Variable(tf.constant(2, dtype=tf.int32))\n      counter = examples.count_up_to(num_batches * batch_size + 2)\n      image = tf.reshape(\n          tf.range(counter * counter), tf.stack([counter, counter]))\n      batch_queue = batcher.BatchQueue(\n          tensor_dict={'image': image},\n          batch_size=batch_size,\n          batch_queue_capacity=100,\n          num_batch_queue_threads=1,\n          prefetch_queue_capacity=100)\n      batch = batch_queue.dequeue()\n\n      for tensor_dict in batch:\n        for tensor in tensor_dict.values():\n          self.assertAllEqual([None, None], tensor.get_shape().as_list())\n\n      tf.initialize_all_variables().run()\n      with slim.queues.QueueRunners(sess):\n        i = 2\n        for _ in range(num_batches):\n          batch_np = sess.run(batch)\n          for tensor_dict in batch_np:\n            for tensor in tensor_dict.values():\n              self.assertAllEqual(tensor, np.arange(i * i).reshape((i, i)))\n              i += 1\n        with self.assertRaises(tf.errors.OutOfRangeError):\n          sess.run(batch)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/core/box_coder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Base box coder.\n\nBox coders convert between coordinate frames, namely image-centric\n(with (0,0) on the top left of image) and anchor-centric (with (0,0) being\ndefined by a specific anchor).\n\nUsers of a BoxCoder can call two methods:\n encode: which encodes a box with respect to a given anchor\n  (or rather, a tensor of boxes wrt a corresponding tensor of anchors) and\n decode: which inverts this encoding with a decode operation.\nIn both cases, the arguments are assumed to be in 1-1 correspondence already;\nit is not the job of a BoxCoder to perform matching.\n\"\"\"\nfrom abc import ABCMeta\nfrom abc import abstractmethod\nfrom abc import abstractproperty\n\nimport tensorflow as tf\n\n\n# Box coder types.\nFASTER_RCNN = 'faster_rcnn'\nKEYPOINT = 'keypoint'\nMEAN_STDDEV = 'mean_stddev'\nSQUARE = 'square'\n\n\nclass BoxCoder(object):\n  \"\"\"Abstract base class for box coder.\"\"\"\n  __metaclass__ = ABCMeta\n\n  @abstractproperty\n  def code_size(self):\n    \"\"\"Return the size of each code.\n\n    This number is a constant and should agree with the output of the `encode`\n    op (e.g. if rel_codes is the output of self.encode(...), then it should have\n    shape [N, code_size()]).  This abstractproperty should be overridden by\n    implementations.\n\n    Returns:\n      an integer constant\n    \"\"\"\n    pass\n\n  def encode(self, boxes, anchors):\n    \"\"\"Encode a box list relative to an anchor collection.\n\n    Args:\n      boxes: BoxList holding N boxes to be encoded\n      anchors: BoxList of N anchors\n\n    Returns:\n      a tensor representing N relative-encoded boxes\n    \"\"\"\n    with tf.name_scope('Encode'):\n      return self._encode(boxes, anchors)\n\n  def decode(self, rel_codes, anchors):\n    \"\"\"Decode boxes that are encoded relative to an anchor collection.\n\n    Args:\n      rel_codes: a tensor representing N relative-encoded boxes\n      anchors: BoxList of anchors\n\n    Returns:\n      boxlist: BoxList holding N boxes encoded in the ordinary way (i.e.,\n        with corners y_min, x_min, y_max, x_max)\n    \"\"\"\n    with tf.name_scope('Decode'):\n      return self._decode(rel_codes, anchors)\n\n  @abstractmethod\n  def _encode(self, boxes, anchors):\n    \"\"\"Method to be overriden by implementations.\n\n    Args:\n      boxes: BoxList holding N boxes to be encoded\n      anchors: BoxList of N anchors\n\n    Returns:\n      a tensor representing N relative-encoded boxes\n    \"\"\"\n    pass\n\n  @abstractmethod\n  def _decode(self, rel_codes, anchors):\n    \"\"\"Method to be overriden by implementations.\n\n    Args:\n      rel_codes: a tensor representing N relative-encoded boxes\n      anchors: BoxList of anchors\n\n    Returns:\n      boxlist: BoxList holding N boxes encoded in the ordinary way (i.e.,\n        with corners y_min, x_min, y_max, x_max)\n    \"\"\"\n    pass\n\n\ndef batch_decode(encoded_boxes, box_coder, anchors):\n  \"\"\"Decode a batch of encoded boxes.\n\n  This op takes a batch of encoded bounding boxes and transforms\n  them to a batch of bounding boxes specified by their corners in\n  the order of [y_min, x_min, y_max, x_max].\n\n  Args:\n    encoded_boxes: a float32 tensor of shape [batch_size, num_anchors,\n      code_size] representing the location of the objects.\n    box_coder: a BoxCoder object.\n    anchors: a BoxList of anchors used to encode `encoded_boxes`.\n\n  Returns:\n    decoded_boxes: a float32 tensor of shape [batch_size, num_anchors,\n      coder_size] representing the corners of the objects in the order\n      of [y_min, x_min, y_max, x_max].\n\n  Raises:\n    ValueError: if batch sizes of the inputs are inconsistent, or if\n    the number of anchors inferred from encoded_boxes and anchors are\n    inconsistent.\n  \"\"\"\n  encoded_boxes.get_shape().assert_has_rank(3)\n  if encoded_boxes.get_shape()[1].value != anchors.num_boxes_static():\n    raise ValueError('The number of anchors inferred from encoded_boxes'\n                     ' and anchors are inconsistent: shape[1] of encoded_boxes'\n                     ' %s should be equal to the number of anchors: %s.' %\n                     (encoded_boxes.get_shape()[1].value,\n                      anchors.num_boxes_static()))\n\n  decoded_boxes = tf.stack([\n      box_coder.decode(boxes, anchors).get()\n      for boxes in tf.unstack(encoded_boxes)\n  ])\n  return decoded_boxes\n"
  },
  {
    "path": "object_detector_app/object_detection/core/box_coder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.core.box_coder.\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.core import box_coder\nfrom object_detection.core import box_list\n\n\nclass MockBoxCoder(box_coder.BoxCoder):\n  \"\"\"Test BoxCoder that encodes/decodes using the multiply-by-two function.\"\"\"\n\n  def code_size(self):\n    return 4\n\n  def _encode(self, boxes, anchors):\n    return 2.0 * boxes.get()\n\n  def _decode(self, rel_codes, anchors):\n    return box_list.BoxList(rel_codes / 2.0)\n\n\nclass BoxCoderTest(tf.test.TestCase):\n\n  def test_batch_decode(self):\n    mock_anchor_corners = tf.constant(\n        [[0, 0.1, 0.2, 0.3], [0.2, 0.4, 0.4, 0.6]], tf.float32)\n    mock_anchors = box_list.BoxList(mock_anchor_corners)\n    mock_box_coder = MockBoxCoder()\n\n    expected_boxes = [[[0.0, 0.1, 0.5, 0.6], [0.5, 0.6, 0.7, 0.8]],\n                      [[0.1, 0.2, 0.3, 0.4], [0.7, 0.8, 0.9, 1.0]]]\n\n    encoded_boxes_list = [mock_box_coder.encode(\n        box_list.BoxList(tf.constant(boxes)), mock_anchors)\n                          for boxes in expected_boxes]\n    encoded_boxes = tf.stack(encoded_boxes_list)\n    decoded_boxes = box_coder.batch_decode(\n        encoded_boxes, mock_box_coder, mock_anchors)\n\n    with self.test_session() as sess:\n      decoded_boxes_result = sess.run(decoded_boxes)\n      self.assertAllClose(expected_boxes, decoded_boxes_result)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/core/box_list.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Bounding Box List definition.\n\nBoxList represents a list of bounding boxes as tensorflow\ntensors, where each bounding box is represented as a row of 4 numbers,\n[y_min, x_min, y_max, x_max].  It is assumed that all bounding boxes\nwithin a given list correspond to a single image.  See also\nbox_list_ops.py for common box related operations (such as area, iou, etc).\n\nOptionally, users can add additional related fields (such as weights).\nWe assume the following things to be true about fields:\n* they correspond to boxes in the box_list along the 0th dimension\n* they have inferrable rank at graph construction time\n* all dimensions except for possibly the 0th can be inferred\n  (i.e., not None) at graph construction time.\n\nSome other notes:\n  * Following tensorflow conventions, we use height, width ordering,\n  and correspondingly, y,x (or ymin, xmin, ymax, xmax) ordering\n  * Tensors are always provided as (flat) [N, 4] tensors.\n\"\"\"\n\nimport tensorflow as tf\n\n\nclass BoxList(object):\n  \"\"\"Box collection.\"\"\"\n\n  def __init__(self, boxes):\n    \"\"\"Constructs box collection.\n\n    Args:\n      boxes: a tensor of shape [N, 4] representing box corners\n\n    Raises:\n      ValueError: if invalid dimensions for bbox data or if bbox data is not in\n          float32 format.\n    \"\"\"\n    if len(boxes.get_shape()) != 2 or boxes.get_shape()[-1] != 4:\n      raise ValueError('Invalid dimensions for box data.')\n    if boxes.dtype != tf.float32:\n      raise ValueError('Invalid tensor type: should be tf.float32')\n    self.data = {'boxes': boxes}\n\n  def num_boxes(self):\n    \"\"\"Returns number of boxes held in collection.\n\n    Returns:\n      a tensor representing the number of boxes held in the collection.\n    \"\"\"\n    return tf.shape(self.data['boxes'])[0]\n\n  def num_boxes_static(self):\n    \"\"\"Returns number of boxes held in collection.\n\n    This number is inferred at graph construction time rather than run-time.\n\n    Returns:\n      Number of boxes held in collection (integer) or None if this is not\n        inferrable at graph construction time.\n    \"\"\"\n    return self.data['boxes'].get_shape()[0].value\n\n  def get_all_fields(self):\n    \"\"\"Returns all fields.\"\"\"\n    return self.data.keys()\n\n  def get_extra_fields(self):\n    \"\"\"Returns all non-box fields (i.e., everything not named 'boxes').\"\"\"\n    return [k for k in self.data.keys() if k != 'boxes']\n\n  def add_field(self, field, field_data):\n    \"\"\"Add field to box list.\n\n    This method can be used to add related box data such as\n    weights/labels, etc.\n\n    Args:\n      field: a string key to access the data via `get`\n      field_data: a tensor containing the data to store in the BoxList\n    \"\"\"\n    self.data[field] = field_data\n\n  def has_field(self, field):\n    return field in self.data\n\n  def get(self):\n    \"\"\"Convenience function for accessing box coordinates.\n\n    Returns:\n      a tensor with shape [N, 4] representing box coordinates.\n    \"\"\"\n    return self.get_field('boxes')\n\n  def set(self, boxes):\n    \"\"\"Convenience function for setting box coordinates.\n\n    Args:\n      boxes: a tensor of shape [N, 4] representing box corners\n\n    Raises:\n      ValueError: if invalid dimensions for bbox data\n    \"\"\"\n    if len(boxes.get_shape()) != 2 or boxes.get_shape()[-1] != 4:\n      raise ValueError('Invalid dimensions for box data.')\n    self.data['boxes'] = boxes\n\n  def get_field(self, field):\n    \"\"\"Accesses a box collection and associated fields.\n\n    This function returns specified field with object; if no field is specified,\n    it returns the box coordinates.\n\n    Args:\n      field: this optional string parameter can be used to specify\n        a related field to be accessed.\n\n    Returns:\n      a tensor representing the box collection or an associated field.\n\n    Raises:\n      ValueError: if invalid field\n    \"\"\"\n    if not self.has_field(field):\n      raise ValueError('field ' + str(field) + ' does not exist')\n    return self.data[field]\n\n  def set_field(self, field, value):\n    \"\"\"Sets the value of a field.\n\n    Updates the field of a box_list with a given value.\n\n    Args:\n      field: (string) name of the field to set value.\n      value: the value to assign to the field.\n\n    Raises:\n      ValueError: if the box_list does not have specified field.\n    \"\"\"\n    if not self.has_field(field):\n      raise ValueError('field %s does not exist' % field)\n    self.data[field] = value\n\n  def get_center_coordinates_and_sizes(self, scope=None):\n    \"\"\"Computes the center coordinates, height and width of the boxes.\n\n    Args:\n      scope: name scope of the function.\n\n    Returns:\n      a list of 4 1-D tensors [ycenter, xcenter, height, width].\n    \"\"\"\n    with tf.name_scope(scope, 'get_center_coordinates_and_sizes'):\n      box_corners = self.get()\n      ymin, xmin, ymax, xmax = tf.unstack(tf.transpose(box_corners))\n      width = xmax - xmin\n      height = ymax - ymin\n      ycenter = ymin + height / 2.\n      xcenter = xmin + width / 2.\n      return [ycenter, xcenter, height, width]\n\n  def transpose_coordinates(self, scope=None):\n    \"\"\"Transpose the coordinate representation in a boxlist.\n\n    Args:\n      scope: name scope of the function.\n    \"\"\"\n    with tf.name_scope(scope, 'transpose_coordinates'):\n      y_min, x_min, y_max, x_max = tf.split(\n          value=self.get(), num_or_size_splits=4, axis=1)\n      self.set(tf.concat([x_min, y_min, x_max, y_max], 1))\n\n  def as_tensor_dict(self, fields=None):\n    \"\"\"Retrieves specified fields as a dictionary of tensors.\n\n    Args:\n      fields: (optional) list of fields to return in the dictionary.\n        If None (default), all fields are returned.\n\n    Returns:\n      tensor_dict: A dictionary of tensors specified by fields.\n\n    Raises:\n      ValueError: if specified field is not contained in boxlist.\n    \"\"\"\n    tensor_dict = {}\n    if fields is None:\n      fields = self.get_all_fields()\n    for field in fields:\n      if not self.has_field(field):\n        raise ValueError('boxlist must contain all specified fields')\n      tensor_dict[field] = self.get_field(field)\n    return tensor_dict\n"
  },
  {
    "path": "object_detector_app/object_detection/core/box_list_ops.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Bounding Box List operations.\n\nExample box operations that are supported:\n  * areas: compute bounding box areas\n  * iou: pairwise intersection-over-union scores\n  * sq_dist: pairwise distances between bounding boxes\n\nWhenever box_list_ops functions output a BoxList, the fields of the incoming\nBoxList are retained unless documented otherwise.\n\"\"\"\nimport tensorflow as tf\n\nfrom object_detection.core import box_list\nfrom object_detection.utils import shape_utils\n\n\nclass SortOrder(object):\n  \"\"\"Enum class for sort order.\n\n  Attributes:\n    ascend: ascend order.\n    descend: descend order.\n  \"\"\"\n  ascend = 1\n  descend = 2\n\n\ndef area(boxlist, scope=None):\n  \"\"\"Computes area of boxes.\n\n  Args:\n    boxlist: BoxList holding N boxes\n    scope: name scope.\n\n  Returns:\n    a tensor with shape [N] representing box areas.\n  \"\"\"\n  with tf.name_scope(scope, 'Area'):\n    y_min, x_min, y_max, x_max = tf.split(\n        value=boxlist.get(), num_or_size_splits=4, axis=1)\n    return tf.squeeze((y_max - y_min) * (x_max - x_min), [1])\n\n\ndef height_width(boxlist, scope=None):\n  \"\"\"Computes height and width of boxes in boxlist.\n\n  Args:\n    boxlist: BoxList holding N boxes\n    scope: name scope.\n\n  Returns:\n    Height: A tensor with shape [N] representing box heights.\n    Width: A tensor with shape [N] representing box widths.\n  \"\"\"\n  with tf.name_scope(scope, 'HeightWidth'):\n    y_min, x_min, y_max, x_max = tf.split(\n        value=boxlist.get(), num_or_size_splits=4, axis=1)\n    return tf.squeeze(y_max - y_min, [1]), tf.squeeze(x_max - x_min, [1])\n\n\ndef scale(boxlist, y_scale, x_scale, scope=None):\n  \"\"\"scale box coordinates in x and y dimensions.\n\n  Args:\n    boxlist: BoxList holding N boxes\n    y_scale: (float) scalar tensor\n    x_scale: (float) scalar tensor\n    scope: name scope.\n\n  Returns:\n    boxlist: BoxList holding N boxes\n  \"\"\"\n  with tf.name_scope(scope, 'Scale'):\n    y_scale = tf.cast(y_scale, tf.float32)\n    x_scale = tf.cast(x_scale, tf.float32)\n    y_min, x_min, y_max, x_max = tf.split(\n        value=boxlist.get(), num_or_size_splits=4, axis=1)\n    y_min = y_scale * y_min\n    y_max = y_scale * y_max\n    x_min = x_scale * x_min\n    x_max = x_scale * x_max\n    scaled_boxlist = box_list.BoxList(\n        tf.concat([y_min, x_min, y_max, x_max], 1))\n    return _copy_extra_fields(scaled_boxlist, boxlist)\n\n\ndef clip_to_window(boxlist, window, filter_nonoverlapping=True, scope=None):\n  \"\"\"Clip bounding boxes to a window.\n\n  This op clips any input bounding boxes (represented by bounding box\n  corners) to a window, optionally filtering out boxes that do not\n  overlap at all with the window.\n\n  Args:\n    boxlist: BoxList holding M_in boxes\n    window: a tensor of shape [4] representing the [y_min, x_min, y_max, x_max]\n      window to which the op should clip boxes.\n    filter_nonoverlapping: whether to filter out boxes that do not overlap at\n      all with the window.\n    scope: name scope.\n\n  Returns:\n    a BoxList holding M_out boxes where M_out <= M_in\n  \"\"\"\n  with tf.name_scope(scope, 'ClipToWindow'):\n    y_min, x_min, y_max, x_max = tf.split(\n        value=boxlist.get(), num_or_size_splits=4, axis=1)\n    win_y_min, win_x_min, win_y_max, win_x_max = tf.unstack(window)\n    y_min_clipped = tf.maximum(tf.minimum(y_min, win_y_max), win_y_min)\n    y_max_clipped = tf.maximum(tf.minimum(y_max, win_y_max), win_y_min)\n    x_min_clipped = tf.maximum(tf.minimum(x_min, win_x_max), win_x_min)\n    x_max_clipped = tf.maximum(tf.minimum(x_max, win_x_max), win_x_min)\n    clipped = box_list.BoxList(\n        tf.concat([y_min_clipped, x_min_clipped, y_max_clipped, x_max_clipped],\n                  1))\n    clipped = _copy_extra_fields(clipped, boxlist)\n    if filter_nonoverlapping:\n      areas = area(clipped)\n      nonzero_area_indices = tf.cast(\n          tf.reshape(tf.where(tf.greater(areas, 0.0)), [-1]), tf.int32)\n      clipped = gather(clipped, nonzero_area_indices)\n    return clipped\n\n\ndef prune_outside_window(boxlist, window, scope=None):\n  \"\"\"Prunes bounding boxes that fall outside a given window.\n\n  This function prunes bounding boxes that even partially fall outside the given\n  window. See also clip_to_window which only prunes bounding boxes that fall\n  completely outside the window, and clips any bounding boxes that partially\n  overflow.\n\n  Args:\n    boxlist: a BoxList holding M_in boxes.\n    window: a float tensor of shape [4] representing [ymin, xmin, ymax, xmax]\n      of the window\n    scope: name scope.\n\n  Returns:\n    pruned_corners: a tensor with shape [M_out, 4] where M_out <= M_in\n    valid_indices: a tensor with shape [M_out] indexing the valid bounding boxes\n     in the input tensor.\n  \"\"\"\n  with tf.name_scope(scope, 'PruneOutsideWindow'):\n    y_min, x_min, y_max, x_max = tf.split(\n        value=boxlist.get(), num_or_size_splits=4, axis=1)\n    win_y_min, win_x_min, win_y_max, win_x_max = tf.unstack(window)\n    coordinate_violations = tf.concat([\n        tf.less(y_min, win_y_min), tf.less(x_min, win_x_min),\n        tf.greater(y_max, win_y_max), tf.greater(x_max, win_x_max)\n    ], 1)\n    valid_indices = tf.reshape(\n        tf.where(tf.logical_not(tf.reduce_any(coordinate_violations, 1))), [-1])\n    return gather(boxlist, valid_indices), valid_indices\n\n\ndef prune_completely_outside_window(boxlist, window, scope=None):\n  \"\"\"Prunes bounding boxes that fall completely outside of the given window.\n\n  The function clip_to_window prunes bounding boxes that fall\n  completely outside the window, but also clips any bounding boxes that\n  partially overflow. This function does not clip partially overflowing boxes.\n\n  Args:\n    boxlist: a BoxList holding M_in boxes.\n    window: a float tensor of shape [4] representing [ymin, xmin, ymax, xmax]\n      of the window\n    scope: name scope.\n\n  Returns:\n    pruned_corners: a tensor with shape [M_out, 4] where M_out <= M_in\n    valid_indices: a tensor with shape [M_out] indexing the valid bounding boxes\n     in the input tensor.\n  \"\"\"\n  with tf.name_scope(scope, 'PruneCompleteleyOutsideWindow'):\n    y_min, x_min, y_max, x_max = tf.split(\n        value=boxlist.get(), num_or_size_splits=4, axis=1)\n    win_y_min, win_x_min, win_y_max, win_x_max = tf.unstack(window)\n    coordinate_violations = tf.concat([\n        tf.greater_equal(y_min, win_y_max), tf.greater_equal(x_min, win_x_max),\n        tf.less_equal(y_max, win_y_min), tf.less_equal(x_max, win_x_min)\n    ], 1)\n    valid_indices = tf.reshape(\n        tf.where(tf.logical_not(tf.reduce_any(coordinate_violations, 1))), [-1])\n    return gather(boxlist, valid_indices), valid_indices\n\n\ndef intersection(boxlist1, boxlist2, scope=None):\n  \"\"\"Compute pairwise intersection areas between boxes.\n\n  Args:\n    boxlist1: BoxList holding N boxes\n    boxlist2: BoxList holding M boxes\n    scope: name scope.\n\n  Returns:\n    a tensor with shape [N, M] representing pairwise intersections\n  \"\"\"\n  with tf.name_scope(scope, 'Intersection'):\n    y_min1, x_min1, y_max1, x_max1 = tf.split(\n        value=boxlist1.get(), num_or_size_splits=4, axis=1)\n    y_min2, x_min2, y_max2, x_max2 = tf.split(\n        value=boxlist2.get(), num_or_size_splits=4, axis=1)\n    all_pairs_min_ymax = tf.minimum(y_max1, tf.transpose(y_max2))\n    all_pairs_max_ymin = tf.maximum(y_min1, tf.transpose(y_min2))\n    intersect_heights = tf.maximum(0.0, all_pairs_min_ymax - all_pairs_max_ymin)\n    all_pairs_min_xmax = tf.minimum(x_max1, tf.transpose(x_max2))\n    all_pairs_max_xmin = tf.maximum(x_min1, tf.transpose(x_min2))\n    intersect_widths = tf.maximum(0.0, all_pairs_min_xmax - all_pairs_max_xmin)\n    return intersect_heights * intersect_widths\n\n\ndef matched_intersection(boxlist1, boxlist2, scope=None):\n  \"\"\"Compute intersection areas between corresponding boxes in two boxlists.\n\n  Args:\n    boxlist1: BoxList holding N boxes\n    boxlist2: BoxList holding N boxes\n    scope: name scope.\n\n  Returns:\n    a tensor with shape [N] representing pairwise intersections\n  \"\"\"\n  with tf.name_scope(scope, 'MatchedIntersection'):\n    y_min1, x_min1, y_max1, x_max1 = tf.split(\n        value=boxlist1.get(), num_or_size_splits=4, axis=1)\n    y_min2, x_min2, y_max2, x_max2 = tf.split(\n        value=boxlist2.get(), num_or_size_splits=4, axis=1)\n    min_ymax = tf.minimum(y_max1, y_max2)\n    max_ymin = tf.maximum(y_min1, y_min2)\n    intersect_heights = tf.maximum(0.0, min_ymax - max_ymin)\n    min_xmax = tf.minimum(x_max1, x_max2)\n    max_xmin = tf.maximum(x_min1, x_min2)\n    intersect_widths = tf.maximum(0.0, min_xmax - max_xmin)\n    return tf.reshape(intersect_heights * intersect_widths, [-1])\n\n\ndef iou(boxlist1, boxlist2, scope=None):\n  \"\"\"Computes pairwise intersection-over-union between box collections.\n\n  Args:\n    boxlist1: BoxList holding N boxes\n    boxlist2: BoxList holding M boxes\n    scope: name scope.\n\n  Returns:\n    a tensor with shape [N, M] representing pairwise iou scores.\n  \"\"\"\n  with tf.name_scope(scope, 'IOU'):\n    intersections = intersection(boxlist1, boxlist2)\n    areas1 = area(boxlist1)\n    areas2 = area(boxlist2)\n    unions = (\n        tf.expand_dims(areas1, 1) + tf.expand_dims(areas2, 0) - intersections)\n    return tf.where(\n        tf.equal(intersections, 0.0),\n        tf.zeros_like(intersections), tf.truediv(intersections, unions))\n\n\ndef matched_iou(boxlist1, boxlist2, scope=None):\n  \"\"\"Compute intersection-over-union between corresponding boxes in boxlists.\n\n  Args:\n    boxlist1: BoxList holding N boxes\n    boxlist2: BoxList holding N boxes\n    scope: name scope.\n\n  Returns:\n    a tensor with shape [N] representing pairwise iou scores.\n  \"\"\"\n  with tf.name_scope(scope, 'MatchedIOU'):\n    intersections = matched_intersection(boxlist1, boxlist2)\n    areas1 = area(boxlist1)\n    areas2 = area(boxlist2)\n    unions = areas1 + areas2 - intersections\n    return tf.where(\n        tf.equal(intersections, 0.0),\n        tf.zeros_like(intersections), tf.truediv(intersections, unions))\n\n\ndef ioa(boxlist1, boxlist2, scope=None):\n  \"\"\"Computes pairwise intersection-over-area between box collections.\n\n  intersection-over-area (IOA) between two boxes box1 and box2 is defined as\n  their intersection area over box2's area. Note that ioa is not symmetric,\n  that is, ioa(box1, box2) != ioa(box2, box1).\n\n  Args:\n    boxlist1: BoxList holding N boxes\n    boxlist2: BoxList holding M boxes\n    scope: name scope.\n\n  Returns:\n    a tensor with shape [N, M] representing pairwise ioa scores.\n  \"\"\"\n  with tf.name_scope(scope, 'IOA'):\n    intersections = intersection(boxlist1, boxlist2)\n    areas = tf.expand_dims(area(boxlist2), 0)\n    return tf.truediv(intersections, areas)\n\n\ndef prune_non_overlapping_boxes(\n    boxlist1, boxlist2, min_overlap=0.0, scope=None):\n  \"\"\"Prunes the boxes in boxlist1 that overlap less than thresh with boxlist2.\n\n  For each box in boxlist1, we want its IOA to be more than minoverlap with\n  at least one of the boxes in boxlist2. If it does not, we remove it.\n\n  Args:\n    boxlist1: BoxList holding N boxes.\n    boxlist2: BoxList holding M boxes.\n    min_overlap: Minimum required overlap between boxes, to count them as\n                overlapping.\n    scope: name scope.\n\n  Returns:\n    new_boxlist1: A pruned boxlist with size [N', 4].\n    keep_inds: A tensor with shape [N'] indexing kept bounding boxes in the\n      first input BoxList `boxlist1`.\n  \"\"\"\n  with tf.name_scope(scope, 'PruneNonOverlappingBoxes'):\n    ioa_ = ioa(boxlist2, boxlist1)  # [M, N] tensor\n    ioa_ = tf.reduce_max(ioa_, reduction_indices=[0])  # [N] tensor\n    keep_bool = tf.greater_equal(ioa_, tf.constant(min_overlap))\n    keep_inds = tf.squeeze(tf.where(keep_bool), squeeze_dims=[1])\n    new_boxlist1 = gather(boxlist1, keep_inds)\n    return new_boxlist1, keep_inds\n\n\ndef prune_small_boxes(boxlist, min_side, scope=None):\n  \"\"\"Prunes small boxes in the boxlist which have a side smaller than min_side.\n\n  Args:\n    boxlist: BoxList holding N boxes.\n    min_side: Minimum width AND height of box to survive pruning.\n    scope: name scope.\n\n  Returns:\n    A pruned boxlist.\n  \"\"\"\n  with tf.name_scope(scope, 'PruneSmallBoxes'):\n    height, width = height_width(boxlist)\n    is_valid = tf.logical_and(tf.greater_equal(width, min_side),\n                              tf.greater_equal(height, min_side))\n    return gather(boxlist, tf.reshape(tf.where(is_valid), [-1]))\n\n\ndef change_coordinate_frame(boxlist, window, scope=None):\n  \"\"\"Change coordinate frame of the boxlist to be relative to window's frame.\n\n  Given a window of the form [ymin, xmin, ymax, xmax],\n  changes bounding box coordinates from boxlist to be relative to this window\n  (e.g., the min corner maps to (0,0) and the max corner maps to (1,1)).\n\n  An example use case is data augmentation: where we are given groundtruth\n  boxes (boxlist) and would like to randomly crop the image to some\n  window (window). In this case we need to change the coordinate frame of\n  each groundtruth box to be relative to this new window.\n\n  Args:\n    boxlist: A BoxList object holding N boxes.\n    window: A rank 1 tensor [4].\n    scope: name scope.\n\n  Returns:\n    Returns a BoxList object with N boxes.\n  \"\"\"\n  with tf.name_scope(scope, 'ChangeCoordinateFrame'):\n    win_height = window[2] - window[0]\n    win_width = window[3] - window[1]\n    boxlist_new = scale(box_list.BoxList(\n        boxlist.get() - [window[0], window[1], window[0], window[1]]),\n                        1.0 / win_height, 1.0 / win_width)\n    boxlist_new = _copy_extra_fields(boxlist_new, boxlist)\n    return boxlist_new\n\n\ndef sq_dist(boxlist1, boxlist2, scope=None):\n  \"\"\"Computes the pairwise squared distances between box corners.\n\n  This op treats each box as if it were a point in a 4d Euclidean space and\n  computes pairwise squared distances.\n\n  Mathematically, we are given two matrices of box coordinates X and Y,\n  where X(i,:) is the i'th row of X, containing the 4 numbers defining the\n  corners of the i'th box in boxlist1. Similarly Y(j,:) corresponds to\n  boxlist2.  We compute\n  Z(i,j) = ||X(i,:) - Y(j,:)||^2\n         = ||X(i,:)||^2 + ||Y(j,:)||^2 - 2 X(i,:)' * Y(j,:),\n\n  Args:\n    boxlist1: BoxList holding N boxes\n    boxlist2: BoxList holding M boxes\n    scope: name scope.\n\n  Returns:\n    a tensor with shape [N, M] representing pairwise distances\n  \"\"\"\n  with tf.name_scope(scope, 'SqDist'):\n    sqnorm1 = tf.reduce_sum(tf.square(boxlist1.get()), 1, keep_dims=True)\n    sqnorm2 = tf.reduce_sum(tf.square(boxlist2.get()), 1, keep_dims=True)\n    innerprod = tf.matmul(boxlist1.get(), boxlist2.get(),\n                          transpose_a=False, transpose_b=True)\n    return sqnorm1 + tf.transpose(sqnorm2) - 2.0 * innerprod\n\n\ndef boolean_mask(boxlist, indicator, fields=None, scope=None):\n  \"\"\"Select boxes from BoxList according to indicator and return new BoxList.\n\n  `boolean_mask` returns the subset of boxes that are marked as \"True\" by the\n  indicator tensor. By default, `boolean_mask` returns boxes corresponding to\n  the input index list, as well as all additional fields stored in the boxlist\n  (indexing into the first dimension).  However one can optionally only draw\n  from a subset of fields.\n\n  Args:\n    boxlist: BoxList holding N boxes\n    indicator: a rank-1 boolean tensor\n    fields: (optional) list of fields to also gather from.  If None (default),\n      all fields are gathered from.  Pass an empty fields list to only gather\n      the box coordinates.\n    scope: name scope.\n\n  Returns:\n    subboxlist: a BoxList corresponding to the subset of the input BoxList\n      specified by indicator\n  Raises:\n    ValueError: if `indicator` is not a rank-1 boolean tensor.\n  \"\"\"\n  with tf.name_scope(scope, 'BooleanMask'):\n    if indicator.shape.ndims != 1:\n      raise ValueError('indicator should have rank 1')\n    if indicator.dtype != tf.bool:\n      raise ValueError('indicator should be a boolean tensor')\n    subboxlist = box_list.BoxList(tf.boolean_mask(boxlist.get(), indicator))\n    if fields is None:\n      fields = boxlist.get_extra_fields()\n    for field in fields:\n      if not boxlist.has_field(field):\n        raise ValueError('boxlist must contain all specified fields')\n      subfieldlist = tf.boolean_mask(boxlist.get_field(field), indicator)\n      subboxlist.add_field(field, subfieldlist)\n    return subboxlist\n\n\ndef gather(boxlist, indices, fields=None, scope=None):\n  \"\"\"Gather boxes from BoxList according to indices and return new BoxList.\n\n  By default, `gather` returns boxes corresponding to the input index list, as\n  well as all additional fields stored in the boxlist (indexing into the\n  first dimension).  However one can optionally only gather from a\n  subset of fields.\n\n  Args:\n    boxlist: BoxList holding N boxes\n    indices: a rank-1 tensor of type int32 / int64\n    fields: (optional) list of fields to also gather from.  If None (default),\n      all fields are gathered from.  Pass an empty fields list to only gather\n      the box coordinates.\n    scope: name scope.\n\n  Returns:\n    subboxlist: a BoxList corresponding to the subset of the input BoxList\n    specified by indices\n  Raises:\n    ValueError: if specified field is not contained in boxlist or if the\n      indices are not of type int32\n  \"\"\"\n  with tf.name_scope(scope, 'Gather'):\n    if len(indices.shape.as_list()) != 1:\n      raise ValueError('indices should have rank 1')\n    if indices.dtype != tf.int32 and indices.dtype != tf.int64:\n      raise ValueError('indices should be an int32 / int64 tensor')\n    subboxlist = box_list.BoxList(tf.gather(boxlist.get(), indices))\n    if fields is None:\n      fields = boxlist.get_extra_fields()\n    for field in fields:\n      if not boxlist.has_field(field):\n        raise ValueError('boxlist must contain all specified fields')\n      subfieldlist = tf.gather(boxlist.get_field(field), indices)\n      subboxlist.add_field(field, subfieldlist)\n    return subboxlist\n\n\ndef concatenate(boxlists, fields=None, scope=None):\n  \"\"\"Concatenate list of BoxLists.\n\n  This op concatenates a list of input BoxLists into a larger BoxList.  It also\n  handles concatenation of BoxList fields as long as the field tensor shapes\n  are equal except for the first dimension.\n\n  Args:\n    boxlists: list of BoxList objects\n    fields: optional list of fields to also concatenate.  By default, all\n      fields from the first BoxList in the list are included in the\n      concatenation.\n    scope: name scope.\n\n  Returns:\n    a BoxList with number of boxes equal to\n      sum([boxlist.num_boxes() for boxlist in BoxList])\n  Raises:\n    ValueError: if boxlists is invalid (i.e., is not a list, is empty, or\n      contains non BoxList objects), or if requested fields are not contained in\n      all boxlists\n  \"\"\"\n  with tf.name_scope(scope, 'Concatenate'):\n    if not isinstance(boxlists, list):\n      raise ValueError('boxlists should be a list')\n    if not boxlists:\n      raise ValueError('boxlists should have nonzero length')\n    for boxlist in boxlists:\n      if not isinstance(boxlist, box_list.BoxList):\n        raise ValueError('all elements of boxlists should be BoxList objects')\n    concatenated = box_list.BoxList(\n        tf.concat([boxlist.get() for boxlist in boxlists], 0))\n    if fields is None:\n      fields = boxlists[0].get_extra_fields()\n    for field in fields:\n      first_field_shape = boxlists[0].get_field(field).get_shape().as_list()\n      first_field_shape[0] = -1\n      if None in first_field_shape:\n        raise ValueError('field %s must have fully defined shape except for the'\n                         ' 0th dimension.' % field)\n      for boxlist in boxlists:\n        if not boxlist.has_field(field):\n          raise ValueError('boxlist must contain all requested fields')\n        field_shape = boxlist.get_field(field).get_shape().as_list()\n        field_shape[0] = -1\n        if field_shape != first_field_shape:\n          raise ValueError('field %s must have same shape for all boxlists '\n                           'except for the 0th dimension.' % field)\n      concatenated_field = tf.concat(\n          [boxlist.get_field(field) for boxlist in boxlists], 0)\n      concatenated.add_field(field, concatenated_field)\n    return concatenated\n\n\ndef sort_by_field(boxlist, field, order=SortOrder.descend, scope=None):\n  \"\"\"Sort boxes and associated fields according to a scalar field.\n\n  A common use case is reordering the boxes according to descending scores.\n\n  Args:\n    boxlist: BoxList holding N boxes.\n    field: A BoxList field for sorting and reordering the BoxList.\n    order: (Optional) descend or ascend. Default is descend.\n    scope: name scope.\n\n  Returns:\n    sorted_boxlist: A sorted BoxList with the field in the specified order.\n\n  Raises:\n    ValueError: if specified field does not exist\n    ValueError: if the order is not either descend or ascend\n  \"\"\"\n  with tf.name_scope(scope, 'SortByField'):\n    if order != SortOrder.descend and order != SortOrder.ascend:\n      raise ValueError('Invalid sort order')\n\n    field_to_sort = boxlist.get_field(field)\n    if len(field_to_sort.shape.as_list()) != 1:\n      raise ValueError('Field should have rank 1')\n\n    num_boxes = boxlist.num_boxes()\n    num_entries = tf.size(field_to_sort)\n    length_assert = tf.Assert(\n        tf.equal(num_boxes, num_entries),\n        ['Incorrect field size: actual vs expected.', num_entries, num_boxes])\n\n    with tf.control_dependencies([length_assert]):\n      # TODO: Remove with tf.device when top_k operation runs correctly on GPU.\n      with tf.device('/cpu:0'):\n        _, sorted_indices = tf.nn.top_k(field_to_sort, num_boxes, sorted=True)\n\n    if order == SortOrder.ascend:\n      sorted_indices = tf.reverse_v2(sorted_indices, [0])\n\n    return gather(boxlist, sorted_indices)\n\n\ndef visualize_boxes_in_image(image, boxlist, normalized=False, scope=None):\n  \"\"\"Overlay bounding box list on image.\n\n  Currently this visualization plots a 1 pixel thick red bounding box on top\n  of the image.  Note that tf.image.draw_bounding_boxes essentially is\n  1 indexed.\n\n  Args:\n    image: an image tensor with shape [height, width, 3]\n    boxlist: a BoxList\n    normalized: (boolean) specify whether corners are to be interpreted\n      as absolute coordinates in image space or normalized with respect to the\n      image size.\n    scope: name scope.\n\n  Returns:\n    image_and_boxes: an image tensor with shape [height, width, 3]\n  \"\"\"\n  with tf.name_scope(scope, 'VisualizeBoxesInImage'):\n    if not normalized:\n      height, width, _ = tf.unstack(tf.shape(image))\n      boxlist = scale(boxlist,\n                      1.0 / tf.cast(height, tf.float32),\n                      1.0 / tf.cast(width, tf.float32))\n    corners = tf.expand_dims(boxlist.get(), 0)\n    image = tf.expand_dims(image, 0)\n    return tf.squeeze(tf.image.draw_bounding_boxes(image, corners), [0])\n\n\ndef filter_field_value_equals(boxlist, field, value, scope=None):\n  \"\"\"Filter to keep only boxes with field entries equal to the given value.\n\n  Args:\n    boxlist: BoxList holding N boxes.\n    field: field name for filtering.\n    value: scalar value.\n    scope: name scope.\n\n  Returns:\n    a BoxList holding M boxes where M <= N\n\n  Raises:\n    ValueError: if boxlist not a BoxList object or if it does not have\n      the specified field.\n  \"\"\"\n  with tf.name_scope(scope, 'FilterFieldValueEquals'):\n    if not isinstance(boxlist, box_list.BoxList):\n      raise ValueError('boxlist must be a BoxList')\n    if not boxlist.has_field(field):\n      raise ValueError('boxlist must contain the specified field')\n    filter_field = boxlist.get_field(field)\n    gather_index = tf.reshape(tf.where(tf.equal(filter_field, value)), [-1])\n    return gather(boxlist, gather_index)\n\n\ndef filter_greater_than(boxlist, thresh, scope=None):\n  \"\"\"Filter to keep only boxes with score exceeding a given threshold.\n\n  This op keeps the collection of boxes whose corresponding scores are\n  greater than the input threshold.\n\n  TODO: Change function name to FilterScoresGreaterThan\n\n  Args:\n    boxlist: BoxList holding N boxes.  Must contain a 'scores' field\n      representing detection scores.\n    thresh: scalar threshold\n    scope: name scope.\n\n  Returns:\n    a BoxList holding M boxes where M <= N\n\n  Raises:\n    ValueError: if boxlist not a BoxList object or if it does not\n      have a scores field\n  \"\"\"\n  with tf.name_scope(scope, 'FilterGreaterThan'):\n    if not isinstance(boxlist, box_list.BoxList):\n      raise ValueError('boxlist must be a BoxList')\n    if not boxlist.has_field('scores'):\n      raise ValueError('input boxlist must have \\'scores\\' field')\n    scores = boxlist.get_field('scores')\n    if len(scores.shape.as_list()) > 2:\n      raise ValueError('Scores should have rank 1 or 2')\n    if len(scores.shape.as_list()) == 2 and scores.shape.as_list()[1] != 1:\n      raise ValueError('Scores should have rank 1 or have shape '\n                       'consistent with [None, 1]')\n    high_score_indices = tf.cast(tf.reshape(\n        tf.where(tf.greater(scores, thresh)),\n        [-1]), tf.int32)\n    return gather(boxlist, high_score_indices)\n\n\ndef non_max_suppression(boxlist, thresh, max_output_size, scope=None):\n  \"\"\"Non maximum suppression.\n\n  This op greedily selects a subset of detection bounding boxes, pruning\n  away boxes that have high IOU (intersection over union) overlap (> thresh)\n  with already selected boxes.  Note that this only works for a single class ---\n  to apply NMS to multi-class predictions, use MultiClassNonMaxSuppression.\n\n  Args:\n    boxlist: BoxList holding N boxes.  Must contain a 'scores' field\n      representing detection scores.\n    thresh: scalar threshold\n    max_output_size: maximum number of retained boxes\n    scope: name scope.\n\n  Returns:\n    a BoxList holding M boxes where M <= max_output_size\n  Raises:\n    ValueError: if thresh is not in [0, 1]\n  \"\"\"\n  with tf.name_scope(scope, 'NonMaxSuppression'):\n    if not 0 <= thresh <= 1.0:\n      raise ValueError('thresh must be between 0 and 1')\n    if not isinstance(boxlist, box_list.BoxList):\n      raise ValueError('boxlist must be a BoxList')\n    if not boxlist.has_field('scores'):\n      raise ValueError('input boxlist must have \\'scores\\' field')\n    selected_indices = tf.image.non_max_suppression(\n        boxlist.get(), boxlist.get_field('scores'),\n        max_output_size, iou_threshold=thresh)\n    return gather(boxlist, selected_indices)\n\n\ndef _copy_extra_fields(boxlist_to_copy_to, boxlist_to_copy_from):\n  \"\"\"Copies the extra fields of boxlist_to_copy_from to boxlist_to_copy_to.\n\n  Args:\n    boxlist_to_copy_to: BoxList to which extra fields are copied.\n    boxlist_to_copy_from: BoxList from which fields are copied.\n\n  Returns:\n    boxlist_to_copy_to with extra fields.\n  \"\"\"\n  for field in boxlist_to_copy_from.get_extra_fields():\n    boxlist_to_copy_to.add_field(field, boxlist_to_copy_from.get_field(field))\n  return boxlist_to_copy_to\n\n\ndef to_normalized_coordinates(boxlist, height, width,\n                              check_range=True, scope=None):\n  \"\"\"Converts absolute box coordinates to normalized coordinates in [0, 1].\n\n  Usually one uses the dynamic shape of the image or conv-layer tensor:\n    boxlist = box_list_ops.to_normalized_coordinates(boxlist,\n                                                     tf.shape(images)[1],\n                                                     tf.shape(images)[2]),\n\n  This function raises an assertion failed error at graph execution time when\n  the maximum coordinate is smaller than 1.01 (which means that coordinates are\n  already normalized). The value 1.01 is to deal with small rounding errors.\n\n  Args:\n    boxlist: BoxList with coordinates in terms of pixel-locations.\n    height: Maximum value for height of absolute box coordinates.\n    width: Maximum value for width of absolute box coordinates.\n    check_range: If True, checks if the coordinates are normalized or not.\n    scope: name scope.\n\n  Returns:\n    boxlist with normalized coordinates in [0, 1].\n  \"\"\"\n  with tf.name_scope(scope, 'ToNormalizedCoordinates'):\n    height = tf.cast(height, tf.float32)\n    width = tf.cast(width, tf.float32)\n\n    if check_range:\n      max_val = tf.reduce_max(boxlist.get())\n      max_assert = tf.Assert(tf.greater(max_val, 1.01),\n                             ['max value is lower than 1.01: ', max_val])\n      with tf.control_dependencies([max_assert]):\n        width = tf.identity(width)\n\n    return scale(boxlist, 1 / height, 1 / width)\n\n\ndef to_absolute_coordinates(boxlist, height, width,\n                            check_range=True, scope=None):\n  \"\"\"Converts normalized box coordinates to absolute pixel coordinates.\n\n  This function raises an assertion failed error when the maximum box coordinate\n  value is larger than 1.01 (in which case coordinates are already absolute).\n\n  Args:\n    boxlist: BoxList with coordinates in range [0, 1].\n    height: Maximum value for height of absolute box coordinates.\n    width: Maximum value for width of absolute box coordinates.\n    check_range: If True, checks if the coordinates are normalized or not.\n    scope: name scope.\n\n  Returns:\n    boxlist with absolute coordinates in terms of the image size.\n\n  \"\"\"\n  with tf.name_scope(scope, 'ToAbsoluteCoordinates'):\n    height = tf.cast(height, tf.float32)\n    width = tf.cast(width, tf.float32)\n\n    # Ensure range of input boxes is correct.\n    if check_range:\n      box_maximum = tf.reduce_max(boxlist.get())\n      max_assert = tf.Assert(tf.greater_equal(1.01, box_maximum),\n                             ['maximum box coordinate value is larger '\n                              'than 1.01: ', box_maximum])\n      with tf.control_dependencies([max_assert]):\n        width = tf.identity(width)\n\n    return scale(boxlist, height, width)\n\n\ndef refine_boxes_multi_class(pool_boxes,\n                             num_classes,\n                             nms_iou_thresh,\n                             nms_max_detections,\n                             voting_iou_thresh=0.5):\n  \"\"\"Refines a pool of boxes using non max suppression and box voting.\n\n  Box refinement is done independently for each class.\n\n  Args:\n    pool_boxes: (BoxList) A collection of boxes to be refined. pool_boxes must\n      have a rank 1 'scores' field and a rank 1 'classes' field.\n    num_classes: (int scalar) Number of classes.\n    nms_iou_thresh: (float scalar) iou threshold for non max suppression (NMS).\n    nms_max_detections: (int scalar) maximum output size for NMS.\n    voting_iou_thresh: (float scalar) iou threshold for box voting.\n\n  Returns:\n    BoxList of refined boxes.\n\n  Raises:\n    ValueError: if\n      a) nms_iou_thresh or voting_iou_thresh is not in [0, 1].\n      b) pool_boxes is not a BoxList.\n      c) pool_boxes does not have a scores and classes field.\n  \"\"\"\n  if not 0.0 <= nms_iou_thresh <= 1.0:\n    raise ValueError('nms_iou_thresh must be between 0 and 1')\n  if not 0.0 <= voting_iou_thresh <= 1.0:\n    raise ValueError('voting_iou_thresh must be between 0 and 1')\n  if not isinstance(pool_boxes, box_list.BoxList):\n    raise ValueError('pool_boxes must be a BoxList')\n  if not pool_boxes.has_field('scores'):\n    raise ValueError('pool_boxes must have a \\'scores\\' field')\n  if not pool_boxes.has_field('classes'):\n    raise ValueError('pool_boxes must have a \\'classes\\' field')\n\n  refined_boxes = []\n  for i in range(num_classes):\n    boxes_class = filter_field_value_equals(pool_boxes, 'classes', i)\n    refined_boxes_class = refine_boxes(boxes_class, nms_iou_thresh,\n                                       nms_max_detections, voting_iou_thresh)\n    refined_boxes.append(refined_boxes_class)\n  return sort_by_field(concatenate(refined_boxes), 'scores')\n\n\ndef refine_boxes(pool_boxes,\n                 nms_iou_thresh,\n                 nms_max_detections,\n                 voting_iou_thresh=0.5):\n  \"\"\"Refines a pool of boxes using non max suppression and box voting.\n\n  Args:\n    pool_boxes: (BoxList) A collection of boxes to be refined. pool_boxes must\n      have a rank 1 'scores' field.\n    nms_iou_thresh: (float scalar) iou threshold for non max suppression (NMS).\n    nms_max_detections: (int scalar) maximum output size for NMS.\n    voting_iou_thresh: (float scalar) iou threshold for box voting.\n\n  Returns:\n    BoxList of refined boxes.\n\n  Raises:\n    ValueError: if\n      a) nms_iou_thresh or voting_iou_thresh is not in [0, 1].\n      b) pool_boxes is not a BoxList.\n      c) pool_boxes does not have a scores field.\n  \"\"\"\n  if not 0.0 <= nms_iou_thresh <= 1.0:\n    raise ValueError('nms_iou_thresh must be between 0 and 1')\n  if not 0.0 <= voting_iou_thresh <= 1.0:\n    raise ValueError('voting_iou_thresh must be between 0 and 1')\n  if not isinstance(pool_boxes, box_list.BoxList):\n    raise ValueError('pool_boxes must be a BoxList')\n  if not pool_boxes.has_field('scores'):\n    raise ValueError('pool_boxes must have a \\'scores\\' field')\n\n  nms_boxes = non_max_suppression(\n      pool_boxes, nms_iou_thresh, nms_max_detections)\n  return box_voting(nms_boxes, pool_boxes, voting_iou_thresh)\n\n\ndef box_voting(selected_boxes, pool_boxes, iou_thresh=0.5):\n  \"\"\"Performs box voting as described in S. Gidaris and N. Komodakis, ICCV 2015.\n\n  Performs box voting as described in 'Object detection via a multi-region &\n  semantic segmentation-aware CNN model', Gidaris and Komodakis, ICCV 2015. For\n  each box 'B' in selected_boxes, we find the set 'S' of boxes in pool_boxes\n  with iou overlap >= iou_thresh. The location of B is set to the weighted\n  average location of boxes in S (scores are used for weighting). And the score\n  of B is set to the average score of boxes in S.\n\n  Args:\n    selected_boxes: BoxList containing a subset of boxes in pool_boxes. These\n      boxes are usually selected from pool_boxes using non max suppression.\n    pool_boxes: BoxList containing a set of (possibly redundant) boxes.\n    iou_thresh: (float scalar) iou threshold for matching boxes in\n      selected_boxes and pool_boxes.\n\n  Returns:\n    BoxList containing averaged locations and scores for each box in\n    selected_boxes.\n\n  Raises:\n    ValueError: if\n      a) selected_boxes or pool_boxes is not a BoxList.\n      b) if iou_thresh is not in [0, 1].\n      c) pool_boxes does not have a scores field.\n  \"\"\"\n  if not 0.0 <= iou_thresh <= 1.0:\n    raise ValueError('iou_thresh must be between 0 and 1')\n  if not isinstance(selected_boxes, box_list.BoxList):\n    raise ValueError('selected_boxes must be a BoxList')\n  if not isinstance(pool_boxes, box_list.BoxList):\n    raise ValueError('pool_boxes must be a BoxList')\n  if not pool_boxes.has_field('scores'):\n    raise ValueError('pool_boxes must have a \\'scores\\' field')\n\n  iou_ = iou(selected_boxes, pool_boxes)\n  match_indicator = tf.to_float(tf.greater(iou_, iou_thresh))\n  num_matches = tf.reduce_sum(match_indicator, 1)\n  # TODO: Handle the case where some boxes in selected_boxes do not match to any\n  # boxes in pool_boxes. For such boxes without any matches, we should return\n  # the original boxes without voting.\n  match_assert = tf.Assert(\n      tf.reduce_all(tf.greater(num_matches, 0)),\n      ['Each box in selected_boxes must match with at least one box '\n       'in pool_boxes.'])\n\n  scores = tf.expand_dims(pool_boxes.get_field('scores'), 1)\n  scores_assert = tf.Assert(\n      tf.reduce_all(tf.greater_equal(scores, 0)),\n      ['Scores must be non negative.'])\n\n  with tf.control_dependencies([scores_assert, match_assert]):\n    sum_scores = tf.matmul(match_indicator, scores)\n  averaged_scores = tf.reshape(sum_scores, [-1]) / num_matches\n\n  box_locations = tf.matmul(match_indicator,\n                            pool_boxes.get() * scores) / sum_scores\n  averaged_boxes = box_list.BoxList(box_locations)\n  _copy_extra_fields(averaged_boxes, selected_boxes)\n  averaged_boxes.add_field('scores', averaged_scores)\n  return averaged_boxes\n\n\ndef pad_or_clip_box_list(boxlist, num_boxes, scope=None):\n  \"\"\"Pads or clips all fields of a BoxList.\n\n  Args:\n    boxlist: A BoxList with arbitrary of number of boxes.\n    num_boxes: First num_boxes in boxlist are kept.\n      The fields are zero-padded if num_boxes is bigger than the\n      actual number of boxes.\n    scope: name scope.\n\n  Returns:\n    BoxList with all fields padded or clipped.\n  \"\"\"\n  with tf.name_scope(scope, 'PadOrClipBoxList'):\n    subboxlist = box_list.BoxList(shape_utils.pad_or_clip_tensor(\n        boxlist.get(), num_boxes))\n    for field in boxlist.get_extra_fields():\n      subfield = shape_utils.pad_or_clip_tensor(\n          boxlist.get_field(field), num_boxes)\n      subboxlist.add_field(field, subfield)\n    return subboxlist\n"
  },
  {
    "path": "object_detector_app/object_detection/core/box_list_ops_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.core.box_list_ops.\"\"\"\nimport numpy as np\nimport tensorflow as tf\nfrom tensorflow.python.framework import errors\n\nfrom object_detection.core import box_list\nfrom object_detection.core import box_list_ops\n\n\nclass BoxListOpsTest(tf.test.TestCase):\n  \"\"\"Tests for common bounding box operations.\"\"\"\n\n  def test_area(self):\n    corners = tf.constant([[0.0, 0.0, 10.0, 20.0], [1.0, 2.0, 3.0, 4.0]])\n    exp_output = [200.0, 4.0]\n    boxes = box_list.BoxList(corners)\n    areas = box_list_ops.area(boxes)\n    with self.test_session() as sess:\n      areas_output = sess.run(areas)\n      self.assertAllClose(areas_output, exp_output)\n\n  def test_height_width(self):\n    corners = tf.constant([[0.0, 0.0, 10.0, 20.0], [1.0, 2.0, 3.0, 4.0]])\n    exp_output_heights = [10., 2.]\n    exp_output_widths = [20., 2.]\n    boxes = box_list.BoxList(corners)\n    heights, widths = box_list_ops.height_width(boxes)\n    with self.test_session() as sess:\n      output_heights, output_widths = sess.run([heights, widths])\n      self.assertAllClose(output_heights, exp_output_heights)\n      self.assertAllClose(output_widths, exp_output_widths)\n\n  def test_scale(self):\n    corners = tf.constant([[0, 0, 100, 200], [50, 120, 100, 140]],\n                          dtype=tf.float32)\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('extra_data', tf.constant([[1], [2]]))\n\n    y_scale = tf.constant(1.0/100)\n    x_scale = tf.constant(1.0/200)\n    scaled_boxes = box_list_ops.scale(boxes, y_scale, x_scale)\n    exp_output = [[0, 0, 1, 1], [0.5, 0.6, 1.0, 0.7]]\n    with self.test_session() as sess:\n      scaled_corners_out = sess.run(scaled_boxes.get())\n      self.assertAllClose(scaled_corners_out, exp_output)\n      extra_data_out = sess.run(scaled_boxes.get_field('extra_data'))\n      self.assertAllEqual(extra_data_out, [[1], [2]])\n\n  def test_clip_to_window_filter_boxes_which_fall_outside_the_window(\n      self):\n    window = tf.constant([0, 0, 9, 14], tf.float32)\n    corners = tf.constant([[5.0, 5.0, 6.0, 6.0],\n                           [-1.0, -2.0, 4.0, 5.0],\n                           [2.0, 3.0, 5.0, 9.0],\n                           [0.0, 0.0, 9.0, 14.0],\n                           [-100.0, -100.0, 300.0, 600.0],\n                           [-10.0, -10.0, -9.0, -9.0]])\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('extra_data', tf.constant([[1], [2], [3], [4], [5], [6]]))\n    exp_output = [[5.0, 5.0, 6.0, 6.0], [0.0, 0.0, 4.0, 5.0],\n                  [2.0, 3.0, 5.0, 9.0], [0.0, 0.0, 9.0, 14.0],\n                  [0.0, 0.0, 9.0, 14.0]]\n    pruned = box_list_ops.clip_to_window(\n        boxes, window, filter_nonoverlapping=True)\n    with self.test_session() as sess:\n      pruned_output = sess.run(pruned.get())\n      self.assertAllClose(pruned_output, exp_output)\n      extra_data_out = sess.run(pruned.get_field('extra_data'))\n      self.assertAllEqual(extra_data_out, [[1], [2], [3], [4], [5]])\n\n  def test_clip_to_window_without_filtering_boxes_which_fall_outside_the_window(\n      self):\n    window = tf.constant([0, 0, 9, 14], tf.float32)\n    corners = tf.constant([[5.0, 5.0, 6.0, 6.0],\n                           [-1.0, -2.0, 4.0, 5.0],\n                           [2.0, 3.0, 5.0, 9.0],\n                           [0.0, 0.0, 9.0, 14.0],\n                           [-100.0, -100.0, 300.0, 600.0],\n                           [-10.0, -10.0, -9.0, -9.0]])\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('extra_data', tf.constant([[1], [2], [3], [4], [5], [6]]))\n    exp_output = [[5.0, 5.0, 6.0, 6.0], [0.0, 0.0, 4.0, 5.0],\n                  [2.0, 3.0, 5.0, 9.0], [0.0, 0.0, 9.0, 14.0],\n                  [0.0, 0.0, 9.0, 14.0], [0.0, 0.0, 0.0, 0.0]]\n    pruned = box_list_ops.clip_to_window(\n        boxes, window, filter_nonoverlapping=False)\n    with self.test_session() as sess:\n      pruned_output = sess.run(pruned.get())\n      self.assertAllClose(pruned_output, exp_output)\n      extra_data_out = sess.run(pruned.get_field('extra_data'))\n      self.assertAllEqual(extra_data_out, [[1], [2], [3], [4], [5], [6]])\n\n  def test_prune_outside_window_filters_boxes_which_fall_outside_the_window(\n      self):\n    window = tf.constant([0, 0, 9, 14], tf.float32)\n    corners = tf.constant([[5.0, 5.0, 6.0, 6.0],\n                           [-1.0, -2.0, 4.0, 5.0],\n                           [2.0, 3.0, 5.0, 9.0],\n                           [0.0, 0.0, 9.0, 14.0],\n                           [-10.0, -10.0, -9.0, -9.0],\n                           [-100.0, -100.0, 300.0, 600.0]])\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('extra_data', tf.constant([[1], [2], [3], [4], [5], [6]]))\n    exp_output = [[5.0, 5.0, 6.0, 6.0],\n                  [2.0, 3.0, 5.0, 9.0],\n                  [0.0, 0.0, 9.0, 14.0]]\n    pruned, keep_indices = box_list_ops.prune_outside_window(boxes, window)\n    with self.test_session() as sess:\n      pruned_output = sess.run(pruned.get())\n      self.assertAllClose(pruned_output, exp_output)\n      keep_indices_out = sess.run(keep_indices)\n      self.assertAllEqual(keep_indices_out, [0, 2, 3])\n      extra_data_out = sess.run(pruned.get_field('extra_data'))\n      self.assertAllEqual(extra_data_out, [[1], [3], [4]])\n\n  def test_prune_completely_outside_window(self):\n    window = tf.constant([0, 0, 9, 14], tf.float32)\n    corners = tf.constant([[5.0, 5.0, 6.0, 6.0],\n                           [-1.0, -2.0, 4.0, 5.0],\n                           [2.0, 3.0, 5.0, 9.0],\n                           [0.0, 0.0, 9.0, 14.0],\n                           [-10.0, -10.0, -9.0, -9.0],\n                           [-100.0, -100.0, 300.0, 600.0]])\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('extra_data', tf.constant([[1], [2], [3], [4], [5], [6]]))\n    exp_output = [[5.0, 5.0, 6.0, 6.0],\n                  [-1.0, -2.0, 4.0, 5.0],\n                  [2.0, 3.0, 5.0, 9.0],\n                  [0.0, 0.0, 9.0, 14.0],\n                  [-100.0, -100.0, 300.0, 600.0]]\n    pruned, keep_indices = box_list_ops.prune_completely_outside_window(boxes,\n                                                                        window)\n    with self.test_session() as sess:\n      pruned_output = sess.run(pruned.get())\n      self.assertAllClose(pruned_output, exp_output)\n      keep_indices_out = sess.run(keep_indices)\n      self.assertAllEqual(keep_indices_out, [0, 1, 2, 3, 5])\n      extra_data_out = sess.run(pruned.get_field('extra_data'))\n      self.assertAllEqual(extra_data_out, [[1], [2], [3], [4], [6]])\n\n  def test_intersection(self):\n    corners1 = tf.constant([[4.0, 3.0, 7.0, 5.0], [5.0, 6.0, 10.0, 7.0]])\n    corners2 = tf.constant([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0],\n                            [0.0, 0.0, 20.0, 20.0]])\n    exp_output = [[2.0, 0.0, 6.0], [1.0, 0.0, 5.0]]\n    boxes1 = box_list.BoxList(corners1)\n    boxes2 = box_list.BoxList(corners2)\n    intersect = box_list_ops.intersection(boxes1, boxes2)\n    with self.test_session() as sess:\n      intersect_output = sess.run(intersect)\n      self.assertAllClose(intersect_output, exp_output)\n\n  def test_matched_intersection(self):\n    corners1 = tf.constant([[4.0, 3.0, 7.0, 5.0], [5.0, 6.0, 10.0, 7.0]])\n    corners2 = tf.constant([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0]])\n    exp_output = [2.0, 0.0]\n    boxes1 = box_list.BoxList(corners1)\n    boxes2 = box_list.BoxList(corners2)\n    intersect = box_list_ops.matched_intersection(boxes1, boxes2)\n    with self.test_session() as sess:\n      intersect_output = sess.run(intersect)\n      self.assertAllClose(intersect_output, exp_output)\n\n  def test_iou(self):\n    corners1 = tf.constant([[4.0, 3.0, 7.0, 5.0], [5.0, 6.0, 10.0, 7.0]])\n    corners2 = tf.constant([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0],\n                            [0.0, 0.0, 20.0, 20.0]])\n    exp_output = [[2.0 / 16.0, 0, 6.0 / 400.0], [1.0 / 16.0, 0.0, 5.0 / 400.0]]\n    boxes1 = box_list.BoxList(corners1)\n    boxes2 = box_list.BoxList(corners2)\n    iou = box_list_ops.iou(boxes1, boxes2)\n    with self.test_session() as sess:\n      iou_output = sess.run(iou)\n      self.assertAllClose(iou_output, exp_output)\n\n  def test_matched_iou(self):\n    corners1 = tf.constant([[4.0, 3.0, 7.0, 5.0], [5.0, 6.0, 10.0, 7.0]])\n    corners2 = tf.constant([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0]])\n    exp_output = [2.0 / 16.0, 0]\n    boxes1 = box_list.BoxList(corners1)\n    boxes2 = box_list.BoxList(corners2)\n    iou = box_list_ops.matched_iou(boxes1, boxes2)\n    with self.test_session() as sess:\n      iou_output = sess.run(iou)\n      self.assertAllClose(iou_output, exp_output)\n\n  def test_iouworks_on_empty_inputs(self):\n    corners1 = tf.constant([[4.0, 3.0, 7.0, 5.0], [5.0, 6.0, 10.0, 7.0]])\n    corners2 = tf.constant([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0],\n                            [0.0, 0.0, 20.0, 20.0]])\n    boxes1 = box_list.BoxList(corners1)\n    boxes2 = box_list.BoxList(corners2)\n    boxes_empty = box_list.BoxList(tf.zeros((0, 4)))\n    iou_empty_1 = box_list_ops.iou(boxes1, boxes_empty)\n    iou_empty_2 = box_list_ops.iou(boxes_empty, boxes2)\n    iou_empty_3 = box_list_ops.iou(boxes_empty, boxes_empty)\n    with self.test_session() as sess:\n      iou_output_1, iou_output_2, iou_output_3 = sess.run(\n          [iou_empty_1, iou_empty_2, iou_empty_3])\n      self.assertAllEqual(iou_output_1.shape, (2, 0))\n      self.assertAllEqual(iou_output_2.shape, (0, 3))\n      self.assertAllEqual(iou_output_3.shape, (0, 0))\n\n  def test_ioa(self):\n    corners1 = tf.constant([[4.0, 3.0, 7.0, 5.0], [5.0, 6.0, 10.0, 7.0]])\n    corners2 = tf.constant([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0],\n                            [0.0, 0.0, 20.0, 20.0]])\n    exp_output_1 = [[2.0 / 12.0, 0, 6.0 / 400.0],\n                    [1.0 / 12.0, 0.0, 5.0 / 400.0]]\n    exp_output_2 = [[2.0 / 6.0, 1.0 / 5.0],\n                    [0, 0],\n                    [6.0 / 6.0, 5.0 / 5.0]]\n    boxes1 = box_list.BoxList(corners1)\n    boxes2 = box_list.BoxList(corners2)\n    ioa_1 = box_list_ops.ioa(boxes1, boxes2)\n    ioa_2 = box_list_ops.ioa(boxes2, boxes1)\n    with self.test_session() as sess:\n      ioa_output_1, ioa_output_2 = sess.run([ioa_1, ioa_2])\n      self.assertAllClose(ioa_output_1, exp_output_1)\n      self.assertAllClose(ioa_output_2, exp_output_2)\n\n  def test_prune_non_overlapping_boxes(self):\n    corners1 = tf.constant([[4.0, 3.0, 7.0, 5.0], [5.0, 6.0, 10.0, 7.0]])\n    corners2 = tf.constant([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0],\n                            [0.0, 0.0, 20.0, 20.0]])\n    boxes1 = box_list.BoxList(corners1)\n    boxes2 = box_list.BoxList(corners2)\n    minoverlap = 0.5\n\n    exp_output_1 = boxes1\n    exp_output_2 = box_list.BoxList(tf.constant(0.0, shape=[0, 4]))\n    output_1, keep_indices_1 = box_list_ops.prune_non_overlapping_boxes(\n        boxes1, boxes2, min_overlap=minoverlap)\n    output_2, keep_indices_2 = box_list_ops.prune_non_overlapping_boxes(\n        boxes2, boxes1, min_overlap=minoverlap)\n    with self.test_session() as sess:\n      (output_1_, keep_indices_1_, output_2_, keep_indices_2_, exp_output_1_,\n       exp_output_2_) = sess.run(\n           [output_1.get(), keep_indices_1,\n            output_2.get(), keep_indices_2,\n            exp_output_1.get(), exp_output_2.get()])\n      self.assertAllClose(output_1_, exp_output_1_)\n      self.assertAllClose(output_2_, exp_output_2_)\n      self.assertAllEqual(keep_indices_1_, [0, 1])\n      self.assertAllEqual(keep_indices_2_, [])\n\n  def test_prune_small_boxes(self):\n    boxes = tf.constant([[4.0, 3.0, 7.0, 5.0],\n                         [5.0, 6.0, 10.0, 7.0],\n                         [3.0, 4.0, 6.0, 8.0],\n                         [14.0, 14.0, 15.0, 15.0],\n                         [0.0, 0.0, 20.0, 20.0]])\n    exp_boxes = [[3.0, 4.0, 6.0, 8.0],\n                 [0.0, 0.0, 20.0, 20.0]]\n    boxes = box_list.BoxList(boxes)\n    pruned_boxes = box_list_ops.prune_small_boxes(boxes, 3)\n    with self.test_session() as sess:\n      pruned_boxes = sess.run(pruned_boxes.get())\n      self.assertAllEqual(pruned_boxes, exp_boxes)\n\n  def test_prune_small_boxes_prunes_boxes_with_negative_side(self):\n    boxes = tf.constant([[4.0, 3.0, 7.0, 5.0],\n                         [5.0, 6.0, 10.0, 7.0],\n                         [3.0, 4.0, 6.0, 8.0],\n                         [14.0, 14.0, 15.0, 15.0],\n                         [0.0, 0.0, 20.0, 20.0],\n                         [2.0, 3.0, 1.5, 7.0],  # negative height\n                         [2.0, 3.0, 5.0, 1.7]])  # negative width\n    exp_boxes = [[3.0, 4.0, 6.0, 8.0],\n                 [0.0, 0.0, 20.0, 20.0]]\n    boxes = box_list.BoxList(boxes)\n    pruned_boxes = box_list_ops.prune_small_boxes(boxes, 3)\n    with self.test_session() as sess:\n      pruned_boxes = sess.run(pruned_boxes.get())\n      self.assertAllEqual(pruned_boxes, exp_boxes)\n\n  def test_change_coordinate_frame(self):\n    corners = tf.constant([[0.25, 0.5, 0.75, 0.75], [0.5, 0.0, 1.0, 1.0]])\n    window = tf.constant([0.25, 0.25, 0.75, 0.75])\n    boxes = box_list.BoxList(corners)\n\n    expected_corners = tf.constant([[0, 0.5, 1.0, 1.0], [0.5, -0.5, 1.5, 1.5]])\n    expected_boxes = box_list.BoxList(expected_corners)\n    output = box_list_ops.change_coordinate_frame(boxes, window)\n\n    with self.test_session() as sess:\n      output_, expected_boxes_ = sess.run([output.get(), expected_boxes.get()])\n      self.assertAllClose(output_, expected_boxes_)\n\n  def test_ioaworks_on_empty_inputs(self):\n    corners1 = tf.constant([[4.0, 3.0, 7.0, 5.0], [5.0, 6.0, 10.0, 7.0]])\n    corners2 = tf.constant([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0],\n                            [0.0, 0.0, 20.0, 20.0]])\n    boxes1 = box_list.BoxList(corners1)\n    boxes2 = box_list.BoxList(corners2)\n    boxes_empty = box_list.BoxList(tf.zeros((0, 4)))\n    ioa_empty_1 = box_list_ops.ioa(boxes1, boxes_empty)\n    ioa_empty_2 = box_list_ops.ioa(boxes_empty, boxes2)\n    ioa_empty_3 = box_list_ops.ioa(boxes_empty, boxes_empty)\n    with self.test_session() as sess:\n      ioa_output_1, ioa_output_2, ioa_output_3 = sess.run(\n          [ioa_empty_1, ioa_empty_2, ioa_empty_3])\n      self.assertAllEqual(ioa_output_1.shape, (2, 0))\n      self.assertAllEqual(ioa_output_2.shape, (0, 3))\n      self.assertAllEqual(ioa_output_3.shape, (0, 0))\n\n  def test_pairwise_distances(self):\n    corners1 = tf.constant([[0.0, 0.0, 0.0, 0.0],\n                            [1.0, 1.0, 0.0, 2.0]])\n    corners2 = tf.constant([[3.0, 4.0, 1.0, 0.0],\n                            [-4.0, 0.0, 0.0, 3.0],\n                            [0.0, 0.0, 0.0, 0.0]])\n    exp_output = [[26, 25, 0], [18, 27, 6]]\n    boxes1 = box_list.BoxList(corners1)\n    boxes2 = box_list.BoxList(corners2)\n    dist_matrix = box_list_ops.sq_dist(boxes1, boxes2)\n    with self.test_session() as sess:\n      dist_output = sess.run(dist_matrix)\n      self.assertAllClose(dist_output, exp_output)\n\n  def test_boolean_mask(self):\n    corners = tf.constant(\n        [4 * [0.0], 4 * [1.0], 4 * [2.0], 4 * [3.0], 4 * [4.0]])\n    indicator = tf.constant([True, False, True, False, True], tf.bool)\n    expected_subset = [4 * [0.0], 4 * [2.0], 4 * [4.0]]\n    boxes = box_list.BoxList(corners)\n    subset = box_list_ops.boolean_mask(boxes, indicator)\n    with self.test_session() as sess:\n      subset_output = sess.run(subset.get())\n      self.assertAllClose(subset_output, expected_subset)\n\n  def test_boolean_mask_with_field(self):\n    corners = tf.constant(\n        [4 * [0.0], 4 * [1.0], 4 * [2.0], 4 * [3.0], 4 * [4.0]])\n    indicator = tf.constant([True, False, True, False, True], tf.bool)\n    weights = tf.constant([[.1], [.3], [.5], [.7], [.9]], tf.float32)\n    expected_subset = [4 * [0.0], 4 * [2.0], 4 * [4.0]]\n    expected_weights = [[.1], [.5], [.9]]\n\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('weights', weights)\n    subset = box_list_ops.boolean_mask(boxes, indicator, ['weights'])\n    with self.test_session() as sess:\n      subset_output, weights_output = sess.run(\n          [subset.get(), subset.get_field('weights')])\n      self.assertAllClose(subset_output, expected_subset)\n      self.assertAllClose(weights_output, expected_weights)\n\n  def test_gather(self):\n    corners = tf.constant(\n        [4 * [0.0], 4 * [1.0], 4 * [2.0], 4 * [3.0], 4 * [4.0]])\n    indices = tf.constant([0, 2, 4], tf.int32)\n    expected_subset = [4 * [0.0], 4 * [2.0], 4 * [4.0]]\n    boxes = box_list.BoxList(corners)\n    subset = box_list_ops.gather(boxes, indices)\n    with self.test_session() as sess:\n      subset_output = sess.run(subset.get())\n      self.assertAllClose(subset_output, expected_subset)\n\n  def test_gather_with_field(self):\n    corners = tf.constant([4*[0.0], 4*[1.0], 4*[2.0], 4*[3.0], 4*[4.0]])\n    indices = tf.constant([0, 2, 4], tf.int32)\n    weights = tf.constant([[.1], [.3], [.5], [.7], [.9]], tf.float32)\n    expected_subset = [4 * [0.0], 4 * [2.0], 4 * [4.0]]\n    expected_weights = [[.1], [.5], [.9]]\n\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('weights', weights)\n    subset = box_list_ops.gather(boxes, indices, ['weights'])\n    with self.test_session() as sess:\n      subset_output, weights_output = sess.run(\n          [subset.get(), subset.get_field('weights')])\n      self.assertAllClose(subset_output, expected_subset)\n      self.assertAllClose(weights_output, expected_weights)\n\n  def test_gather_with_invalid_field(self):\n    corners = tf.constant([4 * [0.0], 4 * [1.0]])\n    indices = tf.constant([0, 1], tf.int32)\n    weights = tf.constant([[.1], [.3]], tf.float32)\n\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('weights', weights)\n    with self.assertRaises(ValueError):\n      box_list_ops.gather(boxes, indices, ['foo', 'bar'])\n\n  def test_gather_with_invalid_inputs(self):\n    corners = tf.constant(\n        [4 * [0.0], 4 * [1.0], 4 * [2.0], 4 * [3.0], 4 * [4.0]])\n    indices_float32 = tf.constant([0, 2, 4], tf.float32)\n    boxes = box_list.BoxList(corners)\n    with self.assertRaises(ValueError):\n      _ = box_list_ops.gather(boxes, indices_float32)\n    indices_2d = tf.constant([[0, 2, 4]], tf.int32)\n    boxes = box_list.BoxList(corners)\n    with self.assertRaises(ValueError):\n      _ = box_list_ops.gather(boxes, indices_2d)\n\n  def test_gather_with_dynamic_indexing(self):\n    corners = tf.constant([4 * [0.0], 4 * [1.0], 4 * [2.0], 4 * [3.0], 4 * [4.0]\n                          ])\n    weights = tf.constant([.5, .3, .7, .1, .9], tf.float32)\n    indices = tf.reshape(tf.where(tf.greater(weights, 0.4)), [-1])\n    expected_subset = [4 * [0.0], 4 * [2.0], 4 * [4.0]]\n    expected_weights = [.5, .7, .9]\n\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('weights', weights)\n    subset = box_list_ops.gather(boxes, indices, ['weights'])\n    with self.test_session() as sess:\n      subset_output, weights_output = sess.run([subset.get(), subset.get_field(\n          'weights')])\n      self.assertAllClose(subset_output, expected_subset)\n      self.assertAllClose(weights_output, expected_weights)\n\n  def test_sort_by_field_ascending_order(self):\n    exp_corners = [[0, 0, 1, 1], [0, 0.1, 1, 1.1], [0, -0.1, 1, 0.9],\n                   [0, 10, 1, 11], [0, 10.1, 1, 11.1], [0, 100, 1, 101]]\n    exp_scores = [.95, .9, .75, .6, .5, .3]\n    exp_weights = [.2, .45, .6, .75, .8, .92]\n    shuffle = [2, 4, 0, 5, 1, 3]\n    corners = tf.constant([exp_corners[i] for i in shuffle], tf.float32)\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('scores', tf.constant(\n        [exp_scores[i] for i in shuffle], tf.float32))\n    boxes.add_field('weights', tf.constant(\n        [exp_weights[i] for i in shuffle], tf.float32))\n    sort_by_weight = box_list_ops.sort_by_field(\n        boxes,\n        'weights',\n        order=box_list_ops.SortOrder.ascend)\n    with self.test_session() as sess:\n      corners_out, scores_out, weights_out = sess.run([\n          sort_by_weight.get(),\n          sort_by_weight.get_field('scores'),\n          sort_by_weight.get_field('weights')])\n      self.assertAllClose(corners_out, exp_corners)\n      self.assertAllClose(scores_out, exp_scores)\n      self.assertAllClose(weights_out, exp_weights)\n\n  def test_sort_by_field_descending_order(self):\n    exp_corners = [[0, 0, 1, 1], [0, 0.1, 1, 1.1], [0, -0.1, 1, 0.9],\n                   [0, 10, 1, 11], [0, 10.1, 1, 11.1], [0, 100, 1, 101]]\n    exp_scores = [.95, .9, .75, .6, .5, .3]\n    exp_weights = [.2, .45, .6, .75, .8, .92]\n    shuffle = [2, 4, 0, 5, 1, 3]\n\n    corners = tf.constant([exp_corners[i] for i in shuffle], tf.float32)\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('scores', tf.constant(\n        [exp_scores[i] for i in shuffle], tf.float32))\n    boxes.add_field('weights', tf.constant(\n        [exp_weights[i] for i in shuffle], tf.float32))\n\n    sort_by_score = box_list_ops.sort_by_field(boxes, 'scores')\n    with self.test_session() as sess:\n      corners_out, scores_out, weights_out = sess.run([sort_by_score.get(\n      ), sort_by_score.get_field('scores'), sort_by_score.get_field('weights')])\n      self.assertAllClose(corners_out, exp_corners)\n      self.assertAllClose(scores_out, exp_scores)\n      self.assertAllClose(weights_out, exp_weights)\n\n  def test_sort_by_field_invalid_inputs(self):\n    corners = tf.constant([4 * [0.0], 4 * [0.5], 4 * [1.0], 4 * [2.0], 4 *\n                           [3.0], 4 * [4.0]])\n    misc = tf.constant([[.95, .9], [.5, .3]], tf.float32)\n    weights = tf.constant([.1, .2], tf.float32)\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('misc', misc)\n    boxes.add_field('weights', weights)\n\n    with self.test_session() as sess:\n      with self.assertRaises(ValueError):\n        box_list_ops.sort_by_field(boxes, 'area')\n\n      with self.assertRaises(ValueError):\n        box_list_ops.sort_by_field(boxes, 'misc')\n\n      with self.assertRaisesWithPredicateMatch(errors.InvalidArgumentError,\n                                               'Incorrect field size'):\n        sess.run(box_list_ops.sort_by_field(boxes, 'weights').get())\n\n  def test_visualize_boxes_in_image(self):\n    image = tf.zeros((6, 4, 3))\n    corners = tf.constant([[0, 0, 5, 3],\n                           [0, 0, 3, 2]], tf.float32)\n    boxes = box_list.BoxList(corners)\n    image_and_boxes = box_list_ops.visualize_boxes_in_image(image, boxes)\n    image_and_boxes_bw = tf.to_float(\n        tf.greater(tf.reduce_sum(image_and_boxes, 2), 0.0))\n    exp_result = [[1, 1, 1, 0],\n                  [1, 1, 1, 0],\n                  [1, 1, 1, 0],\n                  [1, 0, 1, 0],\n                  [1, 1, 1, 0],\n                  [0, 0, 0, 0]]\n    with self.test_session() as sess:\n      output = sess.run(image_and_boxes_bw)\n      self.assertAllEqual(output.astype(int), exp_result)\n\n  def test_filter_field_value_equals(self):\n    corners = tf.constant([[0, 0, 1, 1],\n                           [0, 0.1, 1, 1.1],\n                           [0, -0.1, 1, 0.9],\n                           [0, 10, 1, 11],\n                           [0, 10.1, 1, 11.1],\n                           [0, 100, 1, 101]], tf.float32)\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('classes', tf.constant([1, 2, 1, 2, 2, 1]))\n    exp_output1 = [[0, 0, 1, 1], [0, -0.1, 1, 0.9], [0, 100, 1, 101]]\n    exp_output2 = [[0, 0.1, 1, 1.1], [0, 10, 1, 11], [0, 10.1, 1, 11.1]]\n\n    filtered_boxes1 = box_list_ops.filter_field_value_equals(\n        boxes, 'classes', 1)\n    filtered_boxes2 = box_list_ops.filter_field_value_equals(\n        boxes, 'classes', 2)\n    with self.test_session() as sess:\n      filtered_output1, filtered_output2 = sess.run([filtered_boxes1.get(),\n                                                     filtered_boxes2.get()])\n      self.assertAllClose(filtered_output1, exp_output1)\n      self.assertAllClose(filtered_output2, exp_output2)\n\n  def test_filter_greater_than(self):\n    corners = tf.constant([[0, 0, 1, 1],\n                           [0, 0.1, 1, 1.1],\n                           [0, -0.1, 1, 0.9],\n                           [0, 10, 1, 11],\n                           [0, 10.1, 1, 11.1],\n                           [0, 100, 1, 101]], tf.float32)\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('scores', tf.constant([.1, .75, .9, .5, .5, .8]))\n    thresh = .6\n    exp_output = [[0, 0.1, 1, 1.1], [0, -0.1, 1, 0.9], [0, 100, 1, 101]]\n\n    filtered_boxes = box_list_ops.filter_greater_than(boxes, thresh)\n    with self.test_session() as sess:\n      filtered_output = sess.run(filtered_boxes.get())\n      self.assertAllClose(filtered_output, exp_output)\n\n  def test_clip_box_list(self):\n    boxlist = box_list.BoxList(\n        tf.constant([[0.1, 0.1, 0.4, 0.4], [0.1, 0.1, 0.5, 0.5],\n                     [0.6, 0.6, 0.8, 0.8], [0.2, 0.2, 0.3, 0.3]], tf.float32))\n    boxlist.add_field('classes', tf.constant([0, 0, 1, 1]))\n    boxlist.add_field('scores', tf.constant([0.75, 0.65, 0.3, 0.2]))\n    num_boxes = 2\n    clipped_boxlist = box_list_ops.pad_or_clip_box_list(boxlist, num_boxes)\n\n    expected_boxes = [[0.1, 0.1, 0.4, 0.4], [0.1, 0.1, 0.5, 0.5]]\n    expected_classes = [0, 0]\n    expected_scores = [0.75, 0.65]\n    with self.test_session() as sess:\n      boxes_out, classes_out, scores_out = sess.run(\n          [clipped_boxlist.get(), clipped_boxlist.get_field('classes'),\n           clipped_boxlist.get_field('scores')])\n\n      self.assertAllClose(expected_boxes, boxes_out)\n      self.assertAllEqual(expected_classes, classes_out)\n      self.assertAllClose(expected_scores, scores_out)\n\n  def test_pad_box_list(self):\n    boxlist = box_list.BoxList(\n        tf.constant([[0.1, 0.1, 0.4, 0.4], [0.1, 0.1, 0.5, 0.5]], tf.float32))\n    boxlist.add_field('classes', tf.constant([0, 1]))\n    boxlist.add_field('scores', tf.constant([0.75, 0.2]))\n    num_boxes = 4\n    padded_boxlist = box_list_ops.pad_or_clip_box_list(boxlist, num_boxes)\n\n    expected_boxes = [[0.1, 0.1, 0.4, 0.4], [0.1, 0.1, 0.5, 0.5],\n                      [0, 0, 0, 0], [0, 0, 0, 0]]\n    expected_classes = [0, 1, 0, 0]\n    expected_scores = [0.75, 0.2, 0, 0]\n    with self.test_session() as sess:\n      boxes_out, classes_out, scores_out = sess.run(\n          [padded_boxlist.get(), padded_boxlist.get_field('classes'),\n           padded_boxlist.get_field('scores')])\n\n      self.assertAllClose(expected_boxes, boxes_out)\n      self.assertAllEqual(expected_classes, classes_out)\n      self.assertAllClose(expected_scores, scores_out)\n\n\nclass ConcatenateTest(tf.test.TestCase):\n\n  def test_invalid_input_box_list_list(self):\n    with self.assertRaises(ValueError):\n      box_list_ops.concatenate(None)\n    with self.assertRaises(ValueError):\n      box_list_ops.concatenate([])\n    with self.assertRaises(ValueError):\n      corners = tf.constant([[0, 0, 0, 0]], tf.float32)\n      boxlist = box_list.BoxList(corners)\n      box_list_ops.concatenate([boxlist, 2])\n\n  def test_concatenate_with_missing_fields(self):\n    corners1 = tf.constant([[0, 0, 0, 0], [1, 2, 3, 4]], tf.float32)\n    scores1 = tf.constant([1.0, 2.1])\n    corners2 = tf.constant([[0, 3, 1, 6], [2, 4, 3, 8]], tf.float32)\n    boxlist1 = box_list.BoxList(corners1)\n    boxlist1.add_field('scores', scores1)\n    boxlist2 = box_list.BoxList(corners2)\n    with self.assertRaises(ValueError):\n      box_list_ops.concatenate([boxlist1, boxlist2])\n\n  def test_concatenate_with_incompatible_field_shapes(self):\n    corners1 = tf.constant([[0, 0, 0, 0], [1, 2, 3, 4]], tf.float32)\n    scores1 = tf.constant([1.0, 2.1])\n    corners2 = tf.constant([[0, 3, 1, 6], [2, 4, 3, 8]], tf.float32)\n    scores2 = tf.constant([[1.0, 1.0], [2.1, 3.2]])\n    boxlist1 = box_list.BoxList(corners1)\n    boxlist1.add_field('scores', scores1)\n    boxlist2 = box_list.BoxList(corners2)\n    boxlist2.add_field('scores', scores2)\n    with self.assertRaises(ValueError):\n      box_list_ops.concatenate([boxlist1, boxlist2])\n\n  def test_concatenate_is_correct(self):\n    corners1 = tf.constant([[0, 0, 0, 0], [1, 2, 3, 4]], tf.float32)\n    scores1 = tf.constant([1.0, 2.1])\n    corners2 = tf.constant([[0, 3, 1, 6], [2, 4, 3, 8], [1, 0, 5, 10]],\n                           tf.float32)\n    scores2 = tf.constant([1.0, 2.1, 5.6])\n\n    exp_corners = [[0, 0, 0, 0],\n                   [1, 2, 3, 4],\n                   [0, 3, 1, 6],\n                   [2, 4, 3, 8],\n                   [1, 0, 5, 10]]\n    exp_scores = [1.0, 2.1, 1.0, 2.1, 5.6]\n\n    boxlist1 = box_list.BoxList(corners1)\n    boxlist1.add_field('scores', scores1)\n    boxlist2 = box_list.BoxList(corners2)\n    boxlist2.add_field('scores', scores2)\n    result = box_list_ops.concatenate([boxlist1, boxlist2])\n    with self.test_session() as sess:\n      corners_output, scores_output = sess.run(\n          [result.get(), result.get_field('scores')])\n      self.assertAllClose(corners_output, exp_corners)\n      self.assertAllClose(scores_output, exp_scores)\n\n\nclass NonMaxSuppressionTest(tf.test.TestCase):\n\n  def test_with_invalid_scores_field(self):\n    corners = tf.constant([[0, 0, 1, 1],\n                           [0, 0.1, 1, 1.1],\n                           [0, -0.1, 1, 0.9],\n                           [0, 10, 1, 11],\n                           [0, 10.1, 1, 11.1],\n                           [0, 100, 1, 101]], tf.float32)\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('scores', tf.constant([.9, .75, .6, .95, .5]))\n    iou_thresh = .5\n    max_output_size = 3\n    nms = box_list_ops.non_max_suppression(\n        boxes, iou_thresh, max_output_size)\n    with self.test_session() as sess:\n      with self.assertRaisesWithPredicateMatch(\n          errors.InvalidArgumentError, 'scores has incompatible shape'):\n        sess.run(nms.get())\n\n  def test_select_from_three_clusters(self):\n    corners = tf.constant([[0, 0, 1, 1],\n                           [0, 0.1, 1, 1.1],\n                           [0, -0.1, 1, 0.9],\n                           [0, 10, 1, 11],\n                           [0, 10.1, 1, 11.1],\n                           [0, 100, 1, 101]], tf.float32)\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('scores', tf.constant([.9, .75, .6, .95, .5, .3]))\n    iou_thresh = .5\n    max_output_size = 3\n\n    exp_nms = [[0, 10, 1, 11],\n               [0, 0, 1, 1],\n               [0, 100, 1, 101]]\n    nms = box_list_ops.non_max_suppression(\n        boxes, iou_thresh, max_output_size)\n    with self.test_session() as sess:\n      nms_output = sess.run(nms.get())\n      self.assertAllClose(nms_output, exp_nms)\n\n  def test_select_at_most_two_boxes_from_three_clusters(self):\n    corners = tf.constant([[0, 0, 1, 1],\n                           [0, 0.1, 1, 1.1],\n                           [0, -0.1, 1, 0.9],\n                           [0, 10, 1, 11],\n                           [0, 10.1, 1, 11.1],\n                           [0, 100, 1, 101]], tf.float32)\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('scores', tf.constant([.9, .75, .6, .95, .5, .3]))\n    iou_thresh = .5\n    max_output_size = 2\n\n    exp_nms = [[0, 10, 1, 11],\n               [0, 0, 1, 1]]\n    nms = box_list_ops.non_max_suppression(\n        boxes, iou_thresh, max_output_size)\n    with self.test_session() as sess:\n      nms_output = sess.run(nms.get())\n      self.assertAllClose(nms_output, exp_nms)\n\n  def test_select_at_most_thirty_boxes_from_three_clusters(self):\n    corners = tf.constant([[0, 0, 1, 1],\n                           [0, 0.1, 1, 1.1],\n                           [0, -0.1, 1, 0.9],\n                           [0, 10, 1, 11],\n                           [0, 10.1, 1, 11.1],\n                           [0, 100, 1, 101]], tf.float32)\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('scores', tf.constant([.9, .75, .6, .95, .5, .3]))\n    iou_thresh = .5\n    max_output_size = 30\n\n    exp_nms = [[0, 10, 1, 11],\n               [0, 0, 1, 1],\n               [0, 100, 1, 101]]\n    nms = box_list_ops.non_max_suppression(\n        boxes, iou_thresh, max_output_size)\n    with self.test_session() as sess:\n      nms_output = sess.run(nms.get())\n      self.assertAllClose(nms_output, exp_nms)\n\n  def test_select_single_box(self):\n    corners = tf.constant([[0, 0, 1, 1]], tf.float32)\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('scores', tf.constant([.9]))\n    iou_thresh = .5\n    max_output_size = 3\n\n    exp_nms = [[0, 0, 1, 1]]\n    nms = box_list_ops.non_max_suppression(\n        boxes, iou_thresh, max_output_size)\n    with self.test_session() as sess:\n      nms_output = sess.run(nms.get())\n      self.assertAllClose(nms_output, exp_nms)\n\n  def test_select_from_ten_identical_boxes(self):\n    corners = tf.constant(10 * [[0, 0, 1, 1]], tf.float32)\n    boxes = box_list.BoxList(corners)\n    boxes.add_field('scores', tf.constant(10 * [.9]))\n    iou_thresh = .5\n    max_output_size = 3\n\n    exp_nms = [[0, 0, 1, 1]]\n    nms = box_list_ops.non_max_suppression(\n        boxes, iou_thresh, max_output_size)\n    with self.test_session() as sess:\n      nms_output = sess.run(nms.get())\n      self.assertAllClose(nms_output, exp_nms)\n\n  def test_copy_extra_fields(self):\n    corners = tf.constant([[0, 0, 1, 1],\n                           [0, 0.1, 1, 1.1]], tf.float32)\n    boxes = box_list.BoxList(corners)\n    tensor1 = np.array([[1], [4]])\n    tensor2 = np.array([[1, 1], [2, 2]])\n    boxes.add_field('tensor1', tf.constant(tensor1))\n    boxes.add_field('tensor2', tf.constant(tensor2))\n    new_boxes = box_list.BoxList(tf.constant([[0, 0, 10, 10],\n                                              [1, 3, 5, 5]], tf.float32))\n    new_boxes = box_list_ops._copy_extra_fields(new_boxes, boxes)\n    with self.test_session() as sess:\n      self.assertAllClose(tensor1, sess.run(new_boxes.get_field('tensor1')))\n      self.assertAllClose(tensor2, sess.run(new_boxes.get_field('tensor2')))\n\n\nclass CoordinatesConversionTest(tf.test.TestCase):\n\n  def test_to_normalized_coordinates(self):\n    coordinates = tf.constant([[0, 0, 100, 100],\n                               [25, 25, 75, 75]], tf.float32)\n    img = tf.ones((128, 100, 100, 3))\n    boxlist = box_list.BoxList(coordinates)\n    normalized_boxlist = box_list_ops.to_normalized_coordinates(\n        boxlist, tf.shape(img)[1], tf.shape(img)[2])\n    expected_boxes = [[0, 0, 1, 1],\n                      [0.25, 0.25, 0.75, 0.75]]\n\n    with self.test_session() as sess:\n      normalized_boxes = sess.run(normalized_boxlist.get())\n      self.assertAllClose(normalized_boxes, expected_boxes)\n\n  def test_to_normalized_coordinates_already_normalized(self):\n    coordinates = tf.constant([[0, 0, 1, 1],\n                               [0.25, 0.25, 0.75, 0.75]], tf.float32)\n    img = tf.ones((128, 100, 100, 3))\n    boxlist = box_list.BoxList(coordinates)\n    normalized_boxlist = box_list_ops.to_normalized_coordinates(\n        boxlist, tf.shape(img)[1], tf.shape(img)[2])\n\n    with self.test_session() as sess:\n      with self.assertRaisesOpError('assertion failed'):\n        sess.run(normalized_boxlist.get())\n\n  def test_to_absolute_coordinates(self):\n    coordinates = tf.constant([[0, 0, 1, 1],\n                               [0.25, 0.25, 0.75, 0.75]], tf.float32)\n    img = tf.ones((128, 100, 100, 3))\n    boxlist = box_list.BoxList(coordinates)\n    absolute_boxlist = box_list_ops.to_absolute_coordinates(boxlist,\n                                                            tf.shape(img)[1],\n                                                            tf.shape(img)[2])\n    expected_boxes = [[0, 0, 100, 100],\n                      [25, 25, 75, 75]]\n\n    with self.test_session() as sess:\n      absolute_boxes = sess.run(absolute_boxlist.get())\n      self.assertAllClose(absolute_boxes, expected_boxes)\n\n  def test_to_absolute_coordinates_already_abolute(self):\n    coordinates = tf.constant([[0, 0, 100, 100],\n                               [25, 25, 75, 75]], tf.float32)\n    img = tf.ones((128, 100, 100, 3))\n    boxlist = box_list.BoxList(coordinates)\n    absolute_boxlist = box_list_ops.to_absolute_coordinates(boxlist,\n                                                            tf.shape(img)[1],\n                                                            tf.shape(img)[2])\n\n    with self.test_session() as sess:\n      with self.assertRaisesOpError('assertion failed'):\n        sess.run(absolute_boxlist.get())\n\n  def test_convert_to_normalized_and_back(self):\n    coordinates = np.random.uniform(size=(100, 4))\n    coordinates = np.round(np.sort(coordinates) * 200)\n    coordinates[:, 2:4] += 1\n    coordinates[99, :] = [0, 0, 201, 201]\n    img = tf.ones((128, 202, 202, 3))\n\n    boxlist = box_list.BoxList(tf.constant(coordinates, tf.float32))\n    boxlist = box_list_ops.to_normalized_coordinates(boxlist,\n                                                     tf.shape(img)[1],\n                                                     tf.shape(img)[2])\n    boxlist = box_list_ops.to_absolute_coordinates(boxlist,\n                                                   tf.shape(img)[1],\n                                                   tf.shape(img)[2])\n\n    with self.test_session() as sess:\n      out = sess.run(boxlist.get())\n      self.assertAllClose(out, coordinates)\n\n  def test_convert_to_absolute_and_back(self):\n    coordinates = np.random.uniform(size=(100, 4))\n    coordinates = np.sort(coordinates)\n    coordinates[99, :] = [0, 0, 1, 1]\n    img = tf.ones((128, 202, 202, 3))\n\n    boxlist = box_list.BoxList(tf.constant(coordinates, tf.float32))\n    boxlist = box_list_ops.to_absolute_coordinates(boxlist,\n                                                   tf.shape(img)[1],\n                                                   tf.shape(img)[2])\n    boxlist = box_list_ops.to_normalized_coordinates(boxlist,\n                                                     tf.shape(img)[1],\n                                                     tf.shape(img)[2])\n\n    with self.test_session() as sess:\n      out = sess.run(boxlist.get())\n      self.assertAllClose(out, coordinates)\n\n\nclass BoxRefinementTest(tf.test.TestCase):\n\n  def test_box_voting(self):\n    candidates = box_list.BoxList(\n        tf.constant([[0.1, 0.1, 0.4, 0.4], [0.6, 0.6, 0.8, 0.8]], tf.float32))\n    candidates.add_field('ExtraField', tf.constant([1, 2]))\n    pool = box_list.BoxList(\n        tf.constant([[0.1, 0.1, 0.4, 0.4], [0.1, 0.1, 0.5, 0.5],\n                     [0.6, 0.6, 0.8, 0.8]], tf.float32))\n    pool.add_field('scores', tf.constant([0.75, 0.25, 0.3]))\n    averaged_boxes = box_list_ops.box_voting(candidates, pool)\n    expected_boxes = [[0.1, 0.1, 0.425, 0.425], [0.6, 0.6, 0.8, 0.8]]\n    expected_scores = [0.5, 0.3]\n    with self.test_session() as sess:\n      boxes_out, scores_out, extra_field_out = sess.run(\n          [averaged_boxes.get(), averaged_boxes.get_field('scores'),\n           averaged_boxes.get_field('ExtraField')])\n\n      self.assertAllClose(expected_boxes, boxes_out)\n      self.assertAllClose(expected_scores, scores_out)\n      self.assertAllEqual(extra_field_out, [1, 2])\n\n  def test_box_voting_fails_with_negative_scores(self):\n    candidates = box_list.BoxList(\n        tf.constant([[0.1, 0.1, 0.4, 0.4]], tf.float32))\n    pool = box_list.BoxList(tf.constant([[0.1, 0.1, 0.4, 0.4]], tf.float32))\n    pool.add_field('scores', tf.constant([-0.2]))\n    averaged_boxes = box_list_ops.box_voting(candidates, pool)\n\n    with self.test_session() as sess:\n      with self.assertRaisesOpError('Scores must be non negative'):\n        sess.run([averaged_boxes.get()])\n\n  def test_box_voting_fails_when_unmatched(self):\n    candidates = box_list.BoxList(\n        tf.constant([[0.1, 0.1, 0.4, 0.4]], tf.float32))\n    pool = box_list.BoxList(tf.constant([[0.6, 0.6, 0.8, 0.8]], tf.float32))\n    pool.add_field('scores', tf.constant([0.2]))\n    averaged_boxes = box_list_ops.box_voting(candidates, pool)\n\n    with self.test_session() as sess:\n      with self.assertRaisesOpError('Each box in selected_boxes must match '\n                                    'with at least one box in pool_boxes.'):\n        sess.run([averaged_boxes.get()])\n\n  def test_refine_boxes(self):\n    pool = box_list.BoxList(\n        tf.constant([[0.1, 0.1, 0.4, 0.4], [0.1, 0.1, 0.5, 0.5],\n                     [0.6, 0.6, 0.8, 0.8]], tf.float32))\n    pool.add_field('ExtraField', tf.constant([1, 2, 3]))\n    pool.add_field('scores', tf.constant([0.75, 0.25, 0.3]))\n    refined_boxes = box_list_ops.refine_boxes(pool, 0.5, 10)\n\n    expected_boxes = [[0.1, 0.1, 0.425, 0.425], [0.6, 0.6, 0.8, 0.8]]\n    expected_scores = [0.5, 0.3]\n    with self.test_session() as sess:\n      boxes_out, scores_out, extra_field_out = sess.run(\n          [refined_boxes.get(), refined_boxes.get_field('scores'),\n           refined_boxes.get_field('ExtraField')])\n\n      self.assertAllClose(expected_boxes, boxes_out)\n      self.assertAllClose(expected_scores, scores_out)\n      self.assertAllEqual(extra_field_out, [1, 3])\n\n  def test_refine_boxes_multi_class(self):\n    pool = box_list.BoxList(\n        tf.constant([[0.1, 0.1, 0.4, 0.4], [0.1, 0.1, 0.5, 0.5],\n                     [0.6, 0.6, 0.8, 0.8], [0.2, 0.2, 0.3, 0.3]], tf.float32))\n    pool.add_field('classes', tf.constant([0, 0, 1, 1]))\n    pool.add_field('scores', tf.constant([0.75, 0.25, 0.3, 0.2]))\n    refined_boxes = box_list_ops.refine_boxes_multi_class(pool, 3, 0.5, 10)\n\n    expected_boxes = [[0.1, 0.1, 0.425, 0.425], [0.6, 0.6, 0.8, 0.8],\n                      [0.2, 0.2, 0.3, 0.3]]\n    expected_scores = [0.5, 0.3, 0.2]\n    with self.test_session() as sess:\n      boxes_out, scores_out, extra_field_out = sess.run(\n          [refined_boxes.get(), refined_boxes.get_field('scores'),\n           refined_boxes.get_field('classes')])\n\n      self.assertAllClose(expected_boxes, boxes_out)\n      self.assertAllClose(expected_scores, scores_out)\n      self.assertAllEqual(extra_field_out, [0, 1, 1])\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/core/box_list_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.core.box_list.\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.core import box_list\n\n\nclass BoxListTest(tf.test.TestCase):\n  \"\"\"Tests for BoxList class.\"\"\"\n\n  def test_num_boxes(self):\n    data = tf.constant([[0, 0, 1, 1], [1, 1, 2, 3], [3, 4, 5, 5]], tf.float32)\n    expected_num_boxes = 3\n\n    boxes = box_list.BoxList(data)\n    with self.test_session() as sess:\n      num_boxes_output = sess.run(boxes.num_boxes())\n      self.assertEquals(num_boxes_output, expected_num_boxes)\n\n  def test_get_correct_center_coordinates_and_sizes(self):\n    boxes = [[10.0, 10.0, 20.0, 15.0], [0.2, 0.1, 0.5, 0.4]]\n    boxes = box_list.BoxList(tf.constant(boxes))\n    centers_sizes = boxes.get_center_coordinates_and_sizes()\n    expected_centers_sizes = [[15, 0.35], [12.5, 0.25], [10, 0.3], [5, 0.3]]\n    with self.test_session() as sess:\n      centers_sizes_out = sess.run(centers_sizes)\n      self.assertAllClose(centers_sizes_out, expected_centers_sizes)\n\n  def test_create_box_list_with_dynamic_shape(self):\n    data = tf.constant([[0, 0, 1, 1], [1, 1, 2, 3], [3, 4, 5, 5]], tf.float32)\n    indices = tf.reshape(tf.where(tf.greater([1, 0, 1], 0)), [-1])\n    data = tf.gather(data, indices)\n    assert data.get_shape().as_list() == [None, 4]\n    expected_num_boxes = 2\n\n    boxes = box_list.BoxList(data)\n    with self.test_session() as sess:\n      num_boxes_output = sess.run(boxes.num_boxes())\n      self.assertEquals(num_boxes_output, expected_num_boxes)\n\n  def test_transpose_coordinates(self):\n    boxes = [[10.0, 10.0, 20.0, 15.0], [0.2, 0.1, 0.5, 0.4]]\n    boxes = box_list.BoxList(tf.constant(boxes))\n    boxes.transpose_coordinates()\n    expected_corners = [[10.0, 10.0, 15.0, 20.0], [0.1, 0.2, 0.4, 0.5]]\n    with self.test_session() as sess:\n      corners_out = sess.run(boxes.get())\n      self.assertAllClose(corners_out, expected_corners)\n\n  def test_box_list_invalid_inputs(self):\n    data0 = tf.constant([[[0, 0, 1, 1], [3, 4, 5, 5]]], tf.float32)\n    data1 = tf.constant([[0, 0, 1], [1, 1, 2], [3, 4, 5]], tf.float32)\n    data2 = tf.constant([[0, 0, 1], [1, 1, 2], [3, 4, 5]], tf.int32)\n\n    with self.assertRaises(ValueError):\n      _ = box_list.BoxList(data0)\n    with self.assertRaises(ValueError):\n      _ = box_list.BoxList(data1)\n    with self.assertRaises(ValueError):\n      _ = box_list.BoxList(data2)\n\n  def test_num_boxes_static(self):\n    box_corners = [[10.0, 10.0, 20.0, 15.0], [0.2, 0.1, 0.5, 0.4]]\n    boxes = box_list.BoxList(tf.constant(box_corners))\n    self.assertEquals(boxes.num_boxes_static(), 2)\n    self.assertEquals(type(boxes.num_boxes_static()), int)\n\n  def test_num_boxes_static_for_uninferrable_shape(self):\n    placeholder = tf.placeholder(tf.float32, shape=[None, 4])\n    boxes = box_list.BoxList(placeholder)\n    self.assertEquals(boxes.num_boxes_static(), None)\n\n  def test_as_tensor_dict(self):\n    boxlist = box_list.BoxList(\n        tf.constant([[0.1, 0.1, 0.4, 0.4], [0.1, 0.1, 0.5, 0.5]], tf.float32))\n    boxlist.add_field('classes', tf.constant([0, 1]))\n    boxlist.add_field('scores', tf.constant([0.75, 0.2]))\n    tensor_dict = boxlist.as_tensor_dict()\n\n    expected_boxes = [[0.1, 0.1, 0.4, 0.4], [0.1, 0.1, 0.5, 0.5]]\n    expected_classes = [0, 1]\n    expected_scores = [0.75, 0.2]\n\n    with self.test_session() as sess:\n      tensor_dict_out = sess.run(tensor_dict)\n      self.assertAllEqual(3, len(tensor_dict_out))\n      self.assertAllClose(expected_boxes, tensor_dict_out['boxes'])\n      self.assertAllEqual(expected_classes, tensor_dict_out['classes'])\n      self.assertAllClose(expected_scores, tensor_dict_out['scores'])\n\n  def test_as_tensor_dict_with_features(self):\n    boxlist = box_list.BoxList(\n        tf.constant([[0.1, 0.1, 0.4, 0.4], [0.1, 0.1, 0.5, 0.5]], tf.float32))\n    boxlist.add_field('classes', tf.constant([0, 1]))\n    boxlist.add_field('scores', tf.constant([0.75, 0.2]))\n    tensor_dict = boxlist.as_tensor_dict(['boxes', 'classes', 'scores'])\n\n    expected_boxes = [[0.1, 0.1, 0.4, 0.4], [0.1, 0.1, 0.5, 0.5]]\n    expected_classes = [0, 1]\n    expected_scores = [0.75, 0.2]\n\n    with self.test_session() as sess:\n      tensor_dict_out = sess.run(tensor_dict)\n      self.assertAllEqual(3, len(tensor_dict_out))\n      self.assertAllClose(expected_boxes, tensor_dict_out['boxes'])\n      self.assertAllEqual(expected_classes, tensor_dict_out['classes'])\n      self.assertAllClose(expected_scores, tensor_dict_out['scores'])\n\n  def test_as_tensor_dict_missing_field(self):\n    boxlist = box_list.BoxList(\n        tf.constant([[0.1, 0.1, 0.4, 0.4], [0.1, 0.1, 0.5, 0.5]], tf.float32))\n    boxlist.add_field('classes', tf.constant([0, 1]))\n    boxlist.add_field('scores', tf.constant([0.75, 0.2]))\n    with self.assertRaises(ValueError):\n      boxlist.as_tensor_dict(['foo', 'bar'])\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/core/box_predictor.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Box predictor for object detectors.\n\nBox predictors are classes that take a high level\nimage feature map as input and produce two predictions,\n(1) a tensor encoding box locations, and\n(2) a tensor encoding classes for each box.\n\nThese components are passed directly to loss functions\nin our detection models.\n\nThese modules are separated from the main model since the same\nfew box predictor architectures are shared across many models.\n\"\"\"\nfrom abc import abstractmethod\nimport tensorflow as tf\nfrom object_detection.utils import ops\nfrom object_detection.utils import static_shape\n\nslim = tf.contrib.slim\n\nBOX_ENCODINGS = 'box_encodings'\nCLASS_PREDICTIONS_WITH_BACKGROUND = 'class_predictions_with_background'\nMASK_PREDICTIONS = 'mask_predictions'\n\n\nclass BoxPredictor(object):\n  \"\"\"BoxPredictor.\"\"\"\n\n  def __init__(self, is_training, num_classes):\n    \"\"\"Constructor.\n\n    Args:\n      is_training: Indicates whether the BoxPredictor is in training mode.\n      num_classes: number of classes.  Note that num_classes *does not*\n        include the background category, so if groundtruth labels take values\n        in {0, 1, .., K-1}, num_classes=K (and not K+1, even though the\n        assigned classification targets can range from {0,... K}).\n    \"\"\"\n    self._is_training = is_training\n    self._num_classes = num_classes\n\n  @property\n  def num_classes(self):\n    return self._num_classes\n\n  def predict(self, image_features, num_predictions_per_location, scope,\n              **params):\n    \"\"\"Computes encoded object locations and corresponding confidences.\n\n    Takes a high level image feature map as input and produce two predictions,\n    (1) a tensor encoding box locations, and\n    (2) a tensor encoding class scores for each corresponding box.\n    In this interface, we only assume that two tensors are returned as output\n    and do not assume anything about their shapes.\n\n    Args:\n      image_features: A float tensor of shape [batch_size, height, width,\n        channels] containing features for a batch of images.\n      num_predictions_per_location: an integer representing the number of box\n        predictions to be made per spatial location in the feature map.\n      scope: Variable and Op scope name.\n      **params: Additional keyword arguments for specific implementations of\n              BoxPredictor.\n\n    Returns:\n      A dictionary containing at least the following tensors.\n        box_encodings: A float tensor of shape\n          [batch_size, num_anchors, q, code_size] representing the location of\n          the objects, where q is 1 or the number of classes.\n        class_predictions_with_background: A float tensor of shape\n          [batch_size, num_anchors, num_classes + 1] representing the class\n          predictions for the proposals.\n    \"\"\"\n    with tf.variable_scope(scope):\n      return self._predict(image_features, num_predictions_per_location,\n                           **params)\n\n  # TODO: num_predictions_per_location could be moved to constructor.\n  # This is currently only used by ConvolutionalBoxPredictor.\n  @abstractmethod\n  def _predict(self, image_features, num_predictions_per_location, **params):\n    \"\"\"Implementations must override this method.\n\n    Args:\n      image_features: A float tensor of shape [batch_size, height, width,\n        channels] containing features for a batch of images.\n      num_predictions_per_location: an integer representing the number of box\n        predictions to be made per spatial location in the feature map.\n      **params: Additional keyword arguments for specific implementations of\n              BoxPredictor.\n\n    Returns:\n      A dictionary containing at least the following tensors.\n        box_encodings: A float tensor of shape\n          [batch_size, num_anchors, q, code_size] representing the location of\n          the objects, where q is 1 or the number of classes.\n        class_predictions_with_background: A float tensor of shape\n          [batch_size, num_anchors, num_classes + 1] representing the class\n          predictions for the proposals.\n    \"\"\"\n    pass\n\n\nclass RfcnBoxPredictor(BoxPredictor):\n  \"\"\"RFCN Box Predictor.\n\n  Applies a position sensitve ROI pooling on position sensitive feature maps to\n  predict classes and refined locations. See https://arxiv.org/abs/1605.06409\n  for details.\n\n  This is used for the second stage of the RFCN meta architecture. Notice that\n  locations are *not* shared across classes, thus for each anchor, a separate\n  prediction is made for each class.\n  \"\"\"\n\n  def __init__(self,\n               is_training,\n               num_classes,\n               conv_hyperparams,\n               num_spatial_bins,\n               depth,\n               crop_size,\n               box_code_size):\n    \"\"\"Constructor.\n\n    Args:\n      is_training: Indicates whether the BoxPredictor is in training mode.\n      num_classes: number of classes.  Note that num_classes *does not*\n        include the background category, so if groundtruth labels take values\n        in {0, 1, .., K-1}, num_classes=K (and not K+1, even though the\n        assigned classification targets can range from {0,... K}).\n      conv_hyperparams: Slim arg_scope with hyperparameters for conolutional\n        layers.\n      num_spatial_bins: A list of two integers `[spatial_bins_y,\n        spatial_bins_x]`.\n      depth: Target depth to reduce the input feature maps to.\n      crop_size: A list of two integers `[crop_height, crop_width]`.\n      box_code_size: Size of encoding for each box.\n    \"\"\"\n    super(RfcnBoxPredictor, self).__init__(is_training, num_classes)\n    self._conv_hyperparams = conv_hyperparams\n    self._num_spatial_bins = num_spatial_bins\n    self._depth = depth\n    self._crop_size = crop_size\n    self._box_code_size = box_code_size\n\n  @property\n  def num_classes(self):\n    return self._num_classes\n\n  def _predict(self, image_features, num_predictions_per_location,\n               proposal_boxes):\n    \"\"\"Computes encoded object locations and corresponding confidences.\n\n    Args:\n      image_features: A float tensor of shape [batch_size, height, width,\n        channels] containing features for a batch of images.\n      num_predictions_per_location: an integer representing the number of box\n        predictions to be made per spatial location in the feature map.\n        Currently, this must be set to 1, or an error will be raised.\n      proposal_boxes: A float tensor of shape [batch_size, num_proposals,\n        box_code_size].\n\n    Returns:\n      box_encodings: A float tensor of shape\n        [batch_size, 1, num_classes, code_size] representing the\n        location of the objects.\n      class_predictions_with_background: A float tensor of shape\n        [batch_size, 1, num_classes + 1] representing the class\n        predictions for the proposals.\n    Raises:\n      ValueError: if num_predictions_per_location is not 1.\n    \"\"\"\n    if num_predictions_per_location != 1:\n      raise ValueError('Currently RfcnBoxPredictor only supports '\n                       'predicting a single box per class per location.')\n\n    batch_size = tf.shape(proposal_boxes)[0]\n    num_boxes = tf.shape(proposal_boxes)[1]\n    def get_box_indices(proposals):\n      proposals_shape = proposals.get_shape().as_list()\n      if any(dim is None for dim in proposals_shape):\n        proposals_shape = tf.shape(proposals)\n      ones_mat = tf.ones(proposals_shape[:2], dtype=tf.int32)\n      multiplier = tf.expand_dims(\n          tf.range(start=0, limit=proposals_shape[0]), 1)\n      return tf.reshape(ones_mat * multiplier, [-1])\n\n    net = image_features\n    with slim.arg_scope(self._conv_hyperparams):\n      net = slim.conv2d(net, self._depth, [1, 1], scope='reduce_depth')\n      # Location predictions.\n      location_feature_map_depth = (self._num_spatial_bins[0] *\n                                    self._num_spatial_bins[1] *\n                                    self.num_classes *\n                                    self._box_code_size)\n      location_feature_map = slim.conv2d(net, location_feature_map_depth,\n                                         [1, 1], activation_fn=None,\n                                         scope='refined_locations')\n      box_encodings = ops.position_sensitive_crop_regions(\n          location_feature_map,\n          boxes=tf.reshape(proposal_boxes, [-1, self._box_code_size]),\n          box_ind=get_box_indices(proposal_boxes),\n          crop_size=self._crop_size,\n          num_spatial_bins=self._num_spatial_bins,\n          global_pool=True)\n      box_encodings = tf.squeeze(box_encodings, squeeze_dims=[1, 2])\n      box_encodings = tf.reshape(box_encodings,\n                                 [batch_size * num_boxes, 1, self.num_classes,\n                                  self._box_code_size])\n\n      # Class predictions.\n      total_classes = self.num_classes + 1  # Account for background class.\n      class_feature_map_depth = (self._num_spatial_bins[0] *\n                                 self._num_spatial_bins[1] *\n                                 total_classes)\n      class_feature_map = slim.conv2d(net, class_feature_map_depth, [1, 1],\n                                      activation_fn=None,\n                                      scope='class_predictions')\n      class_predictions_with_background = ops.position_sensitive_crop_regions(\n          class_feature_map,\n          boxes=tf.reshape(proposal_boxes, [-1, self._box_code_size]),\n          box_ind=get_box_indices(proposal_boxes),\n          crop_size=self._crop_size,\n          num_spatial_bins=self._num_spatial_bins,\n          global_pool=True)\n      class_predictions_with_background = tf.squeeze(\n          class_predictions_with_background, squeeze_dims=[1, 2])\n      class_predictions_with_background = tf.reshape(\n          class_predictions_with_background,\n          [batch_size * num_boxes, 1, total_classes])\n\n    return {BOX_ENCODINGS: box_encodings,\n            CLASS_PREDICTIONS_WITH_BACKGROUND:\n            class_predictions_with_background}\n\n\nclass MaskRCNNBoxPredictor(BoxPredictor):\n  \"\"\"Mask R-CNN Box Predictor.\n\n  See Mask R-CNN: He, K., Gkioxari, G., Dollar, P., & Girshick, R. (2017).\n  Mask R-CNN. arXiv preprint arXiv:1703.06870.\n\n  This is used for the second stage of the Mask R-CNN detector where proposals\n  cropped from an image are arranged along the batch dimension of the input\n  image_features tensor. Notice that locations are *not* shared across classes,\n  thus for each anchor, a separate prediction is made for each class.\n\n  In addition to predicting boxes and classes, optionally this class allows\n  predicting masks and/or keypoints inside detection boxes.\n\n  Currently this box predictor makes per-class predictions; that is, each\n  anchor makes a separate box prediction for each class.\n  \"\"\"\n\n  def __init__(self,\n               is_training,\n               num_classes,\n               fc_hyperparams,\n               use_dropout,\n               dropout_keep_prob,\n               box_code_size,\n               conv_hyperparams=None,\n               predict_instance_masks=False,\n               mask_prediction_conv_depth=256,\n               predict_keypoints=False):\n    \"\"\"Constructor.\n\n    Args:\n      is_training: Indicates whether the BoxPredictor is in training mode.\n      num_classes: number of classes.  Note that num_classes *does not*\n        include the background category, so if groundtruth labels take values\n        in {0, 1, .., K-1}, num_classes=K (and not K+1, even though the\n        assigned classification targets can range from {0,... K}).\n      fc_hyperparams: Slim arg_scope with hyperparameters for fully\n        connected ops.\n      use_dropout: Option to use dropout or not.  Note that a single dropout\n        op is applied here prior to both box and class predictions, which stands\n        in contrast to the ConvolutionalBoxPredictor below.\n      dropout_keep_prob: Keep probability for dropout.\n        This is only used if use_dropout is True.\n      box_code_size: Size of encoding for each box.\n      conv_hyperparams: Slim arg_scope with hyperparameters for convolution\n        ops.\n      predict_instance_masks: Whether to predict object masks inside detection\n        boxes.\n      mask_prediction_conv_depth: The depth for the first conv2d_transpose op\n        applied to the image_features in the mask prediciton branch.\n      predict_keypoints: Whether to predict keypoints insde detection boxes.\n\n\n    Raises:\n      ValueError: If predict_instance_masks or predict_keypoints is true.\n    \"\"\"\n    super(MaskRCNNBoxPredictor, self).__init__(is_training, num_classes)\n    self._fc_hyperparams = fc_hyperparams\n    self._use_dropout = use_dropout\n    self._box_code_size = box_code_size\n    self._dropout_keep_prob = dropout_keep_prob\n    self._conv_hyperparams = conv_hyperparams\n    self._predict_instance_masks = predict_instance_masks\n    self._mask_prediction_conv_depth = mask_prediction_conv_depth\n    self._predict_keypoints = predict_keypoints\n    if self._predict_keypoints:\n      raise ValueError('Keypoint prediction is unimplemented.')\n    if ((self._predict_instance_masks or self._predict_keypoints) and\n        self._conv_hyperparams is None):\n      raise ValueError('`conv_hyperparams` must be provided when predicting '\n                       'masks.')\n\n  @property\n  def num_classes(self):\n    return self._num_classes\n\n  def _predict(self, image_features, num_predictions_per_location):\n    \"\"\"Computes encoded object locations and corresponding confidences.\n\n    Flattens image_features and applies fully connected ops (with no\n    non-linearity) to predict box encodings and class predictions.  In this\n    setting, anchors are not spatially arranged in any way and are assumed to\n    have been folded into the batch dimension.  Thus we output 1 for the\n    anchors dimension.\n\n    Args:\n      image_features: A float tensor of shape [batch_size, height, width,\n        channels] containing features for a batch of images.\n      num_predictions_per_location: an integer representing the number of box\n        predictions to be made per spatial location in the feature map.\n        Currently, this must be set to 1, or an error will be raised.\n\n    Returns:\n      A dictionary containing the following tensors.\n        box_encodings: A float tensor of shape\n          [batch_size, 1, num_classes, code_size] representing the\n          location of the objects.\n        class_predictions_with_background: A float tensor of shape\n          [batch_size, 1, num_classes + 1] representing the class\n          predictions for the proposals.\n      If predict_masks is True the dictionary also contains:\n        instance_masks: A float tensor of shape\n          [batch_size, 1, num_classes, image_height, image_width]\n      If predict_keypoints is True the dictionary also contains:\n        keypoints: [batch_size, 1, num_keypoints, 2]\n\n    Raises:\n      ValueError: if num_predictions_per_location is not 1.\n    \"\"\"\n    if num_predictions_per_location != 1:\n      raise ValueError('Currently FullyConnectedBoxPredictor only supports '\n                       'predicting a single box per class per location.')\n    spatial_averaged_image_features = tf.reduce_mean(image_features, [1, 2],\n                                                     keep_dims=True,\n                                                     name='AvgPool')\n    flattened_image_features = slim.flatten(spatial_averaged_image_features)\n    if self._use_dropout:\n      flattened_image_features = slim.dropout(flattened_image_features,\n                                              keep_prob=self._dropout_keep_prob,\n                                              is_training=self._is_training)\n    with slim.arg_scope(self._fc_hyperparams):\n      box_encodings = slim.fully_connected(\n          flattened_image_features,\n          self._num_classes * self._box_code_size,\n          activation_fn=None,\n          scope='BoxEncodingPredictor')\n      class_predictions_with_background = slim.fully_connected(\n          flattened_image_features,\n          self._num_classes + 1,\n          activation_fn=None,\n          scope='ClassPredictor')\n    box_encodings = tf.reshape(\n        box_encodings, [-1, 1, self._num_classes, self._box_code_size])\n    class_predictions_with_background = tf.reshape(\n        class_predictions_with_background, [-1, 1, self._num_classes + 1])\n\n    predictions_dict = {\n        BOX_ENCODINGS: box_encodings,\n        CLASS_PREDICTIONS_WITH_BACKGROUND: class_predictions_with_background\n    }\n\n    if self._predict_instance_masks:\n      with slim.arg_scope(self._conv_hyperparams):\n        upsampled_features = slim.conv2d_transpose(\n            image_features,\n            num_outputs=self._mask_prediction_conv_depth,\n            kernel_size=[2, 2],\n            stride=2)\n        mask_predictions = slim.conv2d(upsampled_features,\n                                       num_outputs=self.num_classes,\n                                       activation_fn=None,\n                                       kernel_size=[1, 1])\n        instance_masks = tf.expand_dims(tf.transpose(mask_predictions,\n                                                     perm=[0, 3, 1, 2]),\n                                        axis=1,\n                                        name='MaskPredictor')\n      predictions_dict[MASK_PREDICTIONS] = instance_masks\n    return predictions_dict\n\n\nclass ConvolutionalBoxPredictor(BoxPredictor):\n  \"\"\"Convolutional Box Predictor.\n\n  Optionally add an intermediate 1x1 convolutional layer after features and\n  predict in parallel branches box_encodings and\n  class_predictions_with_background.\n\n  Currently this box predictor assumes that predictions are \"shared\" across\n  classes --- that is each anchor makes box predictions which do not depend\n  on class.\n  \"\"\"\n\n  def __init__(self,\n               is_training,\n               num_classes,\n               conv_hyperparams,\n               min_depth,\n               max_depth,\n               num_layers_before_predictor,\n               use_dropout,\n               dropout_keep_prob,\n               kernel_size,\n               box_code_size,\n               apply_sigmoid_to_scores=False):\n    \"\"\"Constructor.\n\n    Args:\n      is_training: Indicates whether the BoxPredictor is in training mode.\n      num_classes: number of classes.  Note that num_classes *does not*\n        include the background category, so if groundtruth labels take values\n        in {0, 1, .., K-1}, num_classes=K (and not K+1, even though the\n        assigned classification targets can range from {0,... K}).\n      conv_hyperparams: Slim arg_scope with hyperparameters for convolution ops.\n      min_depth: Minumum feature depth prior to predicting box encodings\n        and class predictions.\n      max_depth: Maximum feature depth prior to predicting box encodings\n        and class predictions. If max_depth is set to 0, no additional\n        feature map will be inserted before location and class predictions.\n      num_layers_before_predictor: Number of the additional conv layers before\n        the predictor.\n      use_dropout: Option to use dropout for class prediction or not.\n      dropout_keep_prob: Keep probability for dropout.\n        This is only used if use_dropout is True.\n      kernel_size: Size of final convolution kernel.  If the\n        spatial resolution of the feature map is smaller than the kernel size,\n        then the kernel size is automatically set to be\n        min(feature_width, feature_height).\n      box_code_size: Size of encoding for each box.\n      apply_sigmoid_to_scores: if True, apply the sigmoid on the output\n        class_predictions.\n\n    Raises:\n      ValueError: if min_depth > max_depth.\n    \"\"\"\n    super(ConvolutionalBoxPredictor, self).__init__(is_training, num_classes)\n    if min_depth > max_depth:\n      raise ValueError('min_depth should be less than or equal to max_depth')\n    self._conv_hyperparams = conv_hyperparams\n    self._min_depth = min_depth\n    self._max_depth = max_depth\n    self._num_layers_before_predictor = num_layers_before_predictor\n    self._use_dropout = use_dropout\n    self._kernel_size = kernel_size\n    self._box_code_size = box_code_size\n    self._dropout_keep_prob = dropout_keep_prob\n    self._apply_sigmoid_to_scores = apply_sigmoid_to_scores\n\n  def _predict(self, image_features, num_predictions_per_location):\n    \"\"\"Computes encoded object locations and corresponding confidences.\n\n    Args:\n      image_features: A float tensor of shape [batch_size, height, width,\n        channels] containing features for a batch of images.\n      num_predictions_per_location: an integer representing the number of box\n        predictions to be made per spatial location in the feature map.\n\n    Returns:\n      A dictionary containing the following tensors.\n        box_encodings: A float tensor of shape [batch_size, num_anchors, 1,\n          code_size] representing the location of the objects, where\n          num_anchors = feat_height * feat_width * num_predictions_per_location\n        class_predictions_with_background: A float tensor of shape\n          [batch_size, num_anchors, num_classes + 1] representing the class\n          predictions for the proposals.\n    \"\"\"\n    features_depth = static_shape.get_depth(image_features.get_shape())\n    depth = max(min(features_depth, self._max_depth), self._min_depth)\n\n    # Add a slot for the background class.\n    num_class_slots = self.num_classes + 1\n    net = image_features\n    with slim.arg_scope(self._conv_hyperparams), \\\n         slim.arg_scope([slim.dropout], is_training=self._is_training):\n      # Add additional conv layers before the predictor.\n      if depth > 0 and self._num_layers_before_predictor > 0:\n        for i in range(self._num_layers_before_predictor):\n          net = slim.conv2d(\n              net, depth, [1, 1], scope='Conv2d_%d_1x1_%d' % (i, depth))\n      with slim.arg_scope([slim.conv2d], activation_fn=None,\n                          normalizer_fn=None, normalizer_params=None):\n        box_encodings = slim.conv2d(\n            net, num_predictions_per_location * self._box_code_size,\n            [self._kernel_size, self._kernel_size],\n            scope='BoxEncodingPredictor')\n        if self._use_dropout:\n          net = slim.dropout(net, keep_prob=self._dropout_keep_prob)\n        class_predictions_with_background = slim.conv2d(\n            net, num_predictions_per_location * num_class_slots,\n            [self._kernel_size, self._kernel_size], scope='ClassPredictor')\n        if self._apply_sigmoid_to_scores:\n          class_predictions_with_background = tf.sigmoid(\n              class_predictions_with_background)\n\n    batch_size = static_shape.get_batch_size(image_features.get_shape())\n    if batch_size is None:\n      features_height = static_shape.get_height(image_features.get_shape())\n      features_width = static_shape.get_width(image_features.get_shape())\n      flattened_predictions_size = (features_height * features_width *\n                                    num_predictions_per_location)\n      box_encodings = tf.reshape(\n          box_encodings,\n          [-1, flattened_predictions_size, 1, self._box_code_size])\n      class_predictions_with_background = tf.reshape(\n          class_predictions_with_background,\n          [-1, flattened_predictions_size, num_class_slots])\n    else:\n      box_encodings = tf.reshape(\n          box_encodings, [batch_size, -1, 1, self._box_code_size])\n      class_predictions_with_background = tf.reshape(\n          class_predictions_with_background, [batch_size, -1, num_class_slots])\n    return {BOX_ENCODINGS: box_encodings,\n            CLASS_PREDICTIONS_WITH_BACKGROUND:\n            class_predictions_with_background}\n"
  },
  {
    "path": "object_detector_app/object_detection/core/box_predictor_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.core.box_predictor.\"\"\"\n\nimport numpy as np\nimport tensorflow as tf\n\nfrom google.protobuf import text_format\nfrom object_detection.builders import hyperparams_builder\nfrom object_detection.core import box_predictor\nfrom object_detection.protos import hyperparams_pb2\n\n\nclass MaskRCNNBoxPredictorTest(tf.test.TestCase):\n\n  def _build_arg_scope_with_hyperparams(self,\n                                        op_type=hyperparams_pb2.Hyperparams.FC):\n    hyperparams = hyperparams_pb2.Hyperparams()\n    hyperparams_text_proto = \"\"\"\n      activation: NONE\n      regularizer {\n        l2_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n    \"\"\"\n    text_format.Merge(hyperparams_text_proto, hyperparams)\n    hyperparams.op = op_type\n    return hyperparams_builder.build(hyperparams, is_training=True)\n\n  def test_get_boxes_with_five_classes(self):\n    image_features = tf.random_uniform([2, 7, 7, 3], dtype=tf.float32)\n    mask_box_predictor = box_predictor.MaskRCNNBoxPredictor(\n        is_training=False,\n        num_classes=5,\n        fc_hyperparams=self._build_arg_scope_with_hyperparams(),\n        use_dropout=False,\n        dropout_keep_prob=0.5,\n        box_code_size=4,\n    )\n    box_predictions = mask_box_predictor.predict(\n        image_features, num_predictions_per_location=1, scope='BoxPredictor')\n    box_encodings = box_predictions[box_predictor.BOX_ENCODINGS]\n    class_predictions_with_background = box_predictions[\n        box_predictor.CLASS_PREDICTIONS_WITH_BACKGROUND]\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      (box_encodings_shape,\n       class_predictions_with_background_shape) = sess.run(\n           [tf.shape(box_encodings),\n            tf.shape(class_predictions_with_background)])\n      self.assertAllEqual(box_encodings_shape, [2, 1, 5, 4])\n      self.assertAllEqual(class_predictions_with_background_shape, [2, 1, 6])\n\n  def test_value_error_on_predict_instance_masks_with_no_conv_hyperparms(self):\n    with self.assertRaises(ValueError):\n      box_predictor.MaskRCNNBoxPredictor(\n          is_training=False,\n          num_classes=5,\n          fc_hyperparams=self._build_arg_scope_with_hyperparams(),\n          use_dropout=False,\n          dropout_keep_prob=0.5,\n          box_code_size=4,\n          predict_instance_masks=True)\n\n  def test_get_instance_masks(self):\n    image_features = tf.random_uniform([2, 7, 7, 3], dtype=tf.float32)\n    mask_box_predictor = box_predictor.MaskRCNNBoxPredictor(\n        is_training=False,\n        num_classes=5,\n        fc_hyperparams=self._build_arg_scope_with_hyperparams(),\n        use_dropout=False,\n        dropout_keep_prob=0.5,\n        box_code_size=4,\n        conv_hyperparams=self._build_arg_scope_with_hyperparams(\n            op_type=hyperparams_pb2.Hyperparams.CONV),\n        predict_instance_masks=True)\n    box_predictions = mask_box_predictor.predict(\n        image_features, num_predictions_per_location=1, scope='BoxPredictor')\n    mask_predictions = box_predictions[box_predictor.MASK_PREDICTIONS]\n    self.assertListEqual([2, 1, 5, 14, 14],\n                         mask_predictions.get_shape().as_list())\n\n  def test_do_not_return_instance_masks_and_keypoints_without_request(self):\n    image_features = tf.random_uniform([2, 7, 7, 3], dtype=tf.float32)\n    mask_box_predictor = box_predictor.MaskRCNNBoxPredictor(\n        is_training=False,\n        num_classes=5,\n        fc_hyperparams=self._build_arg_scope_with_hyperparams(),\n        use_dropout=False,\n        dropout_keep_prob=0.5,\n        box_code_size=4)\n    box_predictions = mask_box_predictor.predict(\n        image_features, num_predictions_per_location=1, scope='BoxPredictor')\n    self.assertEqual(len(box_predictions), 2)\n    self.assertTrue(box_predictor.BOX_ENCODINGS in box_predictions)\n    self.assertTrue(box_predictor.CLASS_PREDICTIONS_WITH_BACKGROUND\n                    in box_predictions)\n\n  def test_value_error_on_predict_keypoints(self):\n    with self.assertRaises(ValueError):\n      box_predictor.MaskRCNNBoxPredictor(\n          is_training=False,\n          num_classes=5,\n          fc_hyperparams=self._build_arg_scope_with_hyperparams(),\n          use_dropout=False,\n          dropout_keep_prob=0.5,\n          box_code_size=4,\n          predict_keypoints=True)\n\n\nclass RfcnBoxPredictorTest(tf.test.TestCase):\n\n  def _build_arg_scope_with_conv_hyperparams(self):\n    conv_hyperparams = hyperparams_pb2.Hyperparams()\n    conv_hyperparams_text_proto = \"\"\"\n      regularizer {\n        l2_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n    \"\"\"\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams)\n    return hyperparams_builder.build(conv_hyperparams, is_training=True)\n\n  def test_get_correct_box_encoding_and_class_prediction_shapes(self):\n    image_features = tf.random_uniform([4, 8, 8, 64], dtype=tf.float32)\n    proposal_boxes = tf.random_normal([4, 2, 4], dtype=tf.float32)\n    rfcn_box_predictor = box_predictor.RfcnBoxPredictor(\n        is_training=False,\n        num_classes=2,\n        conv_hyperparams=self._build_arg_scope_with_conv_hyperparams(),\n        num_spatial_bins=[3, 3],\n        depth=4,\n        crop_size=[12, 12],\n        box_code_size=4\n    )\n    box_predictions = rfcn_box_predictor.predict(\n        image_features, num_predictions_per_location=1, scope='BoxPredictor',\n        proposal_boxes=proposal_boxes)\n    box_encodings = box_predictions[box_predictor.BOX_ENCODINGS]\n    class_predictions_with_background = box_predictions[\n        box_predictor.CLASS_PREDICTIONS_WITH_BACKGROUND]\n\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      (box_encodings_shape,\n       class_predictions_shape) = sess.run(\n           [tf.shape(box_encodings),\n            tf.shape(class_predictions_with_background)])\n      self.assertAllEqual(box_encodings_shape, [8, 1, 2, 4])\n      self.assertAllEqual(class_predictions_shape, [8, 1, 3])\n\n\nclass ConvolutionalBoxPredictorTest(tf.test.TestCase):\n\n  def _build_arg_scope_with_conv_hyperparams(self):\n    conv_hyperparams = hyperparams_pb2.Hyperparams()\n    conv_hyperparams_text_proto = \"\"\"\n      activation: RELU_6\n      regularizer {\n        l2_regularizer {\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n        }\n      }\n    \"\"\"\n    text_format.Merge(conv_hyperparams_text_proto, conv_hyperparams)\n    return hyperparams_builder.build(conv_hyperparams, is_training=True)\n\n  def test_get_boxes_for_five_aspect_ratios_per_location(self):\n    image_features = tf.random_uniform([4, 8, 8, 64], dtype=tf.float32)\n    conv_box_predictor = box_predictor.ConvolutionalBoxPredictor(\n        is_training=False,\n        num_classes=0,\n        conv_hyperparams=self._build_arg_scope_with_conv_hyperparams(),\n        min_depth=0,\n        max_depth=32,\n        num_layers_before_predictor=1,\n        use_dropout=True,\n        dropout_keep_prob=0.8,\n        kernel_size=1,\n        box_code_size=4\n    )\n    box_predictions = conv_box_predictor.predict(\n        image_features, num_predictions_per_location=5, scope='BoxPredictor')\n    box_encodings = box_predictions[box_predictor.BOX_ENCODINGS]\n    objectness_predictions = box_predictions[\n        box_predictor.CLASS_PREDICTIONS_WITH_BACKGROUND]\n\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      (box_encodings_shape,\n       objectness_predictions_shape) = sess.run(\n           [tf.shape(box_encodings), tf.shape(objectness_predictions)])\n      self.assertAllEqual(box_encodings_shape, [4, 320, 1, 4])\n      self.assertAllEqual(objectness_predictions_shape, [4, 320, 1])\n\n  def test_get_boxes_for_one_aspect_ratio_per_location(self):\n    image_features = tf.random_uniform([4, 8, 8, 64], dtype=tf.float32)\n    conv_box_predictor = box_predictor.ConvolutionalBoxPredictor(\n        is_training=False,\n        num_classes=0,\n        conv_hyperparams=self._build_arg_scope_with_conv_hyperparams(),\n        min_depth=0,\n        max_depth=32,\n        num_layers_before_predictor=1,\n        use_dropout=True,\n        dropout_keep_prob=0.8,\n        kernel_size=1,\n        box_code_size=4\n    )\n    box_predictions = conv_box_predictor.predict(\n        image_features, num_predictions_per_location=1, scope='BoxPredictor')\n    box_encodings = box_predictions[box_predictor.BOX_ENCODINGS]\n    objectness_predictions = box_predictions[\n        box_predictor.CLASS_PREDICTIONS_WITH_BACKGROUND]\n\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      (box_encodings_shape,\n       objectness_predictions_shape) = sess.run(\n           [tf.shape(box_encodings), tf.shape(objectness_predictions)])\n      self.assertAllEqual(box_encodings_shape, [4, 64, 1, 4])\n      self.assertAllEqual(objectness_predictions_shape, [4, 64, 1])\n\n  def test_get_multi_class_predictions_for_five_aspect_ratios_per_location(\n      self):\n    num_classes_without_background = 6\n    image_features = tf.random_uniform([4, 8, 8, 64], dtype=tf.float32)\n    conv_box_predictor = box_predictor.ConvolutionalBoxPredictor(\n        is_training=False,\n        num_classes=num_classes_without_background,\n        conv_hyperparams=self._build_arg_scope_with_conv_hyperparams(),\n        min_depth=0,\n        max_depth=32,\n        num_layers_before_predictor=1,\n        use_dropout=True,\n        dropout_keep_prob=0.8,\n        kernel_size=1,\n        box_code_size=4\n    )\n    box_predictions = conv_box_predictor.predict(\n        image_features,\n        num_predictions_per_location=5,\n        scope='BoxPredictor')\n    box_encodings = box_predictions[box_predictor.BOX_ENCODINGS]\n    class_predictions_with_background = box_predictions[\n        box_predictor.CLASS_PREDICTIONS_WITH_BACKGROUND]\n\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      (box_encodings_shape, class_predictions_with_background_shape\n      ) = sess.run([\n          tf.shape(box_encodings), tf.shape(class_predictions_with_background)])\n      self.assertAllEqual(box_encodings_shape, [4, 320, 1, 4])\n      self.assertAllEqual(class_predictions_with_background_shape,\n                          [4, 320, num_classes_without_background+1])\n\n  def test_get_boxes_for_five_aspect_ratios_per_location_fully_convolutional(\n      self):\n    image_features = tf.placeholder(dtype=tf.float32, shape=[4, None, None, 64])\n    conv_box_predictor = box_predictor.ConvolutionalBoxPredictor(\n        is_training=False,\n        num_classes=0,\n        conv_hyperparams=self._build_arg_scope_with_conv_hyperparams(),\n        min_depth=0,\n        max_depth=32,\n        num_layers_before_predictor=1,\n        use_dropout=True,\n        dropout_keep_prob=0.8,\n        kernel_size=1,\n        box_code_size=4\n    )\n    box_predictions = conv_box_predictor.predict(\n        image_features, num_predictions_per_location=5, scope='BoxPredictor')\n    box_encodings = box_predictions[box_predictor.BOX_ENCODINGS]\n    objectness_predictions = box_predictions[\n        box_predictor.CLASS_PREDICTIONS_WITH_BACKGROUND]\n    init_op = tf.global_variables_initializer()\n\n    resolution = 32\n    expected_num_anchors = resolution*resolution*5\n    with self.test_session() as sess:\n      sess.run(init_op)\n      (box_encodings_shape,\n       objectness_predictions_shape) = sess.run(\n           [tf.shape(box_encodings), tf.shape(objectness_predictions)],\n           feed_dict={image_features:\n                      np.random.rand(4, resolution, resolution, 64)})\n      self.assertAllEqual(box_encodings_shape, [4, expected_num_anchors, 1, 4])\n      self.assertAllEqual(objectness_predictions_shape,\n                          [4, expected_num_anchors, 1])\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/core/data_decoder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Interface for data decoders.\n\nData decoders decode the input data and return a dictionary of tensors keyed by\nthe entries in core.reader.Fields.\n\"\"\"\nfrom abc import ABCMeta\nfrom abc import abstractmethod\n\n\nclass DataDecoder(object):\n  \"\"\"Interface for data decoders.\"\"\"\n  __metaclass__ = ABCMeta\n\n  # TODO: snake_case this method.\n  @abstractmethod\n  def Decode(self, data):\n    \"\"\"Return a single image and associated labels.\n\n    Args:\n      data: a string tensor holding a serialized protocol buffer corresponding\n        to data for a single image.\n\n    Returns:\n      tensor_dict: a dictionary containing tensors. Possible keys are defined in\n          reader.Fields.\n    \"\"\"\n    pass\n"
  },
  {
    "path": "object_detector_app/object_detection/core/keypoint_ops.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Keypoint operations.\n\nKeypoints are represented as tensors of shape [num_instances, num_keypoints, 2],\nwhere the last dimension holds rank 2 tensors of the form [y, x] representing\nthe coordinates of the keypoint.\n\"\"\"\nimport numpy as np\nimport tensorflow as tf\n\n\ndef scale(keypoints, y_scale, x_scale, scope=None):\n  \"\"\"Scales keypoint coordinates in x and y dimensions.\n\n  Args:\n    keypoints: a tensor of shape [num_instances, num_keypoints, 2]\n    y_scale: (float) scalar tensor\n    x_scale: (float) scalar tensor\n    scope: name scope.\n\n  Returns:\n    new_keypoints: a tensor of shape [num_instances, num_keypoints, 2]\n  \"\"\"\n  with tf.name_scope(scope, 'Scale'):\n    y_scale = tf.cast(y_scale, tf.float32)\n    x_scale = tf.cast(x_scale, tf.float32)\n    new_keypoints = keypoints * [[[y_scale, x_scale]]]\n    return new_keypoints\n\n\ndef clip_to_window(keypoints, window, scope=None):\n  \"\"\"Clips keypoints to a window.\n\n  This op clips any input keypoints to a window.\n\n  Args:\n    keypoints: a tensor of shape [num_instances, num_keypoints, 2]\n    window: a tensor of shape [4] representing the [y_min, x_min, y_max, x_max]\n      window to which the op should clip the keypoints.\n    scope: name scope.\n\n  Returns:\n    new_keypoints: a tensor of shape [num_instances, num_keypoints, 2]\n  \"\"\"\n  with tf.name_scope(scope, 'ClipToWindow'):\n    y, x = tf.split(value=keypoints, num_or_size_splits=2, axis=2)\n    win_y_min, win_x_min, win_y_max, win_x_max = tf.unstack(window)\n    y = tf.maximum(tf.minimum(y, win_y_max), win_y_min)\n    x = tf.maximum(tf.minimum(x, win_x_max), win_x_min)\n    new_keypoints = tf.concat([y, x], 2)\n    return new_keypoints\n\n\ndef prune_outside_window(keypoints, window, scope=None):\n  \"\"\"Prunes keypoints that fall outside a given window.\n\n  This function replaces keypoints that fall outside the given window with nan.\n  See also clip_to_window which clips any keypoints that fall outside the given\n  window.\n\n  Args:\n    keypoints: a tensor of shape [num_instances, num_keypoints, 2]\n    window: a tensor of shape [4] representing the [y_min, x_min, y_max, x_max]\n      window outside of which the op should prune the keypoints.\n    scope: name scope.\n\n  Returns:\n    new_keypoints: a tensor of shape [num_instances, num_keypoints, 2]\n  \"\"\"\n  with tf.name_scope(scope, 'PruneOutsideWindow'):\n    y, x = tf.split(value=keypoints, num_or_size_splits=2, axis=2)\n    win_y_min, win_x_min, win_y_max, win_x_max = tf.unstack(window)\n\n    valid_indices = tf.logical_and(\n        tf.logical_and(y >= win_y_min, y <= win_y_max),\n        tf.logical_and(x >= win_x_min, x <= win_x_max))\n\n    new_y = tf.where(valid_indices, y, np.nan * tf.ones_like(y))\n    new_x = tf.where(valid_indices, x, np.nan * tf.ones_like(x))\n    new_keypoints = tf.concat([new_y, new_x], 2)\n\n    return new_keypoints\n\n\ndef change_coordinate_frame(keypoints, window, scope=None):\n  \"\"\"Changes coordinate frame of the keypoints to be relative to window's frame.\n\n  Given a window of the form [y_min, x_min, y_max, x_max], changes keypoint\n  coordinates from keypoints of shape [num_instances, num_keypoints, 2]\n  to be relative to this window.\n\n  An example use case is data augmentation: where we are given groundtruth\n  keypoints and would like to randomly crop the image to some window. In this\n  case we need to change the coordinate frame of each groundtruth keypoint to be\n  relative to this new window.\n\n  Args:\n    keypoints: a tensor of shape [num_instances, num_keypoints, 2]\n    window: a tensor of shape [4] representing the [y_min, x_min, y_max, x_max]\n      window we should change the coordinate frame to.\n    scope: name scope.\n\n  Returns:\n    new_keypoints: a tensor of shape [num_instances, num_keypoints, 2]\n  \"\"\"\n  with tf.name_scope(scope, 'ChangeCoordinateFrame'):\n    win_height = window[2] - window[0]\n    win_width = window[3] - window[1]\n    new_keypoints = scale(keypoints - [window[0], window[1]], 1.0 / win_height,\n                          1.0 / win_width)\n    return new_keypoints\n\n\ndef to_normalized_coordinates(keypoints, height, width,\n                              check_range=True, scope=None):\n  \"\"\"Converts absolute keypoint coordinates to normalized coordinates in [0, 1].\n\n  Usually one uses the dynamic shape of the image or conv-layer tensor:\n    keypoints = keypoint_ops.to_normalized_coordinates(keypoints,\n                                                       tf.shape(images)[1],\n                                                       tf.shape(images)[2]),\n\n  This function raises an assertion failed error at graph execution time when\n  the maximum coordinate is smaller than 1.01 (which means that coordinates are\n  already normalized). The value 1.01 is to deal with small rounding errors.\n\n  Args:\n    keypoints: A tensor of shape [num_instances, num_keypoints, 2].\n    height: Maximum value for y coordinate of absolute keypoint coordinates.\n    width: Maximum value for x coordinate of absolute keypoint coordinates.\n    check_range: If True, checks if the coordinates are normalized.\n    scope: name scope.\n\n  Returns:\n    tensor of shape [num_instances, num_keypoints, 2] with normalized\n    coordinates in [0, 1].\n  \"\"\"\n  with tf.name_scope(scope, 'ToNormalizedCoordinates'):\n    height = tf.cast(height, tf.float32)\n    width = tf.cast(width, tf.float32)\n\n    if check_range:\n      max_val = tf.reduce_max(keypoints)\n      max_assert = tf.Assert(tf.greater(max_val, 1.01),\n                             ['max value is lower than 1.01: ', max_val])\n      with tf.control_dependencies([max_assert]):\n        width = tf.identity(width)\n\n    return scale(keypoints, 1.0 / height, 1.0 / width)\n\n\ndef to_absolute_coordinates(keypoints, height, width,\n                            check_range=True, scope=None):\n  \"\"\"Converts normalized keypoint coordinates to absolute pixel coordinates.\n\n  This function raises an assertion failed error when the maximum keypoint\n  coordinate value is larger than 1.01 (in which case coordinates are already\n  absolute).\n\n  Args:\n    keypoints: A tensor of shape [num_instances, num_keypoints, 2]\n    height: Maximum value for y coordinate of absolute keypoint coordinates.\n    width: Maximum value for x coordinate of absolute keypoint coordinates.\n    check_range: If True, checks if the coordinates are normalized or not.\n    scope: name scope.\n\n  Returns:\n    tensor of shape [num_instances, num_keypoints, 2] with absolute coordinates\n    in terms of the image size.\n\n  \"\"\"\n  with tf.name_scope(scope, 'ToAbsoluteCoordinates'):\n    height = tf.cast(height, tf.float32)\n    width = tf.cast(width, tf.float32)\n\n    # Ensure range of input keypoints is correct.\n    if check_range:\n      max_val = tf.reduce_max(keypoints)\n      max_assert = tf.Assert(tf.greater_equal(1.01, max_val),\n                             ['maximum keypoint coordinate value is larger '\n                              'than 1.01: ', max_val])\n      with tf.control_dependencies([max_assert]):\n        width = tf.identity(width)\n\n    return scale(keypoints, height, width)\n\n\ndef flip_horizontal(keypoints, flip_point, flip_permutation, scope=None):\n  \"\"\"Flips the keypoints horizontally around the flip_point.\n\n  This operation flips the x coordinate for each keypoint around the flip_point\n  and also permutes the keypoints in a manner specified by flip_permutation.\n\n  Args:\n    keypoints: a tensor of shape [num_instances, num_keypoints, 2]\n    flip_point:  (float) scalar tensor representing the x coordinate to flip the\n      keypoints around.\n    flip_permutation: rank 1 int32 tensor containing the keypoint flip\n      permutation. This specifies the mapping from original keypoint indices\n      to the flipped keypoint indices. This is used primarily for keypoints\n      that are not reflection invariant. E.g. Suppose there are 3 keypoints\n      representing ['head', 'right_eye', 'left_eye'], then a logical choice for\n      flip_permutation might be [0, 2, 1] since we want to swap the 'left_eye'\n      and 'right_eye' after a horizontal flip.\n    scope: name scope.\n\n  Returns:\n    new_keypoints: a tensor of shape [num_instances, num_keypoints, 2]\n  \"\"\"\n  with tf.name_scope(scope, 'FlipHorizontal'):\n    keypoints = tf.transpose(keypoints, [1, 0, 2])\n    keypoints = tf.gather(keypoints, flip_permutation)\n    v, u = tf.split(value=keypoints, num_or_size_splits=2, axis=2)\n    u = flip_point * 2.0 - u\n    new_keypoints = tf.concat([v, u], 2)\n    new_keypoints = tf.transpose(new_keypoints, [1, 0, 2])\n    return new_keypoints\n"
  },
  {
    "path": "object_detector_app/object_detection/core/keypoint_ops_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.core.keypoint_ops.\"\"\"\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.core import keypoint_ops\n\n\nclass KeypointOpsTest(tf.test.TestCase):\n  \"\"\"Tests for common keypoint operations.\"\"\"\n\n  def test_scale(self):\n    keypoints = tf.constant([\n        [[0.0, 0.0], [100.0, 200.0]],\n        [[50.0, 120.0], [100.0, 140.0]]\n    ])\n    y_scale = tf.constant(1.0 / 100)\n    x_scale = tf.constant(1.0 / 200)\n\n    expected_keypoints = tf.constant([\n        [[0., 0.], [1.0, 1.0]],\n        [[0.5, 0.6], [1.0, 0.7]]\n    ])\n    output = keypoint_ops.scale(keypoints, y_scale, x_scale)\n\n    with self.test_session() as sess:\n      output_, expected_keypoints_ = sess.run([output, expected_keypoints])\n      self.assertAllClose(output_, expected_keypoints_)\n\n  def test_clip_to_window(self):\n    keypoints = tf.constant([\n        [[0.25, 0.5], [0.75, 0.75]],\n        [[0.5, 0.0], [1.0, 1.0]]\n    ])\n    window = tf.constant([0.25, 0.25, 0.75, 0.75])\n\n    expected_keypoints = tf.constant([\n        [[0.25, 0.5], [0.75, 0.75]],\n        [[0.5, 0.25], [0.75, 0.75]]\n    ])\n    output = keypoint_ops.clip_to_window(keypoints, window)\n\n    with self.test_session() as sess:\n      output_, expected_keypoints_ = sess.run([output, expected_keypoints])\n      self.assertAllClose(output_, expected_keypoints_)\n\n  def test_prune_outside_window(self):\n    keypoints = tf.constant([\n        [[0.25, 0.5], [0.75, 0.75]],\n        [[0.5, 0.0], [1.0, 1.0]]\n    ])\n    window = tf.constant([0.25, 0.25, 0.75, 0.75])\n\n    expected_keypoints = tf.constant([[[0.25, 0.5], [0.75, 0.75]],\n                                      [[np.nan, np.nan], [np.nan, np.nan]]])\n    output = keypoint_ops.prune_outside_window(keypoints, window)\n\n    with self.test_session() as sess:\n      output_, expected_keypoints_ = sess.run([output, expected_keypoints])\n      self.assertAllClose(output_, expected_keypoints_)\n\n  def test_change_coordinate_frame(self):\n    keypoints = tf.constant([\n        [[0.25, 0.5], [0.75, 0.75]],\n        [[0.5, 0.0], [1.0, 1.0]]\n    ])\n    window = tf.constant([0.25, 0.25, 0.75, 0.75])\n\n    expected_keypoints = tf.constant([\n        [[0, 0.5], [1.0, 1.0]],\n        [[0.5, -0.5], [1.5, 1.5]]\n    ])\n    output = keypoint_ops.change_coordinate_frame(keypoints, window)\n\n    with self.test_session() as sess:\n      output_, expected_keypoints_ = sess.run([output, expected_keypoints])\n      self.assertAllClose(output_, expected_keypoints_)\n\n  def test_to_normalized_coordinates(self):\n    keypoints = tf.constant([\n        [[10., 30.], [30., 45.]],\n        [[20., 0.], [40., 60.]]\n    ])\n    output = keypoint_ops.to_normalized_coordinates(\n        keypoints, 40, 60)\n    expected_keypoints = tf.constant([\n        [[0.25, 0.5], [0.75, 0.75]],\n        [[0.5, 0.0], [1.0, 1.0]]\n    ])\n\n    with self.test_session() as sess:\n      output_, expected_keypoints_ = sess.run([output, expected_keypoints])\n      self.assertAllClose(output_, expected_keypoints_)\n\n  def test_to_normalized_coordinates_already_normalized(self):\n    keypoints = tf.constant([\n        [[0.25, 0.5], [0.75, 0.75]],\n        [[0.5, 0.0], [1.0, 1.0]]\n    ])\n    output = keypoint_ops.to_normalized_coordinates(\n        keypoints, 40, 60)\n\n    with self.test_session() as sess:\n      with self.assertRaisesOpError('assertion failed'):\n        sess.run(output)\n\n  def test_to_absolute_coordinates(self):\n    keypoints = tf.constant([\n        [[0.25, 0.5], [0.75, 0.75]],\n        [[0.5, 0.0], [1.0, 1.0]]\n    ])\n    output = keypoint_ops.to_absolute_coordinates(\n        keypoints, 40, 60)\n    expected_keypoints = tf.constant([\n        [[10., 30.], [30., 45.]],\n        [[20., 0.], [40., 60.]]\n    ])\n\n    with self.test_session() as sess:\n      output_, expected_keypoints_ = sess.run([output, expected_keypoints])\n      self.assertAllClose(output_, expected_keypoints_)\n\n  def test_to_absolute_coordinates_already_absolute(self):\n    keypoints = tf.constant([\n        [[10., 30.], [30., 45.]],\n        [[20., 0.], [40., 60.]]\n    ])\n    output = keypoint_ops.to_absolute_coordinates(\n        keypoints, 40, 60)\n\n    with self.test_session() as sess:\n      with self.assertRaisesOpError('assertion failed'):\n        sess.run(output)\n\n  def test_flip_horizontal(self):\n    keypoints = tf.constant([\n        [[0.1, 0.1], [0.2, 0.2], [0.3, 0.3]],\n        [[0.4, 0.4], [0.5, 0.5], [0.6, 0.6]]\n    ])\n    flip_permutation = [0, 2, 1]\n\n    expected_keypoints = tf.constant([\n        [[0.1, 0.9], [0.3, 0.7], [0.2, 0.8]],\n        [[0.4, 0.6], [0.6, 0.4], [0.5, 0.5]],\n    ])\n    output = keypoint_ops.flip_horizontal(keypoints, 0.5, flip_permutation)\n\n    with self.test_session() as sess:\n      output_, expected_keypoints_ = sess.run([output, expected_keypoints])\n      self.assertAllClose(output_, expected_keypoints_)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/core/losses.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Classification and regression loss functions for object detection.\n\nLocalization losses:\n * WeightedL2LocalizationLoss\n * WeightedSmoothL1LocalizationLoss\n * WeightedIOULocalizationLoss\n\nClassification losses:\n * WeightedSigmoidClassificationLoss\n * WeightedSoftmaxClassificationLoss\n * BootstrappedSigmoidClassificationLoss\n\"\"\"\nfrom abc import ABCMeta\nfrom abc import abstractmethod\n\nimport tensorflow as tf\n\nfrom object_detection.core import box_list\nfrom object_detection.core import box_list_ops\nfrom object_detection.utils import ops\n\nslim = tf.contrib.slim\n\n\nclass Loss(object):\n  \"\"\"Abstract base class for loss functions.\"\"\"\n  __metaclass__ = ABCMeta\n\n  def __call__(self,\n               prediction_tensor,\n               target_tensor,\n               ignore_nan_targets=False,\n               scope=None,\n               **params):\n    \"\"\"Call the loss function.\n\n    Args:\n      prediction_tensor: a tensor representing predicted quantities.\n      target_tensor: a tensor representing regression or classification targets.\n      ignore_nan_targets: whether to ignore nan targets in the loss computation.\n        E.g. can be used if the target tensor is missing groundtruth data that\n        shouldn't be factored into the loss.\n      scope: Op scope name. Defaults to 'Loss' if None.\n      **params: Additional keyword arguments for specific implementations of\n              the Loss.\n\n    Returns:\n      loss: a tensor representing the value of the loss function.\n    \"\"\"\n    with tf.name_scope(scope, 'Loss',\n                       [prediction_tensor, target_tensor, params]) as scope:\n      if ignore_nan_targets:\n        target_tensor = tf.where(tf.is_nan(target_tensor),\n                                 prediction_tensor,\n                                 target_tensor)\n      return self._compute_loss(prediction_tensor, target_tensor, **params)\n\n  @abstractmethod\n  def _compute_loss(self, prediction_tensor, target_tensor, **params):\n    \"\"\"Method to be overriden by implementations.\n\n    Args:\n      prediction_tensor: a tensor representing predicted quantities\n      target_tensor: a tensor representing regression or classification targets\n      **params: Additional keyword arguments for specific implementations of\n              the Loss.\n\n    Returns:\n      loss: a tensor representing the value of the loss function\n    \"\"\"\n    pass\n\n\nclass WeightedL2LocalizationLoss(Loss):\n  \"\"\"L2 localization loss function with anchorwise output support.\n\n  Loss[b,a] = .5 * ||weights[b,a] * (prediction[b,a,:] - target[b,a,:])||^2\n  \"\"\"\n\n  def __init__(self, anchorwise_output=False):\n    \"\"\"Constructor.\n\n    Args:\n      anchorwise_output: Outputs loss per anchor. (default False)\n\n    \"\"\"\n    self._anchorwise_output = anchorwise_output\n\n  def _compute_loss(self, prediction_tensor, target_tensor, weights):\n    \"\"\"Compute loss function.\n\n    Args:\n      prediction_tensor: A float tensor of shape [batch_size, num_anchors,\n        code_size] representing the (encoded) predicted locations of objects.\n      target_tensor: A float tensor of shape [batch_size, num_anchors,\n        code_size] representing the regression targets\n      weights: a float tensor of shape [batch_size, num_anchors]\n\n    Returns:\n      loss: a (scalar) tensor representing the value of the loss function\n            or a float tensor of shape [batch_size, num_anchors]\n    \"\"\"\n    weighted_diff = (prediction_tensor - target_tensor) * tf.expand_dims(\n        weights, 2)\n    square_diff = 0.5 * tf.square(weighted_diff)\n    if self._anchorwise_output:\n      return tf.reduce_sum(square_diff, 2)\n    return tf.reduce_sum(square_diff)\n\n\nclass WeightedSmoothL1LocalizationLoss(Loss):\n  \"\"\"Smooth L1 localization loss function.\n\n  The smooth L1_loss is defined elementwise as .5 x^2 if |x|<1 and |x|-.5\n  otherwise, where x is the difference between predictions and target.\n\n  See also Equation (3) in the Fast R-CNN paper by Ross Girshick (ICCV 2015)\n  \"\"\"\n\n  def __init__(self, anchorwise_output=False):\n    \"\"\"Constructor.\n\n    Args:\n      anchorwise_output: Outputs loss per anchor. (default False)\n\n    \"\"\"\n    self._anchorwise_output = anchorwise_output\n\n  def _compute_loss(self, prediction_tensor, target_tensor, weights):\n    \"\"\"Compute loss function.\n\n    Args:\n      prediction_tensor: A float tensor of shape [batch_size, num_anchors,\n        code_size] representing the (encoded) predicted locations of objects.\n      target_tensor: A float tensor of shape [batch_size, num_anchors,\n        code_size] representing the regression targets\n      weights: a float tensor of shape [batch_size, num_anchors]\n\n    Returns:\n      loss: a (scalar) tensor representing the value of the loss function\n    \"\"\"\n    diff = prediction_tensor - target_tensor\n    abs_diff = tf.abs(diff)\n    abs_diff_lt_1 = tf.less(abs_diff, 1)\n    anchorwise_smooth_l1norm = tf.reduce_sum(\n        tf.where(abs_diff_lt_1, 0.5 * tf.square(abs_diff), abs_diff - 0.5),\n        2) * weights\n    if self._anchorwise_output:\n      return anchorwise_smooth_l1norm\n    return tf.reduce_sum(anchorwise_smooth_l1norm)\n\n\nclass WeightedIOULocalizationLoss(Loss):\n  \"\"\"IOU localization loss function.\n\n  Sums the IOU for corresponding pairs of predicted/groundtruth boxes\n  and for each pair assign a loss of 1 - IOU.  We then compute a weighted\n  sum over all pairs which is returned as the total loss.\n  \"\"\"\n\n  def _compute_loss(self, prediction_tensor, target_tensor, weights):\n    \"\"\"Compute loss function.\n\n    Args:\n      prediction_tensor: A float tensor of shape [batch_size, num_anchors, 4]\n        representing the decoded predicted boxes\n      target_tensor: A float tensor of shape [batch_size, num_anchors, 4]\n        representing the decoded target boxes\n      weights: a float tensor of shape [batch_size, num_anchors]\n\n    Returns:\n      loss: a (scalar) tensor representing the value of the loss function\n    \"\"\"\n    predicted_boxes = box_list.BoxList(tf.reshape(prediction_tensor, [-1, 4]))\n    target_boxes = box_list.BoxList(tf.reshape(target_tensor, [-1, 4]))\n    per_anchor_iou_loss = 1.0 - box_list_ops.matched_iou(predicted_boxes,\n                                                         target_boxes)\n    return tf.reduce_sum(tf.reshape(weights, [-1]) * per_anchor_iou_loss)\n\n\nclass WeightedSigmoidClassificationLoss(Loss):\n  \"\"\"Sigmoid cross entropy classification loss function.\"\"\"\n\n  def __init__(self, anchorwise_output=False):\n    \"\"\"Constructor.\n\n    Args:\n      anchorwise_output: Outputs loss per anchor. (default False)\n\n    \"\"\"\n    self._anchorwise_output = anchorwise_output\n\n  def _compute_loss(self,\n                    prediction_tensor,\n                    target_tensor,\n                    weights,\n                    class_indices=None):\n    \"\"\"Compute loss function.\n\n    Args:\n      prediction_tensor: A float tensor of shape [batch_size, num_anchors,\n        num_classes] representing the predicted logits for each class\n      target_tensor: A float tensor of shape [batch_size, num_anchors,\n        num_classes] representing one-hot encoded classification targets\n      weights: a float tensor of shape [batch_size, num_anchors]\n      class_indices: (Optional) A 1-D integer tensor of class indices.\n        If provided, computes loss only for the specified class indices.\n\n    Returns:\n      loss: a (scalar) tensor representing the value of the loss function\n            or a float tensor of shape [batch_size, num_anchors]\n    \"\"\"\n    weights = tf.expand_dims(weights, 2)\n    if class_indices is not None:\n      weights *= tf.reshape(\n          ops.indices_to_dense_vector(class_indices,\n                                      tf.shape(prediction_tensor)[2]),\n          [1, 1, -1])\n    per_entry_cross_ent = (tf.nn.sigmoid_cross_entropy_with_logits(\n        labels=target_tensor, logits=prediction_tensor))\n    if self._anchorwise_output:\n      return tf.reduce_sum(per_entry_cross_ent * weights, 2)\n    return tf.reduce_sum(per_entry_cross_ent * weights)\n\n\nclass WeightedSoftmaxClassificationLoss(Loss):\n  \"\"\"Softmax loss function.\"\"\"\n\n  def __init__(self, anchorwise_output=False):\n    \"\"\"Constructor.\n\n    Args:\n      anchorwise_output: Whether to output loss per anchor (default False)\n\n    \"\"\"\n    self._anchorwise_output = anchorwise_output\n\n  def _compute_loss(self, prediction_tensor, target_tensor, weights):\n    \"\"\"Compute loss function.\n\n    Args:\n      prediction_tensor: A float tensor of shape [batch_size, num_anchors,\n        num_classes] representing the predicted logits for each class\n      target_tensor: A float tensor of shape [batch_size, num_anchors,\n        num_classes] representing one-hot encoded classification targets\n      weights: a float tensor of shape [batch_size, num_anchors]\n\n    Returns:\n      loss: a (scalar) tensor representing the value of the loss function\n    \"\"\"\n    num_classes = prediction_tensor.get_shape().as_list()[-1]\n    per_row_cross_ent = (tf.nn.softmax_cross_entropy_with_logits(\n        labels=tf.reshape(target_tensor, [-1, num_classes]),\n        logits=tf.reshape(prediction_tensor, [-1, num_classes])))\n    if self._anchorwise_output:\n      return tf.reshape(per_row_cross_ent, tf.shape(weights)) * weights\n    return tf.reduce_sum(per_row_cross_ent * tf.reshape(weights, [-1]))\n\n\nclass BootstrappedSigmoidClassificationLoss(Loss):\n  \"\"\"Bootstrapped sigmoid cross entropy classification loss function.\n\n  This loss uses a convex combination of training labels and the current model's\n  predictions as training targets in the classification loss. The idea is that\n  as the model improves over time, its predictions can be trusted more and we\n  can use these predictions to mitigate the damage of noisy/incorrect labels,\n  because incorrect labels are likely to be eventually highly inconsistent with\n  other stimuli predicted to have the same label by the model.\n\n  In \"soft\" bootstrapping, we use all predicted class probabilities, whereas in\n  \"hard\" bootstrapping, we use the single class favored by the model.\n\n  See also Training Deep Neural Networks On Noisy Labels with Bootstrapping by\n  Reed et al. (ICLR 2015).\n  \"\"\"\n\n  def __init__(self, alpha, bootstrap_type='soft', anchorwise_output=False):\n    \"\"\"Constructor.\n\n    Args:\n      alpha: a float32 scalar tensor between 0 and 1 representing interpolation\n        weight\n      bootstrap_type: set to either 'hard' or 'soft' (default)\n      anchorwise_output: Outputs loss per anchor. (default False)\n\n    Raises:\n      ValueError: if bootstrap_type is not either 'hard' or 'soft'\n    \"\"\"\n    if bootstrap_type != 'hard' and bootstrap_type != 'soft':\n      raise ValueError('Unrecognized bootstrap_type: must be one of '\n                       '\\'hard\\' or \\'soft.\\'')\n    self._alpha = alpha\n    self._bootstrap_type = bootstrap_type\n    self._anchorwise_output = anchorwise_output\n\n  def _compute_loss(self, prediction_tensor, target_tensor, weights):\n    \"\"\"Compute loss function.\n\n    Args:\n      prediction_tensor: A float tensor of shape [batch_size, num_anchors,\n        num_classes] representing the predicted logits for each class\n      target_tensor: A float tensor of shape [batch_size, num_anchors,\n        num_classes] representing one-hot encoded classification targets\n      weights: a float tensor of shape [batch_size, num_anchors]\n\n    Returns:\n      loss: a (scalar) tensor representing the value of the loss function\n            or a float tensor of shape [batch_size, num_anchors]\n    \"\"\"\n    if self._bootstrap_type == 'soft':\n      bootstrap_target_tensor = self._alpha * target_tensor + (\n          1.0 - self._alpha) * tf.sigmoid(prediction_tensor)\n    else:\n      bootstrap_target_tensor = self._alpha * target_tensor + (\n          1.0 - self._alpha) * tf.cast(\n              tf.sigmoid(prediction_tensor) > 0.5, tf.float32)\n    per_entry_cross_ent = (tf.nn.sigmoid_cross_entropy_with_logits(\n        labels=bootstrap_target_tensor, logits=prediction_tensor))\n    if self._anchorwise_output:\n      return tf.reduce_sum(per_entry_cross_ent * tf.expand_dims(weights, 2), 2)\n    return tf.reduce_sum(per_entry_cross_ent * tf.expand_dims(weights, 2))\n\n\nclass HardExampleMiner(object):\n  \"\"\"Hard example mining for regions in a list of images.\n\n  Implements hard example mining to select a subset of regions to be\n  back-propagated. For each image, selects the regions with highest losses,\n  subject to the condition that a newly selected region cannot have\n  an IOU > iou_threshold with any of the previously selected regions.\n  This can be achieved by re-using a greedy non-maximum suppression algorithm.\n  A constraint on the number of negatives mined per positive region can also be\n  enforced.\n\n  Reference papers: \"Training Region-based Object Detectors with Online\n  Hard Example Mining\" (CVPR 2016) by Srivastava et al., and\n  \"SSD: Single Shot MultiBox Detector\" (ECCV 2016) by Liu et al.\n  \"\"\"\n\n  def __init__(self,\n               num_hard_examples=64,\n               iou_threshold=0.7,\n               loss_type='both',\n               cls_loss_weight=0.05,\n               loc_loss_weight=0.06,\n               max_negatives_per_positive=None,\n               min_negatives_per_image=0):\n    \"\"\"Constructor.\n\n    The hard example mining implemented by this class can replicate the behavior\n    in the two aforementioned papers (Srivastava et al., and Liu et al).\n    To replicate the A2 paper (Srivastava et al), num_hard_examples is set\n    to a fixed parameter (64 by default) and iou_threshold is set to .7 for\n    running non-max-suppression the predicted boxes prior to hard mining.\n    In order to replicate the SSD paper (Liu et al), num_hard_examples should\n    be set to None, max_negatives_per_positive should be 3 and iou_threshold\n    should be 1.0 (in order to effectively turn off NMS).\n\n    Args:\n      num_hard_examples: maximum number of hard examples to be\n        selected per image (prior to enforcing max negative to positive ratio\n        constraint).  If set to None, all examples obtained after NMS are\n        considered.\n      iou_threshold: minimum intersection over union for an example\n        to be discarded during NMS.\n      loss_type: use only classification losses ('cls', default),\n        localization losses ('loc') or both losses ('both').\n        In the last case, cls_loss_weight and loc_loss_weight are used to\n        compute weighted sum of the two losses.\n      cls_loss_weight: weight for classification loss.\n      loc_loss_weight: weight for location loss.\n      max_negatives_per_positive: maximum number of negatives to retain for\n        each positive anchor. By default, num_negatives_per_positive is None,\n        which means that we do not enforce a prespecified negative:positive\n        ratio.  Note also that num_negatives_per_positives can be a float\n        (and will be converted to be a float even if it is passed in otherwise).\n      min_negatives_per_image: minimum number of negative anchors to sample for\n        a given image. Setting this to a positive number allows sampling\n        negatives in an image without any positive anchors and thus not biased\n        towards at least one detection per image.\n    \"\"\"\n    self._num_hard_examples = num_hard_examples\n    self._iou_threshold = iou_threshold\n    self._loss_type = loss_type\n    self._cls_loss_weight = cls_loss_weight\n    self._loc_loss_weight = loc_loss_weight\n    self._max_negatives_per_positive = max_negatives_per_positive\n    self._min_negatives_per_image = min_negatives_per_image\n    if self._max_negatives_per_positive is not None:\n      self._max_negatives_per_positive = float(self._max_negatives_per_positive)\n    self._num_positives_list = None\n    self._num_negatives_list = None\n\n  def __call__(self,\n               location_losses,\n               cls_losses,\n               decoded_boxlist_list,\n               match_list=None):\n    \"\"\"Computes localization and classification losses after hard mining.\n\n    Args:\n      location_losses: a float tensor of shape [num_images, num_anchors]\n        representing anchorwise localization losses.\n      cls_losses: a float tensor of shape [num_images, num_anchors]\n        representing anchorwise classification losses.\n      decoded_boxlist_list: a list of decoded BoxList representing location\n        predictions for each image.\n      match_list: an optional list of matcher.Match objects encoding the match\n        between anchors and groundtruth boxes for each image of the batch,\n        with rows of the Match objects corresponding to groundtruth boxes\n        and columns corresponding to anchors.  Match objects in match_list are\n        used to reference which anchors are positive, negative or ignored.  If\n        self._max_negatives_per_positive exists, these are then used to enforce\n        a prespecified negative to positive ratio.\n\n    Returns:\n      mined_location_loss: a float scalar with sum of localization losses from\n        selected hard examples.\n      mined_cls_loss: a float scalar with sum of classification losses from\n        selected hard examples.\n    Raises:\n      ValueError: if location_losses, cls_losses and decoded_boxlist_list do\n        not have compatible shapes (i.e., they must correspond to the same\n        number of images).\n      ValueError: if match_list is specified but its length does not match\n        len(decoded_boxlist_list).\n    \"\"\"\n    mined_location_losses = []\n    mined_cls_losses = []\n    location_losses = tf.unstack(location_losses)\n    cls_losses = tf.unstack(cls_losses)\n    num_images = len(decoded_boxlist_list)\n    if not match_list:\n      match_list = num_images * [None]\n    if not len(location_losses) == len(decoded_boxlist_list) == len(cls_losses):\n      raise ValueError('location_losses, cls_losses and decoded_boxlist_list '\n                       'do not have compatible shapes.')\n    if not isinstance(match_list, list):\n      raise ValueError('match_list must be a list.')\n    if len(match_list) != len(decoded_boxlist_list):\n      raise ValueError('match_list must either be None or have '\n                       'length=len(decoded_boxlist_list).')\n    num_positives_list = []\n    num_negatives_list = []\n    for ind, detection_boxlist in enumerate(decoded_boxlist_list):\n      box_locations = detection_boxlist.get()\n      match = match_list[ind]\n      image_losses = cls_losses[ind]\n      if self._loss_type == 'loc':\n        image_losses = location_losses[ind]\n      elif self._loss_type == 'both':\n        image_losses *= self._cls_loss_weight\n        image_losses += location_losses[ind] * self._loc_loss_weight\n      if self._num_hard_examples is not None:\n        num_hard_examples = self._num_hard_examples\n      else:\n        num_hard_examples = detection_boxlist.num_boxes()\n      selected_indices = tf.image.non_max_suppression(\n          box_locations, image_losses, num_hard_examples, self._iou_threshold)\n      if self._max_negatives_per_positive is not None and match:\n        (selected_indices, num_positives,\n         num_negatives) = self._subsample_selection_to_desired_neg_pos_ratio(\n             selected_indices, match, self._max_negatives_per_positive,\n             self._min_negatives_per_image)\n        num_positives_list.append(num_positives)\n        num_negatives_list.append(num_negatives)\n      mined_location_losses.append(\n          tf.reduce_sum(tf.gather(location_losses[ind], selected_indices)))\n      mined_cls_losses.append(\n          tf.reduce_sum(tf.gather(cls_losses[ind], selected_indices)))\n    location_loss = tf.reduce_sum(tf.stack(mined_location_losses))\n    cls_loss = tf.reduce_sum(tf.stack(mined_cls_losses))\n    if match and self._max_negatives_per_positive:\n      self._num_positives_list = num_positives_list\n      self._num_negatives_list = num_negatives_list\n    return (location_loss, cls_loss)\n\n  def summarize(self):\n    \"\"\"Summarize the number of positives and negatives after mining.\"\"\"\n    if self._num_positives_list and self._num_negatives_list:\n      avg_num_positives = tf.reduce_mean(tf.to_float(self._num_positives_list))\n      avg_num_negatives = tf.reduce_mean(tf.to_float(self._num_negatives_list))\n      tf.summary.scalar('HardExampleMiner/NumPositives', avg_num_positives)\n      tf.summary.scalar('HardExampleMiner/NumNegatives', avg_num_negatives)\n\n  def _subsample_selection_to_desired_neg_pos_ratio(self,\n                                                    indices,\n                                                    match,\n                                                    max_negatives_per_positive,\n                                                    min_negatives_per_image=0):\n    \"\"\"Subsample a collection of selected indices to a desired neg:pos ratio.\n\n    This function takes a subset of M indices (indexing into a large anchor\n    collection of N anchors where M<N) which are labeled as positive/negative\n    via a Match object (matched indices are positive, unmatched indices\n    are negative).  It returns a subset of the provided indices retaining all\n    positives as well as up to the first K negatives, where:\n      K=floor(num_negative_per_positive * num_positives).\n\n    For example, if indices=[2, 4, 5, 7, 9, 10] (indexing into 12 anchors),\n    with positives=[2, 5] and negatives=[4, 7, 9, 10] and\n    num_negatives_per_positive=1, then the returned subset of indices\n    is [2, 4, 5, 7].\n\n    Args:\n      indices: An integer tensor of shape [M] representing a collection\n        of selected anchor indices\n      match: A matcher.Match object encoding the match between anchors and\n        groundtruth boxes for a given image, with rows of the Match objects\n        corresponding to groundtruth boxes and columns corresponding to anchors.\n      max_negatives_per_positive: (float) maximum number of negatives for\n        each positive anchor.\n      min_negatives_per_image: minimum number of negative anchors for a given\n        image. Allow sampling negatives in image without any positive anchors.\n\n    Returns:\n      selected_indices: An integer tensor of shape [M'] representing a\n        collection of selected anchor indices with M' <= M.\n      num_positives: An integer tensor representing the number of positive\n        examples in selected set of indices.\n      num_negatives: An integer tensor representing the number of negative\n        examples in selected set of indices.\n    \"\"\"\n    positives_indicator = tf.gather(match.matched_column_indicator(), indices)\n    negatives_indicator = tf.gather(match.unmatched_column_indicator(), indices)\n    num_positives = tf.reduce_sum(tf.to_int32(positives_indicator))\n    max_negatives = tf.maximum(min_negatives_per_image,\n                               tf.to_int32(max_negatives_per_positive *\n                                           tf.to_float(num_positives)))\n    topk_negatives_indicator = tf.less_equal(\n        tf.cumsum(tf.to_int32(negatives_indicator)), max_negatives)\n    subsampled_selection_indices = tf.where(\n        tf.logical_or(positives_indicator, topk_negatives_indicator))\n    num_negatives = tf.size(subsampled_selection_indices) - num_positives\n    return (tf.reshape(tf.gather(indices, subsampled_selection_indices), [-1]),\n            num_positives, num_negatives)\n"
  },
  {
    "path": "object_detector_app/object_detection/core/losses_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for google3.research.vale.object_detection.losses.\"\"\"\nimport math\n\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.core import box_list\nfrom object_detection.core import losses\nfrom object_detection.core import matcher\n\n\nclass WeightedL2LocalizationLossTest(tf.test.TestCase):\n\n  def testReturnsCorrectLoss(self):\n    batch_size = 3\n    num_anchors = 10\n    code_size = 4\n    prediction_tensor = tf.ones([batch_size, num_anchors, code_size])\n    target_tensor = tf.zeros([batch_size, num_anchors, code_size])\n    weights = tf.constant([[1, 1, 1, 1, 1, 0, 0, 0, 0, 0],\n                           [1, 1, 1, 1, 1, 0, 0, 0, 0, 0],\n                           [1, 1, 1, 1, 1, 0, 0, 0, 0, 0]], tf.float32)\n    loss_op = losses.WeightedL2LocalizationLoss()\n    loss = loss_op(prediction_tensor, target_tensor, weights=weights)\n\n    expected_loss = (3 * 5 * 4) / 2.0\n    with self.test_session() as sess:\n      loss_output = sess.run(loss)\n      self.assertAllClose(loss_output, expected_loss)\n\n  def testReturnsCorrectAnchorwiseLoss(self):\n    batch_size = 3\n    num_anchors = 16\n    code_size = 4\n    prediction_tensor = tf.ones([batch_size, num_anchors, code_size])\n    target_tensor = tf.zeros([batch_size, num_anchors, code_size])\n    weights = tf.ones([batch_size, num_anchors])\n    loss_op = losses.WeightedL2LocalizationLoss(anchorwise_output=True)\n    loss = loss_op(prediction_tensor, target_tensor, weights=weights)\n\n    expected_loss = np.ones((batch_size, num_anchors)) * 2\n    with self.test_session() as sess:\n      loss_output = sess.run(loss)\n      self.assertAllClose(loss_output, expected_loss)\n\n  def testReturnsCorrectLossSum(self):\n    batch_size = 3\n    num_anchors = 16\n    code_size = 4\n    prediction_tensor = tf.ones([batch_size, num_anchors, code_size])\n    target_tensor = tf.zeros([batch_size, num_anchors, code_size])\n    weights = tf.ones([batch_size, num_anchors])\n    loss_op = losses.WeightedL2LocalizationLoss(anchorwise_output=False)\n    loss = loss_op(prediction_tensor, target_tensor, weights=weights)\n\n    expected_loss = tf.nn.l2_loss(prediction_tensor - target_tensor)\n    with self.test_session() as sess:\n      loss_output = sess.run(loss)\n      expected_loss_output = sess.run(expected_loss)\n      self.assertAllClose(loss_output, expected_loss_output)\n\n  def testReturnsCorrectNanLoss(self):\n    batch_size = 3\n    num_anchors = 10\n    code_size = 4\n    prediction_tensor = tf.ones([batch_size, num_anchors, code_size])\n    target_tensor = tf.concat([\n        tf.zeros([batch_size, num_anchors, code_size / 2]),\n        tf.ones([batch_size, num_anchors, code_size / 2]) * np.nan\n    ], axis=2)\n    weights = tf.ones([batch_size, num_anchors])\n    loss_op = losses.WeightedL2LocalizationLoss()\n    loss = loss_op(prediction_tensor, target_tensor, weights=weights,\n                   ignore_nan_targets=True)\n\n    expected_loss = (3 * 5 * 4) / 2.0\n    with self.test_session() as sess:\n      loss_output = sess.run(loss)\n      self.assertAllClose(loss_output, expected_loss)\n\n\nclass WeightedSmoothL1LocalizationLossTest(tf.test.TestCase):\n\n  def testReturnsCorrectLoss(self):\n    batch_size = 2\n    num_anchors = 3\n    code_size = 4\n    prediction_tensor = tf.constant([[[2.5, 0, .4, 0],\n                                      [0, 0, 0, 0],\n                                      [0, 2.5, 0, .4]],\n                                     [[3.5, 0, 0, 0],\n                                      [0, .4, 0, .9],\n                                      [0, 0, 1.5, 0]]], tf.float32)\n    target_tensor = tf.zeros([batch_size, num_anchors, code_size])\n    weights = tf.constant([[2, 1, 1],\n                           [0, 3, 0]], tf.float32)\n    loss_op = losses.WeightedSmoothL1LocalizationLoss()\n    loss = loss_op(prediction_tensor, target_tensor, weights=weights)\n\n    exp_loss = 7.695\n    with self.test_session() as sess:\n      loss_output = sess.run(loss)\n      self.assertAllClose(loss_output, exp_loss)\n\n\nclass WeightedIOULocalizationLossTest(tf.test.TestCase):\n\n  def testReturnsCorrectLoss(self):\n    prediction_tensor = tf.constant([[[1.5, 0, 2.4, 1],\n                                      [0, 0, 1, 1],\n                                      [0, 0, .5, .25]]])\n    target_tensor = tf.constant([[[1.5, 0, 2.4, 1],\n                                  [0, 0, 1, 1],\n                                  [50, 50, 500.5, 100.25]]])\n    weights = [[1.0, .5, 2.0]]\n    loss_op = losses.WeightedIOULocalizationLoss()\n    loss = loss_op(prediction_tensor, target_tensor, weights=weights)\n    exp_loss = 2.0\n    with self.test_session() as sess:\n      loss_output = sess.run(loss)\n      self.assertAllClose(loss_output, exp_loss)\n\n\nclass WeightedSigmoidClassificationLossTest(tf.test.TestCase):\n\n  def testReturnsCorrectLoss(self):\n    prediction_tensor = tf.constant([[[-100, 100, -100],\n                                      [100, -100, -100],\n                                      [100, 0, -100],\n                                      [-100, -100, 100]],\n                                     [[-100, 0, 100],\n                                      [-100, 100, -100],\n                                      [100, 100, 100],\n                                      [0, 0, -1]]], tf.float32)\n    target_tensor = tf.constant([[[0, 1, 0],\n                                  [1, 0, 0],\n                                  [1, 0, 0],\n                                  [0, 0, 1]],\n                                 [[0, 0, 1],\n                                  [0, 1, 0],\n                                  [1, 1, 1],\n                                  [1, 0, 0]]], tf.float32)\n    weights = tf.constant([[1, 1, 1, 1],\n                           [1, 1, 1, 0]], tf.float32)\n    loss_op = losses.WeightedSigmoidClassificationLoss()\n    loss = loss_op(prediction_tensor, target_tensor, weights=weights)\n\n    exp_loss = -2 * math.log(.5)\n    with self.test_session() as sess:\n      loss_output = sess.run(loss)\n      self.assertAllClose(loss_output, exp_loss)\n\n  def testReturnsCorrectAnchorWiseLoss(self):\n    prediction_tensor = tf.constant([[[-100, 100, -100],\n                                      [100, -100, -100],\n                                      [100, 0, -100],\n                                      [-100, -100, 100]],\n                                     [[-100, 0, 100],\n                                      [-100, 100, -100],\n                                      [100, 100, 100],\n                                      [0, 0, -1]]], tf.float32)\n    target_tensor = tf.constant([[[0, 1, 0],\n                                  [1, 0, 0],\n                                  [1, 0, 0],\n                                  [0, 0, 1]],\n                                 [[0, 0, 1],\n                                  [0, 1, 0],\n                                  [1, 1, 1],\n                                  [1, 0, 0]]], tf.float32)\n    weights = tf.constant([[1, 1, 1, 1],\n                           [1, 1, 1, 0]], tf.float32)\n    loss_op = losses.WeightedSigmoidClassificationLoss(True)\n    loss = loss_op(prediction_tensor, target_tensor, weights=weights)\n\n    exp_loss = np.matrix([[0, 0, -math.log(.5), 0],\n                          [-math.log(.5), 0, 0, 0]])\n    with self.test_session() as sess:\n      loss_output = sess.run(loss)\n      self.assertAllClose(loss_output, exp_loss)\n\n  def testReturnsCorrectLossWithClassIndices(self):\n    prediction_tensor = tf.constant([[[-100, 100, -100, 100],\n                                      [100, -100, -100, -100],\n                                      [100, 0, -100, 100],\n                                      [-100, -100, 100, -100]],\n                                     [[-100, 0, 100, 100],\n                                      [-100, 100, -100, 100],\n                                      [100, 100, 100, 100],\n                                      [0, 0, -1, 100]]], tf.float32)\n    target_tensor = tf.constant([[[0, 1, 0, 0],\n                                  [1, 0, 0, 1],\n                                  [1, 0, 0, 0],\n                                  [0, 0, 1, 1]],\n                                 [[0, 0, 1, 0],\n                                  [0, 1, 0, 0],\n                                  [1, 1, 1, 0],\n                                  [1, 0, 0, 0]]], tf.float32)\n    weights = tf.constant([[1, 1, 1, 1],\n                           [1, 1, 1, 0]], tf.float32)\n    # Ignores the last class.\n    class_indices = tf.constant([0, 1, 2], tf.int32)\n    loss_op = losses.WeightedSigmoidClassificationLoss(True)\n    loss = loss_op(prediction_tensor, target_tensor, weights=weights,\n                   class_indices=class_indices)\n\n    exp_loss = np.matrix([[0, 0, -math.log(.5), 0],\n                          [-math.log(.5), 0, 0, 0]])\n    with self.test_session() as sess:\n      loss_output = sess.run(loss)\n      self.assertAllClose(loss_output, exp_loss)\n\n\nclass WeightedSoftmaxClassificationLossTest(tf.test.TestCase):\n\n  def testReturnsCorrectLoss(self):\n    prediction_tensor = tf.constant([[[-100, 100, -100],\n                                      [100, -100, -100],\n                                      [0, 0, -100],\n                                      [-100, -100, 100]],\n                                     [[-100, 0, 0],\n                                      [-100, 100, -100],\n                                      [-100, 100, -100],\n                                      [100, -100, -100]]], tf.float32)\n    target_tensor = tf.constant([[[0, 1, 0],\n                                  [1, 0, 0],\n                                  [1, 0, 0],\n                                  [0, 0, 1]],\n                                 [[0, 0, 1],\n                                  [0, 1, 0],\n                                  [0, 1, 0],\n                                  [1, 0, 0]]], tf.float32)\n    weights = tf.constant([[1, 1, .5, 1],\n                           [1, 1, 1, 0]], tf.float32)\n    loss_op = losses.WeightedSoftmaxClassificationLoss()\n    loss = loss_op(prediction_tensor, target_tensor, weights=weights)\n\n    exp_loss = - 1.5 * math.log(.5)\n    with self.test_session() as sess:\n      loss_output = sess.run(loss)\n      self.assertAllClose(loss_output, exp_loss)\n\n  def testReturnsCorrectAnchorWiseLoss(self):\n    prediction_tensor = tf.constant([[[-100, 100, -100],\n                                      [100, -100, -100],\n                                      [0, 0, -100],\n                                      [-100, -100, 100]],\n                                     [[-100, 0, 0],\n                                      [-100, 100, -100],\n                                      [-100, 100, -100],\n                                      [100, -100, -100]]], tf.float32)\n    target_tensor = tf.constant([[[0, 1, 0],\n                                  [1, 0, 0],\n                                  [1, 0, 0],\n                                  [0, 0, 1]],\n                                 [[0, 0, 1],\n                                  [0, 1, 0],\n                                  [0, 1, 0],\n                                  [1, 0, 0]]], tf.float32)\n    weights = tf.constant([[1, 1, .5, 1],\n                           [1, 1, 1, 0]], tf.float32)\n    loss_op = losses.WeightedSoftmaxClassificationLoss(True)\n    loss = loss_op(prediction_tensor, target_tensor, weights=weights)\n\n    exp_loss = np.matrix([[0, 0, - 0.5 * math.log(.5), 0],\n                          [-math.log(.5), 0, 0, 0]])\n    with self.test_session() as sess:\n      loss_output = sess.run(loss)\n      self.assertAllClose(loss_output, exp_loss)\n\n\nclass BootstrappedSigmoidClassificationLossTest(tf.test.TestCase):\n\n  def testReturnsCorrectLossSoftBootstrapping(self):\n    prediction_tensor = tf.constant([[[-100, 100, 0],\n                                      [100, -100, -100],\n                                      [100, -100, -100],\n                                      [-100, -100, 100]],\n                                     [[-100, -100, 100],\n                                      [-100, 100, -100],\n                                      [100, 100, 100],\n                                      [0, 0, -1]]], tf.float32)\n    target_tensor = tf.constant([[[0, 1, 0],\n                                  [1, 0, 0],\n                                  [1, 0, 0],\n                                  [0, 0, 1]],\n                                 [[0, 0, 1],\n                                  [0, 1, 0],\n                                  [1, 1, 1],\n                                  [1, 0, 0]]], tf.float32)\n    weights = tf.constant([[1, 1, 1, 1],\n                           [1, 1, 1, 0]], tf.float32)\n    alpha = tf.constant(.5, tf.float32)\n    loss_op = losses.BootstrappedSigmoidClassificationLoss(\n        alpha, bootstrap_type='soft')\n    loss = loss_op(prediction_tensor, target_tensor, weights=weights)\n    exp_loss = -math.log(.5)\n    with self.test_session() as sess:\n      loss_output = sess.run(loss)\n      self.assertAllClose(loss_output, exp_loss)\n\n  def testReturnsCorrectLossHardBootstrapping(self):\n    prediction_tensor = tf.constant([[[-100, 100, 0],\n                                      [100, -100, -100],\n                                      [100, -100, -100],\n                                      [-100, -100, 100]],\n                                     [[-100, -100, 100],\n                                      [-100, 100, -100],\n                                      [100, 100, 100],\n                                      [0, 0, -1]]], tf.float32)\n    target_tensor = tf.constant([[[0, 1, 0],\n                                  [1, 0, 0],\n                                  [1, 0, 0],\n                                  [0, 0, 1]],\n                                 [[0, 0, 1],\n                                  [0, 1, 0],\n                                  [1, 1, 1],\n                                  [1, 0, 0]]], tf.float32)\n    weights = tf.constant([[1, 1, 1, 1],\n                           [1, 1, 1, 0]], tf.float32)\n    alpha = tf.constant(.5, tf.float32)\n    loss_op = losses.BootstrappedSigmoidClassificationLoss(\n        alpha, bootstrap_type='hard')\n    loss = loss_op(prediction_tensor, target_tensor, weights=weights)\n    exp_loss = -math.log(.5)\n    with self.test_session() as sess:\n      loss_output = sess.run(loss)\n      self.assertAllClose(loss_output, exp_loss)\n\n  def testReturnsCorrectAnchorWiseLoss(self):\n    prediction_tensor = tf.constant([[[-100, 100, -100],\n                                      [100, -100, -100],\n                                      [100, 0, -100],\n                                      [-100, -100, 100]],\n                                     [[-100, 0, 100],\n                                      [-100, 100, -100],\n                                      [100, 100, 100],\n                                      [0, 0, -1]]], tf.float32)\n    target_tensor = tf.constant([[[0, 1, 0],\n                                  [1, 0, 0],\n                                  [1, 0, 0],\n                                  [0, 0, 1]],\n                                 [[0, 0, 1],\n                                  [0, 1, 0],\n                                  [1, 1, 1],\n                                  [1, 0, 0]]], tf.float32)\n    weights = tf.constant([[1, 1, 1, 1],\n                           [1, 1, 1, 0]], tf.float32)\n    alpha = tf.constant(.5, tf.float32)\n    loss_op = losses.BootstrappedSigmoidClassificationLoss(\n        alpha, bootstrap_type='hard', anchorwise_output=True)\n    loss = loss_op(prediction_tensor, target_tensor, weights=weights)\n\n    exp_loss = np.matrix([[0, 0, -math.log(.5), 0],\n                          [-math.log(.5), 0, 0, 0]])\n    with self.test_session() as sess:\n      loss_output = sess.run(loss)\n      self.assertAllClose(loss_output, exp_loss)\n\n\nclass HardExampleMinerTest(tf.test.TestCase):\n\n  def testHardMiningWithSingleLossType(self):\n    location_losses = tf.constant([[100, 90, 80, 0],\n                                   [0, 1, 2, 3]], tf.float32)\n    cls_losses = tf.constant([[0, 10, 50, 110],\n                              [9, 6, 3, 0]], tf.float32)\n    box_corners = tf.constant([[0.1, 0.1, 0.9, 0.9],\n                               [0.1, 0.1, 0.9, 0.9],\n                               [0.1, 0.1, 0.9, 0.9],\n                               [0.1, 0.1, 0.9, 0.9]], tf.float32)\n    decoded_boxlist_list = []\n    decoded_boxlist_list.append(box_list.BoxList(box_corners))\n    decoded_boxlist_list.append(box_list.BoxList(box_corners))\n    # Uses only location loss to select hard examples\n    loss_op = losses.HardExampleMiner(num_hard_examples=1,\n                                      iou_threshold=0.0,\n                                      loss_type='loc',\n                                      cls_loss_weight=1,\n                                      loc_loss_weight=1)\n    (loc_loss, cls_loss) = loss_op(location_losses, cls_losses,\n                                   decoded_boxlist_list)\n    exp_loc_loss = 100 + 3\n    exp_cls_loss = 0 + 0\n    with self.test_session() as sess:\n      loc_loss_output = sess.run(loc_loss)\n      self.assertAllClose(loc_loss_output, exp_loc_loss)\n      cls_loss_output = sess.run(cls_loss)\n      self.assertAllClose(cls_loss_output, exp_cls_loss)\n\n  def testHardMiningWithBothLossType(self):\n    location_losses = tf.constant([[100, 90, 80, 0],\n                                   [0, 1, 2, 3]], tf.float32)\n    cls_losses = tf.constant([[0, 10, 50, 110],\n                              [9, 6, 3, 0]], tf.float32)\n    box_corners = tf.constant([[0.1, 0.1, 0.9, 0.9],\n                               [0.1, 0.1, 0.9, 0.9],\n                               [0.1, 0.1, 0.9, 0.9],\n                               [0.1, 0.1, 0.9, 0.9]], tf.float32)\n    decoded_boxlist_list = []\n    decoded_boxlist_list.append(box_list.BoxList(box_corners))\n    decoded_boxlist_list.append(box_list.BoxList(box_corners))\n    loss_op = losses.HardExampleMiner(num_hard_examples=1,\n                                      iou_threshold=0.0,\n                                      loss_type='both',\n                                      cls_loss_weight=1,\n                                      loc_loss_weight=1)\n    (loc_loss, cls_loss) = loss_op(location_losses, cls_losses,\n                                   decoded_boxlist_list)\n    exp_loc_loss = 80 + 0\n    exp_cls_loss = 50 + 9\n    with self.test_session() as sess:\n      loc_loss_output = sess.run(loc_loss)\n      self.assertAllClose(loc_loss_output, exp_loc_loss)\n      cls_loss_output = sess.run(cls_loss)\n      self.assertAllClose(cls_loss_output, exp_cls_loss)\n\n  def testHardMiningNMS(self):\n    location_losses = tf.constant([[100, 90, 80, 0],\n                                   [0, 1, 2, 3]], tf.float32)\n    cls_losses = tf.constant([[0, 10, 50, 110],\n                              [9, 6, 3, 0]], tf.float32)\n    box_corners = tf.constant([[0.1, 0.1, 0.9, 0.9],\n                               [0.9, 0.9, 0.99, 0.99],\n                               [0.1, 0.1, 0.9, 0.9],\n                               [0.1, 0.1, 0.9, 0.9]], tf.float32)\n    decoded_boxlist_list = []\n    decoded_boxlist_list.append(box_list.BoxList(box_corners))\n    decoded_boxlist_list.append(box_list.BoxList(box_corners))\n    loss_op = losses.HardExampleMiner(num_hard_examples=2,\n                                      iou_threshold=0.5,\n                                      loss_type='cls',\n                                      cls_loss_weight=1,\n                                      loc_loss_weight=1)\n    (loc_loss, cls_loss) = loss_op(location_losses, cls_losses,\n                                   decoded_boxlist_list)\n    exp_loc_loss = 0 + 90 + 0 + 1\n    exp_cls_loss = 110 + 10 + 9 + 6\n    with self.test_session() as sess:\n      loc_loss_output = sess.run(loc_loss)\n      self.assertAllClose(loc_loss_output, exp_loc_loss)\n      cls_loss_output = sess.run(cls_loss)\n      self.assertAllClose(cls_loss_output, exp_cls_loss)\n\n  def testEnforceNegativesPerPositiveRatio(self):\n    location_losses = tf.constant([[100, 90, 80, 0, 1, 2,\n                                    3, 10, 20, 100, 20, 3]], tf.float32)\n    cls_losses = tf.constant([[0, 0, 100, 0, 90, 70,\n                               0, 60, 0, 17, 13, 0]], tf.float32)\n    box_corners = tf.constant([[0.0, 0.0, 0.2, 0.1],\n                               [0.0, 0.0, 0.2, 0.1],\n                               [0.0, 0.0, 0.2, 0.1],\n                               [0.0, 0.0, 0.2, 0.1],\n                               [0.0, 0.0, 0.5, 0.1],\n                               [0.0, 0.0, 0.6, 0.1],\n                               [0.0, 0.0, 0.2, 0.1],\n                               [0.0, 0.0, 0.8, 0.1],\n                               [0.0, 0.0, 0.2, 0.1],\n                               [0.0, 0.0, 1.0, 0.1],\n                               [0.0, 0.0, 1.1, 0.1],\n                               [0.0, 0.0, 0.2, 0.1]], tf.float32)\n    match_results = tf.constant([2, -1, 0, -1, -1, 1, -1, -1, -1, -1, -1, 3])\n    match_list = [matcher.Match(match_results)]\n    decoded_boxlist_list = []\n    decoded_boxlist_list.append(box_list.BoxList(box_corners))\n\n    max_negatives_per_positive_list = [0.0, 0.5, 1.0, 1.5, 10]\n    exp_loc_loss_list = [80 + 2,\n                         80 + 1 + 2,\n                         80 + 1 + 2 + 10,\n                         80 + 1 + 2 + 10 + 100,\n                         80 + 1 + 2 + 10 + 100 + 20]\n    exp_cls_loss_list = [100 + 70,\n                         100 + 90 + 70,\n                         100 + 90 + 70 + 60,\n                         100 + 90 + 70 + 60 + 17,\n                         100 + 90 + 70 + 60 + 17 + 13]\n\n    for max_negatives_per_positive, exp_loc_loss, exp_cls_loss in zip(\n        max_negatives_per_positive_list, exp_loc_loss_list, exp_cls_loss_list):\n      loss_op = losses.HardExampleMiner(\n          num_hard_examples=None, iou_threshold=0.9999, loss_type='cls',\n          cls_loss_weight=1, loc_loss_weight=1,\n          max_negatives_per_positive=max_negatives_per_positive)\n      (loc_loss, cls_loss) = loss_op(location_losses, cls_losses,\n                                     decoded_boxlist_list, match_list)\n      loss_op.summarize()\n\n      with self.test_session() as sess:\n        loc_loss_output = sess.run(loc_loss)\n        self.assertAllClose(loc_loss_output, exp_loc_loss)\n        cls_loss_output = sess.run(cls_loss)\n        self.assertAllClose(cls_loss_output, exp_cls_loss)\n\n  def testEnforceNegativesPerPositiveRatioWithMinNegativesPerImage(self):\n    location_losses = tf.constant([[100, 90, 80, 0, 1, 2,\n                                    3, 10, 20, 100, 20, 3]], tf.float32)\n    cls_losses = tf.constant([[0, 0, 100, 0, 90, 70,\n                               0, 60, 0, 17, 13, 0]], tf.float32)\n    box_corners = tf.constant([[0.0, 0.0, 0.2, 0.1],\n                               [0.0, 0.0, 0.2, 0.1],\n                               [0.0, 0.0, 0.2, 0.1],\n                               [0.0, 0.0, 0.2, 0.1],\n                               [0.0, 0.0, 0.5, 0.1],\n                               [0.0, 0.0, 0.6, 0.1],\n                               [0.0, 0.0, 0.2, 0.1],\n                               [0.0, 0.0, 0.8, 0.1],\n                               [0.0, 0.0, 0.2, 0.1],\n                               [0.0, 0.0, 1.0, 0.1],\n                               [0.0, 0.0, 1.1, 0.1],\n                               [0.0, 0.0, 0.2, 0.1]], tf.float32)\n    match_results = tf.constant([-1] * 12)\n    match_list = [matcher.Match(match_results)]\n    decoded_boxlist_list = []\n    decoded_boxlist_list.append(box_list.BoxList(box_corners))\n\n    min_negatives_per_image_list = [0, 1, 2, 4, 5, 6]\n    exp_loc_loss_list = [0,\n                         80,\n                         80 + 1,\n                         80 + 1 + 2 + 10,\n                         80 + 1 + 2 + 10 + 100,\n                         80 + 1 + 2 + 10 + 100 + 20]\n    exp_cls_loss_list = [0,\n                         100,\n                         100 + 90,\n                         100 + 90 + 70 + 60,\n                         100 + 90 + 70 + 60 + 17,\n                         100 + 90 + 70 + 60 + 17 + 13]\n\n    for min_negatives_per_image, exp_loc_loss, exp_cls_loss in zip(\n        min_negatives_per_image_list, exp_loc_loss_list, exp_cls_loss_list):\n      loss_op = losses.HardExampleMiner(\n          num_hard_examples=None, iou_threshold=0.9999, loss_type='cls',\n          cls_loss_weight=1, loc_loss_weight=1,\n          max_negatives_per_positive=3,\n          min_negatives_per_image=min_negatives_per_image)\n      (loc_loss, cls_loss) = loss_op(location_losses, cls_losses,\n                                     decoded_boxlist_list, match_list)\n      with self.test_session() as sess:\n        loc_loss_output = sess.run(loc_loss)\n        self.assertAllClose(loc_loss_output, exp_loc_loss)\n        cls_loss_output = sess.run(cls_loss)\n        self.assertAllClose(cls_loss_output, exp_cls_loss)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/core/matcher.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Matcher interface and Match class.\n\nThis module defines the Matcher interface and the Match object. The job of the\nmatcher is to match row and column indices based on the similarity matrix and\nother optional parameters. Each column is matched to at most one row. There\nare three possibilities for the matching:\n\n1) match: A column matches a row.\n2) no_match: A column does not match any row.\n3) ignore: A column that is neither 'match' nor no_match.\n\nThe ignore case is regularly encountered in object detection: when an anchor has\na relatively small overlap with a ground-truth box, one neither wants to\nconsider this box a positive example (match) nor a negative example (no match).\n\nThe Match class is used to store the match results and it provides simple apis\nto query the results.\n\"\"\"\nfrom abc import ABCMeta\nfrom abc import abstractmethod\n\nimport tensorflow as tf\n\n\nclass Match(object):\n  \"\"\"Class to store results from the matcher.\n\n  This class is used to store the results from the matcher. It provides\n  convenient methods to query the matching results.\n  \"\"\"\n\n  def __init__(self, match_results):\n    \"\"\"Constructs a Match object.\n\n    Args:\n      match_results: Integer tensor of shape [N] with (1) match_results[i]>=0,\n        meaning that column i is matched with row match_results[i].\n        (2) match_results[i]=-1, meaning that column i is not matched.\n        (3) match_results[i]=-2, meaning that column i is ignored.\n\n    Raises:\n      ValueError: if match_results does not have rank 1 or is not an\n        integer int32 scalar tensor\n    \"\"\"\n    if match_results.shape.ndims != 1:\n      raise ValueError('match_results should have rank 1')\n    if match_results.dtype != tf.int32:\n      raise ValueError('match_results should be an int32 or int64 scalar '\n                       'tensor')\n    self._match_results = match_results\n\n  @property\n  def match_results(self):\n    \"\"\"The accessor for match results.\n\n    Returns:\n      the tensor which encodes the match results.\n    \"\"\"\n    return self._match_results\n\n  def matched_column_indices(self):\n    \"\"\"Returns column indices that match to some row.\n\n    The indices returned by this op are always sorted in increasing order.\n\n    Returns:\n      column_indices: int32 tensor of shape [K] with column indices.\n    \"\"\"\n    return self._reshape_and_cast(tf.where(tf.greater(self._match_results, -1)))\n\n  def matched_column_indicator(self):\n    \"\"\"Returns column indices that are matched.\n\n    Returns:\n      column_indices: int32 tensor of shape [K] with column indices.\n    \"\"\"\n    return tf.greater_equal(self._match_results, 0)\n\n  def num_matched_columns(self):\n    \"\"\"Returns number (int32 scalar tensor) of matched columns.\"\"\"\n    return tf.size(self.matched_column_indices())\n\n  def unmatched_column_indices(self):\n    \"\"\"Returns column indices that do not match any row.\n\n    The indices returned by this op are always sorted in increasing order.\n\n    Returns:\n      column_indices: int32 tensor of shape [K] with column indices.\n    \"\"\"\n    return self._reshape_and_cast(tf.where(tf.equal(self._match_results, -1)))\n\n  def unmatched_column_indicator(self):\n    \"\"\"Returns column indices that are unmatched.\n\n    Returns:\n      column_indices: int32 tensor of shape [K] with column indices.\n    \"\"\"\n    return tf.equal(self._match_results, -1)\n\n  def num_unmatched_columns(self):\n    \"\"\"Returns number (int32 scalar tensor) of unmatched columns.\"\"\"\n    return tf.size(self.unmatched_column_indices())\n\n  def ignored_column_indices(self):\n    \"\"\"Returns column indices that are ignored (neither Matched nor Unmatched).\n\n    The indices returned by this op are always sorted in increasing order.\n\n    Returns:\n      column_indices: int32 tensor of shape [K] with column indices.\n    \"\"\"\n    return self._reshape_and_cast(tf.where(self.ignored_column_indicator()))\n\n  def ignored_column_indicator(self):\n    \"\"\"Returns boolean column indicator where True means the colum is ignored.\n\n    Returns:\n      column_indicator: boolean vector which is True for all ignored column\n      indices.\n    \"\"\"\n    return tf.equal(self._match_results, -2)\n\n  def num_ignored_columns(self):\n    \"\"\"Returns number (int32 scalar tensor) of matched columns.\"\"\"\n    return tf.size(self.ignored_column_indices())\n\n  def unmatched_or_ignored_column_indices(self):\n    \"\"\"Returns column indices that are unmatched or ignored.\n\n    The indices returned by this op are always sorted in increasing order.\n\n    Returns:\n      column_indices: int32 tensor of shape [K] with column indices.\n    \"\"\"\n    return self._reshape_and_cast(tf.where(tf.greater(0, self._match_results)))\n\n  def matched_row_indices(self):\n    \"\"\"Returns row indices that match some column.\n\n    The indices returned by this op are ordered so as to be in correspondence\n    with the output of matched_column_indicator().  For example if\n    self.matched_column_indicator() is [0,2], and self.matched_row_indices() is\n    [7, 3], then we know that column 0 was matched to row 7 and column 2 was\n    matched to row 3.\n\n    Returns:\n      row_indices: int32 tensor of shape [K] with row indices.\n    \"\"\"\n    return self._reshape_and_cast(\n        tf.gather(self._match_results, self.matched_column_indices()))\n\n  def _reshape_and_cast(self, t):\n    return tf.cast(tf.reshape(t, [-1]), tf.int32)\n\n\nclass Matcher(object):\n  \"\"\"Abstract base class for matcher.\n  \"\"\"\n  __metaclass__ = ABCMeta\n\n  def match(self, similarity_matrix, scope=None, **params):\n    \"\"\"Computes matches among row and column indices and returns the result.\n\n    Computes matches among the row and column indices based on the similarity\n    matrix and optional arguments.\n\n    Args:\n      similarity_matrix: Float tensor of shape [N, M] with pairwise similarity\n        where higher value means more similar.\n      scope: Op scope name. Defaults to 'Match' if None.\n      **params: Additional keyword arguments for specific implementations of\n        the Matcher.\n\n    Returns:\n      A Match object with the results of matching.\n    \"\"\"\n    with tf.name_scope(scope, 'Match', [similarity_matrix, params]) as scope:\n      return Match(self._match(similarity_matrix, **params))\n\n  @abstractmethod\n  def _match(self, similarity_matrix, **params):\n    \"\"\"Method to be overriden by implementations.\n\n    Args:\n      similarity_matrix: Float tensor of shape [N, M] with pairwise similarity\n        where higher value means more similar.\n      **params: Additional keyword arguments for specific implementations of\n        the Matcher.\n\n    Returns:\n      match_results: Integer tensor of shape [M]: match_results[i]>=0 means\n        that column i is matched to row match_results[i], match_results[i]=-1\n        means that the column is not matched. match_results[i]=-2 means that\n        the column is ignored (usually this happens when there is a very weak\n        match which one neither wants as positive nor negative example).\n    \"\"\"\n    pass\n"
  },
  {
    "path": "object_detector_app/object_detection/core/matcher_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.core.matcher.\"\"\"\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.core import matcher\n\n\nclass AnchorMatcherTest(tf.test.TestCase):\n\n  def test_get_correct_matched_columnIndices(self):\n    match_results = tf.constant([3, 1, -1, 0, -1, 5, -2])\n    match = matcher.Match(match_results)\n    expected_column_indices = [0, 1, 3, 5]\n    matched_column_indices = match.matched_column_indices()\n    self.assertEquals(matched_column_indices.dtype, tf.int32)\n    with self.test_session() as sess:\n      matched_column_indices = sess.run(matched_column_indices)\n      self.assertAllEqual(matched_column_indices, expected_column_indices)\n\n  def test_get_correct_counts(self):\n    match_results = tf.constant([3, 1, -1, 0, -1, 5, -2])\n    match = matcher.Match(match_results)\n    exp_num_matched_columns = 4\n    exp_num_unmatched_columns = 2\n    exp_num_ignored_columns = 1\n    num_matched_columns = match.num_matched_columns()\n    num_unmatched_columns = match.num_unmatched_columns()\n    num_ignored_columns = match.num_ignored_columns()\n    self.assertEquals(num_matched_columns.dtype, tf.int32)\n    self.assertEquals(num_unmatched_columns.dtype, tf.int32)\n    self.assertEquals(num_ignored_columns.dtype, tf.int32)\n    with self.test_session() as sess:\n      (num_matched_columns_out, num_unmatched_columns_out,\n       num_ignored_columns_out) = sess.run(\n           [num_matched_columns, num_unmatched_columns, num_ignored_columns])\n      self.assertAllEqual(num_matched_columns_out, exp_num_matched_columns)\n      self.assertAllEqual(num_unmatched_columns_out, exp_num_unmatched_columns)\n      self.assertAllEqual(num_ignored_columns_out, exp_num_ignored_columns)\n\n  def testGetCorrectUnmatchedColumnIndices(self):\n    match_results = tf.constant([3, 1, -1, 0, -1, 5, -2])\n    match = matcher.Match(match_results)\n    expected_column_indices = [2, 4]\n    unmatched_column_indices = match.unmatched_column_indices()\n    self.assertEquals(unmatched_column_indices.dtype, tf.int32)\n    with self.test_session() as sess:\n      unmatched_column_indices = sess.run(unmatched_column_indices)\n      self.assertAllEqual(unmatched_column_indices, expected_column_indices)\n\n  def testGetCorrectMatchedRowIndices(self):\n    match_results = tf.constant([3, 1, -1, 0, -1, 5, -2])\n    match = matcher.Match(match_results)\n    expected_row_indices = [3, 1, 0, 5]\n    matched_row_indices = match.matched_row_indices()\n    self.assertEquals(matched_row_indices.dtype, tf.int32)\n    with self.test_session() as sess:\n      matched_row_inds = sess.run(matched_row_indices)\n      self.assertAllEqual(matched_row_inds, expected_row_indices)\n\n  def test_get_correct_ignored_column_indices(self):\n    match_results = tf.constant([3, 1, -1, 0, -1, 5, -2])\n    match = matcher.Match(match_results)\n    expected_column_indices = [6]\n    ignored_column_indices = match.ignored_column_indices()\n    self.assertEquals(ignored_column_indices.dtype, tf.int32)\n    with self.test_session() as sess:\n      ignored_column_indices = sess.run(ignored_column_indices)\n      self.assertAllEqual(ignored_column_indices, expected_column_indices)\n\n  def test_get_correct_matched_column_indicator(self):\n    match_results = tf.constant([3, 1, -1, 0, -1, 5, -2])\n    match = matcher.Match(match_results)\n    expected_column_indicator = [True, True, False, True, False, True, False]\n    matched_column_indicator = match.matched_column_indicator()\n    self.assertEquals(matched_column_indicator.dtype, tf.bool)\n    with self.test_session() as sess:\n      matched_column_indicator = sess.run(matched_column_indicator)\n      self.assertAllEqual(matched_column_indicator, expected_column_indicator)\n\n  def test_get_correct_unmatched_column_indicator(self):\n    match_results = tf.constant([3, 1, -1, 0, -1, 5, -2])\n    match = matcher.Match(match_results)\n    expected_column_indicator = [False, False, True, False, True, False, False]\n    unmatched_column_indicator = match.unmatched_column_indicator()\n    self.assertEquals(unmatched_column_indicator.dtype, tf.bool)\n    with self.test_session() as sess:\n      unmatched_column_indicator = sess.run(unmatched_column_indicator)\n      self.assertAllEqual(unmatched_column_indicator, expected_column_indicator)\n\n  def test_get_correct_ignored_column_indicator(self):\n    match_results = tf.constant([3, 1, -1, 0, -1, 5, -2])\n    match = matcher.Match(match_results)\n    expected_column_indicator = [False, False, False, False, False, False, True]\n    ignored_column_indicator = match.ignored_column_indicator()\n    self.assertEquals(ignored_column_indicator.dtype, tf.bool)\n    with self.test_session() as sess:\n      ignored_column_indicator = sess.run(ignored_column_indicator)\n      self.assertAllEqual(ignored_column_indicator, expected_column_indicator)\n\n  def test_get_correct_unmatched_ignored_column_indices(self):\n    match_results = tf.constant([3, 1, -1, 0, -1, 5, -2])\n    match = matcher.Match(match_results)\n    expected_column_indices = [2, 4, 6]\n    unmatched_ignored_column_indices = (match.\n                                        unmatched_or_ignored_column_indices())\n    self.assertEquals(unmatched_ignored_column_indices.dtype, tf.int32)\n    with self.test_session() as sess:\n      unmatched_ignored_column_indices = sess.run(\n          unmatched_ignored_column_indices)\n      self.assertAllEqual(unmatched_ignored_column_indices,\n                          expected_column_indices)\n\n  def test_all_columns_accounted_for(self):\n    # Note: deliberately setting to small number so not always\n    # all possibilities appear (matched, unmatched, ignored)\n    num_matches = 10\n    match_results = tf.random_uniform(\n        [num_matches], minval=-2, maxval=5, dtype=tf.int32)\n    match = matcher.Match(match_results)\n    matched_column_indices = match.matched_column_indices()\n    unmatched_column_indices = match.unmatched_column_indices()\n    ignored_column_indices = match.ignored_column_indices()\n    with self.test_session() as sess:\n      matched, unmatched, ignored = sess.run([\n          matched_column_indices, unmatched_column_indices,\n          ignored_column_indices\n      ])\n      all_indices = np.hstack((matched, unmatched, ignored))\n      all_indices_sorted = np.sort(all_indices)\n      self.assertAllEqual(all_indices_sorted,\n                          np.arange(num_matches, dtype=np.int32))\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/core/minibatch_sampler.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Base minibatch sampler module.\n\nThe job of the minibatch_sampler is to subsample a minibatch based on some\ncriterion.\n\nThe main function call is:\n    subsample(indicator, batch_size, **params).\nIndicator is a 1d boolean tensor where True denotes which examples can be\nsampled. It returns a boolean indicator where True denotes an example has been\nsampled..\n\nSubclasses should implement the Subsample function and can make use of the\n@staticmethod SubsampleIndicator.\n\"\"\"\n\nfrom abc import ABCMeta\nfrom abc import abstractmethod\n\nimport tensorflow as tf\n\nfrom object_detection.utils import ops\n\n\nclass MinibatchSampler(object):\n  \"\"\"Abstract base class for subsampling minibatches.\"\"\"\n  __metaclass__ = ABCMeta\n\n  def __init__(self):\n    \"\"\"Constructs a minibatch sampler.\"\"\"\n    pass\n\n  @abstractmethod\n  def subsample(self, indicator, batch_size, **params):\n    \"\"\"Returns subsample of entries in indicator.\n\n    Args:\n      indicator: boolean tensor of shape [N] whose True entries can be sampled.\n      batch_size: desired batch size.\n      **params: additional keyword arguments for specific implementations of\n          the MinibatchSampler.\n\n    Returns:\n      sample_indicator: boolean tensor of shape [N] whose True entries have been\n      sampled. If sum(indicator) >= batch_size, sum(is_sampled) = batch_size\n    \"\"\"\n    pass\n\n  @staticmethod\n  def subsample_indicator(indicator, num_samples):\n    \"\"\"Subsample indicator vector.\n\n    Given a boolean indicator vector with M elements set to `True`, the function\n    assigns all but `num_samples` of these previously `True` elements to\n    `False`. If `num_samples` is greater than M, the original indicator vector\n    is returned.\n\n    Args:\n      indicator: a 1-dimensional boolean tensor indicating which elements\n        are allowed to be sampled and which are not.\n      num_samples: int32 scalar tensor\n\n    Returns:\n      a boolean tensor with the same shape as input (indicator) tensor\n    \"\"\"\n    indices = tf.where(indicator)\n    indices = tf.random_shuffle(indices)\n    indices = tf.reshape(indices, [-1])\n\n    num_samples = tf.minimum(tf.size(indices), num_samples)\n    selected_indices = tf.slice(indices, [0], tf.reshape(num_samples, [1]))\n\n    selected_indicator = ops.indices_to_dense_vector(selected_indices,\n                                                     tf.shape(indicator)[0])\n\n    return tf.equal(selected_indicator, 1)\n"
  },
  {
    "path": "object_detector_app/object_detection/core/minibatch_sampler_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for google3.research.vale.object_detection.minibatch_sampler.\"\"\"\n\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.core import minibatch_sampler\n\n\nclass MinibatchSamplerTest(tf.test.TestCase):\n\n  def test_subsample_indicator_when_more_true_elements_than_num_samples(self):\n    np_indicator = [True, False, True, False, True, True, False]\n    indicator = tf.constant(np_indicator)\n    samples = minibatch_sampler.MinibatchSampler.subsample_indicator(\n        indicator, 3)\n    with self.test_session() as sess:\n      samples_out = sess.run(samples)\n      self.assertTrue(np.sum(samples_out), 3)\n      self.assertAllEqual(samples_out,\n                          np.logical_and(samples_out, np_indicator))\n\n  def test_subsample_when_more_true_elements_than_num_samples_no_shape(self):\n    np_indicator = [True, False, True, False, True, True, False]\n    indicator = tf.placeholder(tf.bool)\n    feed_dict = {indicator: np_indicator}\n\n    samples = minibatch_sampler.MinibatchSampler.subsample_indicator(\n        indicator, 3)\n    with self.test_session() as sess:\n      samples_out = sess.run(samples, feed_dict=feed_dict)\n      self.assertTrue(np.sum(samples_out), 3)\n      self.assertAllEqual(samples_out,\n                          np.logical_and(samples_out, np_indicator))\n\n  def test_subsample_indicator_when_less_true_elements_than_num_samples(self):\n    np_indicator = [True, False, True, False, True, True, False]\n    indicator = tf.constant(np_indicator)\n    samples = minibatch_sampler.MinibatchSampler.subsample_indicator(\n        indicator, 5)\n    with self.test_session() as sess:\n      samples_out = sess.run(samples)\n      self.assertTrue(np.sum(samples_out), 4)\n      self.assertAllEqual(samples_out,\n                          np.logical_and(samples_out, np_indicator))\n\n  def test_subsample_indicator_when_num_samples_is_zero(self):\n    np_indicator = [True, False, True, False, True, True, False]\n    indicator = tf.constant(np_indicator)\n    samples_none = minibatch_sampler.MinibatchSampler.subsample_indicator(\n        indicator, 0)\n    with self.test_session() as sess:\n      samples_none_out = sess.run(samples_none)\n      self.assertAllEqual(\n          np.zeros_like(samples_none_out, dtype=bool),\n          samples_none_out)\n\n  def test_subsample_indicator_when_indicator_all_false(self):\n    indicator_empty = tf.zeros([0], dtype=tf.bool)\n    samples_empty = minibatch_sampler.MinibatchSampler.subsample_indicator(\n        indicator_empty, 4)\n    with self.test_session() as sess:\n      samples_empty_out = sess.run(samples_empty)\n      self.assertEqual(0, samples_empty_out.size)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/core/model.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Abstract detection model.\n\nThis file defines a generic base class for detection models.  Programs that are\ndesigned to work with arbitrary detection models should only depend on this\nclass.  We intend for the functions in this class to follow tensor-in/tensor-out\ndesign, thus all functions have tensors or lists/dictionaries holding tensors as\ninputs and outputs.\n\nAbstractly, detection models predict output tensors given input images\nwhich can be passed to a loss function at training time or passed to a\npostprocessing function at eval time.  The computation graphs at a high level\nconsequently look as follows:\n\nTraining time:\ninputs (images tensor) -> preprocess -> predict -> loss -> outputs (loss tensor)\n\nEvaluation time:\ninputs (images tensor) -> preprocess -> predict -> postprocess\n -> outputs (boxes tensor, scores tensor, classes tensor, num_detections tensor)\n\nDetectionModels must thus implement four functions (1) preprocess, (2) predict,\n(3) postprocess and (4) loss.  DetectionModels should make no assumptions about\nthe input size or aspect ratio --- they are responsible for doing any\nresize/reshaping necessary (see docstring for the preprocess function).\nOutput classes are always integers in the range [0, num_classes).  Any mapping\nof these integers to semantic labels is to be handled outside of this class.\n\nBy default, DetectionModels produce bounding box detections; However, we support\na handful of auxiliary annotations associated with each bounding box, namely,\ninstance masks and keypoints.\n\"\"\"\nfrom abc import ABCMeta\nfrom abc import abstractmethod\n\nfrom object_detection.core import standard_fields as fields\n\n\nclass DetectionModel(object):\n  \"\"\"Abstract base class for detection models.\"\"\"\n  __metaclass__ = ABCMeta\n\n  def __init__(self, num_classes):\n    \"\"\"Constructor.\n\n    Args:\n      num_classes: number of classes.  Note that num_classes *does not* include\n      background categories that might be implicitly be predicted in various\n      implementations.\n    \"\"\"\n    self._num_classes = num_classes\n    self._groundtruth_lists = {}\n\n  @property\n  def num_classes(self):\n    return self._num_classes\n\n  def groundtruth_lists(self, field):\n    \"\"\"Access list of groundtruth tensors.\n\n    Args:\n      field: a string key, options are\n        fields.BoxListFields.{boxes,classes,masks,keypoints}\n\n    Returns:\n      a list of tensors holding groundtruth information (see also\n      provide_groundtruth function below), with one entry for each image in the\n      batch.\n    Raises:\n      RuntimeError: if the field has not been provided via provide_groundtruth.\n    \"\"\"\n    if field not in self._groundtruth_lists:\n      raise RuntimeError('Groundtruth tensor %s has not been provided', field)\n    return self._groundtruth_lists[field]\n\n  @abstractmethod\n  def preprocess(self, inputs):\n    \"\"\"Input preprocessing.\n\n    To be overridden by implementations.\n\n    This function is responsible for any scaling/shifting of input values that\n    is necessary prior to running the detector on an input image.\n    It is also responsible for any resizing that might be necessary as images\n    are assumed to arrive in arbitrary sizes.  While this function could\n    conceivably be part of the predict method (below), it is often convenient\n    to keep these separate --- for example, we may want to preprocess on one\n    device, place onto a queue, and let another device (e.g., the GPU) handle\n    prediction.\n\n    A few important notes about the preprocess function:\n    + We assume that this operation does not have any trainable variables nor\n    does it affect the groundtruth annotations in any way (thus data\n    augmentation operations such as random cropping should be performed\n    externally).\n    + There is no assumption that the batchsize in this function is the same as\n    the batch size in the predict function.  In fact, we recommend calling the\n    preprocess function prior to calling any batching operations (which should\n    happen outside of the model) and thus assuming that batch sizes are equal\n    to 1 in the preprocess function.\n    + There is also no explicit assumption that the output resolutions\n    must be fixed across inputs --- this is to support \"fully convolutional\"\n    settings in which input images can have different shapes/resolutions.\n\n    Args:\n      inputs: a [batch, height_in, width_in, channels] float32 tensor\n        representing a batch of images with values between 0 and 255.0.\n\n    Returns:\n      preprocessed_inputs: a [batch, height_out, width_out, channels] float32\n        tensor representing a batch of images.\n    \"\"\"\n    pass\n\n  @abstractmethod\n  def predict(self, preprocessed_inputs):\n    \"\"\"Predict prediction tensors from inputs tensor.\n\n    Outputs of this function can be passed to loss or postprocess functions.\n\n    Args:\n      preprocessed_inputs: a [batch, height, width, channels] float32 tensor\n        representing a batch of images.\n\n    Returns:\n      prediction_dict: a dictionary holding prediction tensors to be\n        passed to the Loss or Postprocess functions.\n    \"\"\"\n    pass\n\n  @abstractmethod\n  def postprocess(self, prediction_dict, **params):\n    \"\"\"Convert predicted output tensors to final detections.\n\n    Outputs adhere to the following conventions:\n    * Classes are integers in [0, num_classes); background classes are removed\n      and the first non-background class is mapped to 0.\n    * Boxes are to be interpreted as being in [y_min, x_min, y_max, x_max]\n      format and normalized relative to the image window.\n    * `num_detections` is provided for settings where detections are padded to a\n      fixed number of boxes.\n    * We do not specifically assume any kind of probabilistic interpretation\n      of the scores --- the only important thing is their relative ordering.\n      Thus implementations of the postprocess function are free to output\n      logits, probabilities, calibrated probabilities, or anything else.\n\n    Args:\n      prediction_dict: a dictionary holding prediction tensors.\n      **params: Additional keyword arguments for specific implementations of\n        DetectionModel.\n\n    Returns:\n      detections: a dictionary containing the following fields\n        detection_boxes: [batch, max_detections, 4]\n        detection_scores: [batch, max_detections]\n        detection_classes: [batch, max_detections]\n        instance_masks: [batch, max_detections, image_height, image_width]\n          (optional)\n        keypoints: [batch, max_detections, num_keypoints, 2] (optional)\n        num_detections: [batch]\n    \"\"\"\n    pass\n\n  @abstractmethod\n  def loss(self, prediction_dict):\n    \"\"\"Compute scalar loss tensors with respect to provided groundtruth.\n\n    Calling this function requires that groundtruth tensors have been\n    provided via the provide_groundtruth function.\n\n    Args:\n      prediction_dict: a dictionary holding predicted tensors\n\n    Returns:\n      a dictionary mapping strings (loss names) to scalar tensors representing\n        loss values.\n    \"\"\"\n    pass\n\n  def provide_groundtruth(self,\n                          groundtruth_boxes_list,\n                          groundtruth_classes_list,\n                          groundtruth_masks_list=None,\n                          groundtruth_keypoints_list=None):\n    \"\"\"Provide groundtruth tensors.\n\n    Args:\n      groundtruth_boxes_list: a list of 2-D tf.float32 tensors of shape\n        [num_boxes, 4] containing coordinates of the groundtruth boxes.\n          Groundtruth boxes are provided in [y_min, x_min, y_max, x_max]\n          format and assumed to be normalized and clipped\n          relative to the image window with y_min <= y_max and x_min <= x_max.\n      groundtruth_classes_list: a list of 2-D tf.float32 one-hot (or k-hot)\n        tensors of shape [num_boxes, num_classes] containing the class targets\n        with the 0th index assumed to map to the first non-background class.\n      groundtruth_masks_list: a list of 2-D tf.float32 tensors of\n        shape [max_detections, height_in, width_in] containing instance\n        masks with values in {0, 1}.  If None, no masks are provided.\n        Mask resolution `height_in`x`width_in` must agree with the resolution\n        of the input image tensor provided to the `preprocess` function.\n      groundtruth_keypoints_list: a list of 2-D tf.float32 tensors of\n        shape [batch, max_detections, num_keypoints, 2] containing keypoints.\n        Keypoints are assumed to be provided in normalized coordinates and\n        missing keypoints should be encoded as NaN.\n    \"\"\"\n    self._groundtruth_lists[fields.BoxListFields.boxes] = groundtruth_boxes_list\n    self._groundtruth_lists[\n        fields.BoxListFields.classes] = groundtruth_classes_list\n    if groundtruth_masks_list:\n      self._groundtruth_lists[\n          fields.BoxListFields.masks] = groundtruth_masks_list\n    if groundtruth_keypoints_list:\n      self._groundtruth_lists[\n          fields.BoxListFields.keypoints] = groundtruth_keypoints_list\n\n  @abstractmethod\n  def restore_fn(self, checkpoint_path, from_detection_checkpoint=True):\n    \"\"\"Return callable for loading a foreign checkpoint into tensorflow graph.\n\n    Loads variables from a different tensorflow graph (typically feature\n    extractor variables). This enables the model to initialize based on weights\n    from another task. For example, the feature extractor variables from a\n    classification model can be used to bootstrap training of an object\n    detector. When loading from an object detection model, the checkpoint model\n    should have the same parameters as this detection model with exception of\n    the num_classes parameter.\n\n    Args:\n      checkpoint_path: path to checkpoint to restore.\n      from_detection_checkpoint: whether to restore from a full detection\n        checkpoint (with compatible variable names) or to restore from a\n        classification checkpoint for initialization prior to training.\n\n    Returns:\n      a callable which takes a tf.Session as input and loads a checkpoint when\n        run.\n    \"\"\"\n    pass\n"
  },
  {
    "path": "object_detector_app/object_detection/core/post_processing.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Post-processing operations on detected boxes.\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.core import box_list\nfrom object_detection.core import box_list_ops\nfrom object_detection.core import standard_fields as fields\n\n\ndef multiclass_non_max_suppression(boxes,\n                                   scores,\n                                   score_thresh,\n                                   iou_thresh,\n                                   max_size_per_class,\n                                   max_total_size=0,\n                                   clip_window=None,\n                                   change_coordinate_frame=False,\n                                   masks=None,\n                                   additional_fields=None,\n                                   scope=None):\n  \"\"\"Multi-class version of non maximum suppression.\n\n  This op greedily selects a subset of detection bounding boxes, pruning\n  away boxes that have high IOU (intersection over union) overlap (> thresh)\n  with already selected boxes.  It operates independently for each class for\n  which scores are provided (via the scores field of the input box_list),\n  pruning boxes with score less than a provided threshold prior to\n  applying NMS.\n\n  Please note that this operation is performed on *all* classes, therefore any\n  background classes should be removed prior to calling this function.\n\n  Args:\n    boxes: A [k, q, 4] float32 tensor containing k detections. `q` can be either\n      number of classes or 1 depending on whether a separate box is predicted\n      per class.\n    scores: A [k, num_classes] float32 tensor containing the scores for each of\n      the k detections.\n    score_thresh: scalar threshold for score (low scoring boxes are removed).\n    iou_thresh: scalar threshold for IOU (new boxes that have high IOU overlap\n      with previously selected boxes are removed).\n    max_size_per_class: maximum number of retained boxes per class.\n    max_total_size: maximum number of boxes retained over all classes. By\n      default returns all boxes retained after capping boxes per class.\n    clip_window: A float32 tensor of the form [y_min, x_min, y_max, x_max]\n      representing the window to clip and normalize boxes to before performing\n      non-max suppression.\n    change_coordinate_frame: Whether to normalize coordinates after clipping\n      relative to clip_window (this can only be set to True if a clip_window\n      is provided)\n    masks: (optional) a [k, q, mask_height, mask_width] float32 tensor\n      containing box masks. `q` can be either number of classes or 1 depending\n      on whether a separate mask is predicted per class.\n    additional_fields: (optional) If not None, a dictionary that maps keys to\n      tensors whose first dimensions are all of size `k`. After non-maximum\n      suppression, all tensors corresponding to the selected boxes will be\n      added to resulting BoxList.\n    scope: name scope.\n\n  Returns:\n    a BoxList holding M boxes with a rank-1 scores field representing\n      corresponding scores for each box with scores sorted in decreasing order\n      and a rank-1 classes field representing a class label for each box.\n      If masks, keypoints, keypoint_heatmaps is not None, the boxlist will\n      contain masks, keypoints, keypoint_heatmaps corresponding to boxes.\n\n  Raises:\n    ValueError: if iou_thresh is not in [0, 1] or if input boxlist does not have\n      a valid scores field.\n  \"\"\"\n  if not 0 <= iou_thresh <= 1.0:\n    raise ValueError('iou_thresh must be between 0 and 1')\n  if scores.shape.ndims != 2:\n    raise ValueError('scores field must be of rank 2')\n  if scores.shape[1].value is None:\n    raise ValueError('scores must have statically defined second '\n                     'dimension')\n  if boxes.shape.ndims != 3:\n    raise ValueError('boxes must be of rank 3.')\n  if not (boxes.shape[1].value == scores.shape[1].value or\n          boxes.shape[1].value == 1):\n    raise ValueError('second dimension of boxes must be either 1 or equal '\n                     'to the second dimension of scores')\n  if boxes.shape[2].value != 4:\n    raise ValueError('last dimension of boxes must be of size 4.')\n  if change_coordinate_frame and clip_window is None:\n    raise ValueError('if change_coordinate_frame is True, then a clip_window'\n                     'must be specified.')\n\n  with tf.name_scope(scope, 'MultiClassNonMaxSuppression'):\n    num_boxes = tf.shape(boxes)[0]\n    num_scores = tf.shape(scores)[0]\n    num_classes = scores.get_shape()[1]\n\n    length_assert = tf.Assert(\n        tf.equal(num_boxes, num_scores),\n        ['Incorrect scores field length: actual vs expected.',\n         num_scores, num_boxes])\n\n    selected_boxes_list = []\n    per_class_boxes_list = tf.unstack(boxes, axis=1)\n    if masks is not None:\n      per_class_masks_list = tf.unstack(masks, axis=1)\n    boxes_ids = (range(num_classes) if len(per_class_boxes_list) > 1\n                 else [0] * num_classes)\n    for class_idx, boxes_idx in zip(range(num_classes), boxes_ids):\n      per_class_boxes = per_class_boxes_list[boxes_idx]\n      boxlist_and_class_scores = box_list.BoxList(per_class_boxes)\n      with tf.control_dependencies([length_assert]):\n        class_scores = tf.reshape(\n            tf.slice(scores, [0, class_idx], tf.stack([num_scores, 1])), [-1])\n      boxlist_and_class_scores.add_field(fields.BoxListFields.scores,\n                                         class_scores)\n      if masks is not None:\n        per_class_masks = per_class_masks_list[boxes_idx]\n        boxlist_and_class_scores.add_field(fields.BoxListFields.masks,\n                                           per_class_masks)\n      if additional_fields is not None:\n        for key, tensor in additional_fields.iteritems():\n          boxlist_and_class_scores.add_field(key, tensor)\n      boxlist_filtered = box_list_ops.filter_greater_than(\n          boxlist_and_class_scores, score_thresh)\n      if clip_window is not None:\n        boxlist_filtered = box_list_ops.clip_to_window(\n            boxlist_filtered, clip_window)\n        if change_coordinate_frame:\n          boxlist_filtered = box_list_ops.change_coordinate_frame(\n              boxlist_filtered, clip_window)\n      max_selection_size = tf.minimum(max_size_per_class,\n                                      boxlist_filtered.num_boxes())\n      selected_indices = tf.image.non_max_suppression(\n          boxlist_filtered.get(),\n          boxlist_filtered.get_field(fields.BoxListFields.scores),\n          max_selection_size,\n          iou_threshold=iou_thresh)\n      nms_result = box_list_ops.gather(boxlist_filtered, selected_indices)\n      nms_result.add_field(\n          fields.BoxListFields.classes, (tf.zeros_like(\n              nms_result.get_field(fields.BoxListFields.scores)) + class_idx))\n      selected_boxes_list.append(nms_result)\n    selected_boxes = box_list_ops.concatenate(selected_boxes_list)\n    sorted_boxes = box_list_ops.sort_by_field(selected_boxes,\n                                              fields.BoxListFields.scores)\n    if max_total_size:\n      max_total_size = tf.minimum(max_total_size,\n                                  sorted_boxes.num_boxes())\n      sorted_boxes = box_list_ops.gather(sorted_boxes,\n                                         tf.range(max_total_size))\n    return sorted_boxes\n\n\ndef batch_multiclass_non_max_suppression(boxes,\n                                         scores,\n                                         score_thresh,\n                                         iou_thresh,\n                                         max_size_per_class,\n                                         max_total_size=0,\n                                         clip_window=None,\n                                         change_coordinate_frame=False,\n                                         num_valid_boxes=None,\n                                         masks=None,\n                                         scope=None):\n  \"\"\"Multi-class version of non maximum suppression that operates on a batch.\n\n  This op is similar to `multiclass_non_max_suppression` but operates on a batch\n  of boxes and scores. See documentation for `multiclass_non_max_suppression`\n  for details.\n\n  Args:\n    boxes: A [batch_size, num_anchors, q, 4] float32 tensor containing\n      detections. If `q` is 1 then same boxes are used for all classes\n        otherwise, if `q` is equal to number of classes, class-specific boxes\n        are used.\n    scores: A [batch_size, num_anchors, num_classes] float32 tensor containing\n      the scores for each of the `num_anchors` detections.\n    score_thresh: scalar threshold for score (low scoring boxes are removed).\n    iou_thresh: scalar threshold for IOU (new boxes that have high IOU overlap\n      with previously selected boxes are removed).\n    max_size_per_class: maximum number of retained boxes per class.\n    max_total_size: maximum number of boxes retained over all classes. By\n      default returns all boxes retained after capping boxes per class.\n    clip_window: A float32 tensor of the form [y_min, x_min, y_max, x_max]\n      representing the window to clip boxes to before performing non-max\n      suppression.\n    change_coordinate_frame: Whether to normalize coordinates after clipping\n      relative to clip_window (this can only be set to True if a clip_window\n      is provided)\n    num_valid_boxes: (optional) a Tensor of type `int32`. A 1-D tensor of shape\n      [batch_size] representing the number of valid boxes to be considered\n        for each image in the batch.  This parameter allows for ignoring zero\n        paddings.\n    masks: (optional) a [batch_size, num_anchors, q, mask_height, mask_width]\n      float32 tensor containing box masks. `q` can be either number of classes\n      or 1 depending on whether a separate mask is predicted per class.\n    scope: tf scope name.\n\n  Returns:\n    A dictionary containing the following entries:\n    'detection_boxes': A [batch_size, max_detections, 4] float32 tensor\n      containing the non-max suppressed boxes.\n    'detection_scores': A [bath_size, max_detections] float32 tensor containing\n      the scores for the boxes.\n    'detection_classes': A [batch_size, max_detections] float32 tensor\n      containing the class for boxes.\n    'num_detections': A [batchsize] float32 tensor indicating the number of\n      valid detections per batch item. Only the top num_detections[i] entries in\n      nms_boxes[i], nms_scores[i] and nms_class[i] are valid. the rest of the\n      entries are zero paddings.\n    'detection_masks': (optional) a\n      [batch_size, max_detections, mask_height, mask_width] float32 tensor\n      containing masks for each selected box.\n\n  Raises:\n    ValueError: if iou_thresh is not in [0, 1] or if input boxlist does not have\n      a valid scores field.\n  \"\"\"\n  q = boxes.shape[2].value\n  num_classes = scores.shape[2].value\n  if q != 1 and q != num_classes:\n    raise ValueError('third dimension of boxes must be either 1 or equal '\n                     'to the third dimension of scores')\n\n  with tf.name_scope(scope, 'BatchMultiClassNonMaxSuppression'):\n    per_image_boxes_list = tf.unstack(boxes)\n    per_image_scores_list = tf.unstack(scores)\n    num_valid_boxes_list = len(per_image_boxes_list) * [None]\n    per_image_masks_list = len(per_image_boxes_list) * [None]\n    if num_valid_boxes is not None:\n      num_valid_boxes_list = tf.unstack(num_valid_boxes)\n    if masks is not None:\n      per_image_masks_list = tf.unstack(masks)\n\n    detection_boxes_list = []\n    detection_scores_list = []\n    detection_classes_list = []\n    num_detections_list = []\n    detection_masks_list = []\n    for (per_image_boxes, per_image_scores, per_image_masks, num_valid_boxes\n        ) in zip(per_image_boxes_list, per_image_scores_list,\n                 per_image_masks_list, num_valid_boxes_list):\n      if num_valid_boxes is not None:\n        per_image_boxes = tf.reshape(\n            tf.slice(per_image_boxes, 3*[0],\n                     tf.stack([num_valid_boxes, -1, -1])), [-1, q, 4])\n        per_image_scores = tf.reshape(\n            tf.slice(per_image_scores, [0, 0],\n                     tf.stack([num_valid_boxes, -1])), [-1, num_classes])\n        if masks is not None:\n          per_image_masks = tf.reshape(\n              tf.slice(per_image_masks, 4*[0],\n                       tf.stack([num_valid_boxes, -1, -1, -1])),\n              [-1, q, masks.shape[3].value, masks.shape[4].value])\n      nmsed_boxlist = multiclass_non_max_suppression(\n          per_image_boxes,\n          per_image_scores,\n          score_thresh,\n          iou_thresh,\n          max_size_per_class,\n          max_total_size,\n          masks=per_image_masks,\n          clip_window=clip_window,\n          change_coordinate_frame=change_coordinate_frame)\n      num_detections_list.append(tf.to_float(nmsed_boxlist.num_boxes()))\n      padded_boxlist = box_list_ops.pad_or_clip_box_list(nmsed_boxlist,\n                                                         max_total_size)\n      detection_boxes_list.append(padded_boxlist.get())\n      detection_scores_list.append(\n          padded_boxlist.get_field(fields.BoxListFields.scores))\n      detection_classes_list.append(\n          padded_boxlist.get_field(fields.BoxListFields.classes))\n      if masks is not None:\n        detection_masks_list.append(\n            padded_boxlist.get_field(fields.BoxListFields.masks))\n\n    nms_dict = {\n        'detection_boxes': tf.stack(detection_boxes_list),\n        'detection_scores': tf.stack(detection_scores_list),\n        'detection_classes': tf.stack(detection_classes_list),\n        'num_detections': tf.stack(num_detections_list)\n    }\n    if masks is not None:\n      nms_dict['detection_masks'] = tf.stack(detection_masks_list)\n    return nms_dict\n"
  },
  {
    "path": "object_detector_app/object_detection/core/post_processing_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for tensorflow_models.object_detection.core.post_processing.\"\"\"\nimport numpy as np\nimport tensorflow as tf\nfrom object_detection.core import post_processing\nfrom object_detection.core import standard_fields as fields\n\n\nclass MulticlassNonMaxSuppressionTest(tf.test.TestCase):\n\n  def test_with_invalid_scores_size(self):\n    boxes = tf.constant([[[0, 0, 1, 1]],\n                         [[0, 0.1, 1, 1.1]],\n                         [[0, -0.1, 1, 0.9]],\n                         [[0, 10, 1, 11]],\n                         [[0, 10.1, 1, 11.1]],\n                         [[0, 100, 1, 101]]], tf.float32)\n    scores = tf.constant([[.9], [.75], [.6], [.95], [.5]])\n    iou_thresh = .5\n    score_thresh = 0.6\n    max_output_size = 3\n    nms = post_processing.multiclass_non_max_suppression(\n        boxes, scores, score_thresh, iou_thresh, max_output_size)\n    with self.test_session() as sess:\n      with self.assertRaisesWithPredicateMatch(\n          tf.errors.InvalidArgumentError, 'Incorrect scores field length'):\n        sess.run(nms.get())\n\n  def test_multiclass_nms_select_with_shared_boxes(self):\n    boxes = tf.constant([[[0, 0, 1, 1]],\n                         [[0, 0.1, 1, 1.1]],\n                         [[0, -0.1, 1, 0.9]],\n                         [[0, 10, 1, 11]],\n                         [[0, 10.1, 1, 11.1]],\n                         [[0, 100, 1, 101]],\n                         [[0, 1000, 1, 1002]],\n                         [[0, 1000, 1, 1002.1]]], tf.float32)\n    scores = tf.constant([[.9, 0.01], [.75, 0.05],\n                          [.6, 0.01], [.95, 0],\n                          [.5, 0.01], [.3, 0.01],\n                          [.01, .85], [.01, .5]])\n    score_thresh = 0.1\n    iou_thresh = .5\n    max_output_size = 4\n\n    exp_nms_corners = [[0, 10, 1, 11],\n                       [0, 0, 1, 1],\n                       [0, 1000, 1, 1002],\n                       [0, 100, 1, 101]]\n    exp_nms_scores = [.95, .9, .85, .3]\n    exp_nms_classes = [0, 0, 1, 0]\n\n    nms = post_processing.multiclass_non_max_suppression(\n        boxes, scores, score_thresh, iou_thresh, max_output_size)\n    with self.test_session() as sess:\n      nms_corners_output, nms_scores_output, nms_classes_output = sess.run(\n          [nms.get(), nms.get_field(fields.BoxListFields.scores),\n           nms.get_field(fields.BoxListFields.classes)])\n      self.assertAllClose(nms_corners_output, exp_nms_corners)\n      self.assertAllClose(nms_scores_output, exp_nms_scores)\n      self.assertAllClose(nms_classes_output, exp_nms_classes)\n\n  def test_multiclass_nms_select_with_shared_boxes_given_keypoints(self):\n    boxes = tf.constant([[[0, 0, 1, 1]],\n                         [[0, 0.1, 1, 1.1]],\n                         [[0, -0.1, 1, 0.9]],\n                         [[0, 10, 1, 11]],\n                         [[0, 10.1, 1, 11.1]],\n                         [[0, 100, 1, 101]],\n                         [[0, 1000, 1, 1002]],\n                         [[0, 1000, 1, 1002.1]]], tf.float32)\n    scores = tf.constant([[.9, 0.01], [.75, 0.05],\n                          [.6, 0.01], [.95, 0],\n                          [.5, 0.01], [.3, 0.01],\n                          [.01, .85], [.01, .5]])\n    num_keypoints = 6\n    keypoints = tf.tile(\n        tf.reshape(tf.range(8), [8, 1, 1]),\n        [1, num_keypoints, 2])\n    score_thresh = 0.1\n    iou_thresh = .5\n    max_output_size = 4\n\n    exp_nms_corners = [[0, 10, 1, 11],\n                       [0, 0, 1, 1],\n                       [0, 1000, 1, 1002],\n                       [0, 100, 1, 101]]\n    exp_nms_scores = [.95, .9, .85, .3]\n    exp_nms_classes = [0, 0, 1, 0]\n    exp_nms_keypoints_tensor = tf.tile(\n        tf.reshape(tf.constant([3, 0, 6, 5], dtype=tf.float32), [4, 1, 1]),\n        [1, num_keypoints, 2])\n\n    nms = post_processing.multiclass_non_max_suppression(\n        boxes, scores, score_thresh, iou_thresh, max_output_size,\n        additional_fields={\n            fields.BoxListFields.keypoints: keypoints})\n\n    with self.test_session() as sess:\n      (nms_corners_output,\n       nms_scores_output,\n       nms_classes_output,\n       nms_keypoints,\n       exp_nms_keypoints) = sess.run([\n           nms.get(),\n           nms.get_field(fields.BoxListFields.scores),\n           nms.get_field(fields.BoxListFields.classes),\n           nms.get_field(fields.BoxListFields.keypoints),\n           exp_nms_keypoints_tensor\n       ])\n      self.assertAllClose(nms_corners_output, exp_nms_corners)\n      self.assertAllClose(nms_scores_output, exp_nms_scores)\n      self.assertAllClose(nms_classes_output, exp_nms_classes)\n      self.assertAllEqual(nms_keypoints, exp_nms_keypoints)\n\n  def test_multiclass_nms_with_shared_boxes_given_keypoint_heatmaps(self):\n    boxes = tf.constant([[[0, 0, 1, 1]],\n                         [[0, 0.1, 1, 1.1]],\n                         [[0, -0.1, 1, 0.9]],\n                         [[0, 10, 1, 11]],\n                         [[0, 10.1, 1, 11.1]],\n                         [[0, 100, 1, 101]],\n                         [[0, 1000, 1, 1002]],\n                         [[0, 1000, 1, 1002.1]]], tf.float32)\n\n    scores = tf.constant([[.9, 0.01], [.75, 0.05],\n                          [.6, 0.01], [.95, 0],\n                          [.5, 0.01], [.3, 0.01],\n                          [.01, .85], [.01, .5]])\n\n    num_boxes = tf.shape(boxes)[0]\n    heatmap_height = 5\n    heatmap_width = 5\n    num_keypoints = 17\n    keypoint_heatmaps = tf.ones(\n        [num_boxes, heatmap_height, heatmap_width, num_keypoints],\n        dtype=tf.float32)\n\n    score_thresh = 0.1\n    iou_thresh = .5\n    max_output_size = 4\n    exp_nms_corners = [[0, 10, 1, 11],\n                       [0, 0, 1, 1],\n                       [0, 1000, 1, 1002],\n                       [0, 100, 1, 101]]\n\n    exp_nms_scores = [.95, .9, .85, .3]\n    exp_nms_classes = [0, 0, 1, 0]\n    exp_nms_keypoint_heatmaps = np.ones(\n        (4, heatmap_height, heatmap_width, num_keypoints), dtype=np.float32)\n\n    nms = post_processing.multiclass_non_max_suppression(\n        boxes, scores, score_thresh, iou_thresh, max_output_size,\n        additional_fields={\n            fields.BoxListFields.keypoint_heatmaps: keypoint_heatmaps})\n\n    with self.test_session() as sess:\n      (nms_corners_output,\n       nms_scores_output,\n       nms_classes_output,\n       nms_keypoint_heatmaps) = sess.run(\n           [nms.get(),\n            nms.get_field(fields.BoxListFields.scores),\n            nms.get_field(fields.BoxListFields.classes),\n            nms.get_field(fields.BoxListFields.keypoint_heatmaps)])\n\n      self.assertAllClose(nms_corners_output, exp_nms_corners)\n      self.assertAllClose(nms_scores_output, exp_nms_scores)\n      self.assertAllClose(nms_classes_output, exp_nms_classes)\n      self.assertAllEqual(nms_keypoint_heatmaps, exp_nms_keypoint_heatmaps)\n\n  def test_multiclass_nms_with_additional_fields(self):\n    boxes = tf.constant([[[0, 0, 1, 1]],\n                         [[0, 0.1, 1, 1.1]],\n                         [[0, -0.1, 1, 0.9]],\n                         [[0, 10, 1, 11]],\n                         [[0, 10.1, 1, 11.1]],\n                         [[0, 100, 1, 101]],\n                         [[0, 1000, 1, 1002]],\n                         [[0, 1000, 1, 1002.1]]], tf.float32)\n\n    scores = tf.constant([[.9, 0.01], [.75, 0.05],\n                          [.6, 0.01], [.95, 0],\n                          [.5, 0.01], [.3, 0.01],\n                          [.01, .85], [.01, .5]])\n\n    coarse_boxes_key = 'coarse_boxes'\n    coarse_boxes = tf.constant([[0.1, 0.1, 1.1, 1.1],\n                                [0.1, 0.2, 1.1, 1.2],\n                                [0.1, -0.2, 1.1, 1.0],\n                                [0.1, 10.1, 1.1, 11.1],\n                                [0.1, 10.2, 1.1, 11.2],\n                                [0.1, 100.1, 1.1, 101.1],\n                                [0.1, 1000.1, 1.1, 1002.1],\n                                [0.1, 1000.1, 1.1, 1002.2]], tf.float32)\n\n    score_thresh = 0.1\n    iou_thresh = .5\n    max_output_size = 4\n\n    exp_nms_corners = np.array([[0, 10, 1, 11],\n                                [0, 0, 1, 1],\n                                [0, 1000, 1, 1002],\n                                [0, 100, 1, 101]], dtype=np.float32)\n\n    exp_nms_coarse_corners = np.array([[0.1, 10.1, 1.1, 11.1],\n                                       [0.1, 0.1, 1.1, 1.1],\n                                       [0.1, 1000.1, 1.1, 1002.1],\n                                       [0.1, 100.1, 1.1, 101.1]],\n                                      dtype=np.float32)\n\n    exp_nms_scores = [.95, .9, .85, .3]\n    exp_nms_classes = [0, 0, 1, 0]\n\n    nms = post_processing.multiclass_non_max_suppression(\n        boxes, scores, score_thresh, iou_thresh, max_output_size,\n        additional_fields={coarse_boxes_key: coarse_boxes})\n\n    with self.test_session() as sess:\n      (nms_corners_output,\n       nms_scores_output,\n       nms_classes_output,\n       nms_coarse_corners) = sess.run(\n           [nms.get(),\n            nms.get_field(fields.BoxListFields.scores),\n            nms.get_field(fields.BoxListFields.classes),\n            nms.get_field(coarse_boxes_key)])\n\n      self.assertAllClose(nms_corners_output, exp_nms_corners)\n      self.assertAllClose(nms_scores_output, exp_nms_scores)\n      self.assertAllClose(nms_classes_output, exp_nms_classes)\n      self.assertAllEqual(nms_coarse_corners, exp_nms_coarse_corners)\n\n  def test_multiclass_nms_select_with_shared_boxes_given_masks(self):\n    boxes = tf.constant([[[0, 0, 1, 1]],\n                         [[0, 0.1, 1, 1.1]],\n                         [[0, -0.1, 1, 0.9]],\n                         [[0, 10, 1, 11]],\n                         [[0, 10.1, 1, 11.1]],\n                         [[0, 100, 1, 101]],\n                         [[0, 1000, 1, 1002]],\n                         [[0, 1000, 1, 1002.1]]], tf.float32)\n    scores = tf.constant([[.9, 0.01], [.75, 0.05],\n                          [.6, 0.01], [.95, 0],\n                          [.5, 0.01], [.3, 0.01],\n                          [.01, .85], [.01, .5]])\n    num_classes = 2\n    mask_height = 3\n    mask_width = 3\n    masks = tf.tile(\n        tf.reshape(tf.range(8), [8, 1, 1, 1]),\n        [1, num_classes, mask_height, mask_width])\n    score_thresh = 0.1\n    iou_thresh = .5\n    max_output_size = 4\n\n    exp_nms_corners = [[0, 10, 1, 11],\n                       [0, 0, 1, 1],\n                       [0, 1000, 1, 1002],\n                       [0, 100, 1, 101]]\n    exp_nms_scores = [.95, .9, .85, .3]\n    exp_nms_classes = [0, 0, 1, 0]\n    exp_nms_masks_tensor = tf.tile(\n        tf.reshape(tf.constant([3, 0, 6, 5], dtype=tf.float32), [4, 1, 1]),\n        [1, mask_height, mask_width])\n\n    nms = post_processing.multiclass_non_max_suppression(boxes, scores,\n                                                         score_thresh,\n                                                         iou_thresh,\n                                                         max_output_size,\n                                                         masks=masks)\n    with self.test_session() as sess:\n      (nms_corners_output,\n       nms_scores_output,\n       nms_classes_output,\n       nms_masks,\n       exp_nms_masks) = sess.run([nms.get(),\n                                  nms.get_field(fields.BoxListFields.scores),\n                                  nms.get_field(fields.BoxListFields.classes),\n                                  nms.get_field(fields.BoxListFields.masks),\n                                  exp_nms_masks_tensor])\n      self.assertAllClose(nms_corners_output, exp_nms_corners)\n      self.assertAllClose(nms_scores_output, exp_nms_scores)\n      self.assertAllClose(nms_classes_output, exp_nms_classes)\n      self.assertAllEqual(nms_masks, exp_nms_masks)\n\n  def test_multiclass_nms_select_with_clip_window(self):\n    boxes = tf.constant([[[0, 0, 10, 10]],\n                         [[1, 1, 11, 11]]], tf.float32)\n    scores = tf.constant([[.9], [.75]])\n    clip_window = tf.constant([5, 4, 8, 7], tf.float32)\n    score_thresh = 0.0\n    iou_thresh = 0.5\n    max_output_size = 100\n\n    exp_nms_corners = [[5, 4, 8, 7]]\n    exp_nms_scores = [.9]\n    exp_nms_classes = [0]\n\n    nms = post_processing.multiclass_non_max_suppression(\n        boxes, scores, score_thresh, iou_thresh, max_output_size,\n        clip_window=clip_window)\n    with self.test_session() as sess:\n      nms_corners_output, nms_scores_output, nms_classes_output = sess.run(\n          [nms.get(), nms.get_field(fields.BoxListFields.scores),\n           nms.get_field(fields.BoxListFields.classes)])\n      self.assertAllClose(nms_corners_output, exp_nms_corners)\n      self.assertAllClose(nms_scores_output, exp_nms_scores)\n      self.assertAllClose(nms_classes_output, exp_nms_classes)\n\n  def test_multiclass_nms_select_with_clip_window_change_coordinate_frame(self):\n    boxes = tf.constant([[[0, 0, 10, 10]],\n                         [[1, 1, 11, 11]]], tf.float32)\n    scores = tf.constant([[.9], [.75]])\n    clip_window = tf.constant([5, 4, 8, 7], tf.float32)\n    score_thresh = 0.0\n    iou_thresh = 0.5\n    max_output_size = 100\n\n    exp_nms_corners = [[0, 0, 1, 1]]\n    exp_nms_scores = [.9]\n    exp_nms_classes = [0]\n\n    nms = post_processing.multiclass_non_max_suppression(\n        boxes, scores, score_thresh, iou_thresh, max_output_size,\n        clip_window=clip_window, change_coordinate_frame=True)\n    with self.test_session() as sess:\n      nms_corners_output, nms_scores_output, nms_classes_output = sess.run(\n          [nms.get(), nms.get_field(fields.BoxListFields.scores),\n           nms.get_field(fields.BoxListFields.classes)])\n      self.assertAllClose(nms_corners_output, exp_nms_corners)\n      self.assertAllClose(nms_scores_output, exp_nms_scores)\n      self.assertAllClose(nms_classes_output, exp_nms_classes)\n\n  def test_multiclass_nms_select_with_per_class_cap(self):\n    boxes = tf.constant([[[0, 0, 1, 1]],\n                         [[0, 0.1, 1, 1.1]],\n                         [[0, -0.1, 1, 0.9]],\n                         [[0, 10, 1, 11]],\n                         [[0, 10.1, 1, 11.1]],\n                         [[0, 100, 1, 101]],\n                         [[0, 1000, 1, 1002]],\n                         [[0, 1000, 1, 1002.1]]], tf.float32)\n    scores = tf.constant([[.9, 0.01], [.75, 0.05],\n                          [.6, 0.01], [.95, 0],\n                          [.5, 0.01], [.3, 0.01],\n                          [.01, .85], [.01, .5]])\n    score_thresh = 0.1\n    iou_thresh = .5\n    max_size_per_class = 2\n\n    exp_nms_corners = [[0, 10, 1, 11],\n                       [0, 0, 1, 1],\n                       [0, 1000, 1, 1002]]\n    exp_nms_scores = [.95, .9, .85]\n    exp_nms_classes = [0, 0, 1]\n\n    nms = post_processing.multiclass_non_max_suppression(\n        boxes, scores, score_thresh, iou_thresh, max_size_per_class)\n    with self.test_session() as sess:\n      nms_corners_output, nms_scores_output, nms_classes_output = sess.run(\n          [nms.get(), nms.get_field(fields.BoxListFields.scores),\n           nms.get_field(fields.BoxListFields.classes)])\n      self.assertAllClose(nms_corners_output, exp_nms_corners)\n      self.assertAllClose(nms_scores_output, exp_nms_scores)\n      self.assertAllClose(nms_classes_output, exp_nms_classes)\n\n  def test_multiclass_nms_select_with_total_cap(self):\n    boxes = tf.constant([[[0, 0, 1, 1]],\n                         [[0, 0.1, 1, 1.1]],\n                         [[0, -0.1, 1, 0.9]],\n                         [[0, 10, 1, 11]],\n                         [[0, 10.1, 1, 11.1]],\n                         [[0, 100, 1, 101]],\n                         [[0, 1000, 1, 1002]],\n                         [[0, 1000, 1, 1002.1]]], tf.float32)\n    scores = tf.constant([[.9, 0.01], [.75, 0.05],\n                          [.6, 0.01], [.95, 0],\n                          [.5, 0.01], [.3, 0.01],\n                          [.01, .85], [.01, .5]])\n    score_thresh = 0.1\n    iou_thresh = .5\n    max_size_per_class = 4\n    max_total_size = 2\n\n    exp_nms_corners = [[0, 10, 1, 11],\n                       [0, 0, 1, 1]]\n    exp_nms_scores = [.95, .9]\n    exp_nms_classes = [0, 0]\n\n    nms = post_processing.multiclass_non_max_suppression(\n        boxes, scores, score_thresh, iou_thresh, max_size_per_class,\n        max_total_size)\n    with self.test_session() as sess:\n      nms_corners_output, nms_scores_output, nms_classes_output = sess.run(\n          [nms.get(), nms.get_field(fields.BoxListFields.scores),\n           nms.get_field(fields.BoxListFields.classes)])\n      self.assertAllClose(nms_corners_output, exp_nms_corners)\n      self.assertAllClose(nms_scores_output, exp_nms_scores)\n      self.assertAllClose(nms_classes_output, exp_nms_classes)\n\n  def test_multiclass_nms_threshold_then_select_with_shared_boxes(self):\n    boxes = tf.constant([[[0, 0, 1, 1]],\n                         [[0, 0.1, 1, 1.1]],\n                         [[0, -0.1, 1, 0.9]],\n                         [[0, 10, 1, 11]],\n                         [[0, 10.1, 1, 11.1]],\n                         [[0, 100, 1, 101]],\n                         [[0, 1000, 1, 1002]],\n                         [[0, 1000, 1, 1002.1]]], tf.float32)\n    scores = tf.constant([[.9], [.75], [.6], [.95], [.5], [.3], [.01], [.01]])\n    score_thresh = 0.1\n    iou_thresh = .5\n    max_output_size = 3\n\n    exp_nms = [[0, 10, 1, 11],\n               [0, 0, 1, 1],\n               [0, 100, 1, 101]]\n    nms = post_processing.multiclass_non_max_suppression(\n        boxes, scores, score_thresh, iou_thresh, max_output_size)\n    with self.test_session() as sess:\n      nms_output = sess.run(nms.get())\n      self.assertAllClose(nms_output, exp_nms)\n\n  def test_multiclass_nms_select_with_separate_boxes(self):\n    boxes = tf.constant([[[0, 0, 1, 1], [0, 0, 4, 5]],\n                         [[0, 0.1, 1, 1.1], [0, 0.1, 2, 1.1]],\n                         [[0, -0.1, 1, 0.9], [0, -0.1, 1, 0.9]],\n                         [[0, 10, 1, 11], [0, 10, 1, 11]],\n                         [[0, 10.1, 1, 11.1], [0, 10.1, 1, 11.1]],\n                         [[0, 100, 1, 101], [0, 100, 1, 101]],\n                         [[0, 1000, 1, 1002], [0, 999, 2, 1004]],\n                         [[0, 1000, 1, 1002.1], [0, 999, 2, 1002.7]]],\n                        tf.float32)\n    scores = tf.constant([[.9, 0.01], [.75, 0.05],\n                          [.6, 0.01], [.95, 0],\n                          [.5, 0.01], [.3, 0.01],\n                          [.01, .85], [.01, .5]])\n    score_thresh = 0.1\n    iou_thresh = .5\n    max_output_size = 4\n\n    exp_nms_corners = [[0, 10, 1, 11],\n                       [0, 0, 1, 1],\n                       [0, 999, 2, 1004],\n                       [0, 100, 1, 101]]\n    exp_nms_scores = [.95, .9, .85, .3]\n    exp_nms_classes = [0, 0, 1, 0]\n\n    nms = post_processing.multiclass_non_max_suppression(\n        boxes, scores, score_thresh, iou_thresh, max_output_size)\n    with self.test_session() as sess:\n      nms_corners_output, nms_scores_output, nms_classes_output = sess.run(\n          [nms.get(), nms.get_field(fields.BoxListFields.scores),\n           nms.get_field(fields.BoxListFields.classes)])\n      self.assertAllClose(nms_corners_output, exp_nms_corners)\n      self.assertAllClose(nms_scores_output, exp_nms_scores)\n      self.assertAllClose(nms_classes_output, exp_nms_classes)\n\n  def test_batch_multiclass_nms_with_batch_size_1(self):\n    boxes = tf.constant([[[[0, 0, 1, 1], [0, 0, 4, 5]],\n                          [[0, 0.1, 1, 1.1], [0, 0.1, 2, 1.1]],\n                          [[0, -0.1, 1, 0.9], [0, -0.1, 1, 0.9]],\n                          [[0, 10, 1, 11], [0, 10, 1, 11]],\n                          [[0, 10.1, 1, 11.1], [0, 10.1, 1, 11.1]],\n                          [[0, 100, 1, 101], [0, 100, 1, 101]],\n                          [[0, 1000, 1, 1002], [0, 999, 2, 1004]],\n                          [[0, 1000, 1, 1002.1], [0, 999, 2, 1002.7]]]],\n                        tf.float32)\n    scores = tf.constant([[[.9, 0.01], [.75, 0.05],\n                           [.6, 0.01], [.95, 0],\n                           [.5, 0.01], [.3, 0.01],\n                           [.01, .85], [.01, .5]]])\n    score_thresh = 0.1\n    iou_thresh = .5\n    max_output_size = 4\n\n    exp_nms_corners = [[[0, 10, 1, 11],\n                        [0, 0, 1, 1],\n                        [0, 999, 2, 1004],\n                        [0, 100, 1, 101]]]\n    exp_nms_scores = [[.95, .9, .85, .3]]\n    exp_nms_classes = [[0, 0, 1, 0]]\n\n    nms_dict = post_processing.batch_multiclass_non_max_suppression(\n        boxes, scores, score_thresh, iou_thresh,\n        max_size_per_class=max_output_size, max_total_size=max_output_size)\n    with self.test_session() as sess:\n      nms_output = sess.run(nms_dict)\n      self.assertAllClose(nms_output['detection_boxes'], exp_nms_corners)\n      self.assertAllClose(nms_output['detection_scores'], exp_nms_scores)\n      self.assertAllClose(nms_output['detection_classes'], exp_nms_classes)\n      self.assertEqual(nms_output['num_detections'], [4])\n\n  def test_batch_multiclass_nms_with_batch_size_2(self):\n    boxes = tf.constant([[[[0, 0, 1, 1], [0, 0, 4, 5]],\n                          [[0, 0.1, 1, 1.1], [0, 0.1, 2, 1.1]],\n                          [[0, -0.1, 1, 0.9], [0, -0.1, 1, 0.9]],\n                          [[0, 10, 1, 11], [0, 10, 1, 11]]],\n                         [[[0, 10.1, 1, 11.1], [0, 10.1, 1, 11.1]],\n                          [[0, 100, 1, 101], [0, 100, 1, 101]],\n                          [[0, 1000, 1, 1002], [0, 999, 2, 1004]],\n                          [[0, 1000, 1, 1002.1], [0, 999, 2, 1002.7]]]],\n                        tf.float32)\n    scores = tf.constant([[[.9, 0.01], [.75, 0.05],\n                           [.6, 0.01], [.95, 0]],\n                          [[.5, 0.01], [.3, 0.01],\n                           [.01, .85], [.01, .5]]])\n    score_thresh = 0.1\n    iou_thresh = .5\n    max_output_size = 4\n\n    exp_nms_corners = [[[0, 10, 1, 11],\n                        [0, 0, 1, 1],\n                        [0, 0, 0, 0],\n                        [0, 0, 0, 0]],\n                       [[0, 999, 2, 1004],\n                        [0, 10.1, 1, 11.1],\n                        [0, 100, 1, 101],\n                        [0, 0, 0, 0]]]\n    exp_nms_scores = [[.95, .9, 0, 0],\n                      [.85, .5, .3, 0]]\n    exp_nms_classes = [[0, 0, 0, 0],\n                       [1, 0, 0, 0]]\n\n    nms_dict = post_processing.batch_multiclass_non_max_suppression(\n        boxes, scores, score_thresh, iou_thresh,\n        max_size_per_class=max_output_size, max_total_size=max_output_size)\n    with self.test_session() as sess:\n      nms_output = sess.run(nms_dict)\n      self.assertAllClose(nms_output['detection_boxes'], exp_nms_corners)\n      self.assertAllClose(nms_output['detection_scores'], exp_nms_scores)\n      self.assertAllClose(nms_output['detection_classes'], exp_nms_classes)\n      self.assertAllClose(nms_output['num_detections'], [2, 3])\n\n  def test_batch_multiclass_nms_with_masks(self):\n    boxes = tf.constant([[[[0, 0, 1, 1], [0, 0, 4, 5]],\n                          [[0, 0.1, 1, 1.1], [0, 0.1, 2, 1.1]],\n                          [[0, -0.1, 1, 0.9], [0, -0.1, 1, 0.9]],\n                          [[0, 10, 1, 11], [0, 10, 1, 11]]],\n                         [[[0, 10.1, 1, 11.1], [0, 10.1, 1, 11.1]],\n                          [[0, 100, 1, 101], [0, 100, 1, 101]],\n                          [[0, 1000, 1, 1002], [0, 999, 2, 1004]],\n                          [[0, 1000, 1, 1002.1], [0, 999, 2, 1002.7]]]],\n                        tf.float32)\n    scores = tf.constant([[[.9, 0.01], [.75, 0.05],\n                           [.6, 0.01], [.95, 0]],\n                          [[.5, 0.01], [.3, 0.01],\n                           [.01, .85], [.01, .5]]])\n    masks = tf.constant([[[[[0, 1], [2, 3]], [[1, 2], [3, 4]]],\n                          [[[2, 3], [4, 5]], [[3, 4], [5, 6]]],\n                          [[[4, 5], [6, 7]], [[5, 6], [7, 8]]],\n                          [[[6, 7], [8, 9]], [[7, 8], [9, 10]]]],\n                         [[[[8, 9], [10, 11]], [[9, 10], [11, 12]]],\n                          [[[10, 11], [12, 13]], [[11, 12], [13, 14]]],\n                          [[[12, 13], [14, 15]], [[13, 14], [15, 16]]],\n                          [[[14, 15], [16, 17]], [[15, 16], [17, 18]]]]],\n                        tf.float32)\n    score_thresh = 0.1\n    iou_thresh = .5\n    max_output_size = 4\n\n    exp_nms_corners = [[[0, 10, 1, 11],\n                        [0, 0, 1, 1],\n                        [0, 0, 0, 0],\n                        [0, 0, 0, 0]],\n                       [[0, 999, 2, 1004],\n                        [0, 10.1, 1, 11.1],\n                        [0, 100, 1, 101],\n                        [0, 0, 0, 0]]]\n    exp_nms_scores = [[.95, .9, 0, 0],\n                      [.85, .5, .3, 0]]\n    exp_nms_classes = [[0, 0, 0, 0],\n                       [1, 0, 0, 0]]\n    exp_nms_masks = [[[[6, 7], [8, 9]],\n                      [[0, 1], [2, 3]],\n                      [[0, 0], [0, 0]],\n                      [[0, 0], [0, 0]]],\n                     [[[13, 14], [15, 16]],\n                      [[8, 9], [10, 11]],\n                      [[10, 11], [12, 13]],\n                      [[0, 0], [0, 0]]]]\n\n    nms_dict = post_processing.batch_multiclass_non_max_suppression(\n        boxes, scores, score_thresh, iou_thresh,\n        max_size_per_class=max_output_size, max_total_size=max_output_size,\n        masks=masks)\n    with self.test_session() as sess:\n      nms_output = sess.run(nms_dict)\n      self.assertAllClose(nms_output['detection_boxes'], exp_nms_corners)\n      self.assertAllClose(nms_output['detection_scores'], exp_nms_scores)\n      self.assertAllClose(nms_output['detection_classes'], exp_nms_classes)\n      self.assertAllClose(nms_output['num_detections'], [2, 3])\n      self.assertAllClose(nms_output['detection_masks'], exp_nms_masks)\n\n  def test_batch_multiclass_nms_with_masks_and_num_valid_boxes(self):\n    boxes = tf.constant([[[[0, 0, 1, 1], [0, 0, 4, 5]],\n                          [[0, 0.1, 1, 1.1], [0, 0.1, 2, 1.1]],\n                          [[0, -0.1, 1, 0.9], [0, -0.1, 1, 0.9]],\n                          [[0, 10, 1, 11], [0, 10, 1, 11]]],\n                         [[[0, 10.1, 1, 11.1], [0, 10.1, 1, 11.1]],\n                          [[0, 100, 1, 101], [0, 100, 1, 101]],\n                          [[0, 1000, 1, 1002], [0, 999, 2, 1004]],\n                          [[0, 1000, 1, 1002.1], [0, 999, 2, 1002.7]]]],\n                        tf.float32)\n    scores = tf.constant([[[.9, 0.01], [.75, 0.05],\n                           [.6, 0.01], [.95, 0]],\n                          [[.5, 0.01], [.3, 0.01],\n                           [.01, .85], [.01, .5]]])\n    masks = tf.constant([[[[[0, 1], [2, 3]], [[1, 2], [3, 4]]],\n                          [[[2, 3], [4, 5]], [[3, 4], [5, 6]]],\n                          [[[4, 5], [6, 7]], [[5, 6], [7, 8]]],\n                          [[[6, 7], [8, 9]], [[7, 8], [9, 10]]]],\n                         [[[[8, 9], [10, 11]], [[9, 10], [11, 12]]],\n                          [[[10, 11], [12, 13]], [[11, 12], [13, 14]]],\n                          [[[12, 13], [14, 15]], [[13, 14], [15, 16]]],\n                          [[[14, 15], [16, 17]], [[15, 16], [17, 18]]]]],\n                        tf.float32)\n    num_valid_boxes = tf.constant([1, 1], tf.int32)\n    score_thresh = 0.1\n    iou_thresh = .5\n    max_output_size = 4\n\n    exp_nms_corners = [[[0, 0, 1, 1],\n                        [0, 0, 0, 0],\n                        [0, 0, 0, 0],\n                        [0, 0, 0, 0]],\n                       [[0, 10.1, 1, 11.1],\n                        [0, 0, 0, 0],\n                        [0, 0, 0, 0],\n                        [0, 0, 0, 0]]]\n    exp_nms_scores = [[.9, 0, 0, 0],\n                      [.5, 0, 0, 0]]\n    exp_nms_classes = [[0, 0, 0, 0],\n                       [0, 0, 0, 0]]\n    exp_nms_masks = [[[[0, 1], [2, 3]],\n                      [[0, 0], [0, 0]],\n                      [[0, 0], [0, 0]],\n                      [[0, 0], [0, 0]]],\n                     [[[8, 9], [10, 11]],\n                      [[0, 0], [0, 0]],\n                      [[0, 0], [0, 0]],\n                      [[0, 0], [0, 0]]]]\n\n    nms_dict = post_processing.batch_multiclass_non_max_suppression(\n        boxes, scores, score_thresh, iou_thresh,\n        max_size_per_class=max_output_size, max_total_size=max_output_size,\n        num_valid_boxes=num_valid_boxes, masks=masks)\n    with self.test_session() as sess:\n      nms_output = sess.run(nms_dict)\n      self.assertAllClose(nms_output['detection_boxes'], exp_nms_corners)\n      self.assertAllClose(nms_output['detection_scores'], exp_nms_scores)\n      self.assertAllClose(nms_output['detection_classes'], exp_nms_classes)\n      self.assertAllClose(nms_output['num_detections'], [1, 1])\n      self.assertAllClose(nms_output['detection_masks'], exp_nms_masks)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/core/prefetcher.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Provides functions to prefetch tensors to feed into models.\"\"\"\nimport tensorflow as tf\n\n\ndef prefetch(tensor_dict, capacity):\n  \"\"\"Creates a prefetch queue for tensors.\n\n  Creates a FIFO queue to asynchronously enqueue tensor_dicts and returns a\n  dequeue op that evaluates to a tensor_dict. This function is useful in\n  prefetching preprocessed tensors so that the data is readily available for\n  consumers.\n\n  Example input pipeline when you don't need batching:\n  ----------------------------------------------------\n  key, string_tensor = slim.parallel_reader.parallel_read(...)\n  tensor_dict = decoder.decode(string_tensor)\n  tensor_dict = preprocessor.preprocess(tensor_dict, ...)\n  prefetch_queue = prefetcher.prefetch(tensor_dict, capacity=20)\n  tensor_dict = prefetch_queue.dequeue()\n  outputs = Model(tensor_dict)\n  ...\n  ----------------------------------------------------\n\n  For input pipelines with batching, refer to core/batcher.py\n\n  Args:\n    tensor_dict: a dictionary of tensors to prefetch.\n    capacity: the size of the prefetch queue.\n\n  Returns:\n    a FIFO prefetcher queue\n  \"\"\"\n  names = tensor_dict.keys()\n  dtypes = [t.dtype for t in tensor_dict.values()]\n  shapes = [t.get_shape() for t in tensor_dict.values()]\n  prefetch_queue = tf.PaddingFIFOQueue(capacity, dtypes=dtypes,\n                                       shapes=shapes,\n                                       names=names,\n                                       name='prefetch_queue')\n  enqueue_op = prefetch_queue.enqueue(tensor_dict)\n  tf.train.queue_runner.add_queue_runner(tf.train.queue_runner.QueueRunner(\n      prefetch_queue, [enqueue_op]))\n  tf.summary.scalar('queue/%s/fraction_of_%d_full' % (prefetch_queue.name,\n                                                      capacity),\n                    tf.to_float(prefetch_queue.size()) * (1. / capacity))\n  return prefetch_queue\n"
  },
  {
    "path": "object_detector_app/object_detection/core/prefetcher_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.core.prefetcher.\"\"\"\nimport tensorflow as tf\n\nfrom object_detection.core import prefetcher\n\nslim = tf.contrib.slim\n\n\nclass PrefetcherTest(tf.test.TestCase):\n\n  def test_prefetch_tensors_with_fully_defined_shapes(self):\n    with self.test_session() as sess:\n      batch_size = 10\n      image_size = 32\n      num_batches = 5\n      examples = tf.Variable(tf.constant(0, dtype=tf.int64))\n      counter = examples.count_up_to(num_batches)\n      image = tf.random_normal([batch_size, image_size,\n                                image_size, 3],\n                               dtype=tf.float32,\n                               name='images')\n      label = tf.random_uniform([batch_size, 1], 0, 10,\n                                dtype=tf.int32, name='labels')\n\n      prefetch_queue = prefetcher.prefetch(tensor_dict={'counter': counter,\n                                                        'image': image,\n                                                        'label': label},\n                                           capacity=100)\n      tensor_dict = prefetch_queue.dequeue()\n\n      self.assertAllEqual(tensor_dict['image'].get_shape().as_list(),\n                          [batch_size, image_size, image_size, 3])\n      self.assertAllEqual(tensor_dict['label'].get_shape().as_list(),\n                          [batch_size, 1])\n\n      tf.initialize_all_variables().run()\n      with slim.queues.QueueRunners(sess):\n        for _ in range(num_batches):\n          results = sess.run(tensor_dict)\n          self.assertEquals(results['image'].shape,\n                            (batch_size, image_size, image_size, 3))\n          self.assertEquals(results['label'].shape, (batch_size, 1))\n        with self.assertRaises(tf.errors.OutOfRangeError):\n          sess.run(tensor_dict)\n\n  def test_prefetch_tensors_with_partially_defined_shapes(self):\n    with self.test_session() as sess:\n      batch_size = 10\n      image_size = 32\n      num_batches = 5\n      examples = tf.Variable(tf.constant(0, dtype=tf.int64))\n      counter = examples.count_up_to(num_batches)\n      image = tf.random_normal([batch_size,\n                                tf.Variable(image_size),\n                                tf.Variable(image_size), 3],\n                               dtype=tf.float32,\n                               name='image')\n      image.set_shape([batch_size, None, None, 3])\n      label = tf.random_uniform([batch_size, tf.Variable(1)], 0,\n                                10, dtype=tf.int32, name='label')\n      label.set_shape([batch_size, None])\n\n      prefetch_queue = prefetcher.prefetch(tensor_dict={'counter': counter,\n                                                        'image': image,\n                                                        'label': label},\n                                           capacity=100)\n      tensor_dict = prefetch_queue.dequeue()\n\n      self.assertAllEqual(tensor_dict['image'].get_shape().as_list(),\n                          [batch_size, None, None, 3])\n      self.assertAllEqual(tensor_dict['label'].get_shape().as_list(),\n                          [batch_size, None])\n\n      tf.initialize_all_variables().run()\n      with slim.queues.QueueRunners(sess):\n        for _ in range(num_batches):\n          results = sess.run(tensor_dict)\n          self.assertEquals(results['image'].shape,\n                            (batch_size, image_size, image_size, 3))\n          self.assertEquals(results['label'].shape, (batch_size, 1))\n        with self.assertRaises(tf.errors.OutOfRangeError):\n          sess.run(tensor_dict)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/core/preprocessor.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Preprocess images and bounding boxes for detection.\n\nWe perform two sets of operations in preprocessing stage:\n(a) operations that are applied to both training and testing data,\n(b) operations that are applied only to training data for the purpose of\n    data augmentation.\n\nA preprocessing function receives a set of inputs,\ne.g. an image and bounding boxes,\nperforms an operation on them, and returns them.\nSome examples are: randomly cropping the image, randomly mirroring the image,\n                   randomly changing the brightness, contrast, hue and\n                   randomly jittering the bounding boxes.\n\nThe preprocess function receives a tensor_dict which is a dictionary that maps\ndifferent field names to their tensors. For example,\ntensor_dict[fields.InputDataFields.image] holds the image tensor.\nThe image is a rank 4 tensor: [1, height, width, channels] with\ndtype=tf.float32. The groundtruth_boxes is a rank 2 tensor: [N, 4] where\nin each row there is a box with [ymin xmin ymax xmax].\nBoxes are in normalized coordinates meaning\ntheir coordinate values range in [0, 1]\n\nImportant Note: In tensor_dict, images is a rank 4 tensor, but preprocessing\nfunctions receive a rank 3 tensor for processing the image. Thus, inside the\npreprocess function we squeeze the image to become a rank 3 tensor and then\nwe pass it to the functions. At the end of the preprocess we expand the image\nback to rank 4.\n\"\"\"\n\nimport sys\nimport tensorflow as tf\n\nfrom tensorflow.python.ops import control_flow_ops\n\nfrom object_detection.core import box_list\nfrom object_detection.core import box_list_ops\nfrom object_detection.core import keypoint_ops\nfrom object_detection.core import standard_fields as fields\n\n\ndef _apply_with_random_selector(x, func, num_cases):\n  \"\"\"Computes func(x, sel), with sel sampled from [0...num_cases-1].\n\n  Args:\n    x: input Tensor.\n    func: Python function to apply.\n    num_cases: Python int32, number of cases to sample sel from.\n\n  Returns:\n    The result of func(x, sel), where func receives the value of the\n    selector as a python integer, but sel is sampled dynamically.\n  \"\"\"\n  rand_sel = tf.random_uniform([], maxval=num_cases, dtype=tf.int32)\n  # Pass the real x only to one of the func calls.\n  return control_flow_ops.merge([func(\n      control_flow_ops.switch(x, tf.equal(rand_sel, case))[1], case)\n                                 for case in range(num_cases)])[0]\n\n\ndef _apply_with_random_selector_tuples(x, func, num_cases):\n  \"\"\"Computes func(x, sel), with sel sampled from [0...num_cases-1].\n\n  Args:\n    x: A tuple of input tensors.\n    func: Python function to apply.\n    num_cases: Python int32, number of cases to sample sel from.\n\n  Returns:\n    The result of func(x, sel), where func receives the value of the\n    selector as a python integer, but sel is sampled dynamically.\n  \"\"\"\n  num_inputs = len(x)\n  rand_sel = tf.random_uniform([], maxval=num_cases, dtype=tf.int32)\n  # Pass the real x only to one of the func calls.\n\n  tuples = [list() for t in x]\n  for case in range(num_cases):\n    new_x = [control_flow_ops.switch(t, tf.equal(rand_sel, case))[1] for t in x]\n    output = func(tuple(new_x), case)\n    for j in range(num_inputs):\n      tuples[j].append(output[j])\n\n  for i in range(num_inputs):\n    tuples[i] = control_flow_ops.merge(tuples[i])[0]\n  return tuple(tuples)\n\n\ndef _random_integer(minval, maxval, seed):\n  \"\"\"Returns a random 0-D tensor between minval and maxval.\n\n  Args:\n    minval: minimum value of the random tensor.\n    maxval: maximum value of the random tensor.\n    seed: random seed.\n\n  Returns:\n    A random 0-D tensor between minval and maxval.\n  \"\"\"\n  return tf.random_uniform(\n      [], minval=minval, maxval=maxval, dtype=tf.int32, seed=seed)\n\n\ndef normalize_image(image, original_minval, original_maxval, target_minval,\n                    target_maxval):\n  \"\"\"Normalizes pixel values in the image.\n\n  Moves the pixel values from the current [original_minval, original_maxval]\n  range to a the [target_minval, target_maxval] range.\n\n  Args:\n    image: rank 3 float32 tensor containing 1\n           image -> [height, width, channels].\n    original_minval: current image minimum value.\n    original_maxval: current image maximum value.\n    target_minval: target image minimum value.\n    target_maxval: target image maximum value.\n\n  Returns:\n    image: image which is the same shape as input image.\n  \"\"\"\n  with tf.name_scope('NormalizeImage', values=[image]):\n    original_minval = float(original_minval)\n    original_maxval = float(original_maxval)\n    target_minval = float(target_minval)\n    target_maxval = float(target_maxval)\n    image = tf.to_float(image)\n    image = tf.subtract(image, original_minval)\n    image = tf.multiply(image, (target_maxval - target_minval) /\n                        (original_maxval - original_minval))\n    image = tf.add(image, target_minval)\n    return image\n\n\ndef flip_boxes(boxes):\n  \"\"\"Left-right flip the boxes.\n\n  Args:\n    boxes: rank 2 float32 tensor containing the bounding boxes -> [N, 4].\n           Boxes are in normalized form meaning their coordinates vary\n           between [0, 1].\n           Each row is in the form of [ymin, xmin, ymax, xmax].\n\n  Returns:\n    Flipped boxes.\n  \"\"\"\n  # Flip boxes.\n  ymin, xmin, ymax, xmax = tf.split(value=boxes, num_or_size_splits=4, axis=1)\n  flipped_xmin = tf.subtract(1.0, xmax)\n  flipped_xmax = tf.subtract(1.0, xmin)\n  flipped_boxes = tf.concat([ymin, flipped_xmin, ymax, flipped_xmax], 1)\n  return flipped_boxes\n\n\ndef retain_boxes_above_threshold(\n    boxes, labels, label_scores, masks=None, keypoints=None, threshold=0.0):\n  \"\"\"Retains boxes whose label score is above a given threshold.\n\n  If the label score for a box is missing (represented by NaN), the box is\n  retained. The boxes that don't pass the threshold will not appear in the\n  returned tensor.\n\n  Args:\n    boxes: float32 tensor of shape [num_instance, 4] representing boxes\n      location in normalized coordinates.\n    labels: rank 1 int32 tensor of shape [num_instance] containing the object\n      classes.\n    label_scores: float32 tensor of shape [num_instance] representing the\n      score for each box.\n    masks: (optional) rank 3 float32 tensor with shape\n      [num_instances, height, width] containing instance masks. The masks are of\n      the same height, width as the input `image`.\n    keypoints: (optional) rank 3 float32 tensor with shape\n      [num_instances, num_keypoints, 2]. The keypoints are in y-x normalized\n      coordinates.\n    threshold: scalar python float.\n\n  Returns:\n    retained_boxes: [num_retained_instance, 4]\n    retianed_labels: [num_retained_instance]\n    retained_label_scores: [num_retained_instance]\n\n    If masks, or keypoints are not None, the function also returns:\n\n    retained_masks: [num_retained_instance, height, width]\n    retained_keypoints: [num_retained_instance, num_keypoints, 2]\n  \"\"\"\n  with tf.name_scope('RetainBoxesAboveThreshold',\n                     values=[boxes, labels, label_scores]):\n    indices = tf.where(\n        tf.logical_or(label_scores > threshold, tf.is_nan(label_scores)))\n    indices = tf.squeeze(indices, axis=1)\n    retained_boxes = tf.gather(boxes, indices)\n    retained_labels = tf.gather(labels, indices)\n    retained_label_scores = tf.gather(label_scores, indices)\n    result = [retained_boxes, retained_labels, retained_label_scores]\n\n    if masks is not None:\n      retained_masks = tf.gather(masks, indices)\n      result.append(retained_masks)\n\n    if keypoints is not None:\n      retained_keypoints = tf.gather(keypoints, indices)\n      result.append(retained_keypoints)\n\n    return result\n\n\ndef _flip_masks(masks):\n  \"\"\"Left-right flips masks.\n\n  Args:\n    masks: rank 3 float32 tensor with shape\n      [num_instances, height, width] representing instance masks.\n\n  Returns:\n    flipped masks: rank 3 float32 tensor with shape\n      [num_instances, height, width] representing instance masks.\n  \"\"\"\n  return masks[:, :, ::-1]\n\n\ndef random_horizontal_flip(\n    image,\n    boxes=None,\n    masks=None,\n    keypoints=None,\n    keypoint_flip_permutation=None,\n    seed=None):\n  \"\"\"Randomly decides whether to mirror the image and detections or not.\n\n  The probability of flipping the image is 50%.\n\n  Args:\n    image: rank 3 float32 tensor with shape [height, width, channels].\n    boxes: (optional) rank 2 float32 tensor with shape [N, 4]\n           containing the bounding boxes.\n           Boxes are in normalized form meaning their coordinates vary\n           between [0, 1].\n           Each row is in the form of [ymin, xmin, ymax, xmax].\n    masks: (optional) rank 3 float32 tensor with shape\n           [num_instances, height, width] containing instance masks. The masks\n           are of the same height, width as the input `image`.\n    keypoints: (optional) rank 3 float32 tensor with shape\n               [num_instances, num_keypoints, 2]. The keypoints are in y-x\n               normalized coordinates.\n    keypoint_flip_permutation: rank 1 int32 tensor containing keypoint flip\n                               permutation.\n    seed: random seed\n\n  Returns:\n    image: image which is the same shape as input image.\n\n    If boxes, masks, keypoints, and keypoint_flip_permutation is not None,\n    the function also returns the following tensors.\n\n    boxes: rank 2 float32 tensor containing the bounding boxes -> [N, 4].\n           Boxes are in normalized form meaning their coordinates vary\n           between [0, 1].\n    masks: rank 3 float32 tensor with shape [num_instances, height, width]\n           containing instance masks.\n    keypoints: rank 3 float32 tensor with shape\n               [num_instances, num_keypoints, 2]\n\n  Raises:\n    ValueError: if keypoints are provided but keypoint_flip_permutation is not.\n  \"\"\"\n  def _flip_image(image):\n    # flip image\n    image_flipped = tf.image.flip_left_right(image)\n    return image_flipped\n\n  if keypoints is not None and keypoint_flip_permutation is None:\n    raise ValueError(\n        'keypoints are provided but keypoints_flip_permutation is not provided')\n\n  with tf.name_scope('RandomHorizontalFlip', values=[image, boxes]):\n    result = []\n    # random variable defining whether to do flip or not\n    do_a_flip_random = tf.random_uniform([], seed=seed)\n    # flip only if there are bounding boxes in image!\n    do_a_flip_random = tf.logical_and(\n        tf.greater(tf.size(boxes), 0), tf.greater(do_a_flip_random, 0.5))\n\n    # flip image\n    image = tf.cond(do_a_flip_random, lambda: _flip_image(image), lambda: image)\n    result.append(image)\n\n    # flip boxes\n    if boxes is not None:\n      boxes = tf.cond(\n          do_a_flip_random, lambda: flip_boxes(boxes), lambda: boxes)\n      result.append(boxes)\n\n    # flip masks\n    if masks is not None:\n      masks = tf.cond(\n          do_a_flip_random, lambda: _flip_masks(masks), lambda: masks)\n      result.append(masks)\n\n    # flip keypoints\n    if keypoints is not None and keypoint_flip_permutation is not None:\n      permutation = keypoint_flip_permutation\n      keypoints = tf.cond(\n          do_a_flip_random,\n          lambda: keypoint_ops.flip_horizontal(keypoints, 0.5, permutation),\n          lambda: keypoints)\n      result.append(keypoints)\n\n    return tuple(result)\n\n\ndef random_pixel_value_scale(image, minval=0.9, maxval=1.1, seed=None):\n  \"\"\"Scales each value in the pixels of the image.\n\n     This function scales each pixel independent of the other ones.\n     For each value in image tensor, draws a random number between\n     minval and maxval and multiples the values with them.\n\n  Args:\n    image: rank 3 float32 tensor contains 1 image -> [height, width, channels]\n           with pixel values varying between [0, 1].\n    minval: lower ratio of scaling pixel values.\n    maxval: upper ratio of scaling pixel values.\n    seed: random seed.\n\n  Returns:\n    image: image which is the same shape as input image.\n    boxes: boxes which is the same shape as input boxes.\n  \"\"\"\n  with tf.name_scope('RandomPixelValueScale', values=[image]):\n    color_coef = tf.random_uniform(\n        tf.shape(image),\n        minval=minval,\n        maxval=maxval,\n        dtype=tf.float32,\n        seed=seed)\n    image = tf.multiply(image, color_coef)\n    image = tf.clip_by_value(image, 0.0, 1.0)\n\n  return image\n\n\ndef random_image_scale(image,\n                       masks=None,\n                       min_scale_ratio=0.5,\n                       max_scale_ratio=2.0,\n                       seed=None):\n  \"\"\"Scales the image size.\n\n  Args:\n    image: rank 3 float32 tensor contains 1 image -> [height, width, channels].\n    masks: (optional) rank 3 float32 tensor containing masks with\n      size [height, width, num_masks]. The value is set to None if there are no\n      masks.\n    min_scale_ratio: minimum scaling ratio.\n    max_scale_ratio: maximum scaling ratio.\n    seed: random seed.\n\n  Returns:\n    image: image which is the same rank as input image.\n    masks: If masks is not none, resized masks which are the same rank as input\n      masks will be returned.\n  \"\"\"\n  with tf.name_scope('RandomImageScale', values=[image]):\n    result = []\n    image_shape = tf.shape(image)\n    image_height = image_shape[0]\n    image_width = image_shape[1]\n    size_coef = tf.random_uniform([],\n                                  minval=min_scale_ratio,\n                                  maxval=max_scale_ratio,\n                                  dtype=tf.float32, seed=seed)\n    image_newysize = tf.to_int32(\n        tf.multiply(tf.to_float(image_height), size_coef))\n    image_newxsize = tf.to_int32(\n        tf.multiply(tf.to_float(image_width), size_coef))\n    image = tf.image.resize_images(\n        image, [image_newysize, image_newxsize], align_corners=True)\n    result.append(image)\n    if masks:\n      masks = tf.image.resize_nearest_neighbor(\n          masks, [image_newysize, image_newxsize], align_corners=True)\n      result.append(masks)\n    return tuple(result)\n\n\ndef random_rgb_to_gray(image, probability=0.1, seed=None):\n  \"\"\"Changes the image from RGB to Grayscale with the given probability.\n\n  Args:\n    image: rank 3 float32 tensor contains 1 image -> [height, width, channels]\n           with pixel values varying between [0, 1].\n    probability: the probability of returning a grayscale image.\n            The probability should be a number between [0, 1].\n    seed: random seed.\n\n  Returns:\n    image: image which is the same shape as input image.\n  \"\"\"\n  def _image_to_gray(image):\n    image_gray1 = tf.image.rgb_to_grayscale(image)\n    image_gray3 = tf.image.grayscale_to_rgb(image_gray1)\n    return image_gray3\n\n  with tf.name_scope('RandomRGBtoGray', values=[image]):\n    # random variable defining whether to do flip or not\n    do_gray_random = tf.random_uniform([], seed=seed)\n\n    image = tf.cond(\n        tf.greater(do_gray_random, probability), lambda: image,\n        lambda: _image_to_gray(image))\n\n  return image\n\n\ndef random_adjust_brightness(image, max_delta=0.2):\n  \"\"\"Randomly adjusts brightness.\n\n  Makes sure the output image is still between 0 and 1.\n\n  Args:\n    image: rank 3 float32 tensor contains 1 image -> [height, width, channels]\n           with pixel values varying between [0, 1].\n    max_delta: how much to change the brightness. A value between [0, 1).\n\n  Returns:\n    image: image which is the same shape as input image.\n    boxes: boxes which is the same shape as input boxes.\n  \"\"\"\n  with tf.name_scope('RandomAdjustBrightness', values=[image]):\n    image = tf.image.random_brightness(image, max_delta)\n    image = tf.clip_by_value(image, clip_value_min=0.0, clip_value_max=1.0)\n    return image\n\n\ndef random_adjust_contrast(image, min_delta=0.8, max_delta=1.25):\n  \"\"\"Randomly adjusts contrast.\n\n  Makes sure the output image is still between 0 and 1.\n\n  Args:\n    image: rank 3 float32 tensor contains 1 image -> [height, width, channels]\n           with pixel values varying between [0, 1].\n    min_delta: see max_delta.\n    max_delta: how much to change the contrast. Contrast will change with a\n               value between min_delta and max_delta. This value will be\n               multiplied to the current contrast of the image.\n\n  Returns:\n    image: image which is the same shape as input image.\n  \"\"\"\n  with tf.name_scope('RandomAdjustContrast', values=[image]):\n    image = tf.image.random_contrast(image, min_delta, max_delta)\n    image = tf.clip_by_value(image, clip_value_min=0.0, clip_value_max=1.0)\n    return image\n\n\ndef random_adjust_hue(image, max_delta=0.02):\n  \"\"\"Randomly adjusts hue.\n\n  Makes sure the output image is still between 0 and 1.\n\n  Args:\n    image: rank 3 float32 tensor contains 1 image -> [height, width, channels]\n           with pixel values varying between [0, 1].\n    max_delta: change hue randomly with a value between 0 and max_delta.\n\n  Returns:\n    image: image which is the same shape as input image.\n  \"\"\"\n  with tf.name_scope('RandomAdjustHue', values=[image]):\n    image = tf.image.random_hue(image, max_delta)\n    image = tf.clip_by_value(image, clip_value_min=0.0, clip_value_max=1.0)\n    return image\n\n\ndef random_adjust_saturation(image, min_delta=0.8, max_delta=1.25):\n  \"\"\"Randomly adjusts saturation.\n\n  Makes sure the output image is still between 0 and 1.\n\n  Args:\n    image: rank 3 float32 tensor contains 1 image -> [height, width, channels]\n           with pixel values varying between [0, 1].\n    min_delta: see max_delta.\n    max_delta: how much to change the saturation. Saturation will change with a\n               value between min_delta and max_delta. This value will be\n               multiplied to the current saturation of the image.\n\n  Returns:\n    image: image which is the same shape as input image.\n  \"\"\"\n  with tf.name_scope('RandomAdjustSaturation', values=[image]):\n    image = tf.image.random_saturation(image, min_delta, max_delta)\n    image = tf.clip_by_value(image, clip_value_min=0.0, clip_value_max=1.0)\n    return image\n\n\ndef random_distort_color(image, color_ordering=0):\n  \"\"\"Randomly distorts color.\n\n  Randomly distorts color using a combination of brightness, hue, contrast\n  and saturation changes. Makes sure the output image is still between 0 and 1.\n\n  Args:\n    image: rank 3 float32 tensor contains 1 image -> [height, width, channels]\n           with pixel values varying between [0, 1].\n    color_ordering: Python int, a type of distortion (valid values: 0, 1).\n\n  Returns:\n    image: image which is the same shape as input image.\n\n  Raises:\n    ValueError: if color_ordering is not in {0, 1}.\n  \"\"\"\n  with tf.name_scope('RandomDistortColor', values=[image]):\n    if color_ordering == 0:\n      image = tf.image.random_brightness(image, max_delta=32. / 255.)\n      image = tf.image.random_saturation(image, lower=0.5, upper=1.5)\n      image = tf.image.random_hue(image, max_delta=0.2)\n      image = tf.image.random_contrast(image, lower=0.5, upper=1.5)\n    elif color_ordering == 1:\n      image = tf.image.random_brightness(image, max_delta=32. / 255.)\n      image = tf.image.random_contrast(image, lower=0.5, upper=1.5)\n      image = tf.image.random_saturation(image, lower=0.5, upper=1.5)\n      image = tf.image.random_hue(image, max_delta=0.2)\n    else:\n      raise ValueError('color_ordering must be in {0, 1}')\n\n    # The random_* ops do not necessarily clamp.\n    image = tf.clip_by_value(image, 0.0, 1.0)\n    return image\n\n\ndef random_jitter_boxes(boxes, ratio=0.05, seed=None):\n  \"\"\"Randomly jitter boxes in image.\n\n  Args:\n    boxes: rank 2 float32 tensor containing the bounding boxes -> [N, 4].\n           Boxes are in normalized form meaning their coordinates vary\n           between [0, 1].\n           Each row is in the form of [ymin, xmin, ymax, xmax].\n    ratio: The ratio of the box width and height that the corners can jitter.\n           For example if the width is 100 pixels and ratio is 0.05,\n           the corners can jitter up to 5 pixels in the x direction.\n    seed: random seed.\n\n  Returns:\n    boxes: boxes which is the same shape as input boxes.\n  \"\"\"\n  def random_jitter_box(box, ratio, seed):\n    \"\"\"Randomly jitter box.\n\n    Args:\n      box: bounding box [1, 1, 4].\n      ratio: max ratio between jittered box and original box,\n      a number between [0, 0.5].\n      seed: random seed.\n\n    Returns:\n      jittered_box: jittered box.\n    \"\"\"\n    rand_numbers = tf.random_uniform(\n        [1, 1, 4], minval=-ratio, maxval=ratio, dtype=tf.float32, seed=seed)\n    box_width = tf.subtract(box[0, 0, 3], box[0, 0, 1])\n    box_height = tf.subtract(box[0, 0, 2], box[0, 0, 0])\n    hw_coefs = tf.stack([box_height, box_width, box_height, box_width])\n    hw_rand_coefs = tf.multiply(hw_coefs, rand_numbers)\n    jittered_box = tf.add(box, hw_rand_coefs)\n    jittered_box = tf.clip_by_value(jittered_box, 0.0, 1.0)\n    return jittered_box\n\n  with tf.name_scope('RandomJitterBoxes', values=[boxes]):\n    # boxes are [N, 4]. Lets first make them [N, 1, 1, 4]\n    boxes_shape = tf.shape(boxes)\n    boxes = tf.expand_dims(boxes, 1)\n    boxes = tf.expand_dims(boxes, 2)\n\n    distorted_boxes = tf.map_fn(\n        lambda x: random_jitter_box(x, ratio, seed), boxes, dtype=tf.float32)\n\n    distorted_boxes = tf.reshape(distorted_boxes, boxes_shape)\n\n    return distorted_boxes\n\n\ndef _strict_random_crop_image(image,\n                              boxes,\n                              labels,\n                              masks=None,\n                              keypoints=None,\n                              min_object_covered=1.0,\n                              aspect_ratio_range=(0.75, 1.33),\n                              area_range=(0.1, 1.0),\n                              overlap_thresh=0.3):\n  \"\"\"Performs random crop.\n\n  Note: boxes will be clipped to the crop. Keypoint coordinates that are\n  outside the crop will be set to NaN, which is consistent with the original\n  keypoint encoding for non-existing keypoints. This function always crops\n  the image and is supposed to be used by `random_crop_image` function which\n  sometimes returns image unchanged.\n\n  Args:\n    image: rank 3 float32 tensor containing 1 image -> [height, width, channels]\n           with pixel values varying between [0, 1].\n    boxes: rank 2 float32 tensor containing the bounding boxes with shape\n           [num_instances, 4].\n           Boxes are in normalized form meaning their coordinates vary\n           between [0, 1].\n           Each row is in the form of [ymin, xmin, ymax, xmax].\n    labels: rank 1 int32 tensor containing the object classes.\n    masks: (optional) rank 3 float32 tensor with shape\n           [num_instances, height, width] containing instance masks. The masks\n           are of the same height, width as the input `image`.\n    keypoints: (optional) rank 3 float32 tensor with shape\n               [num_instances, num_keypoints, 2]. The keypoints are in y-x\n               normalized coordinates.\n    min_object_covered: the cropped image must cover at least this fraction of\n                        at least one of the input bounding boxes.\n    aspect_ratio_range: allowed range for aspect ratio of cropped image.\n    area_range: allowed range for area ratio between cropped image and the\n                original image.\n    overlap_thresh: minimum overlap thresh with new cropped\n                    image to keep the box.\n\n  Returns:\n    image: image which is the same rank as input image.\n    boxes: boxes which is the same rank as input boxes.\n           Boxes are in normalized form.\n    labels: new labels.\n\n    If masks, or keypoints is not None, the function also returns:\n\n    masks: rank 3 float32 tensor with shape [num_instances, height, width]\n           containing instance masks.\n    keypoints: rank 3 float32 tensor with shape\n               [num_instances, num_keypoints, 2]\n  \"\"\"\n  with tf.name_scope('RandomCropImage', values=[image, boxes]):\n    image_shape = tf.shape(image)\n\n    # boxes are [N, 4]. Lets first make them [N, 1, 4].\n    boxes_expanded = tf.expand_dims(\n        tf.clip_by_value(\n            boxes, clip_value_min=0.0, clip_value_max=1.0), 1)\n\n    sample_distorted_bounding_box = tf.image.sample_distorted_bounding_box(\n        image_shape,\n        bounding_boxes=boxes_expanded,\n        min_object_covered=min_object_covered,\n        aspect_ratio_range=aspect_ratio_range,\n        area_range=area_range,\n        max_attempts=100,\n        use_image_if_no_bounding_boxes=True)\n\n    im_box_begin, im_box_size, im_box = sample_distorted_bounding_box\n\n    new_image = tf.slice(image, im_box_begin, im_box_size)\n    new_image.set_shape([None, None, image.get_shape()[2]])\n\n    # [1, 4]\n    im_box_rank2 = tf.squeeze(im_box, squeeze_dims=[0])\n    # [4]\n    im_box_rank1 = tf.squeeze(im_box)\n\n    boxlist = box_list.BoxList(boxes)\n    boxlist.add_field('labels', labels)\n\n    im_boxlist = box_list.BoxList(im_box_rank2)\n\n    # remove boxes that are outside cropped image\n    boxlist, inside_window_ids = box_list_ops.prune_completely_outside_window(\n        boxlist, im_box_rank1)\n\n    # remove boxes that are outside image\n    overlapping_boxlist, keep_ids = box_list_ops.prune_non_overlapping_boxes(\n        boxlist, im_boxlist, overlap_thresh)\n\n    # change the coordinate of the remaining boxes\n    new_labels = overlapping_boxlist.get_field('labels')\n    new_boxlist = box_list_ops.change_coordinate_frame(overlapping_boxlist,\n                                                       im_box_rank1)\n    new_boxes = new_boxlist.get()\n    new_boxes = tf.clip_by_value(\n        new_boxes, clip_value_min=0.0, clip_value_max=1.0)\n\n    result = [new_image, new_boxes, new_labels]\n\n    if masks is not None:\n      masks_of_boxes_inside_window = tf.gather(masks, inside_window_ids)\n      masks_of_boxes_completely_inside_window = tf.gather(\n          masks_of_boxes_inside_window, keep_ids)\n      masks_box_begin = [im_box_begin[2], im_box_begin[0], im_box_begin[1]]\n      masks_box_size = [im_box_size[2], im_box_size[0], im_box_size[1]]\n      new_masks = tf.slice(\n          masks_of_boxes_completely_inside_window,\n          masks_box_begin, masks_box_size)\n      result.append(new_masks)\n\n    if keypoints is not None:\n      keypoints_of_boxes_inside_window = tf.gather(keypoints, inside_window_ids)\n      keypoints_of_boxes_completely_inside_window = tf.gather(\n          keypoints_of_boxes_inside_window, keep_ids)\n      new_keypoints = keypoint_ops.change_coordinate_frame(\n          keypoints_of_boxes_completely_inside_window, im_box_rank1)\n      new_keypoints = keypoint_ops.prune_outside_window(new_keypoints,\n                                                        [0.0, 0.0, 1.0, 1.0])\n      result.append(new_keypoints)\n\n    return tuple(result)\n\n\ndef random_crop_image(image,\n                      boxes,\n                      labels,\n                      masks=None,\n                      keypoints=None,\n                      min_object_covered=1.0,\n                      aspect_ratio_range=(0.75, 1.33),\n                      area_range=(0.1, 1.0),\n                      overlap_thresh=0.3,\n                      random_coef=0.0,\n                      seed=None):\n  \"\"\"Randomly crops the image.\n\n  Given the input image and its bounding boxes, this op randomly\n  crops a subimage.  Given a user-provided set of input constraints,\n  the crop window is resampled until it satisfies these constraints.\n  If within 100 trials it is unable to find a valid crop, the original\n  image is returned. See the Args section for a description of the input\n  constraints. Both input boxes and returned Boxes are in normalized\n  form (e.g., lie in the unit square [0, 1]).\n  This function will return the original image with probability random_coef.\n\n  Note: boxes will be clipped to the crop. Keypoint coordinates that are\n  outside the crop will be set to NaN, which is consistent with the original\n  keypoint encoding for non-existing keypoints.\n\n  Args:\n    image: rank 3 float32 tensor contains 1 image -> [height, width, channels]\n           with pixel values varying between [0, 1].\n    boxes: rank 2 float32 tensor containing the bounding boxes with shape\n           [num_instances, 4].\n           Boxes are in normalized form meaning their coordinates vary\n           between [0, 1].\n           Each row is in the form of [ymin, xmin, ymax, xmax].\n    labels: rank 1 int32 tensor containing the object classes.\n    masks: (optional) rank 3 float32 tensor with shape\n           [num_instances, height, width] containing instance masks. The masks\n           are of the same height, width as the input `image`.\n    keypoints: (optional) rank 3 float32 tensor with shape\n               [num_instances, num_keypoints, 2]. The keypoints are in y-x\n               normalized coordinates.\n    min_object_covered: the cropped image must cover at least this fraction of\n                        at least one of the input bounding boxes.\n    aspect_ratio_range: allowed range for aspect ratio of cropped image.\n    area_range: allowed range for area ratio between cropped image and the\n                original image.\n    overlap_thresh: minimum overlap thresh with new cropped\n                    image to keep the box.\n    random_coef: a random coefficient that defines the chance of getting the\n                 original image. If random_coef is 0, we will always get the\n                 cropped image, and if it is 1.0, we will always get the\n                 original image.\n    seed: random seed.\n\n  Returns:\n    image: Image shape will be [new_height, new_width, channels].\n    boxes: boxes which is the same rank as input boxes. Boxes are in normalized\n           form.\n    labels: new labels.\n\n    If masks, or keypoints are not None, the function also returns:\n\n    masks: rank 3 float32 tensor with shape [num_instances, height, width]\n           containing instance masks.\n    keypoints: rank 3 float32 tensor with shape\n               [num_instances, num_keypoints, 2]\n  \"\"\"\n\n  def strict_random_crop_image_fn():\n    return _strict_random_crop_image(\n        image,\n        boxes,\n        labels,\n        masks=masks,\n        keypoints=keypoints,\n        min_object_covered=min_object_covered,\n        aspect_ratio_range=aspect_ratio_range,\n        area_range=area_range,\n        overlap_thresh=overlap_thresh)\n\n  # avoids tf.cond to make faster RCNN training on borg. See b/140057645.\n  if random_coef < sys.float_info.min:\n    result = strict_random_crop_image_fn()\n  else:\n    do_a_crop_random = tf.random_uniform([], seed=seed)\n    do_a_crop_random = tf.greater(do_a_crop_random, random_coef)\n\n    outputs = [image, boxes, labels]\n    if masks is not None:\n      outputs.append(masks)\n    if keypoints is not None:\n      outputs.append(keypoints)\n\n    result = tf.cond(do_a_crop_random,\n                     strict_random_crop_image_fn,\n                     lambda: tuple(outputs))\n  return result\n\n\ndef random_pad_image(image,\n                     boxes,\n                     min_image_size=None,\n                     max_image_size=None,\n                     pad_color=None,\n                     seed=None):\n  \"\"\"Randomly pads the image.\n\n  This function randomly pads the image with zeros. The final size of the\n  padded image will be between min_image_size and max_image_size.\n  if min_image_size is smaller than the input image size, min_image_size will\n  be set to the input image size. The same for max_image_size. The input image\n  will be located at a uniformly random location inside the padded image.\n  The relative location of the boxes to the original image will remain the same.\n\n  Args:\n    image: rank 3 float32 tensor containing 1 image -> [height, width, channels]\n           with pixel values varying between [0, 1].\n    boxes: rank 2 float32 tensor containing the bounding boxes -> [N, 4].\n           Boxes are in normalized form meaning their coordinates vary\n           between [0, 1].\n           Each row is in the form of [ymin, xmin, ymax, xmax].\n    min_image_size: a tensor of size [min_height, min_width], type tf.int32.\n                    If passed as None, will be set to image size\n                    [height, width].\n    max_image_size: a tensor of size [max_height, max_width], type tf.int32.\n                    If passed as None, will be set to twice the\n                    image [height * 2, width * 2].\n    pad_color: padding color. A rank 1 tensor of [3] with dtype=tf.float32.\n               if set as None, it will be set to average color of the input\n               image.\n\n    seed: random seed.\n\n  Returns:\n    image: Image shape will be [new_height, new_width, channels].\n    boxes: boxes which is the same rank as input boxes. Boxes are in normalized\n           form.\n  \"\"\"\n  if pad_color is None:\n    pad_color = tf.reduce_mean(image, reduction_indices=[0, 1])\n\n  image_shape = tf.shape(image)\n  image_height = image_shape[0]\n  image_width = image_shape[1]\n\n  if max_image_size is None:\n    max_image_size = tf.stack([image_height * 2, image_width * 2])\n  max_image_size = tf.maximum(max_image_size,\n                              tf.stack([image_height, image_width]))\n\n  if min_image_size is None:\n    min_image_size = tf.stack([image_height, image_width])\n  min_image_size = tf.maximum(min_image_size,\n                              tf.stack([image_height, image_width]))\n\n  target_height = tf.cond(\n      max_image_size[0] > min_image_size[0],\n      lambda: _random_integer(min_image_size[0], max_image_size[0], seed),\n      lambda: max_image_size[0])\n\n  target_width = tf.cond(\n      max_image_size[1] > min_image_size[1],\n      lambda: _random_integer(min_image_size[1], max_image_size[1], seed),\n      lambda: max_image_size[1])\n\n  offset_height = tf.cond(\n      target_height > image_height,\n      lambda: _random_integer(0, target_height - image_height, seed),\n      lambda: tf.constant(0, dtype=tf.int32))\n\n  offset_width = tf.cond(\n      target_width > image_width,\n      lambda: _random_integer(0, target_width - image_width, seed),\n      lambda: tf.constant(0, dtype=tf.int32))\n\n  new_image = tf.image.pad_to_bounding_box(\n      image, offset_height=offset_height, offset_width=offset_width,\n      target_height=target_height, target_width=target_width)\n\n  # Setting color of the padded pixels\n  image_ones = tf.ones_like(image)\n  image_ones_padded = tf.image.pad_to_bounding_box(\n      image_ones, offset_height=offset_height, offset_width=offset_width,\n      target_height=target_height, target_width=target_width)\n  image_color_paded = (1.0 - image_ones_padded) * pad_color\n  new_image += image_color_paded\n\n  # setting boxes\n  new_window = tf.to_float(\n      tf.stack([\n          -offset_height, -offset_width, target_height - offset_height,\n          target_width - offset_width\n      ]))\n  new_window /= tf.to_float(\n      tf.stack([image_height, image_width, image_height, image_width]))\n  boxlist = box_list.BoxList(boxes)\n  new_boxlist = box_list_ops.change_coordinate_frame(boxlist, new_window)\n  new_boxes = new_boxlist.get()\n\n  return new_image, new_boxes\n\n\ndef random_crop_pad_image(image,\n                          boxes,\n                          labels,\n                          min_object_covered=1.0,\n                          aspect_ratio_range=(0.75, 1.33),\n                          area_range=(0.1, 1.0),\n                          overlap_thresh=0.3,\n                          random_coef=0.0,\n                          min_padded_size_ratio=None,\n                          max_padded_size_ratio=None,\n                          pad_color=None,\n                          seed=None):\n  \"\"\"Randomly crops and pads the image.\n\n  Given an input image and its bounding boxes, this op first randomly crops\n  the image and then randomly pads the image with background values. Parameters\n  min_padded_size_ratio and max_padded_size_ratio, determine the range of the\n  final output image size.  Specifically, the final image size will have a size\n  in the range of min_padded_size_ratio * tf.shape(image) and\n  max_padded_size_ratio * tf.shape(image). Note that these ratios are with\n  respect to the size of the original image, so we can't capture the same\n  effect easily by independently applying RandomCropImage\n  followed by RandomPadImage.\n\n  Args:\n    image: rank 3 float32 tensor containing 1 image -> [height, width, channels]\n           with pixel values varying between [0, 1].\n    boxes: rank 2 float32 tensor containing the bounding boxes -> [N, 4].\n           Boxes are in normalized form meaning their coordinates vary\n           between [0, 1].\n           Each row is in the form of [ymin, xmin, ymax, xmax].\n    labels: rank 1 int32 tensor containing the object classes.\n    min_object_covered: the cropped image must cover at least this fraction of\n                        at least one of the input bounding boxes.\n    aspect_ratio_range: allowed range for aspect ratio of cropped image.\n    area_range: allowed range for area ratio between cropped image and the\n                original image.\n    overlap_thresh: minimum overlap thresh with new cropped\n                    image to keep the box.\n    random_coef: a random coefficient that defines the chance of getting the\n                 original image. If random_coef is 0, we will always get the\n                 cropped image, and if it is 1.0, we will always get the\n                 original image.\n    min_padded_size_ratio: min ratio of padded image height and width to the\n                           input image's height and width. If None, it will\n                           be set to [0.0, 0.0].\n    max_padded_size_ratio: max ratio of padded image height and width to the\n                           input image's height and width. If None, it will\n                           be set to [2.0, 2.0].\n    pad_color: padding color. A rank 1 tensor of [3] with dtype=tf.float32.\n               if set as None, it will be set to average color of the randomly\n               cropped image.\n    seed: random seed.\n\n  Returns:\n    padded_image: padded image.\n    padded_boxes: boxes which is the same rank as input boxes. Boxes are in\n                  normalized form.\n    cropped_labels: cropped labels.\n  \"\"\"\n  image_size = tf.shape(image)\n  image_height = image_size[0]\n  image_width = image_size[1]\n  if min_padded_size_ratio is None:\n    min_padded_size_ratio = tf.constant([0.0, 0.0], tf.float32)\n  if max_padded_size_ratio is None:\n    max_padded_size_ratio = tf.constant([2.0, 2.0], tf.float32)\n  cropped_image, cropped_boxes, cropped_labels = random_crop_image(\n      image=image,\n      boxes=boxes,\n      labels=labels,\n      min_object_covered=min_object_covered,\n      aspect_ratio_range=aspect_ratio_range,\n      area_range=area_range,\n      overlap_thresh=overlap_thresh,\n      random_coef=random_coef,\n      seed=seed)\n\n  min_image_size = tf.to_int32(\n      tf.to_float(tf.stack([image_height, image_width])) *\n      min_padded_size_ratio)\n  max_image_size = tf.to_int32(\n      tf.to_float(tf.stack([image_height, image_width])) *\n      max_padded_size_ratio)\n\n  padded_image, padded_boxes = random_pad_image(\n      cropped_image,\n      cropped_boxes,\n      min_image_size=min_image_size,\n      max_image_size=max_image_size,\n      pad_color=pad_color,\n      seed=seed)\n\n  return padded_image, padded_boxes, cropped_labels\n\n\ndef random_crop_to_aspect_ratio(image,\n                                boxes,\n                                labels,\n                                masks=None,\n                                keypoints=None,\n                                aspect_ratio=1.0,\n                                overlap_thresh=0.3,\n                                seed=None):\n  \"\"\"Randomly crops an image to the specified aspect ratio.\n\n  Randomly crops the a portion of the image such that the crop is of the\n  specified aspect ratio, and the crop is as large as possible. If the specified\n  aspect ratio is larger than the aspect ratio of the image, this op will\n  randomly remove rows from the top and bottom of the image. If the specified\n  aspect ratio is less than the aspect ratio of the image, this op will randomly\n  remove cols from the left and right of the image. If the specified aspect\n  ratio is the same as the aspect ratio of the image, this op will return the\n  image.\n\n  Args:\n    image: rank 3 float32 tensor contains 1 image -> [height, width, channels]\n           with pixel values varying between [0, 1].\n    boxes: rank 2 float32 tensor containing the bounding boxes -> [N, 4].\n           Boxes are in normalized form meaning their coordinates vary\n           between [0, 1].\n           Each row is in the form of [ymin, xmin, ymax, xmax].\n    labels: rank 1 int32 tensor containing the object classes.\n    masks: (optional) rank 3 float32 tensor with shape\n           [num_instances, height, width] containing instance masks. The masks\n           are of the same height, width as the input `image`.\n    keypoints: (optional) rank 3 float32 tensor with shape\n               [num_instances, num_keypoints, 2]. The keypoints are in y-x\n               normalized coordinates.\n    aspect_ratio: the aspect ratio of cropped image.\n    overlap_thresh: minimum overlap thresh with new cropped\n                    image to keep the box.\n    seed: random seed.\n\n  Returns:\n    image: image which is the same rank as input image.\n    boxes: boxes which is the same rank as input boxes.\n           Boxes are in normalized form.\n    labels: new labels.\n\n    If masks, or keypoints is not None, the function also returns:\n\n    masks: rank 3 float32 tensor with shape [num_instances, height, width]\n           containing instance masks.\n    keypoints: rank 3 float32 tensor with shape\n               [num_instances, num_keypoints, 2]\n\n  Raises:\n    ValueError: If image is not a 3D tensor.\n  \"\"\"\n  if len(image.get_shape()) != 3:\n    raise ValueError('Image should be 3D tensor')\n\n  with tf.name_scope('RandomCropToAspectRatio', values=[image]):\n    image_shape = tf.shape(image)\n    orig_height = image_shape[0]\n    orig_width = image_shape[1]\n    orig_aspect_ratio = tf.to_float(orig_width) / tf.to_float(orig_height)\n    new_aspect_ratio = tf.constant(aspect_ratio, dtype=tf.float32)\n    def target_height_fn():\n      return tf.to_int32(\n          tf.round(\n              tf.to_float(orig_height) * orig_aspect_ratio / new_aspect_ratio))\n    target_height = tf.cond(\n        orig_aspect_ratio >= new_aspect_ratio,\n        lambda: orig_height,\n        target_height_fn)\n    def target_width_fn():\n      return tf.to_int32(\n          tf.round(\n              tf.to_float(orig_width) * new_aspect_ratio / orig_aspect_ratio))\n    target_width = tf.cond(\n        orig_aspect_ratio <= new_aspect_ratio,\n        lambda: orig_width,\n        target_width_fn)\n\n    # either offset_height = 0 and offset_width is randomly chosen from\n    # [0, offset_width - target_width), or else offset_width = 0 and\n    # offset_height is randomly chosen from [0, offset_height - target_height)\n    offset_height = _random_integer(0, orig_height - target_height + 1, seed)\n    offset_width = _random_integer(0, orig_width - target_width + 1, seed)\n    new_image = tf.image.crop_to_bounding_box(\n        image, offset_height, offset_width, target_height, target_width)\n\n    im_box = tf.stack([\n        tf.to_float(offset_height) / tf.to_float(orig_height),\n        tf.to_float(offset_width) / tf.to_float(orig_width),\n        tf.to_float(offset_height + target_height) / tf.to_float(orig_height),\n        tf.to_float(offset_width + target_width) / tf.to_float(orig_width)\n    ])\n\n    boxlist = box_list.BoxList(boxes)\n    boxlist.add_field('labels', labels)\n\n    im_boxlist = box_list.BoxList(tf.expand_dims(im_box, 0))\n\n    # remove boxes whose overlap with the image is less than overlap_thresh\n    overlapping_boxlist, keep_ids = box_list_ops.prune_non_overlapping_boxes(\n        boxlist, im_boxlist, overlap_thresh)\n\n    # change the coordinate of the remaining boxes\n    new_labels = overlapping_boxlist.get_field('labels')\n    new_boxlist = box_list_ops.change_coordinate_frame(overlapping_boxlist,\n                                                       im_box)\n    new_boxlist = box_list_ops.clip_to_window(new_boxlist,\n                                              tf.constant(\n                                                  [0.0, 0.0, 1.0, 1.0],\n                                                  tf.float32))\n    new_boxes = new_boxlist.get()\n\n    result = [new_image, new_boxes, new_labels]\n\n    if masks is not None:\n      masks_inside_window = tf.gather(masks, keep_ids)\n      masks_box_begin = tf.stack([0, offset_height, offset_width])\n      masks_box_size = tf.stack([-1, target_height, target_width])\n      new_masks = tf.slice(masks_inside_window, masks_box_begin, masks_box_size)\n      result.append(new_masks)\n\n    if keypoints is not None:\n      keypoints_inside_window = tf.gather(keypoints, keep_ids)\n      new_keypoints = keypoint_ops.change_coordinate_frame(\n          keypoints_inside_window, im_box)\n      new_keypoints = keypoint_ops.prune_outside_window(new_keypoints,\n                                                        [0.0, 0.0, 1.0, 1.0])\n      result.append(new_keypoints)\n\n    return tuple(result)\n\n\ndef random_black_patches(image,\n                         max_black_patches=10,\n                         probability=0.5,\n                         size_to_image_ratio=0.1,\n                         random_seed=None):\n  \"\"\"Randomly adds some black patches to the image.\n\n  This op adds up to max_black_patches square black patches of a fixed size\n  to the image where size is specified via the size_to_image_ratio parameter.\n\n  Args:\n    image: rank 3 float32 tensor containing 1 image -> [height, width, channels]\n           with pixel values varying between [0, 1].\n    max_black_patches: number of times that the function tries to add a\n                       black box to the image.\n    probability: at each try, what is the chance of adding a box.\n    size_to_image_ratio: Determines the ratio of the size of the black patches\n                         to the size of the image.\n                         box_size = size_to_image_ratio *\n                                    min(image_width, image_height)\n    random_seed: random seed.\n\n  Returns:\n    image\n  \"\"\"\n  def add_black_patch_to_image(image):\n    \"\"\"Function for adding one patch to the image.\n\n    Args:\n      image: image\n\n    Returns:\n      image with a randomly added black box\n    \"\"\"\n    image_shape = tf.shape(image)\n    image_height = image_shape[0]\n    image_width = image_shape[1]\n    box_size = tf.to_int32(\n        tf.multiply(\n            tf.minimum(tf.to_float(image_height), tf.to_float(image_width)),\n            size_to_image_ratio))\n    normalized_y_min = tf.random_uniform(\n        [], minval=0.0, maxval=(1.0 - size_to_image_ratio), seed=random_seed)\n    normalized_x_min = tf.random_uniform(\n        [], minval=0.0, maxval=(1.0 - size_to_image_ratio), seed=random_seed)\n    y_min = tf.to_int32(normalized_y_min * tf.to_float(image_height))\n    x_min = tf.to_int32(normalized_x_min * tf.to_float(image_width))\n    black_box = tf.ones([box_size, box_size, 3], dtype=tf.float32)\n    mask = 1.0 - tf.image.pad_to_bounding_box(black_box, y_min, x_min,\n                                              image_height, image_width)\n    image = tf.multiply(image, mask)\n    return image\n\n  with tf.name_scope('RandomBlackPatchInImage', values=[image]):\n    for _ in range(max_black_patches):\n      random_prob = tf.random_uniform([], minval=0.0, maxval=1.0,\n                                      dtype=tf.float32, seed=random_seed)\n      image = tf.cond(\n          tf.greater(random_prob, probability), lambda: image,\n          lambda: add_black_patch_to_image(image))\n\n    return image\n\n\ndef image_to_float(image):\n  \"\"\"Used in Faster R-CNN. Casts image pixel values to float.\n\n  Args:\n    image: input image which might be in tf.uint8 or sth else format\n\n  Returns:\n    image: image in tf.float32 format.\n  \"\"\"\n  with tf.name_scope('ImageToFloat', values=[image]):\n    image = tf.to_float(image)\n    return image\n\n\ndef random_resize_method(image, target_size):\n  \"\"\"Uses a random resize method to resize the image to target size.\n\n  Args:\n    image: a rank 3 tensor.\n    target_size: a list of [target_height, target_width]\n\n  Returns:\n    resized image.\n  \"\"\"\n\n  resized_image = _apply_with_random_selector(\n      image,\n      lambda x, method: tf.image.resize_images(x, target_size, method),\n      num_cases=4)\n\n  return resized_image\n\n\ndef resize_to_range(image,\n                    masks=None,\n                    min_dimension=None,\n                    max_dimension=None,\n                    align_corners=False):\n  \"\"\"Resizes an image so its dimensions are within the provided value.\n\n  The output size can be described by two cases:\n  1. If the image can be rescaled so its minimum dimension is equal to the\n     provided value without the other dimension exceeding max_dimension,\n     then do so.\n  2. Otherwise, resize so the largest dimension is equal to max_dimension.\n\n  Args:\n    image: A 3D tensor of shape [height, width, channels]\n    masks: (optional) rank 3 float32 tensor with shape\n           [num_instances, height, width] containing instance masks.\n    min_dimension: (optional) (scalar) desired size of the smaller image\n                   dimension.\n    max_dimension: (optional) (scalar) maximum allowed size\n                   of the larger image dimension.\n    align_corners: bool. If true, exactly align all 4 corners of the input\n                   and output. Defaults to False.\n\n  Returns:\n    A 3D tensor of shape [new_height, new_width, channels],\n    where the image has been resized (with bilinear interpolation) so that\n    min(new_height, new_width) == min_dimension or\n    max(new_height, new_width) == max_dimension.\n\n    If masks is not None, also outputs masks:\n    A 3D tensor of shape [num_instances, new_height, new_width]\n\n  Raises:\n    ValueError: if the image is not a 3D tensor.\n  \"\"\"\n  if len(image.get_shape()) != 3:\n    raise ValueError('Image should be 3D tensor')\n\n  with tf.name_scope('ResizeToRange', values=[image, min_dimension]):\n    image_shape = tf.shape(image)\n    orig_height = tf.to_float(image_shape[0])\n    orig_width = tf.to_float(image_shape[1])\n    orig_min_dim = tf.minimum(orig_height, orig_width)\n\n    # Calculates the larger of the possible sizes\n    min_dimension = tf.constant(min_dimension, dtype=tf.float32)\n    large_scale_factor = min_dimension / orig_min_dim\n    # Scaling orig_(height|width) by large_scale_factor will make the smaller\n    # dimension equal to min_dimension, save for floating point rounding errors.\n    # For reasonably-sized images, taking the nearest integer will reliably\n    # eliminate this error.\n    large_height = tf.to_int32(tf.round(orig_height * large_scale_factor))\n    large_width = tf.to_int32(tf.round(orig_width * large_scale_factor))\n    large_size = tf.stack([large_height, large_width])\n\n    if max_dimension:\n      # Calculates the smaller of the possible sizes, use that if the larger\n      # is too big.\n      orig_max_dim = tf.maximum(orig_height, orig_width)\n      max_dimension = tf.constant(max_dimension, dtype=tf.float32)\n      small_scale_factor = max_dimension / orig_max_dim\n      # Scaling orig_(height|width) by small_scale_factor will make the larger\n      # dimension equal to max_dimension, save for floating point rounding\n      # errors. For reasonably-sized images, taking the nearest integer will\n      # reliably eliminate this error.\n      small_height = tf.to_int32(tf.round(orig_height * small_scale_factor))\n      small_width = tf.to_int32(tf.round(orig_width * small_scale_factor))\n      small_size = tf.stack([small_height, small_width])\n\n      new_size = tf.cond(\n          tf.to_float(tf.reduce_max(large_size)) > max_dimension,\n          lambda: small_size, lambda: large_size)\n    else:\n      new_size = large_size\n\n    new_image = tf.image.resize_images(image, new_size,\n                                       align_corners=align_corners)\n\n    result = new_image\n    if masks is not None:\n      num_instances = tf.shape(masks)[0]\n\n      def resize_masks_branch():\n        new_masks = tf.expand_dims(masks, 3)\n        new_masks = tf.image.resize_nearest_neighbor(\n            new_masks, new_size, align_corners=align_corners)\n        new_masks = tf.squeeze(new_masks, axis=3)\n        return new_masks\n\n      def reshape_masks_branch():\n        new_masks = tf.reshape(masks, [0, new_size[0], new_size[1]])\n        return new_masks\n\n      masks = tf.cond(num_instances > 0,\n                      resize_masks_branch,\n                      reshape_masks_branch)\n      result = [new_image, masks]\n\n    return result\n\n\ndef scale_boxes_to_pixel_coordinates(image, boxes, keypoints=None):\n  \"\"\"Scales boxes from normalized to pixel coordinates.\n\n  Args:\n    image: A 3D float32 tensor of shape [height, width, channels].\n    boxes: A 2D float32 tensor of shape [num_boxes, 4] containing the bounding\n      boxes in normalized coordinates. Each row is of the form\n      [ymin, xmin, ymax, xmax].\n    keypoints: (optional) rank 3 float32 tensor with shape\n      [num_instances, num_keypoints, 2]. The keypoints are in y-x normalized\n      coordinates.\n\n  Returns:\n    image: unchanged input image.\n    scaled_boxes: a 2D float32 tensor of shape [num_boxes, 4] containing the\n      bounding boxes in pixel coordinates.\n    scaled_keypoints: a 3D float32 tensor with shape\n      [num_instances, num_keypoints, 2] containing the keypoints in pixel\n      coordinates.\n  \"\"\"\n  boxlist = box_list.BoxList(boxes)\n  image_height = tf.shape(image)[0]\n  image_width = tf.shape(image)[1]\n  scaled_boxes = box_list_ops.scale(boxlist, image_height, image_width).get()\n  result = [image, scaled_boxes]\n  if keypoints is not None:\n    scaled_keypoints = keypoint_ops.scale(keypoints, image_height, image_width)\n    result.append(scaled_keypoints)\n  return tuple(result)\n\n\n# pylint: disable=g-doc-return-or-yield\ndef resize_image(image,\n                 masks=None,\n                 new_height=600,\n                 new_width=1024,\n                 method=tf.image.ResizeMethod.BILINEAR,\n                 align_corners=False):\n  \"\"\"See `tf.image.resize_images` for detailed doc.\"\"\"\n  with tf.name_scope(\n      'ResizeImage',\n      values=[image, new_height, new_width, method, align_corners]):\n    new_image = tf.image.resize_images(image, [new_height, new_width],\n                                       method=method,\n                                       align_corners=align_corners)\n    result = new_image\n    if masks is not None:\n      num_instances = tf.shape(masks)[0]\n      new_size = tf.constant([new_height, new_width], dtype=tf.int32)\n      def resize_masks_branch():\n        new_masks = tf.expand_dims(masks, 3)\n        new_masks = tf.image.resize_nearest_neighbor(\n            new_masks, new_size, align_corners=align_corners)\n        new_masks = tf.squeeze(new_masks, axis=3)\n        return new_masks\n\n      def reshape_masks_branch():\n        new_masks = tf.reshape(masks, [0, new_size[0], new_size[1]])\n        return new_masks\n\n      masks = tf.cond(num_instances > 0,\n                      resize_masks_branch,\n                      reshape_masks_branch)\n      result = [new_image, masks]\n\n    return result\n\n\ndef subtract_channel_mean(image, means=None):\n  \"\"\"Normalizes an image by subtracting a mean from each channel.\n\n  Args:\n    image: A 3D tensor of shape [height, width, channels]\n    means: float list containing a mean for each channel\n  Returns:\n    normalized_images: a tensor of shape [height, width, channels]\n  Raises:\n    ValueError: if images is not a 4D tensor or if the number of means is not\n      equal to the number of channels.\n  \"\"\"\n  with tf.name_scope('SubtractChannelMean', values=[image, means]):\n    if len(image.get_shape()) != 3:\n      raise ValueError('Input must be of size [height, width, channels]')\n    if len(means) != image.get_shape()[-1]:\n      raise ValueError('len(means) must match the number of channels')\n    return image - [[means]]\n\n\ndef one_hot_encoding(labels, num_classes=None):\n  \"\"\"One-hot encodes the multiclass labels.\n\n  Example usage:\n    labels = tf.constant([1, 4], dtype=tf.int32)\n    one_hot = OneHotEncoding(labels, num_classes=5)\n    one_hot.eval()    # evaluates to [0, 1, 0, 0, 1]\n\n  Args:\n    labels: A tensor of shape [None] corresponding to the labels.\n    num_classes: Number of classes in the dataset.\n  Returns:\n    onehot_labels: a tensor of shape [num_classes] corresponding to the one hot\n      encoding of the labels.\n  Raises:\n    ValueError: if num_classes is not specified.\n  \"\"\"\n  with tf.name_scope('OneHotEncoding', values=[labels]):\n    if num_classes is None:\n      raise ValueError('num_classes must be specified')\n\n    labels = tf.one_hot(labels, num_classes, 1, 0)\n    return tf.reduce_max(labels, 0)\n\n\ndef rgb_to_gray(image):\n  \"\"\"Converts a 3 channel RGB image to a 1 channel grayscale image.\n\n  Args:\n    image: Rank 3 float32 tensor containing 1 image -> [height, width, 3]\n           with pixel values varying between [0, 1].\n\n  Returns:\n    image: A single channel grayscale image -> [image, height, 1].\n  \"\"\"\n  return tf.image.rgb_to_grayscale(image)\n\n\ndef ssd_random_crop(image,\n                    boxes,\n                    labels,\n                    masks=None,\n                    keypoints=None,\n                    min_object_covered=(0.0, 0.1, 0.3, 0.5, 0.7, 0.9, 1.0),\n                    aspect_ratio_range=((0.5, 2.0),) * 7,\n                    area_range=((0.1, 1.0),) * 7,\n                    overlap_thresh=(0.0, 0.1, 0.3, 0.5, 0.7, 0.9, 1.0),\n                    random_coef=(0.15,) * 7,\n                    seed=None):\n  \"\"\"Random crop preprocessing with default parameters as in SSD paper.\n\n  Liu et al., SSD: Single shot multibox detector.\n  For further information on random crop preprocessing refer to RandomCrop\n  function above.\n\n  Args:\n    image: rank 3 float32 tensor contains 1 image -> [height, width, channels]\n           with pixel values varying between [0, 1].\n    boxes: rank 2 float32 tensor containing the bounding boxes -> [N, 4].\n           Boxes are in normalized form meaning their coordinates vary\n           between [0, 1].\n           Each row is in the form of [ymin, xmin, ymax, xmax].\n    labels: rank 1 int32 tensor containing the object classes.\n    masks: (optional) rank 3 float32 tensor with shape\n           [num_instances, height, width] containing instance masks. The masks\n           are of the same height, width as the input `image`.\n    keypoints: (optional) rank 3 float32 tensor with shape\n               [num_instances, num_keypoints, 2]. The keypoints are in y-x\n               normalized coordinates.\n    min_object_covered: the cropped image must cover at least this fraction of\n                        at least one of the input bounding boxes.\n    aspect_ratio_range: allowed range for aspect ratio of cropped image.\n    area_range: allowed range for area ratio between cropped image and the\n                original image.\n    overlap_thresh: minimum overlap thresh with new cropped\n                    image to keep the box.\n    random_coef: a random coefficient that defines the chance of getting the\n                 original image. If random_coef is 0, we will always get the\n                 cropped image, and if it is 1.0, we will always get the\n                 original image.\n    seed: random seed.\n\n  Returns:\n    image: image which is the same rank as input image.\n    boxes: boxes which is the same rank as input boxes.\n           Boxes are in normalized form.\n    labels: new labels.\n\n    If masks, or keypoints is not None, the function also returns:\n\n    masks: rank 3 float32 tensor with shape [num_instances, height, width]\n           containing instance masks.\n    keypoints: rank 3 float32 tensor with shape\n               [num_instances, num_keypoints, 2]\n  \"\"\"\n  def random_crop_selector(selected_result, index):\n    \"\"\"Applies random_crop_image to selected result.\n\n    Args:\n      selected_result: A tuple containing image, boxes, labels, keypoints (if\n                       not None), and masks (if not None).\n      index: The index that was randomly selected.\n\n    Returns: A tuple containing image, boxes, labels, keypoints (if not None),\n             and masks (if not None).\n    \"\"\"\n    i = 3\n    image, boxes, labels = selected_result[:i]\n    selected_masks = None\n    selected_keypoints = None\n    if masks is not None:\n      selected_masks = selected_result[i]\n      i += 1\n    if keypoints is not None:\n      selected_keypoints = selected_result[i]\n\n    return random_crop_image(\n        image=image,\n        boxes=boxes,\n        labels=labels,\n        masks=selected_masks,\n        keypoints=selected_keypoints,\n        min_object_covered=min_object_covered[index],\n        aspect_ratio_range=aspect_ratio_range[index],\n        area_range=area_range[index],\n        overlap_thresh=overlap_thresh[index],\n        random_coef=random_coef[index],\n        seed=seed)\n\n  result = _apply_with_random_selector_tuples(\n      tuple(\n          t for t in (image, boxes, labels, masks, keypoints) if t is not None),\n      random_crop_selector,\n      num_cases=len(min_object_covered))\n  return result\n\n\ndef ssd_random_crop_pad(image,\n                        boxes,\n                        labels,\n                        min_object_covered=(0.1, 0.3, 0.5, 0.7, 0.9, 1.0),\n                        aspect_ratio_range=((0.5, 2.0),) * 6,\n                        area_range=((0.1, 1.0),) * 6,\n                        overlap_thresh=(0.1, 0.3, 0.5, 0.7, 0.9, 1.0),\n                        random_coef=(0.15,) * 6,\n                        min_padded_size_ratio=(None,) * 6,\n                        max_padded_size_ratio=(None,) * 6,\n                        pad_color=(None,) * 6,\n                        seed=None):\n  \"\"\"Random crop preprocessing with default parameters as in SSD paper.\n\n  Liu et al., SSD: Single shot multibox detector.\n  For further information on random crop preprocessing refer to RandomCrop\n  function above.\n\n  Args:\n    image: rank 3 float32 tensor containing 1 image -> [height, width, channels]\n           with pixel values varying between [0, 1].\n    boxes: rank 2 float32 tensor containing the bounding boxes -> [N, 4].\n           Boxes are in normalized form meaning their coordinates vary\n           between [0, 1].\n           Each row is in the form of [ymin, xmin, ymax, xmax].\n    labels: rank 1 int32 tensor containing the object classes.\n    min_object_covered: the cropped image must cover at least this fraction of\n                        at least one of the input bounding boxes.\n    aspect_ratio_range: allowed range for aspect ratio of cropped image.\n    area_range: allowed range for area ratio between cropped image and the\n                original image.\n    overlap_thresh: minimum overlap thresh with new cropped\n                    image to keep the box.\n    random_coef: a random coefficient that defines the chance of getting the\n                 original image. If random_coef is 0, we will always get the\n                 cropped image, and if it is 1.0, we will always get the\n                 original image.\n    min_padded_size_ratio: min ratio of padded image height and width to the\n                           input image's height and width. If None, it will\n                           be set to [0.0, 0.0].\n    max_padded_size_ratio: max ratio of padded image height and width to the\n                           input image's height and width. If None, it will\n                           be set to [2.0, 2.0].\n    pad_color: padding color. A rank 1 tensor of [3] with dtype=tf.float32.\n               if set as None, it will be set to average color of the randomly\n               cropped image.\n    seed: random seed.\n\n  Returns:\n    image: Image shape will be [new_height, new_width, channels].\n    boxes: boxes which is the same rank as input boxes. Boxes are in normalized\n           form.\n    new_labels: new labels.\n  \"\"\"\n  def random_crop_pad_selector(image_boxes_labels, index):\n    image, boxes, labels = image_boxes_labels\n\n    return random_crop_pad_image(\n        image,\n        boxes,\n        labels,\n        min_object_covered=min_object_covered[index],\n        aspect_ratio_range=aspect_ratio_range[index],\n        area_range=area_range[index],\n        overlap_thresh=overlap_thresh[index],\n        random_coef=random_coef[index],\n        min_padded_size_ratio=min_padded_size_ratio[index],\n        max_padded_size_ratio=max_padded_size_ratio[index],\n        pad_color=pad_color[index],\n        seed=seed)\n\n  new_image, new_boxes, new_labels = _apply_with_random_selector_tuples(\n      (image, boxes, labels),\n      random_crop_pad_selector,\n      num_cases=len(min_object_covered))\n  return new_image, new_boxes, new_labels\n\n\ndef ssd_random_crop_fixed_aspect_ratio(\n    image,\n    boxes,\n    labels,\n    masks=None,\n    keypoints=None,\n    min_object_covered=(0.0, 0.1, 0.3, 0.5, 0.7, 0.9, 1.0),\n    aspect_ratio=1.0,\n    area_range=((0.1, 1.0),) * 7,\n    overlap_thresh=(0.0, 0.1, 0.3, 0.5, 0.7, 0.9, 1.0),\n    random_coef=(0.15,) * 7,\n    seed=None):\n  \"\"\"Random crop preprocessing with default parameters as in SSD paper.\n\n  Liu et al., SSD: Single shot multibox detector.\n  For further information on random crop preprocessing refer to RandomCrop\n  function above.\n\n  The only difference is that the aspect ratio of the crops are fixed.\n\n  Args:\n    image: rank 3 float32 tensor contains 1 image -> [height, width, channels]\n           with pixel values varying between [0, 1].\n    boxes: rank 2 float32 tensor containing the bounding boxes -> [N, 4].\n           Boxes are in normalized form meaning their coordinates vary\n           between [0, 1].\n           Each row is in the form of [ymin, xmin, ymax, xmax].\n    labels: rank 1 int32 tensor containing the object classes.\n    masks: (optional) rank 3 float32 tensor with shape\n           [num_instances, height, width] containing instance masks. The masks\n           are of the same height, width as the input `image`.\n    keypoints: (optional) rank 3 float32 tensor with shape\n               [num_instances, num_keypoints, 2]. The keypoints are in y-x\n               normalized coordinates.\n    min_object_covered: the cropped image must cover at least this fraction of\n                        at least one of the input bounding boxes.\n    aspect_ratio: aspect ratio of the cropped image.\n    area_range: allowed range for area ratio between cropped image and the\n                original image.\n    overlap_thresh: minimum overlap thresh with new cropped\n                    image to keep the box.\n    random_coef: a random coefficient that defines the chance of getting the\n                 original image. If random_coef is 0, we will always get the\n                 cropped image, and if it is 1.0, we will always get the\n                 original image.\n    seed: random seed.\n\n  Returns:\n    image: image which is the same rank as input image.\n    boxes: boxes which is the same rank as input boxes.\n           Boxes are in normalized form.\n    labels: new labels.\n\n    If masks, or keypoints is not None, the function also returns:\n\n    masks: rank 3 float32 tensor with shape [num_instances, height, width]\n           containing instance masks.\n    keypoints: rank 3 float32 tensor with shape\n               [num_instances, num_keypoints, 2]\n\n  \"\"\"\n  aspect_ratio_range = ((aspect_ratio, aspect_ratio),) * len(area_range)\n\n  crop_result = ssd_random_crop(image, boxes, labels, masks, keypoints,\n                                min_object_covered, aspect_ratio_range,\n                                area_range, overlap_thresh, random_coef, seed)\n  i = 3\n  new_image, new_boxes, new_labels = crop_result[:i]\n  new_masks = None\n  new_keypoints = None\n  if masks is not None:\n    new_masks = crop_result[i]\n    i += 1\n  if keypoints is not None:\n    new_keypoints = crop_result[i]\n  result = random_crop_to_aspect_ratio(\n      new_image,\n      new_boxes,\n      new_labels,\n      new_masks,\n      new_keypoints,\n      aspect_ratio=aspect_ratio,\n      seed=seed)\n\n  return result\n\n\ndef get_default_func_arg_map(include_instance_masks=False,\n                             include_keypoints=False):\n  \"\"\"Returns the default mapping from a preprocessor function to its args.\n\n  Args:\n    include_instance_masks: If True, preprocessing functions will modify the\n      instance masks, too.\n    include_keypoints: If True, preprocessing functions will modify the\n      keypoints, too.\n\n  Returns:\n    A map from preprocessing functions to the arguments they receive.\n  \"\"\"\n  groundtruth_instance_masks = None\n  if include_instance_masks:\n    groundtruth_instance_masks = (\n        fields.InputDataFields.groundtruth_instance_masks)\n\n  groundtruth_keypoints = None\n  if include_keypoints:\n    groundtruth_keypoints = fields.InputDataFields.groundtruth_keypoints\n\n  prep_func_arg_map = {\n      normalize_image: (fields.InputDataFields.image,),\n      random_horizontal_flip: (fields.InputDataFields.image,\n                               fields.InputDataFields.groundtruth_boxes,\n                               groundtruth_instance_masks,\n                               groundtruth_keypoints,),\n      random_pixel_value_scale: (fields.InputDataFields.image,),\n      random_image_scale: (fields.InputDataFields.image,\n                           groundtruth_instance_masks,),\n      random_rgb_to_gray: (fields.InputDataFields.image,),\n      random_adjust_brightness: (fields.InputDataFields.image,),\n      random_adjust_contrast: (fields.InputDataFields.image,),\n      random_adjust_hue: (fields.InputDataFields.image,),\n      random_adjust_saturation: (fields.InputDataFields.image,),\n      random_distort_color: (fields.InputDataFields.image,),\n      random_jitter_boxes: (fields.InputDataFields.groundtruth_boxes,),\n      random_crop_image: (fields.InputDataFields.image,\n                          fields.InputDataFields.groundtruth_boxes,\n                          fields.InputDataFields.groundtruth_classes,\n                          groundtruth_instance_masks,\n                          groundtruth_keypoints,),\n      random_pad_image: (fields.InputDataFields.image,\n                         fields.InputDataFields.groundtruth_boxes),\n      random_crop_pad_image: (fields.InputDataFields.image,\n                              fields.InputDataFields.groundtruth_boxes,\n                              fields.InputDataFields.groundtruth_classes),\n      random_crop_to_aspect_ratio: (fields.InputDataFields.image,\n                                    fields.InputDataFields.groundtruth_boxes,\n                                    fields.InputDataFields.groundtruth_classes,\n                                    groundtruth_instance_masks,\n                                    groundtruth_keypoints,),\n      random_black_patches: (fields.InputDataFields.image,),\n      retain_boxes_above_threshold: (\n          fields.InputDataFields.groundtruth_boxes,\n          fields.InputDataFields.groundtruth_classes,\n          fields.InputDataFields.groundtruth_label_scores,\n          groundtruth_instance_masks,\n          groundtruth_keypoints,),\n      image_to_float: (fields.InputDataFields.image,),\n      random_resize_method: (fields.InputDataFields.image,),\n      resize_to_range: (fields.InputDataFields.image,\n                        groundtruth_instance_masks,),\n      scale_boxes_to_pixel_coordinates: (\n          fields.InputDataFields.image,\n          fields.InputDataFields.groundtruth_boxes,\n          groundtruth_keypoints,),\n      flip_boxes: (fields.InputDataFields.groundtruth_boxes,),\n      resize_image: (fields.InputDataFields.image,\n                     groundtruth_instance_masks,),\n      subtract_channel_mean: (fields.InputDataFields.image,),\n      one_hot_encoding: (fields.InputDataFields.groundtruth_image_classes,),\n      rgb_to_gray: (fields.InputDataFields.image,),\n      ssd_random_crop: (fields.InputDataFields.image,\n                        fields.InputDataFields.groundtruth_boxes,\n                        fields.InputDataFields.groundtruth_classes,\n                        groundtruth_instance_masks,\n                        groundtruth_keypoints,),\n      ssd_random_crop_pad: (fields.InputDataFields.image,\n                            fields.InputDataFields.groundtruth_boxes,\n                            fields.InputDataFields.groundtruth_classes),\n      ssd_random_crop_fixed_aspect_ratio: (\n          fields.InputDataFields.image,\n          fields.InputDataFields.groundtruth_boxes,\n          fields.InputDataFields.groundtruth_classes,\n          groundtruth_instance_masks,\n          groundtruth_keypoints,),\n  }\n\n  return prep_func_arg_map\n\n\ndef preprocess(tensor_dict, preprocess_options, func_arg_map=None):\n  \"\"\"Preprocess images and bounding boxes.\n\n  Various types of preprocessing (to be implemented) based on the\n  preprocess_options dictionary e.g. \"crop image\" (affects image and possibly\n  boxes), \"white balance image\" (affects only image), etc. If self._options\n  is None, no preprocessing is done.\n\n  Args:\n    tensor_dict: dictionary that contains images, boxes, and can contain other\n                 things as well.\n                 images-> rank 4 float32 tensor contains\n                          1 image -> [1, height, width, 3].\n                          with pixel values varying between [0, 1]\n                 boxes-> rank 2 float32 tensor containing\n                         the bounding boxes -> [N, 4].\n                         Boxes are in normalized form meaning\n                         their coordinates vary between [0, 1].\n                         Each row is in the form\n                         of [ymin, xmin, ymax, xmax].\n    preprocess_options: It is a list of tuples, where each tuple contains a\n                        function and a dictionary that contains arguments and\n                        their values.\n    func_arg_map: mapping from preprocessing functions to arguments that they\n                  expect to receive and return.\n\n  Returns:\n    tensor_dict: which contains the preprocessed images, bounding boxes, etc.\n\n  Raises:\n    ValueError: (a) If the functions passed to Preprocess\n                    are not in func_arg_map.\n                (b) If the arguments that a function needs\n                    do not exist in tensor_dict.\n                (c) If image in tensor_dict is not rank 4\n  \"\"\"\n  if func_arg_map is None:\n    func_arg_map = get_default_func_arg_map()\n\n  # changes the images to image (rank 4 to rank 3) since the functions\n  # receive rank 3 tensor for image\n  if fields.InputDataFields.image in tensor_dict:\n    images = tensor_dict[fields.InputDataFields.image]\n    if len(images.get_shape()) != 4:\n      raise ValueError('images in tensor_dict should be rank 4')\n    image = tf.squeeze(images, squeeze_dims=[0])\n    tensor_dict[fields.InputDataFields.image] = image\n\n  # Preprocess inputs based on preprocess_options\n  for option in preprocess_options:\n    func, params = option\n    if func not in func_arg_map:\n      raise ValueError('The function %s does not exist in func_arg_map' %\n                       (func.__name__))\n    arg_names = func_arg_map[func]\n    for a in arg_names:\n      if a is not None and a not in tensor_dict:\n        raise ValueError('The function %s requires argument %s' %\n                         (func.__name__, a))\n\n    def get_arg(key):\n      return tensor_dict[key] if key is not None else None\n    args = [get_arg(a) for a in arg_names]\n    results = func(*args, **params)\n    if not isinstance(results, (list, tuple)):\n      results = (results,)\n    # Removes None args since the return values will not contain those.\n    arg_names = [arg_name for arg_name in arg_names if arg_name is not None]\n    for res, arg_name in zip(results, arg_names):\n      tensor_dict[arg_name] = res\n\n  # changes the image to images (rank 3 to rank 4) to be compatible to what\n  # we received in the first place\n  if fields.InputDataFields.image in tensor_dict:\n    image = tensor_dict[fields.InputDataFields.image]\n    images = tf.expand_dims(image, 0)\n    tensor_dict[fields.InputDataFields.image] = images\n\n  return tensor_dict\n"
  },
  {
    "path": "object_detector_app/object_detection/core/preprocessor_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.core.preprocessor.\"\"\"\n\nimport mock\nimport numpy as np\n\nimport tensorflow as tf\n\nfrom object_detection.core import preprocessor\nfrom object_detection.core import standard_fields as fields\n\n\nclass PreprocessorTest(tf.test.TestCase):\n\n  def createColorfulTestImage(self):\n    ch255 = tf.fill([1, 100, 200, 1], tf.constant(255, dtype=tf.uint8))\n    ch128 = tf.fill([1, 100, 200, 1], tf.constant(128, dtype=tf.uint8))\n    ch0 = tf.fill([1, 100, 200, 1], tf.constant(0, dtype=tf.uint8))\n    imr = tf.concat([ch255, ch0, ch0], 3)\n    img = tf.concat([ch255, ch255, ch0], 3)\n    imb = tf.concat([ch255, ch0, ch255], 3)\n    imw = tf.concat([ch128, ch128, ch128], 3)\n    imu = tf.concat([imr, img], 2)\n    imd = tf.concat([imb, imw], 2)\n    im = tf.concat([imu, imd], 1)\n    return im\n\n  def createTestImages(self):\n    images_r = tf.constant([[[128, 128, 128, 128], [0, 0, 128, 128],\n                             [0, 128, 128, 128], [192, 192, 128, 128]]],\n                           dtype=tf.uint8)\n    images_r = tf.expand_dims(images_r, 3)\n    images_g = tf.constant([[[0, 0, 128, 128], [0, 0, 128, 128],\n                             [0, 128, 192, 192], [192, 192, 128, 192]]],\n                           dtype=tf.uint8)\n    images_g = tf.expand_dims(images_g, 3)\n    images_b = tf.constant([[[128, 128, 192, 0], [0, 0, 128, 192],\n                             [0, 128, 128, 0], [192, 192, 192, 128]]],\n                           dtype=tf.uint8)\n    images_b = tf.expand_dims(images_b, 3)\n    images = tf.concat([images_r, images_g, images_b], 3)\n    return images\n\n  def createTestBoxes(self):\n    boxes = tf.constant(\n        [[0.0, 0.25, 0.75, 1.0], [0.25, 0.5, 0.75, 1.0]], dtype=tf.float32)\n    return boxes\n\n  def createTestLabelScores(self):\n    return tf.constant([1.0, 0.5], dtype=tf.float32)\n\n  def createTestLabelScoresWithMissingScore(self):\n    return tf.constant([0.5, np.nan], dtype=tf.float32)\n\n  def createTestMasks(self):\n    mask = np.array([\n        [[255.0, 0.0, 0.0],\n         [255.0, 0.0, 0.0],\n         [255.0, 0.0, 0.0]],\n        [[255.0, 255.0, 0.0],\n         [255.0, 255.0, 0.0],\n         [255.0, 255.0, 0.0]]])\n    return tf.constant(mask, dtype=tf.float32)\n\n  def createTestKeypoints(self):\n    keypoints = np.array([\n        [[0.1, 0.1], [0.2, 0.2], [0.3, 0.3]],\n        [[0.4, 0.4], [0.5, 0.5], [0.6, 0.6]],\n    ])\n    return tf.constant(keypoints, dtype=tf.float32)\n\n  def createTestKeypointsInsideCrop(self):\n    keypoints = np.array([\n        [[0.4, 0.4], [0.5, 0.5], [0.6, 0.6]],\n        [[0.4, 0.4], [0.5, 0.5], [0.6, 0.6]],\n    ])\n    return tf.constant(keypoints, dtype=tf.float32)\n\n  def createTestKeypointsOutsideCrop(self):\n    keypoints = np.array([\n        [[0.1, 0.1], [0.2, 0.2], [0.3, 0.3]],\n        [[0.1, 0.1], [0.2, 0.2], [0.3, 0.3]],\n    ])\n    return tf.constant(keypoints, dtype=tf.float32)\n\n  def createKeypointFlipPermutation(self):\n    return np.array([0, 2, 1], dtype=np.int32)\n\n  def createTestLabels(self):\n    labels = tf.constant([1, 2], dtype=tf.int32)\n    return labels\n\n  def createTestBoxesOutOfImage(self):\n    boxes = tf.constant(\n        [[-0.1, 0.25, 0.75, 1], [0.25, 0.5, 0.75, 1.1]], dtype=tf.float32)\n    return boxes\n\n  def expectedImagesAfterNormalization(self):\n    images_r = tf.constant([[[0, 0, 0, 0], [-1, -1, 0, 0],\n                             [-1, 0, 0, 0], [0.5, 0.5, 0, 0]]],\n                           dtype=tf.float32)\n    images_r = tf.expand_dims(images_r, 3)\n    images_g = tf.constant([[[-1, -1, 0, 0], [-1, -1, 0, 0],\n                             [-1, 0, 0.5, 0.5], [0.5, 0.5, 0, 0.5]]],\n                           dtype=tf.float32)\n    images_g = tf.expand_dims(images_g, 3)\n    images_b = tf.constant([[[0, 0, 0.5, -1], [-1, -1, 0, 0.5],\n                             [-1, 0, 0, -1], [0.5, 0.5, 0.5, 0]]],\n                           dtype=tf.float32)\n    images_b = tf.expand_dims(images_b, 3)\n    images = tf.concat([images_r, images_g, images_b], 3)\n    return images\n\n  def expectedMaxImageAfterColorScale(self):\n    images_r = tf.constant([[[0.1, 0.1, 0.1, 0.1], [-0.9, -0.9, 0.1, 0.1],\n                             [-0.9, 0.1, 0.1, 0.1], [0.6, 0.6, 0.1, 0.1]]],\n                           dtype=tf.float32)\n    images_r = tf.expand_dims(images_r, 3)\n    images_g = tf.constant([[[-0.9, -0.9, 0.1, 0.1], [-0.9, -0.9, 0.1, 0.1],\n                             [-0.9, 0.1, 0.6, 0.6], [0.6, 0.6, 0.1, 0.6]]],\n                           dtype=tf.float32)\n    images_g = tf.expand_dims(images_g, 3)\n    images_b = tf.constant([[[0.1, 0.1, 0.6, -0.9], [-0.9, -0.9, 0.1, 0.6],\n                             [-0.9, 0.1, 0.1, -0.9], [0.6, 0.6, 0.6, 0.1]]],\n                           dtype=tf.float32)\n    images_b = tf.expand_dims(images_b, 3)\n    images = tf.concat([images_r, images_g, images_b], 3)\n    return images\n\n  def expectedMinImageAfterColorScale(self):\n    images_r = tf.constant([[[-0.1, -0.1, -0.1, -0.1], [-1, -1, -0.1, -0.1],\n                             [-1, -0.1, -0.1, -0.1], [0.4, 0.4, -0.1, -0.1]]],\n                           dtype=tf.float32)\n    images_r = tf.expand_dims(images_r, 3)\n    images_g = tf.constant([[[-1, -1, -0.1, -0.1], [-1, -1, -0.1, -0.1],\n                             [-1, -0.1, 0.4, 0.4], [0.4, 0.4, -0.1, 0.4]]],\n                           dtype=tf.float32)\n    images_g = tf.expand_dims(images_g, 3)\n    images_b = tf.constant([[[-0.1, -0.1, 0.4, -1], [-1, -1, -0.1, 0.4],\n                             [-1, -0.1, -0.1, -1], [0.4, 0.4, 0.4, -0.1]]],\n                           dtype=tf.float32)\n    images_b = tf.expand_dims(images_b, 3)\n    images = tf.concat([images_r, images_g, images_b], 3)\n    return images\n\n  def expectedImagesAfterMirroring(self):\n    images_r = tf.constant([[[0, 0, 0, 0], [0, 0, -1, -1],\n                             [0, 0, 0, -1], [0, 0, 0.5, 0.5]]],\n                           dtype=tf.float32)\n    images_r = tf.expand_dims(images_r, 3)\n    images_g = tf.constant([[[0, 0, -1, -1], [0, 0, -1, -1],\n                             [0.5, 0.5, 0, -1], [0.5, 0, 0.5, 0.5]]],\n                           dtype=tf.float32)\n    images_g = tf.expand_dims(images_g, 3)\n    images_b = tf.constant([[[-1, 0.5, 0, 0], [0.5, 0, -1, -1],\n                             [-1, 0, 0, -1], [0, 0.5, 0.5, 0.5]]],\n                           dtype=tf.float32)\n    images_b = tf.expand_dims(images_b, 3)\n    images = tf.concat([images_r, images_g, images_b], 3)\n    return images\n\n  def expectedBoxesAfterMirroring(self):\n    boxes = tf.constant([[0.0, 0.0, 0.75, 0.75], [0.25, 0.0, 0.75, 0.5]],\n                        dtype=tf.float32)\n    return boxes\n\n  def expectedBoxesAfterXY(self):\n    boxes = tf.constant([[0.25, 0.0, 1.0, 0.75], [0.5, 0.25, 1, 0.75]],\n                        dtype=tf.float32)\n    return boxes\n\n  def expectedMasksAfterMirroring(self):\n    mask = np.array([\n        [[0.0, 0.0, 255.0],\n         [0.0, 0.0, 255.0],\n         [0.0, 0.0, 255.0]],\n        [[0.0, 255.0, 255.0],\n         [0.0, 255.0, 255.0],\n         [0.0, 255.0, 255.0]]])\n    return tf.constant(mask, dtype=tf.float32)\n\n  def expectedLabelScoresAfterThresholding(self):\n    return tf.constant([1.0], dtype=tf.float32)\n\n  def expectedBoxesAfterThresholding(self):\n    return tf.constant([[0.0, 0.25, 0.75, 1.0]], dtype=tf.float32)\n\n  def expectedLabelsAfterThresholding(self):\n    return tf.constant([1], dtype=tf.float32)\n\n  def expectedMasksAfterThresholding(self):\n    mask = np.array([\n        [[255.0, 0.0, 0.0],\n         [255.0, 0.0, 0.0],\n         [255.0, 0.0, 0.0]]])\n    return tf.constant(mask, dtype=tf.float32)\n\n  def expectedKeypointsAfterThresholding(self):\n    keypoints = np.array([\n        [[0.1, 0.1], [0.2, 0.2], [0.3, 0.3]]\n    ])\n    return tf.constant(keypoints, dtype=tf.float32)\n\n  def expectedLabelScoresAfterThresholdingWithMissingScore(self):\n    return tf.constant([np.nan], dtype=tf.float32)\n\n  def expectedBoxesAfterThresholdingWithMissingScore(self):\n    return tf.constant([[0.25, 0.5, 0.75, 1]], dtype=tf.float32)\n\n  def expectedLabelsAfterThresholdingWithMissingScore(self):\n    return tf.constant([2], dtype=tf.float32)\n\n  def testNormalizeImage(self):\n    preprocess_options = [(preprocessor.normalize_image, {\n        'original_minval': 0,\n        'original_maxval': 256,\n        'target_minval': -1,\n        'target_maxval': 1\n    })]\n    images = self.createTestImages()\n    tensor_dict = {fields.InputDataFields.image: images}\n    tensor_dict = preprocessor.preprocess(tensor_dict, preprocess_options)\n    images = tensor_dict[fields.InputDataFields.image]\n    images_expected = self.expectedImagesAfterNormalization()\n\n    with self.test_session() as sess:\n      (images_, images_expected_) = sess.run(\n          [images, images_expected])\n      images_shape_ = images_.shape\n      images_expected_shape_ = images_expected_.shape\n      expected_shape = [1, 4, 4, 3]\n      self.assertAllEqual(images_expected_shape_, images_shape_)\n      self.assertAllEqual(images_shape_, expected_shape)\n      self.assertAllClose(images_, images_expected_)\n\n  def testRetainBoxesAboveThreshold(self):\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    label_scores = self.createTestLabelScores()\n    (retained_boxes, retained_labels,\n     retained_label_scores) = preprocessor.retain_boxes_above_threshold(\n         boxes, labels, label_scores, threshold=0.6)\n    with self.test_session() as sess:\n      (retained_boxes_, retained_labels_, retained_label_scores_,\n       expected_retained_boxes_, expected_retained_labels_,\n       expected_retained_label_scores_) = sess.run([\n           retained_boxes, retained_labels, retained_label_scores,\n           self.expectedBoxesAfterThresholding(),\n           self.expectedLabelsAfterThresholding(),\n           self.expectedLabelScoresAfterThresholding()])\n      self.assertAllClose(\n          retained_boxes_, expected_retained_boxes_)\n      self.assertAllClose(\n          retained_labels_, expected_retained_labels_)\n      self.assertAllClose(\n          retained_label_scores_, expected_retained_label_scores_)\n\n  def testRetainBoxesAboveThresholdWithMasks(self):\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    label_scores = self.createTestLabelScores()\n    masks = self.createTestMasks()\n    _, _, _, retained_masks = preprocessor.retain_boxes_above_threshold(\n        boxes, labels, label_scores, masks, threshold=0.6)\n    with self.test_session() as sess:\n      retained_masks_, expected_retained_masks_ = sess.run([\n          retained_masks, self.expectedMasksAfterThresholding()])\n\n      self.assertAllClose(\n          retained_masks_, expected_retained_masks_)\n\n  def testRetainBoxesAboveThresholdWithKeypoints(self):\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    label_scores = self.createTestLabelScores()\n    keypoints = self.createTestKeypoints()\n    (_, _, _, retained_keypoints) = preprocessor.retain_boxes_above_threshold(\n        boxes, labels, label_scores, keypoints=keypoints, threshold=0.6)\n    with self.test_session() as sess:\n      (retained_keypoints_,\n       expected_retained_keypoints_) = sess.run([\n           retained_keypoints,\n           self.expectedKeypointsAfterThresholding()])\n\n      self.assertAllClose(\n          retained_keypoints_, expected_retained_keypoints_)\n\n  def testRetainBoxesAboveThresholdWithMissingScore(self):\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    label_scores = self.createTestLabelScoresWithMissingScore()\n    (retained_boxes, retained_labels,\n     retained_label_scores) = preprocessor.retain_boxes_above_threshold(\n         boxes, labels, label_scores, threshold=0.6)\n    with self.test_session() as sess:\n      (retained_boxes_, retained_labels_, retained_label_scores_,\n       expected_retained_boxes_, expected_retained_labels_,\n       expected_retained_label_scores_) = sess.run([\n           retained_boxes, retained_labels, retained_label_scores,\n           self.expectedBoxesAfterThresholdingWithMissingScore(),\n           self.expectedLabelsAfterThresholdingWithMissingScore(),\n           self.expectedLabelScoresAfterThresholdingWithMissingScore()])\n      self.assertAllClose(\n          retained_boxes_, expected_retained_boxes_)\n      self.assertAllClose(\n          retained_labels_, expected_retained_labels_)\n      self.assertAllClose(\n          retained_label_scores_, expected_retained_label_scores_)\n\n  def testRandomFlipBoxes(self):\n    boxes = self.createTestBoxes()\n\n    # Case where the boxes are flipped.\n    boxes_expected1 = self.expectedBoxesAfterMirroring()\n\n    # Case where the boxes are not flipped.\n    boxes_expected2 = boxes\n\n    # After elementwise multiplication, the result should be all-zero since one\n    # of them is all-zero.\n    boxes_diff = tf.multiply(\n        tf.squared_difference(boxes, boxes_expected1),\n        tf.squared_difference(boxes, boxes_expected2))\n    expected_result = tf.zeros_like(boxes_diff)\n\n    with self.test_session() as sess:\n      (boxes_diff, expected_result) = sess.run([boxes_diff, expected_result])\n      self.assertAllEqual(boxes_diff, expected_result)\n\n  def testFlipMasks(self):\n    test_mask = self.createTestMasks()\n    flipped_mask = preprocessor._flip_masks(test_mask)\n    expected_mask = self.expectedMasksAfterMirroring()\n    with self.test_session() as sess:\n      flipped_mask, expected_mask = sess.run([flipped_mask, expected_mask])\n      self.assertAllEqual(flipped_mask.flatten(), expected_mask.flatten())\n\n  def testRandomHorizontalFlip(self):\n    preprocess_options = [(preprocessor.random_horizontal_flip, {})]\n    images = self.expectedImagesAfterNormalization()\n    boxes = self.createTestBoxes()\n    tensor_dict = {fields.InputDataFields.image: images,\n                   fields.InputDataFields.groundtruth_boxes: boxes}\n    images_expected1 = self.expectedImagesAfterMirroring()\n    boxes_expected1 = self.expectedBoxesAfterMirroring()\n    images_expected2 = images\n    boxes_expected2 = boxes\n    tensor_dict = preprocessor.preprocess(tensor_dict, preprocess_options)\n    images = tensor_dict[fields.InputDataFields.image]\n    boxes = tensor_dict[fields.InputDataFields.groundtruth_boxes]\n\n    boxes_diff1 = tf.squared_difference(boxes, boxes_expected1)\n    boxes_diff2 = tf.squared_difference(boxes, boxes_expected2)\n    boxes_diff = tf.multiply(boxes_diff1, boxes_diff2)\n    boxes_diff_expected = tf.zeros_like(boxes_diff)\n\n    images_diff1 = tf.squared_difference(images, images_expected1)\n    images_diff2 = tf.squared_difference(images, images_expected2)\n    images_diff = tf.multiply(images_diff1, images_diff2)\n    images_diff_expected = tf.zeros_like(images_diff)\n\n    with self.test_session() as sess:\n      (images_diff_, images_diff_expected_, boxes_diff_,\n       boxes_diff_expected_) = sess.run([images_diff, images_diff_expected,\n                                         boxes_diff, boxes_diff_expected])\n      self.assertAllClose(boxes_diff_, boxes_diff_expected_)\n      self.assertAllClose(images_diff_, images_diff_expected_)\n\n  def testRunRandomHorizontalFlipWithMaskAndKeypoints(self):\n    preprocess_options = [(preprocessor.random_horizontal_flip, {})]\n    image_height = 3\n    image_width = 3\n    images = tf.random_uniform([1, image_height, image_width, 3])\n    boxes = self.createTestBoxes()\n    masks = self.createTestMasks()\n    keypoints = self.createTestKeypoints()\n    keypoint_flip_permutation = self.createKeypointFlipPermutation()\n    tensor_dict = {\n        fields.InputDataFields.image: images,\n        fields.InputDataFields.groundtruth_boxes: boxes,\n        fields.InputDataFields.groundtruth_instance_masks: masks,\n        fields.InputDataFields.groundtruth_keypoints: keypoints\n    }\n    preprocess_options = [\n        (preprocessor.random_horizontal_flip,\n         {'keypoint_flip_permutation': keypoint_flip_permutation})]\n    preprocessor_arg_map = preprocessor.get_default_func_arg_map(\n        include_instance_masks=True, include_keypoints=True)\n    tensor_dict = preprocessor.preprocess(\n        tensor_dict, preprocess_options, func_arg_map=preprocessor_arg_map)\n    boxes = tensor_dict[fields.InputDataFields.groundtruth_boxes]\n    masks = tensor_dict[fields.InputDataFields.groundtruth_instance_masks]\n    keypoints = tensor_dict[fields.InputDataFields.groundtruth_keypoints]\n    with self.test_session() as sess:\n      boxes, masks, keypoints = sess.run([boxes, masks, keypoints])\n      self.assertTrue(boxes is not None)\n      self.assertTrue(masks is not None)\n      self.assertTrue(keypoints is not None)\n\n  def testRandomPixelValueScale(self):\n    preprocessing_options = []\n    preprocessing_options.append((preprocessor.normalize_image, {\n        'original_minval': 0,\n        'original_maxval': 255,\n        'target_minval': 0,\n        'target_maxval': 1\n    }))\n    preprocessing_options.append((preprocessor.random_pixel_value_scale, {}))\n    images = self.createTestImages()\n    tensor_dict = {fields.InputDataFields.image: images}\n    tensor_dict = preprocessor.preprocess(tensor_dict, preprocessing_options)\n    images_min = tf.to_float(images) * 0.9 / 255.0\n    images_max = tf.to_float(images) * 1.1 / 255.0\n    images = tensor_dict[fields.InputDataFields.image]\n    values_greater = tf.greater_equal(images, images_min)\n    values_less = tf.less_equal(images, images_max)\n    values_true = tf.fill([1, 4, 4, 3], True)\n    with self.test_session() as sess:\n      (values_greater_, values_less_, values_true_) = sess.run(\n          [values_greater, values_less, values_true])\n      self.assertAllClose(values_greater_, values_true_)\n      self.assertAllClose(values_less_, values_true_)\n\n  def testRandomImageScale(self):\n    preprocess_options = [(preprocessor.random_image_scale, {})]\n    images_original = self.createTestImages()\n    tensor_dict = {fields.InputDataFields.image: images_original}\n    tensor_dict = preprocessor.preprocess(tensor_dict, preprocess_options)\n    images_scaled = tensor_dict[fields.InputDataFields.image]\n    images_original_shape = tf.shape(images_original)\n    images_scaled_shape = tf.shape(images_scaled)\n    with self.test_session() as sess:\n      (images_original_shape_, images_scaled_shape_) = sess.run(\n          [images_original_shape, images_scaled_shape])\n      self.assertTrue(\n          images_original_shape_[1] * 0.5 <= images_scaled_shape_[1])\n      self.assertTrue(\n          images_original_shape_[1] * 2.0 >= images_scaled_shape_[1])\n      self.assertTrue(\n          images_original_shape_[2] * 0.5 <= images_scaled_shape_[2])\n      self.assertTrue(\n          images_original_shape_[2] * 2.0 >= images_scaled_shape_[2])\n\n  def testRandomRGBtoGray(self):\n    preprocess_options = [(preprocessor.random_rgb_to_gray, {})]\n    images_original = self.createTestImages()\n    tensor_dict = {fields.InputDataFields.image: images_original}\n    tensor_dict = preprocessor.preprocess(tensor_dict, preprocess_options)\n    images_gray = tensor_dict[fields.InputDataFields.image]\n    images_gray_r, images_gray_g, images_gray_b = tf.split(\n        value=images_gray, num_or_size_splits=3, axis=3)\n    images_r, images_g, images_b = tf.split(\n        value=images_original, num_or_size_splits=3, axis=3)\n    images_r_diff1 = tf.squared_difference(tf.to_float(images_r),\n                                           tf.to_float(images_gray_r))\n    images_r_diff2 = tf.squared_difference(tf.to_float(images_gray_r),\n                                           tf.to_float(images_gray_g))\n    images_r_diff = tf.multiply(images_r_diff1, images_r_diff2)\n    images_g_diff1 = tf.squared_difference(tf.to_float(images_g),\n                                           tf.to_float(images_gray_g))\n    images_g_diff2 = tf.squared_difference(tf.to_float(images_gray_g),\n                                           tf.to_float(images_gray_b))\n    images_g_diff = tf.multiply(images_g_diff1, images_g_diff2)\n    images_b_diff1 = tf.squared_difference(tf.to_float(images_b),\n                                           tf.to_float(images_gray_b))\n    images_b_diff2 = tf.squared_difference(tf.to_float(images_gray_b),\n                                           tf.to_float(images_gray_r))\n    images_b_diff = tf.multiply(images_b_diff1, images_b_diff2)\n    image_zero1 = tf.constant(0, dtype=tf.float32, shape=[1, 4, 4, 1])\n    with self.test_session() as sess:\n      (images_r_diff_, images_g_diff_, images_b_diff_, image_zero1_) = sess.run(\n          [images_r_diff, images_g_diff, images_b_diff, image_zero1])\n      self.assertAllClose(images_r_diff_, image_zero1_)\n      self.assertAllClose(images_g_diff_, image_zero1_)\n      self.assertAllClose(images_b_diff_, image_zero1_)\n\n  def testRandomAdjustBrightness(self):\n    preprocessing_options = []\n    preprocessing_options.append((preprocessor.normalize_image, {\n        'original_minval': 0,\n        'original_maxval': 255,\n        'target_minval': 0,\n        'target_maxval': 1\n    }))\n    preprocessing_options.append((preprocessor.random_adjust_brightness, {}))\n    images_original = self.createTestImages()\n    tensor_dict = {fields.InputDataFields.image: images_original}\n    tensor_dict = preprocessor.preprocess(tensor_dict, preprocessing_options)\n    images_bright = tensor_dict[fields.InputDataFields.image]\n    image_original_shape = tf.shape(images_original)\n    image_bright_shape = tf.shape(images_bright)\n    with self.test_session() as sess:\n      (image_original_shape_, image_bright_shape_) = sess.run(\n          [image_original_shape, image_bright_shape])\n      self.assertAllEqual(image_original_shape_, image_bright_shape_)\n\n  def testRandomAdjustContrast(self):\n    preprocessing_options = []\n    preprocessing_options.append((preprocessor.normalize_image, {\n        'original_minval': 0,\n        'original_maxval': 255,\n        'target_minval': 0,\n        'target_maxval': 1\n    }))\n    preprocessing_options.append((preprocessor.random_adjust_contrast, {}))\n    images_original = self.createTestImages()\n    tensor_dict = {fields.InputDataFields.image: images_original}\n    tensor_dict = preprocessor.preprocess(tensor_dict, preprocessing_options)\n    images_contrast = tensor_dict[fields.InputDataFields.image]\n    image_original_shape = tf.shape(images_original)\n    image_contrast_shape = tf.shape(images_contrast)\n    with self.test_session() as sess:\n      (image_original_shape_, image_contrast_shape_) = sess.run(\n          [image_original_shape, image_contrast_shape])\n      self.assertAllEqual(image_original_shape_, image_contrast_shape_)\n\n  def testRandomAdjustHue(self):\n    preprocessing_options = []\n    preprocessing_options.append((preprocessor.normalize_image, {\n        'original_minval': 0,\n        'original_maxval': 255,\n        'target_minval': 0,\n        'target_maxval': 1\n    }))\n    preprocessing_options.append((preprocessor.random_adjust_hue, {}))\n    images_original = self.createTestImages()\n    tensor_dict = {fields.InputDataFields.image: images_original}\n    tensor_dict = preprocessor.preprocess(tensor_dict, preprocessing_options)\n    images_hue = tensor_dict[fields.InputDataFields.image]\n    image_original_shape = tf.shape(images_original)\n    image_hue_shape = tf.shape(images_hue)\n    with self.test_session() as sess:\n      (image_original_shape_, image_hue_shape_) = sess.run(\n          [image_original_shape, image_hue_shape])\n      self.assertAllEqual(image_original_shape_, image_hue_shape_)\n\n  def testRandomDistortColor(self):\n    preprocessing_options = []\n    preprocessing_options.append((preprocessor.normalize_image, {\n        'original_minval': 0,\n        'original_maxval': 255,\n        'target_minval': 0,\n        'target_maxval': 1\n    }))\n    preprocessing_options.append((preprocessor.random_distort_color, {}))\n    images_original = self.createTestImages()\n    images_original_shape = tf.shape(images_original)\n    tensor_dict = {fields.InputDataFields.image: images_original}\n    tensor_dict = preprocessor.preprocess(tensor_dict, preprocessing_options)\n    images_distorted_color = tensor_dict[fields.InputDataFields.image]\n    images_distorted_color_shape = tf.shape(images_distorted_color)\n    with self.test_session() as sess:\n      (images_original_shape_, images_distorted_color_shape_) = sess.run(\n          [images_original_shape, images_distorted_color_shape])\n      self.assertAllEqual(images_original_shape_, images_distorted_color_shape_)\n\n  def testRandomJitterBoxes(self):\n    preprocessing_options = []\n    preprocessing_options.append((preprocessor.random_jitter_boxes, {}))\n    boxes = self.createTestBoxes()\n    boxes_shape = tf.shape(boxes)\n    tensor_dict = {fields.InputDataFields.groundtruth_boxes: boxes}\n    tensor_dict = preprocessor.preprocess(tensor_dict, preprocessing_options)\n    distorted_boxes = tensor_dict[fields.InputDataFields.groundtruth_boxes]\n    distorted_boxes_shape = tf.shape(distorted_boxes)\n\n    with self.test_session() as sess:\n      (boxes_shape_, distorted_boxes_shape_) = sess.run(\n          [boxes_shape, distorted_boxes_shape])\n      self.assertAllEqual(boxes_shape_, distorted_boxes_shape_)\n\n  def testRandomCropImage(self):\n    preprocessing_options = []\n    preprocessing_options.append((preprocessor.normalize_image, {\n        'original_minval': 0,\n        'original_maxval': 255,\n        'target_minval': 0,\n        'target_maxval': 1\n    }))\n    preprocessing_options.append((preprocessor.random_crop_image, {}))\n    images = self.createTestImages()\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    tensor_dict = {fields.InputDataFields.image: images,\n                   fields.InputDataFields.groundtruth_boxes: boxes,\n                   fields.InputDataFields.groundtruth_classes: labels}\n    distorted_tensor_dict = preprocessor.preprocess(tensor_dict,\n                                                    preprocessing_options)\n    distorted_images = distorted_tensor_dict[fields.InputDataFields.image]\n    distorted_boxes = distorted_tensor_dict[\n        fields.InputDataFields.groundtruth_boxes]\n    boxes_rank = tf.rank(boxes)\n    distorted_boxes_rank = tf.rank(distorted_boxes)\n    images_rank = tf.rank(images)\n    distorted_images_rank = tf.rank(distorted_images)\n    self.assertEqual(3, distorted_images.get_shape()[3])\n\n    with self.test_session() as sess:\n      (boxes_rank_, distorted_boxes_rank_, images_rank_,\n       distorted_images_rank_) = sess.run([\n           boxes_rank, distorted_boxes_rank, images_rank, distorted_images_rank\n       ])\n      self.assertAllEqual(boxes_rank_, distorted_boxes_rank_)\n      self.assertAllEqual(images_rank_, distorted_images_rank_)\n\n  def testRandomCropImageGrayscale(self):\n    preprocessing_options = [(preprocessor.rgb_to_gray, {}),\n                             (preprocessor.normalize_image, {\n                                 'original_minval': 0,\n                                 'original_maxval': 255,\n                                 'target_minval': 0,\n                                 'target_maxval': 1,\n                             }),\n                             (preprocessor.random_crop_image, {})]\n    images = self.createTestImages()\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    tensor_dict = {\n        fields.InputDataFields.image: images,\n        fields.InputDataFields.groundtruth_boxes: boxes,\n        fields.InputDataFields.groundtruth_classes: labels\n    }\n    distorted_tensor_dict = preprocessor.preprocess(\n        tensor_dict, preprocessing_options)\n    distorted_images = distorted_tensor_dict[fields.InputDataFields.image]\n    distorted_boxes = distorted_tensor_dict[\n        fields.InputDataFields.groundtruth_boxes]\n    boxes_rank = tf.rank(boxes)\n    distorted_boxes_rank = tf.rank(distorted_boxes)\n    images_rank = tf.rank(images)\n    distorted_images_rank = tf.rank(distorted_images)\n    self.assertEqual(1, distorted_images.get_shape()[3])\n\n    with self.test_session() as sess:\n      session_results = sess.run([\n          boxes_rank, distorted_boxes_rank, images_rank, distorted_images_rank\n      ])\n      (boxes_rank_, distorted_boxes_rank_, images_rank_,\n       distorted_images_rank_) = session_results\n      self.assertAllEqual(boxes_rank_, distorted_boxes_rank_)\n      self.assertAllEqual(images_rank_, distorted_images_rank_)\n\n  def testRandomCropImageWithBoxOutOfImage(self):\n    preprocessing_options = []\n    preprocessing_options.append((preprocessor.normalize_image, {\n        'original_minval': 0,\n        'original_maxval': 255,\n        'target_minval': 0,\n        'target_maxval': 1\n    }))\n    preprocessing_options.append((preprocessor.random_crop_image, {}))\n    images = self.createTestImages()\n    boxes = self.createTestBoxesOutOfImage()\n    labels = self.createTestLabels()\n    tensor_dict = {fields.InputDataFields.image: images,\n                   fields.InputDataFields.groundtruth_boxes: boxes,\n                   fields.InputDataFields.groundtruth_classes: labels}\n    distorted_tensor_dict = preprocessor.preprocess(tensor_dict,\n                                                    preprocessing_options)\n    distorted_images = distorted_tensor_dict[fields.InputDataFields.image]\n    distorted_boxes = distorted_tensor_dict[\n        fields.InputDataFields.groundtruth_boxes]\n    boxes_rank = tf.rank(boxes)\n    distorted_boxes_rank = tf.rank(distorted_boxes)\n    images_rank = tf.rank(images)\n    distorted_images_rank = tf.rank(distorted_images)\n\n    with self.test_session() as sess:\n      (boxes_rank_, distorted_boxes_rank_, images_rank_,\n       distorted_images_rank_) = sess.run(\n           [boxes_rank, distorted_boxes_rank, images_rank,\n            distorted_images_rank])\n      self.assertAllEqual(boxes_rank_, distorted_boxes_rank_)\n      self.assertAllEqual(images_rank_, distorted_images_rank_)\n\n  def testRandomCropImageWithRandomCoefOne(self):\n    preprocessing_options = [(preprocessor.normalize_image, {\n        'original_minval': 0,\n        'original_maxval': 255,\n        'target_minval': 0,\n        'target_maxval': 1\n    })]\n\n    images = self.createTestImages()\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    tensor_dict = {fields.InputDataFields.image: images,\n                   fields.InputDataFields.groundtruth_boxes: boxes,\n                   fields.InputDataFields.groundtruth_classes: labels}\n    tensor_dict = preprocessor.preprocess(tensor_dict, preprocessing_options)\n    images = tensor_dict[fields.InputDataFields.image]\n\n    preprocessing_options = [(preprocessor.random_crop_image, {\n        'random_coef': 1.0\n    })]\n    distorted_tensor_dict = preprocessor.preprocess(tensor_dict,\n                                                    preprocessing_options)\n\n    distorted_images = distorted_tensor_dict[fields.InputDataFields.image]\n    distorted_boxes = distorted_tensor_dict[\n        fields.InputDataFields.groundtruth_boxes]\n    distorted_labels = distorted_tensor_dict[\n        fields.InputDataFields.groundtruth_classes]\n    boxes_shape = tf.shape(boxes)\n    distorted_boxes_shape = tf.shape(distorted_boxes)\n    images_shape = tf.shape(images)\n    distorted_images_shape = tf.shape(distorted_images)\n\n    with self.test_session() as sess:\n      (boxes_shape_, distorted_boxes_shape_, images_shape_,\n       distorted_images_shape_, images_, distorted_images_,\n       boxes_, distorted_boxes_, labels_, distorted_labels_) = sess.run(\n           [boxes_shape, distorted_boxes_shape, images_shape,\n            distorted_images_shape, images, distorted_images,\n            boxes, distorted_boxes, labels, distorted_labels])\n      self.assertAllEqual(boxes_shape_, distorted_boxes_shape_)\n      self.assertAllEqual(images_shape_, distorted_images_shape_)\n      self.assertAllClose(images_, distorted_images_)\n      self.assertAllClose(boxes_, distorted_boxes_)\n      self.assertAllEqual(labels_, distorted_labels_)\n\n  def testRandomCropWithMockSampleDistortedBoundingBox(self):\n    preprocessing_options = [(preprocessor.normalize_image, {\n        'original_minval': 0,\n        'original_maxval': 255,\n        'target_minval': 0,\n        'target_maxval': 1\n    })]\n\n    images = self.createColorfulTestImage()\n    boxes = tf.constant([[0.1, 0.1, 0.8, 0.3],\n                         [0.2, 0.4, 0.75, 0.75],\n                         [0.3, 0.1, 0.4, 0.7]], dtype=tf.float32)\n    labels = tf.constant([1, 7, 11], dtype=tf.int32)\n    tensor_dict = {fields.InputDataFields.image: images,\n                   fields.InputDataFields.groundtruth_boxes: boxes,\n                   fields.InputDataFields.groundtruth_classes: labels}\n    tensor_dict = preprocessor.preprocess(tensor_dict, preprocessing_options)\n    images = tensor_dict[fields.InputDataFields.image]\n\n    preprocessing_options = [(preprocessor.random_crop_image, {})]\n    with mock.patch.object(\n        tf.image,\n        'sample_distorted_bounding_box') as mock_sample_distorted_bounding_box:\n      mock_sample_distorted_bounding_box.return_value = (tf.constant(\n          [6, 143, 0], dtype=tf.int32), tf.constant(\n              [190, 237, -1], dtype=tf.int32), tf.constant(\n                  [[[0.03, 0.3575, 0.98, 0.95]]], dtype=tf.float32))\n\n      distorted_tensor_dict = preprocessor.preprocess(tensor_dict,\n                                                      preprocessing_options)\n\n      distorted_boxes = distorted_tensor_dict[\n          fields.InputDataFields.groundtruth_boxes]\n      distorted_labels = distorted_tensor_dict[\n          fields.InputDataFields.groundtruth_classes]\n      expected_boxes = tf.constant([[0.178947, 0.07173, 0.75789469, 0.66244733],\n                                    [0.28421, 0.0, 0.38947365, 0.57805908]],\n                                   dtype=tf.float32)\n      expected_labels = tf.constant([7, 11], dtype=tf.int32)\n\n      with self.test_session() as sess:\n        (distorted_boxes_, distorted_labels_,\n         expected_boxes_, expected_labels_) = sess.run(\n             [distorted_boxes, distorted_labels,\n              expected_boxes, expected_labels])\n        self.assertAllClose(distorted_boxes_, expected_boxes_)\n        self.assertAllEqual(distorted_labels_, expected_labels_)\n\n  def testStrictRandomCropImageWithMasks(self):\n    image = self.createColorfulTestImage()[0]\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    masks = tf.random_uniform([2, 200, 400], dtype=tf.float32)\n    with mock.patch.object(\n        tf.image,\n        'sample_distorted_bounding_box'\n    ) as mock_sample_distorted_bounding_box:\n      mock_sample_distorted_bounding_box.return_value = (\n          tf.constant([6, 143, 0], dtype=tf.int32),\n          tf.constant([190, 237, -1], dtype=tf.int32),\n          tf.constant([[[0.03, 0.3575, 0.98, 0.95]]], dtype=tf.float32))\n      (new_image, new_boxes, new_labels,\n       new_masks) = preprocessor._strict_random_crop_image(\n           image, boxes, labels, masks=masks)\n      with self.test_session() as sess:\n        new_image, new_boxes, new_labels, new_masks = sess.run([\n            new_image, new_boxes, new_labels, new_masks])\n\n        expected_boxes = np.array([\n            [0.0, 0.0, 0.75789469, 1.0],\n            [0.23157893, 0.24050637, 0.75789469, 1.0],\n        ], dtype=np.float32)\n        self.assertAllEqual(new_image.shape, [190, 237, 3])\n        self.assertAllEqual(new_masks.shape, [2, 190, 237])\n        self.assertAllClose(\n            new_boxes.flatten(), expected_boxes.flatten())\n\n  def testStrictRandomCropImageWithKeypoints(self):\n    image = self.createColorfulTestImage()[0]\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    keypoints = self.createTestKeypoints()\n    with mock.patch.object(\n        tf.image,\n        'sample_distorted_bounding_box'\n    ) as mock_sample_distorted_bounding_box:\n      mock_sample_distorted_bounding_box.return_value = (\n          tf.constant([6, 143, 0], dtype=tf.int32),\n          tf.constant([190, 237, -1], dtype=tf.int32),\n          tf.constant([[[0.03, 0.3575, 0.98, 0.95]]], dtype=tf.float32))\n      (new_image, new_boxes, new_labels,\n       new_keypoints) = preprocessor._strict_random_crop_image(\n           image, boxes, labels, keypoints=keypoints)\n      with self.test_session() as sess:\n        new_image, new_boxes, new_labels, new_keypoints = sess.run([\n            new_image, new_boxes, new_labels, new_keypoints])\n\n        expected_boxes = np.array([\n            [0.0, 0.0, 0.75789469, 1.0],\n            [0.23157893, 0.24050637, 0.75789469, 1.0],\n        ], dtype=np.float32)\n        expected_keypoints = np.array([\n            [[np.nan, np.nan],\n             [np.nan, np.nan],\n             [np.nan, np.nan]],\n            [[0.38947368, 0.07173],\n             [0.49473682, 0.24050637],\n             [0.60000002, 0.40928277]]\n        ], dtype=np.float32)\n        self.assertAllEqual(new_image.shape, [190, 237, 3])\n        self.assertAllClose(\n            new_boxes.flatten(), expected_boxes.flatten())\n        self.assertAllClose(\n            new_keypoints.flatten(), expected_keypoints.flatten())\n\n  def testRunRandomCropImageWithMasks(self):\n    image = self.createColorfulTestImage()\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    masks = tf.random_uniform([2, 200, 400], dtype=tf.float32)\n\n    tensor_dict = {\n        fields.InputDataFields.image: image,\n        fields.InputDataFields.groundtruth_boxes: boxes,\n        fields.InputDataFields.groundtruth_classes: labels,\n        fields.InputDataFields.groundtruth_instance_masks: masks,\n    }\n\n    preprocessor_arg_map = preprocessor.get_default_func_arg_map(\n        include_instance_masks=True)\n\n    preprocessing_options = [(preprocessor.random_crop_image, {})]\n\n    with mock.patch.object(\n        tf.image,\n        'sample_distorted_bounding_box'\n    ) as mock_sample_distorted_bounding_box:\n      mock_sample_distorted_bounding_box.return_value = (\n          tf.constant([6, 143, 0], dtype=tf.int32),\n          tf.constant([190, 237, -1], dtype=tf.int32),\n          tf.constant([[[0.03, 0.3575, 0.98, 0.95]]], dtype=tf.float32))\n      distorted_tensor_dict = preprocessor.preprocess(\n          tensor_dict, preprocessing_options, func_arg_map=preprocessor_arg_map)\n      distorted_image = distorted_tensor_dict[fields.InputDataFields.image]\n      distorted_boxes = distorted_tensor_dict[\n          fields.InputDataFields.groundtruth_boxes]\n      distorted_labels = distorted_tensor_dict[\n          fields.InputDataFields.groundtruth_classes]\n      distorted_masks = distorted_tensor_dict[\n          fields.InputDataFields.groundtruth_instance_masks]\n      with self.test_session() as sess:\n        (distorted_image_, distorted_boxes_, distorted_labels_,\n         distorted_masks_) = sess.run(\n             [distorted_image, distorted_boxes, distorted_labels,\n              distorted_masks])\n\n        expected_boxes = np.array([\n            [0.0, 0.0, 0.75789469, 1.0],\n            [0.23157893, 0.24050637, 0.75789469, 1.0],\n        ], dtype=np.float32)\n        self.assertAllEqual(distorted_image_.shape, [1, 190, 237, 3])\n        self.assertAllEqual(distorted_masks_.shape, [2, 190, 237])\n        self.assertAllEqual(distorted_labels_, [1, 2])\n        self.assertAllClose(\n            distorted_boxes_.flatten(), expected_boxes.flatten())\n\n  def testRunRandomCropImageWithKeypointsInsideCrop(self):\n    image = self.createColorfulTestImage()\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    keypoints = self.createTestKeypointsInsideCrop()\n\n    tensor_dict = {\n        fields.InputDataFields.image: image,\n        fields.InputDataFields.groundtruth_boxes: boxes,\n        fields.InputDataFields.groundtruth_classes: labels,\n        fields.InputDataFields.groundtruth_keypoints: keypoints\n    }\n\n    preprocessor_arg_map = preprocessor.get_default_func_arg_map(\n        include_keypoints=True)\n\n    preprocessing_options = [(preprocessor.random_crop_image, {})]\n\n    with mock.patch.object(\n        tf.image,\n        'sample_distorted_bounding_box'\n    ) as mock_sample_distorted_bounding_box:\n      mock_sample_distorted_bounding_box.return_value = (\n          tf.constant([6, 143, 0], dtype=tf.int32),\n          tf.constant([190, 237, -1], dtype=tf.int32),\n          tf.constant([[[0.03, 0.3575, 0.98, 0.95]]], dtype=tf.float32))\n      distorted_tensor_dict = preprocessor.preprocess(\n          tensor_dict, preprocessing_options, func_arg_map=preprocessor_arg_map)\n      distorted_image = distorted_tensor_dict[fields.InputDataFields.image]\n      distorted_boxes = distorted_tensor_dict[\n          fields.InputDataFields.groundtruth_boxes]\n      distorted_labels = distorted_tensor_dict[\n          fields.InputDataFields.groundtruth_classes]\n      distorted_keypoints = distorted_tensor_dict[\n          fields.InputDataFields.groundtruth_keypoints]\n      with self.test_session() as sess:\n        (distorted_image_, distorted_boxes_, distorted_labels_,\n         distorted_keypoints_) = sess.run(\n             [distorted_image, distorted_boxes, distorted_labels,\n              distorted_keypoints])\n\n        expected_boxes = np.array([\n            [0.0, 0.0, 0.75789469, 1.0],\n            [0.23157893, 0.24050637, 0.75789469, 1.0],\n        ], dtype=np.float32)\n        expected_keypoints = np.array([\n            [[0.38947368, 0.07173],\n             [0.49473682, 0.24050637],\n             [0.60000002, 0.40928277]],\n            [[0.38947368, 0.07173],\n             [0.49473682, 0.24050637],\n             [0.60000002, 0.40928277]]\n        ])\n        self.assertAllEqual(distorted_image_.shape, [1, 190, 237, 3])\n        self.assertAllEqual(distorted_labels_, [1, 2])\n        self.assertAllClose(\n            distorted_boxes_.flatten(), expected_boxes.flatten())\n        self.assertAllClose(\n            distorted_keypoints_.flatten(), expected_keypoints.flatten())\n\n  def testRunRandomCropImageWithKeypointsOutsideCrop(self):\n    image = self.createColorfulTestImage()\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    keypoints = self.createTestKeypointsOutsideCrop()\n\n    tensor_dict = {\n        fields.InputDataFields.image: image,\n        fields.InputDataFields.groundtruth_boxes: boxes,\n        fields.InputDataFields.groundtruth_classes: labels,\n        fields.InputDataFields.groundtruth_keypoints: keypoints\n    }\n\n    preprocessor_arg_map = preprocessor.get_default_func_arg_map(\n        include_keypoints=True)\n\n    preprocessing_options = [(preprocessor.random_crop_image, {})]\n\n    with mock.patch.object(\n        tf.image,\n        'sample_distorted_bounding_box'\n    ) as mock_sample_distorted_bounding_box:\n      mock_sample_distorted_bounding_box.return_value = (\n          tf.constant([6, 143, 0], dtype=tf.int32),\n          tf.constant([190, 237, -1], dtype=tf.int32),\n          tf.constant([[[0.03, 0.3575, 0.98, 0.95]]], dtype=tf.float32))\n      distorted_tensor_dict = preprocessor.preprocess(\n          tensor_dict, preprocessing_options, func_arg_map=preprocessor_arg_map)\n      distorted_image = distorted_tensor_dict[fields.InputDataFields.image]\n      distorted_boxes = distorted_tensor_dict[\n          fields.InputDataFields.groundtruth_boxes]\n      distorted_labels = distorted_tensor_dict[\n          fields.InputDataFields.groundtruth_classes]\n      distorted_keypoints = distorted_tensor_dict[\n          fields.InputDataFields.groundtruth_keypoints]\n      with self.test_session() as sess:\n        (distorted_image_, distorted_boxes_, distorted_labels_,\n         distorted_keypoints_) = sess.run(\n             [distorted_image, distorted_boxes, distorted_labels,\n              distorted_keypoints])\n\n        expected_boxes = np.array([\n            [0.0, 0.0, 0.75789469, 1.0],\n            [0.23157893, 0.24050637, 0.75789469, 1.0],\n        ], dtype=np.float32)\n        expected_keypoints = np.array([\n            [[np.nan, np.nan],\n             [np.nan, np.nan],\n             [np.nan, np.nan]],\n            [[np.nan, np.nan],\n             [np.nan, np.nan],\n             [np.nan, np.nan]],\n        ])\n        self.assertAllEqual(distorted_image_.shape, [1, 190, 237, 3])\n        self.assertAllEqual(distorted_labels_, [1, 2])\n        self.assertAllClose(\n            distorted_boxes_.flatten(), expected_boxes.flatten())\n        self.assertAllClose(\n            distorted_keypoints_.flatten(), expected_keypoints.flatten())\n\n  def testRunRetainBoxesAboveThreshold(self):\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    label_scores = self.createTestLabelScores()\n\n    tensor_dict = {\n        fields.InputDataFields.groundtruth_boxes: boxes,\n        fields.InputDataFields.groundtruth_classes: labels,\n        fields.InputDataFields.groundtruth_label_scores: label_scores\n    }\n\n    preprocessing_options = [\n        (preprocessor.retain_boxes_above_threshold, {'threshold': 0.6})\n    ]\n\n    retained_tensor_dict = preprocessor.preprocess(\n        tensor_dict, preprocessing_options)\n    retained_boxes = retained_tensor_dict[\n        fields.InputDataFields.groundtruth_boxes]\n    retained_labels = retained_tensor_dict[\n        fields.InputDataFields.groundtruth_classes]\n    retained_label_scores = retained_tensor_dict[\n        fields.InputDataFields.groundtruth_label_scores]\n\n    with self.test_session() as sess:\n      (retained_boxes_, retained_labels_,\n       retained_label_scores_, expected_retained_boxes_,\n       expected_retained_labels_, expected_retained_label_scores_) = sess.run(\n           [retained_boxes, retained_labels, retained_label_scores,\n            self.expectedBoxesAfterThresholding(),\n            self.expectedLabelsAfterThresholding(),\n            self.expectedLabelScoresAfterThresholding()])\n\n      self.assertAllClose(retained_boxes_, expected_retained_boxes_)\n      self.assertAllClose(retained_labels_, expected_retained_labels_)\n      self.assertAllClose(\n          retained_label_scores_, expected_retained_label_scores_)\n\n  def testRunRetainBoxesAboveThresholdWithMasks(self):\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    label_scores = self.createTestLabelScores()\n    masks = self.createTestMasks()\n\n    tensor_dict = {\n        fields.InputDataFields.groundtruth_boxes: boxes,\n        fields.InputDataFields.groundtruth_classes: labels,\n        fields.InputDataFields.groundtruth_label_scores: label_scores,\n        fields.InputDataFields.groundtruth_instance_masks: masks\n    }\n\n    preprocessor_arg_map = preprocessor.get_default_func_arg_map(\n        include_instance_masks=True)\n\n    preprocessing_options = [\n        (preprocessor.retain_boxes_above_threshold, {'threshold': 0.6})\n    ]\n\n    retained_tensor_dict = preprocessor.preprocess(\n        tensor_dict, preprocessing_options, func_arg_map=preprocessor_arg_map)\n    retained_masks = retained_tensor_dict[\n        fields.InputDataFields.groundtruth_instance_masks]\n\n    with self.test_session() as sess:\n      (retained_masks_, expected_masks_) = sess.run(\n          [retained_masks,\n           self.expectedMasksAfterThresholding()])\n      self.assertAllClose(retained_masks_, expected_masks_)\n\n  def testRunRetainBoxesAboveThresholdWithKeypoints(self):\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    label_scores = self.createTestLabelScores()\n    keypoints = self.createTestKeypoints()\n\n    tensor_dict = {\n        fields.InputDataFields.groundtruth_boxes: boxes,\n        fields.InputDataFields.groundtruth_classes: labels,\n        fields.InputDataFields.groundtruth_label_scores: label_scores,\n        fields.InputDataFields.groundtruth_keypoints: keypoints\n    }\n\n    preprocessor_arg_map = preprocessor.get_default_func_arg_map(\n        include_keypoints=True)\n\n    preprocessing_options = [\n        (preprocessor.retain_boxes_above_threshold, {'threshold': 0.6})\n    ]\n\n    retained_tensor_dict = preprocessor.preprocess(\n        tensor_dict, preprocessing_options, func_arg_map=preprocessor_arg_map)\n    retained_keypoints = retained_tensor_dict[\n        fields.InputDataFields.groundtruth_keypoints]\n\n    with self.test_session() as sess:\n      (retained_keypoints_, expected_keypoints_) = sess.run(\n          [retained_keypoints,\n           self.expectedKeypointsAfterThresholding()])\n      self.assertAllClose(retained_keypoints_, expected_keypoints_)\n\n  def testRunRandomCropToAspectRatioWithMasks(self):\n    image = self.createColorfulTestImage()\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    masks = tf.random_uniform([2, 200, 400], dtype=tf.float32)\n\n    tensor_dict = {\n        fields.InputDataFields.image: image,\n        fields.InputDataFields.groundtruth_boxes: boxes,\n        fields.InputDataFields.groundtruth_classes: labels,\n        fields.InputDataFields.groundtruth_instance_masks: masks\n    }\n\n    preprocessor_arg_map = preprocessor.get_default_func_arg_map(\n        include_instance_masks=True)\n\n    preprocessing_options = [(preprocessor.random_crop_to_aspect_ratio, {})]\n\n    with mock.patch.object(preprocessor,\n                           '_random_integer') as mock_random_integer:\n      mock_random_integer.return_value = tf.constant(0, dtype=tf.int32)\n      distorted_tensor_dict = preprocessor.preprocess(\n          tensor_dict, preprocessing_options, func_arg_map=preprocessor_arg_map)\n      distorted_image = distorted_tensor_dict[fields.InputDataFields.image]\n      distorted_boxes = distorted_tensor_dict[\n          fields.InputDataFields.groundtruth_boxes]\n      distorted_labels = distorted_tensor_dict[\n          fields.InputDataFields.groundtruth_classes]\n      distorted_masks = distorted_tensor_dict[\n          fields.InputDataFields.groundtruth_instance_masks]\n      with self.test_session() as sess:\n        (distorted_image_, distorted_boxes_, distorted_labels_,\n         distorted_masks_) = sess.run([\n             distorted_image, distorted_boxes, distorted_labels, distorted_masks\n         ])\n\n        expected_boxes = np.array([0.0, 0.5, 0.75, 1.0], dtype=np.float32)\n        self.assertAllEqual(distorted_image_.shape, [1, 200, 200, 3])\n        self.assertAllEqual(distorted_labels_, [1])\n        self.assertAllClose(distorted_boxes_.flatten(),\n                            expected_boxes.flatten())\n        self.assertAllEqual(distorted_masks_.shape, [1, 200, 200])\n\n  def testRunRandomCropToAspectRatioWithKeypoints(self):\n    image = self.createColorfulTestImage()\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    keypoints = self.createTestKeypoints()\n\n    tensor_dict = {\n        fields.InputDataFields.image: image,\n        fields.InputDataFields.groundtruth_boxes: boxes,\n        fields.InputDataFields.groundtruth_classes: labels,\n        fields.InputDataFields.groundtruth_keypoints: keypoints\n    }\n\n    preprocessor_arg_map = preprocessor.get_default_func_arg_map(\n        include_keypoints=True)\n\n    preprocessing_options = [(preprocessor.random_crop_to_aspect_ratio, {})]\n\n    with mock.patch.object(preprocessor,\n                           '_random_integer') as mock_random_integer:\n      mock_random_integer.return_value = tf.constant(0, dtype=tf.int32)\n      distorted_tensor_dict = preprocessor.preprocess(\n          tensor_dict, preprocessing_options, func_arg_map=preprocessor_arg_map)\n      distorted_image = distorted_tensor_dict[fields.InputDataFields.image]\n      distorted_boxes = distorted_tensor_dict[\n          fields.InputDataFields.groundtruth_boxes]\n      distorted_labels = distorted_tensor_dict[\n          fields.InputDataFields.groundtruth_classes]\n      distorted_keypoints = distorted_tensor_dict[\n          fields.InputDataFields.groundtruth_keypoints]\n      with self.test_session() as sess:\n        (distorted_image_, distorted_boxes_, distorted_labels_,\n         distorted_keypoints_) = sess.run([\n             distorted_image, distorted_boxes, distorted_labels,\n             distorted_keypoints\n         ])\n\n        expected_boxes = np.array([0.0, 0.5, 0.75, 1.0], dtype=np.float32)\n        expected_keypoints = np.array(\n            [[0.1, 0.2], [0.2, 0.4], [0.3, 0.6]], dtype=np.float32)\n        self.assertAllEqual(distorted_image_.shape, [1, 200, 200, 3])\n        self.assertAllEqual(distorted_labels_, [1])\n        self.assertAllClose(distorted_boxes_.flatten(),\n                            expected_boxes.flatten())\n        self.assertAllClose(distorted_keypoints_.flatten(),\n                            expected_keypoints.flatten())\n\n  def testRandomPadImage(self):\n    preprocessing_options = [(preprocessor.normalize_image, {\n        'original_minval': 0,\n        'original_maxval': 255,\n        'target_minval': 0,\n        'target_maxval': 1\n    })]\n\n    images = self.createTestImages()\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    tensor_dict = {fields.InputDataFields.image: images,\n                   fields.InputDataFields.groundtruth_boxes: boxes,\n                   fields.InputDataFields.groundtruth_classes: labels}\n    tensor_dict = preprocessor.preprocess(tensor_dict, preprocessing_options)\n    images = tensor_dict[fields.InputDataFields.image]\n\n    preprocessing_options = [(preprocessor.random_pad_image, {})]\n    padded_tensor_dict = preprocessor.preprocess(tensor_dict,\n                                                 preprocessing_options)\n\n    padded_images = padded_tensor_dict[fields.InputDataFields.image]\n    padded_boxes = padded_tensor_dict[\n        fields.InputDataFields.groundtruth_boxes]\n    boxes_shape = tf.shape(boxes)\n    padded_boxes_shape = tf.shape(padded_boxes)\n    images_shape = tf.shape(images)\n    padded_images_shape = tf.shape(padded_images)\n\n    with self.test_session() as sess:\n      (boxes_shape_, padded_boxes_shape_, images_shape_,\n       padded_images_shape_, boxes_, padded_boxes_) = sess.run(\n           [boxes_shape, padded_boxes_shape, images_shape,\n            padded_images_shape, boxes, padded_boxes])\n      self.assertAllEqual(boxes_shape_, padded_boxes_shape_)\n      self.assertTrue((images_shape_[1] >= padded_images_shape_[1] * 0.5).all)\n      self.assertTrue((images_shape_[2] >= padded_images_shape_[2] * 0.5).all)\n      self.assertTrue((images_shape_[1] <= padded_images_shape_[1]).all)\n      self.assertTrue((images_shape_[2] <= padded_images_shape_[2]).all)\n      self.assertTrue(np.all((boxes_[:, 2] - boxes_[:, 0]) >= (\n          padded_boxes_[:, 2] - padded_boxes_[:, 0])))\n      self.assertTrue(np.all((boxes_[:, 3] - boxes_[:, 1]) >= (\n          padded_boxes_[:, 3] - padded_boxes_[:, 1])))\n\n  def testRandomCropPadImageWithRandomCoefOne(self):\n    preprocessing_options = [(preprocessor.normalize_image, {\n        'original_minval': 0,\n        'original_maxval': 255,\n        'target_minval': 0,\n        'target_maxval': 1\n    })]\n\n    images = self.createTestImages()\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    tensor_dict = {fields.InputDataFields.image: images,\n                   fields.InputDataFields.groundtruth_boxes: boxes,\n                   fields.InputDataFields.groundtruth_classes: labels}\n    tensor_dict = preprocessor.preprocess(tensor_dict, preprocessing_options)\n    images = tensor_dict[fields.InputDataFields.image]\n\n    preprocessing_options = [(preprocessor.random_crop_pad_image, {\n        'random_coef': 1.0\n    })]\n    padded_tensor_dict = preprocessor.preprocess(tensor_dict,\n                                                 preprocessing_options)\n\n    padded_images = padded_tensor_dict[fields.InputDataFields.image]\n    padded_boxes = padded_tensor_dict[\n        fields.InputDataFields.groundtruth_boxes]\n    boxes_shape = tf.shape(boxes)\n    padded_boxes_shape = tf.shape(padded_boxes)\n    images_shape = tf.shape(images)\n    padded_images_shape = tf.shape(padded_images)\n\n    with self.test_session() as sess:\n      (boxes_shape_, padded_boxes_shape_, images_shape_,\n       padded_images_shape_, boxes_, padded_boxes_) = sess.run(\n           [boxes_shape, padded_boxes_shape, images_shape,\n            padded_images_shape, boxes, padded_boxes])\n      self.assertAllEqual(boxes_shape_, padded_boxes_shape_)\n      self.assertTrue((images_shape_[1] >= padded_images_shape_[1] * 0.5).all)\n      self.assertTrue((images_shape_[2] >= padded_images_shape_[2] * 0.5).all)\n      self.assertTrue((images_shape_[1] <= padded_images_shape_[1]).all)\n      self.assertTrue((images_shape_[2] <= padded_images_shape_[2]).all)\n      self.assertTrue(np.all((boxes_[:, 2] - boxes_[:, 0]) >= (\n          padded_boxes_[:, 2] - padded_boxes_[:, 0])))\n      self.assertTrue(np.all((boxes_[:, 3] - boxes_[:, 1]) >= (\n          padded_boxes_[:, 3] - padded_boxes_[:, 1])))\n\n  def testRandomCropToAspectRatio(self):\n    preprocessing_options = [(preprocessor.normalize_image, {\n        'original_minval': 0,\n        'original_maxval': 255,\n        'target_minval': 0,\n        'target_maxval': 1\n    })]\n\n    images = self.createTestImages()\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    tensor_dict = {\n        fields.InputDataFields.image: images,\n        fields.InputDataFields.groundtruth_boxes: boxes,\n        fields.InputDataFields.groundtruth_classes: labels\n    }\n    tensor_dict = preprocessor.preprocess(tensor_dict, preprocessing_options)\n    images = tensor_dict[fields.InputDataFields.image]\n\n    preprocessing_options = [(preprocessor.random_crop_to_aspect_ratio, {\n        'aspect_ratio': 2.0\n    })]\n    cropped_tensor_dict = preprocessor.preprocess(tensor_dict,\n                                                  preprocessing_options)\n\n    cropped_images = cropped_tensor_dict[fields.InputDataFields.image]\n    cropped_boxes = cropped_tensor_dict[\n        fields.InputDataFields.groundtruth_boxes]\n    boxes_shape = tf.shape(boxes)\n    cropped_boxes_shape = tf.shape(cropped_boxes)\n    images_shape = tf.shape(images)\n    cropped_images_shape = tf.shape(cropped_images)\n\n    with self.test_session() as sess:\n      (boxes_shape_, cropped_boxes_shape_, images_shape_,\n       cropped_images_shape_) = sess.run([\n           boxes_shape, cropped_boxes_shape, images_shape, cropped_images_shape\n       ])\n      self.assertAllEqual(boxes_shape_, cropped_boxes_shape_)\n      self.assertEqual(images_shape_[1], cropped_images_shape_[1] * 2)\n      self.assertEqual(images_shape_[2], cropped_images_shape_[2])\n\n  def testRandomBlackPatches(self):\n    preprocessing_options = []\n    preprocessing_options.append((preprocessor.normalize_image, {\n        'original_minval': 0,\n        'original_maxval': 255,\n        'target_minval': 0,\n        'target_maxval': 1\n    }))\n    preprocessing_options.append((preprocessor.random_black_patches, {\n        'size_to_image_ratio': 0.5\n    }))\n    images = self.createTestImages()\n    tensor_dict = {fields.InputDataFields.image: images}\n    blacked_tensor_dict = preprocessor.preprocess(tensor_dict,\n                                                  preprocessing_options)\n    blacked_images = blacked_tensor_dict[fields.InputDataFields.image]\n    images_shape = tf.shape(images)\n    blacked_images_shape = tf.shape(blacked_images)\n\n    with self.test_session() as sess:\n      (images_shape_, blacked_images_shape_) = sess.run(\n          [images_shape, blacked_images_shape])\n      self.assertAllEqual(images_shape_, blacked_images_shape_)\n\n  def testRandomResizeMethod(self):\n    preprocessing_options = []\n    preprocessing_options.append((preprocessor.normalize_image, {\n        'original_minval': 0,\n        'original_maxval': 255,\n        'target_minval': 0,\n        'target_maxval': 1\n    }))\n    preprocessing_options.append((preprocessor.random_resize_method, {\n        'target_size': (75, 150)\n    }))\n    images = self.createTestImages()\n    tensor_dict = {fields.InputDataFields.image: images}\n    resized_tensor_dict = preprocessor.preprocess(tensor_dict,\n                                                  preprocessing_options)\n    resized_images = resized_tensor_dict[fields.InputDataFields.image]\n    resized_images_shape = tf.shape(resized_images)\n    expected_images_shape = tf.constant([1, 75, 150, 3], dtype=tf.int32)\n\n    with self.test_session() as sess:\n      (expected_images_shape_, resized_images_shape_) = sess.run(\n          [expected_images_shape, resized_images_shape])\n      self.assertAllEqual(expected_images_shape_,\n                          resized_images_shape_)\n\n  def testResizeToRange(self):\n    \"\"\"Tests image resizing, checking output sizes.\"\"\"\n    in_shape_list = [[60, 40, 3], [15, 30, 3], [15, 50, 3]]\n    min_dim = 50\n    max_dim = 100\n    expected_shape_list = [[75, 50, 3], [50, 100, 3], [30, 100, 3]]\n\n    for in_shape, expected_shape in zip(in_shape_list, expected_shape_list):\n      in_image = tf.random_uniform(in_shape)\n      out_image = preprocessor.resize_to_range(\n          in_image, min_dimension=min_dim, max_dimension=max_dim)\n      out_image_shape = tf.shape(out_image)\n\n      with self.test_session() as sess:\n        out_image_shape = sess.run(out_image_shape)\n        self.assertAllEqual(out_image_shape, expected_shape)\n\n  def testResizeToRangeWithMasks(self):\n    \"\"\"Tests image resizing, checking output sizes.\"\"\"\n    in_image_shape_list = [[60, 40, 3], [15, 30, 3]]\n    in_masks_shape_list = [[15, 60, 40], [10, 15, 30]]\n    min_dim = 50\n    max_dim = 100\n    expected_image_shape_list = [[75, 50, 3], [50, 100, 3]]\n    expected_masks_shape_list = [[15, 75, 50], [10, 50, 100]]\n\n    for (in_image_shape, expected_image_shape, in_masks_shape,\n         expected_mask_shape) in zip(in_image_shape_list,\n                                     expected_image_shape_list,\n                                     in_masks_shape_list,\n                                     expected_masks_shape_list):\n      in_image = tf.random_uniform(in_image_shape)\n      in_masks = tf.random_uniform(in_masks_shape)\n      out_image, out_masks = preprocessor.resize_to_range(\n          in_image, in_masks, min_dimension=min_dim, max_dimension=max_dim)\n      out_image_shape = tf.shape(out_image)\n      out_masks_shape = tf.shape(out_masks)\n\n      with self.test_session() as sess:\n        out_image_shape, out_masks_shape = sess.run(\n            [out_image_shape, out_masks_shape])\n        self.assertAllEqual(out_image_shape, expected_image_shape)\n        self.assertAllEqual(out_masks_shape, expected_mask_shape)\n\n  def testResizeToRangeWithNoInstanceMask(self):\n    \"\"\"Tests image resizing, checking output sizes.\"\"\"\n    in_image_shape_list = [[60, 40, 3], [15, 30, 3]]\n    in_masks_shape_list = [[0, 60, 40], [0, 15, 30]]\n    min_dim = 50\n    max_dim = 100\n    expected_image_shape_list = [[75, 50, 3], [50, 100, 3]]\n    expected_masks_shape_list = [[0, 75, 50], [0, 50, 100]]\n\n    for (in_image_shape, expected_image_shape, in_masks_shape,\n         expected_mask_shape) in zip(in_image_shape_list,\n                                     expected_image_shape_list,\n                                     in_masks_shape_list,\n                                     expected_masks_shape_list):\n      in_image = tf.random_uniform(in_image_shape)\n      in_masks = tf.random_uniform(in_masks_shape)\n      out_image, out_masks = preprocessor.resize_to_range(\n          in_image, in_masks, min_dimension=min_dim, max_dimension=max_dim)\n      out_image_shape = tf.shape(out_image)\n      out_masks_shape = tf.shape(out_masks)\n\n      with self.test_session() as sess:\n        out_image_shape, out_masks_shape = sess.run(\n            [out_image_shape, out_masks_shape])\n        self.assertAllEqual(out_image_shape, expected_image_shape)\n        self.assertAllEqual(out_masks_shape, expected_mask_shape)\n\n  def testResizeImageWithMasks(self):\n    \"\"\"Tests image resizing, checking output sizes.\"\"\"\n    in_image_shape_list = [[60, 40, 3], [15, 30, 3]]\n    in_masks_shape_list = [[15, 60, 40], [10, 15, 30]]\n    height = 50\n    width = 100\n    expected_image_shape_list = [[50, 100, 3], [50, 100, 3]]\n    expected_masks_shape_list = [[15, 50, 100], [10, 50, 100]]\n\n    for (in_image_shape, expected_image_shape, in_masks_shape,\n         expected_mask_shape) in zip(in_image_shape_list,\n                                     expected_image_shape_list,\n                                     in_masks_shape_list,\n                                     expected_masks_shape_list):\n      in_image = tf.random_uniform(in_image_shape)\n      in_masks = tf.random_uniform(in_masks_shape)\n      out_image, out_masks = preprocessor.resize_image(\n          in_image, in_masks, new_height=height, new_width=width)\n      out_image_shape = tf.shape(out_image)\n      out_masks_shape = tf.shape(out_masks)\n\n      with self.test_session() as sess:\n        out_image_shape, out_masks_shape = sess.run(\n            [out_image_shape, out_masks_shape])\n        self.assertAllEqual(out_image_shape, expected_image_shape)\n        self.assertAllEqual(out_masks_shape, expected_mask_shape)\n\n  def testResizeImageWithNoInstanceMask(self):\n    \"\"\"Tests image resizing, checking output sizes.\"\"\"\n    in_image_shape_list = [[60, 40, 3], [15, 30, 3]]\n    in_masks_shape_list = [[0, 60, 40], [0, 15, 30]]\n    height = 50\n    width = 100\n    expected_image_shape_list = [[50, 100, 3], [50, 100, 3]]\n    expected_masks_shape_list = [[0, 50, 100], [0, 50, 100]]\n\n    for (in_image_shape, expected_image_shape, in_masks_shape,\n         expected_mask_shape) in zip(in_image_shape_list,\n                                     expected_image_shape_list,\n                                     in_masks_shape_list,\n                                     expected_masks_shape_list):\n      in_image = tf.random_uniform(in_image_shape)\n      in_masks = tf.random_uniform(in_masks_shape)\n      out_image, out_masks = preprocessor.resize_image(\n          in_image, in_masks, new_height=height, new_width=width)\n      out_image_shape = tf.shape(out_image)\n      out_masks_shape = tf.shape(out_masks)\n\n      with self.test_session() as sess:\n        out_image_shape, out_masks_shape = sess.run(\n            [out_image_shape, out_masks_shape])\n        self.assertAllEqual(out_image_shape, expected_image_shape)\n        self.assertAllEqual(out_masks_shape, expected_mask_shape)\n\n  def testResizeToRange4DImageTensor(self):\n    image = tf.random_uniform([1, 200, 300, 3])\n    with self.assertRaises(ValueError):\n      preprocessor.resize_to_range(image, 500, 600)\n\n  def testResizeToRangeSameMinMax(self):\n    \"\"\"Tests image resizing, checking output sizes.\"\"\"\n    in_shape_list = [[312, 312, 3], [299, 299, 3]]\n    min_dim = 320\n    max_dim = 320\n    expected_shape_list = [[320, 320, 3], [320, 320, 3]]\n\n    for in_shape, expected_shape in zip(in_shape_list, expected_shape_list):\n      in_image = tf.random_uniform(in_shape)\n      out_image = preprocessor.resize_to_range(\n          in_image, min_dimension=min_dim, max_dimension=max_dim)\n      out_image_shape = tf.shape(out_image)\n\n      with self.test_session() as sess:\n        out_image_shape = sess.run(out_image_shape)\n        self.assertAllEqual(out_image_shape, expected_shape)\n\n  def testScaleBoxesToPixelCoordinates(self):\n    \"\"\"Tests box scaling, checking scaled values.\"\"\"\n    in_shape = [60, 40, 3]\n    in_boxes = [[0.1, 0.2, 0.4, 0.6],\n                [0.5, 0.3, 0.9, 0.7]]\n\n    expected_boxes = [[6., 8., 24., 24.],\n                      [30., 12., 54., 28.]]\n\n    in_image = tf.random_uniform(in_shape)\n    in_boxes = tf.constant(in_boxes)\n    _, out_boxes = preprocessor.scale_boxes_to_pixel_coordinates(\n        in_image, boxes=in_boxes)\n    with self.test_session() as sess:\n      out_boxes = sess.run(out_boxes)\n      self.assertAllClose(out_boxes, expected_boxes)\n\n  def testScaleBoxesToPixelCoordinatesWithKeypoints(self):\n    \"\"\"Tests box and keypoint scaling, checking scaled values.\"\"\"\n    in_shape = [60, 40, 3]\n    in_boxes = self.createTestBoxes()\n    in_keypoints = self.createTestKeypoints()\n\n    expected_boxes = [[0., 10., 45., 40.],\n                      [15., 20., 45., 40.]]\n    expected_keypoints = [\n        [[6., 4.], [12., 8.], [18., 12.]],\n        [[24., 16.], [30., 20.], [36., 24.]],\n    ]\n\n    in_image = tf.random_uniform(in_shape)\n    _, out_boxes, out_keypoints = preprocessor.scale_boxes_to_pixel_coordinates(\n        in_image, boxes=in_boxes, keypoints=in_keypoints)\n    with self.test_session() as sess:\n      out_boxes_, out_keypoints_ = sess.run([out_boxes, out_keypoints])\n      self.assertAllClose(out_boxes_, expected_boxes)\n      self.assertAllClose(out_keypoints_, expected_keypoints)\n\n  def testSubtractChannelMean(self):\n    \"\"\"Tests whether channel means have been subtracted.\"\"\"\n    with self.test_session():\n      image = tf.zeros((240, 320, 3))\n      means = [1, 2, 3]\n      actual = preprocessor.subtract_channel_mean(image, means=means)\n      actual = actual.eval()\n\n      self.assertTrue((actual[:, :, 0] == -1).all())\n      self.assertTrue((actual[:, :, 1] == -2).all())\n      self.assertTrue((actual[:, :, 2] == -3).all())\n\n  def testOneHotEncoding(self):\n    \"\"\"Tests one hot encoding of multiclass labels.\"\"\"\n    with self.test_session():\n      labels = tf.constant([1, 4, 2], dtype=tf.int32)\n      one_hot = preprocessor.one_hot_encoding(labels, num_classes=5)\n      one_hot = one_hot.eval()\n\n      self.assertAllEqual([0, 1, 1, 0, 1], one_hot)\n\n  def testSSDRandomCrop(self):\n    preprocessing_options = [\n        (preprocessor.normalize_image, {\n            'original_minval': 0,\n            'original_maxval': 255,\n            'target_minval': 0,\n            'target_maxval': 1\n        }),\n        (preprocessor.ssd_random_crop, {})]\n    images = self.createTestImages()\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    tensor_dict = {fields.InputDataFields.image: images,\n                   fields.InputDataFields.groundtruth_boxes: boxes,\n                   fields.InputDataFields.groundtruth_classes: labels}\n    distorted_tensor_dict = preprocessor.preprocess(tensor_dict,\n                                                    preprocessing_options)\n    distorted_images = distorted_tensor_dict[fields.InputDataFields.image]\n    distorted_boxes = distorted_tensor_dict[\n        fields.InputDataFields.groundtruth_boxes]\n\n    images_rank = tf.rank(images)\n    distorted_images_rank = tf.rank(distorted_images)\n    boxes_rank = tf.rank(boxes)\n    distorted_boxes_rank = tf.rank(distorted_boxes)\n\n    with self.test_session() as sess:\n      (boxes_rank_, distorted_boxes_rank_, images_rank_,\n       distorted_images_rank_) = sess.run(\n           [boxes_rank, distorted_boxes_rank, images_rank,\n            distorted_images_rank])\n      self.assertAllEqual(boxes_rank_, distorted_boxes_rank_)\n      self.assertAllEqual(images_rank_, distorted_images_rank_)\n\n  def testSSDRandomCropPad(self):\n    images = self.createTestImages()\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    preprocessing_options = [\n        (preprocessor.normalize_image, {\n            'original_minval': 0,\n            'original_maxval': 255,\n            'target_minval': 0,\n            'target_maxval': 1\n        }),\n        (preprocessor.ssd_random_crop_pad, {})]\n    tensor_dict = {fields.InputDataFields.image: images,\n                   fields.InputDataFields.groundtruth_boxes: boxes,\n                   fields.InputDataFields.groundtruth_classes: labels}\n    distorted_tensor_dict = preprocessor.preprocess(tensor_dict,\n                                                    preprocessing_options)\n    distorted_images = distorted_tensor_dict[fields.InputDataFields.image]\n    distorted_boxes = distorted_tensor_dict[\n        fields.InputDataFields.groundtruth_boxes]\n\n    images_rank = tf.rank(images)\n    distorted_images_rank = tf.rank(distorted_images)\n    boxes_rank = tf.rank(boxes)\n    distorted_boxes_rank = tf.rank(distorted_boxes)\n\n    with self.test_session() as sess:\n      (boxes_rank_, distorted_boxes_rank_, images_rank_,\n       distorted_images_rank_) = sess.run([\n           boxes_rank, distorted_boxes_rank, images_rank, distorted_images_rank\n       ])\n      self.assertAllEqual(boxes_rank_, distorted_boxes_rank_)\n      self.assertAllEqual(images_rank_, distorted_images_rank_)\n\n  def testSSDRandomCropFixedAspectRatio(self):\n    images = self.createTestImages()\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    preprocessing_options = [\n        (preprocessor.normalize_image, {\n            'original_minval': 0,\n            'original_maxval': 255,\n            'target_minval': 0,\n            'target_maxval': 1\n        }),\n        (preprocessor.ssd_random_crop_fixed_aspect_ratio, {})]\n    tensor_dict = {\n        fields.InputDataFields.image: images,\n        fields.InputDataFields.groundtruth_boxes: boxes,\n        fields.InputDataFields.groundtruth_classes: labels\n    }\n    distorted_tensor_dict = preprocessor.preprocess(tensor_dict,\n                                                    preprocessing_options)\n    distorted_images = distorted_tensor_dict[fields.InputDataFields.image]\n    distorted_boxes = distorted_tensor_dict[\n        fields.InputDataFields.groundtruth_boxes]\n\n    images_rank = tf.rank(images)\n    distorted_images_rank = tf.rank(distorted_images)\n    boxes_rank = tf.rank(boxes)\n    distorted_boxes_rank = tf.rank(distorted_boxes)\n\n    with self.test_session() as sess:\n      (boxes_rank_, distorted_boxes_rank_, images_rank_,\n       distorted_images_rank_) = sess.run(\n           [boxes_rank, distorted_boxes_rank, images_rank,\n            distorted_images_rank])\n      self.assertAllEqual(boxes_rank_, distorted_boxes_rank_)\n      self.assertAllEqual(images_rank_, distorted_images_rank_)\n\n  def testSSDRandomCropFixedAspectRatioWithMasksAndKeypoints(self):\n    images = self.createTestImages()\n    boxes = self.createTestBoxes()\n    labels = self.createTestLabels()\n    masks = self.createTestMasks()\n    keypoints = self.createTestKeypoints()\n    preprocessing_options = [\n        (preprocessor.normalize_image, {\n            'original_minval': 0,\n            'original_maxval': 255,\n            'target_minval': 0,\n            'target_maxval': 1\n        }),\n        (preprocessor.ssd_random_crop_fixed_aspect_ratio, {})]\n    tensor_dict = {\n        fields.InputDataFields.image: images,\n        fields.InputDataFields.groundtruth_boxes: boxes,\n        fields.InputDataFields.groundtruth_classes: labels,\n        fields.InputDataFields.groundtruth_instance_masks: masks,\n        fields.InputDataFields.groundtruth_keypoints: keypoints,\n    }\n    preprocessor_arg_map = preprocessor.get_default_func_arg_map(\n        include_instance_masks=True, include_keypoints=True)\n    distorted_tensor_dict = preprocessor.preprocess(\n        tensor_dict, preprocessing_options, func_arg_map=preprocessor_arg_map)\n    distorted_images = distorted_tensor_dict[fields.InputDataFields.image]\n    distorted_boxes = distorted_tensor_dict[\n        fields.InputDataFields.groundtruth_boxes]\n\n    images_rank = tf.rank(images)\n    distorted_images_rank = tf.rank(distorted_images)\n    boxes_rank = tf.rank(boxes)\n    distorted_boxes_rank = tf.rank(distorted_boxes)\n\n    with self.test_session() as sess:\n      (boxes_rank_, distorted_boxes_rank_, images_rank_,\n       distorted_images_rank_) = sess.run(\n           [boxes_rank, distorted_boxes_rank, images_rank,\n            distorted_images_rank])\n      self.assertAllEqual(boxes_rank_, distorted_boxes_rank_)\n      self.assertAllEqual(images_rank_, distorted_images_rank_)\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/core/region_similarity_calculator.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Region Similarity Calculators for BoxLists.\n\nRegion Similarity Calculators compare a pairwise measure of similarity\nbetween the boxes in two BoxLists.\n\"\"\"\nfrom abc import ABCMeta\nfrom abc import abstractmethod\n\nimport tensorflow as tf\n\nfrom object_detection.core import box_list_ops\n\n\nclass RegionSimilarityCalculator(object):\n  \"\"\"Abstract base class for region similarity calculator.\"\"\"\n  __metaclass__ = ABCMeta\n\n  def compare(self, boxlist1, boxlist2, scope=None):\n    \"\"\"Computes matrix of pairwise similarity between BoxLists.\n\n    This op (to be overriden) computes a measure of pairwise similarity between\n    the boxes in the given BoxLists. Higher values indicate more similarity.\n\n    Note that this method simply measures similarity and does not explicitly\n    perform a matching.\n\n    Args:\n      boxlist1: BoxList holding N boxes.\n      boxlist2: BoxList holding M boxes.\n      scope: Op scope name. Defaults to 'Compare' if None.\n\n    Returns:\n      a (float32) tensor of shape [N, M] with pairwise similarity score.\n    \"\"\"\n    with tf.name_scope(scope, 'Compare', [boxlist1, boxlist2]) as scope:\n      return self._compare(boxlist1, boxlist2)\n\n  @abstractmethod\n  def _compare(self, boxlist1, boxlist2):\n    pass\n\n\nclass IouSimilarity(RegionSimilarityCalculator):\n  \"\"\"Class to compute similarity based on Intersection over Union (IOU) metric.\n\n  This class computes pairwise similarity between two BoxLists based on IOU.\n  \"\"\"\n\n  def _compare(self, boxlist1, boxlist2):\n    \"\"\"Compute pairwise IOU similarity between the two BoxLists.\n\n    Args:\n      boxlist1: BoxList holding N boxes.\n      boxlist2: BoxList holding M boxes.\n\n    Returns:\n      A tensor with shape [N, M] representing pairwise iou scores.\n    \"\"\"\n    return box_list_ops.iou(boxlist1, boxlist2)\n\n\nclass NegSqDistSimilarity(RegionSimilarityCalculator):\n  \"\"\"Class to compute similarity based on the squared distance metric.\n\n  This class computes pairwise similarity between two BoxLists based on the\n  negative squared distance metric.\n  \"\"\"\n\n  def _compare(self, boxlist1, boxlist2):\n    \"\"\"Compute matrix of (negated) sq distances.\n\n    Args:\n      boxlist1: BoxList holding N boxes.\n      boxlist2: BoxList holding M boxes.\n\n    Returns:\n      A tensor with shape [N, M] representing negated pairwise squared distance.\n    \"\"\"\n    return -1 * box_list_ops.sq_dist(boxlist1, boxlist2)\n\n\nclass IoaSimilarity(RegionSimilarityCalculator):\n  \"\"\"Class to compute similarity based on Intersection over Area (IOA) metric.\n\n  This class computes pairwise similarity between two BoxLists based on their\n  pairwise intersections divided by the areas of second BoxLists.\n  \"\"\"\n\n  def _compare(self, boxlist1, boxlist2):\n    \"\"\"Compute pairwise IOA similarity between the two BoxLists.\n\n    Args:\n      boxlist1: BoxList holding N boxes.\n      boxlist2: BoxList holding M boxes.\n\n    Returns:\n      A tensor with shape [N, M] representing pairwise IOA scores.\n    \"\"\"\n    return box_list_ops.ioa(boxlist1, boxlist2)\n"
  },
  {
    "path": "object_detector_app/object_detection/core/region_similarity_calculator_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for region_similarity_calculator.\"\"\"\nimport tensorflow as tf\n\nfrom object_detection.core import box_list\nfrom object_detection.core import region_similarity_calculator\n\n\nclass RegionSimilarityCalculatorTest(tf.test.TestCase):\n\n  def test_get_correct_pairwise_similarity_based_on_iou(self):\n    corners1 = tf.constant([[4.0, 3.0, 7.0, 5.0], [5.0, 6.0, 10.0, 7.0]])\n    corners2 = tf.constant([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0],\n                            [0.0, 0.0, 20.0, 20.0]])\n    exp_output = [[2.0 / 16.0, 0, 6.0 / 400.0], [1.0 / 16.0, 0.0, 5.0 / 400.0]]\n    boxes1 = box_list.BoxList(corners1)\n    boxes2 = box_list.BoxList(corners2)\n    iou_similarity_calculator = region_similarity_calculator.IouSimilarity()\n    iou_similarity = iou_similarity_calculator.compare(boxes1, boxes2)\n    with self.test_session() as sess:\n      iou_output = sess.run(iou_similarity)\n      self.assertAllClose(iou_output, exp_output)\n\n  def test_get_correct_pairwise_similarity_based_on_squared_distances(self):\n    corners1 = tf.constant([[0.0, 0.0, 0.0, 0.0],\n                            [1.0, 1.0, 0.0, 2.0]])\n    corners2 = tf.constant([[3.0, 4.0, 1.0, 0.0],\n                            [-4.0, 0.0, 0.0, 3.0],\n                            [0.0, 0.0, 0.0, 0.0]])\n    exp_output = [[-26, -25, 0], [-18, -27, -6]]\n    boxes1 = box_list.BoxList(corners1)\n    boxes2 = box_list.BoxList(corners2)\n    dist_similarity_calc = region_similarity_calculator.NegSqDistSimilarity()\n    dist_similarity = dist_similarity_calc.compare(boxes1, boxes2)\n    with self.test_session() as sess:\n      dist_output = sess.run(dist_similarity)\n      self.assertAllClose(dist_output, exp_output)\n\n  def test_get_correct_pairwise_similarity_based_on_ioa(self):\n    corners1 = tf.constant([[4.0, 3.0, 7.0, 5.0], [5.0, 6.0, 10.0, 7.0]])\n    corners2 = tf.constant([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0],\n                            [0.0, 0.0, 20.0, 20.0]])\n    exp_output_1 = [[2.0 / 12.0, 0, 6.0 / 400.0],\n                    [1.0 / 12.0, 0.0, 5.0 / 400.0]]\n    exp_output_2 = [[2.0 / 6.0, 1.0 / 5.0],\n                    [0, 0],\n                    [6.0 / 6.0, 5.0 / 5.0]]\n    boxes1 = box_list.BoxList(corners1)\n    boxes2 = box_list.BoxList(corners2)\n    ioa_similarity_calculator = region_similarity_calculator.IoaSimilarity()\n    ioa_similarity_1 = ioa_similarity_calculator.compare(boxes1, boxes2)\n    ioa_similarity_2 = ioa_similarity_calculator.compare(boxes2, boxes1)\n    with self.test_session() as sess:\n      iou_output_1, iou_output_2 = sess.run(\n          [ioa_similarity_1, ioa_similarity_2])\n      self.assertAllClose(iou_output_1, exp_output_1)\n      self.assertAllClose(iou_output_2, exp_output_2)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/core/standard_fields.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Contains classes specifying naming conventions used for object detection.\n\n\nSpecifies:\n  InputDataFields: standard fields used by reader/preprocessor/batcher.\n  BoxListFields: standard field used by BoxList\n  TfExampleFields: standard fields for tf-example data format (go/tf-example).\n\"\"\"\n\n\nclass InputDataFields(object):\n  \"\"\"Names for the input tensors.\n\n  Holds the standard data field names to use for identifying input tensors. This\n  should be used by the decoder to identify keys for the returned tensor_dict\n  containing input tensors. And it should be used by the model to identify the\n  tensors it needs.\n\n  Attributes:\n    image: image.\n    original_image: image in the original input size.\n    key: unique key corresponding to image.\n    source_id: source of the original image.\n    filename: original filename of the dataset (without common path).\n    groundtruth_image_classes: image-level class labels.\n    groundtruth_boxes: coordinates of the ground truth boxes in the image.\n    groundtruth_classes: box-level class labels.\n    groundtruth_label_types: box-level label types (e.g. explicit negative).\n    groundtruth_is_crowd: is the groundtruth a single object or a crowd.\n    groundtruth_area: area of a groundtruth segment.\n    groundtruth_difficult: is a `difficult` object\n    proposal_boxes: coordinates of object proposal boxes.\n    proposal_objectness: objectness score of each proposal.\n    groundtruth_instance_masks: ground truth instance masks.\n    groundtruth_instance_classes: instance mask-level class labels.\n    groundtruth_keypoints: ground truth keypoints.\n    groundtruth_keypoint_visibilities: ground truth keypoint visibilities.\n    groundtruth_label_scores: groundtruth label scores.\n  \"\"\"\n  image = 'image'\n  original_image = 'original_image'\n  key = 'key'\n  source_id = 'source_id'\n  filename = 'filename'\n  groundtruth_image_classes = 'groundtruth_image_classes'\n  groundtruth_boxes = 'groundtruth_boxes'\n  groundtruth_classes = 'groundtruth_classes'\n  groundtruth_label_types = 'groundtruth_label_types'\n  groundtruth_is_crowd = 'groundtruth_is_crowd'\n  groundtruth_area = 'groundtruth_area'\n  groundtruth_difficult = 'groundtruth_difficult'\n  proposal_boxes = 'proposal_boxes'\n  proposal_objectness = 'proposal_objectness'\n  groundtruth_instance_masks = 'groundtruth_instance_masks'\n  groundtruth_instance_classes = 'groundtruth_instance_classes'\n  groundtruth_keypoints = 'groundtruth_keypoints'\n  groundtruth_keypoint_visibilities = 'groundtruth_keypoint_visibilities'\n  groundtruth_label_scores = 'groundtruth_label_scores'\n\n\nclass BoxListFields(object):\n  \"\"\"Naming conventions for BoxLists.\n\n  Attributes:\n    boxes: bounding box coordinates.\n    classes: classes per bounding box.\n    scores: scores per bounding box.\n    weights: sample weights per bounding box.\n    objectness: objectness score per bounding box.\n    masks: masks per bounding box.\n    keypoints: keypoints per bounding box.\n    keypoint_heatmaps: keypoint heatmaps per bounding box.\n  \"\"\"\n  boxes = 'boxes'\n  classes = 'classes'\n  scores = 'scores'\n  weights = 'weights'\n  objectness = 'objectness'\n  masks = 'masks'\n  keypoints = 'keypoints'\n  keypoint_heatmaps = 'keypoint_heatmaps'\n\n\nclass TfExampleFields(object):\n  \"\"\"TF-example proto feature names for object detection.\n\n  Holds the standard feature names to load from an Example proto for object\n  detection.\n\n  Attributes:\n    image_encoded: JPEG encoded string\n    image_format: image format, e.g. \"JPEG\"\n    filename: filename\n    channels: number of channels of image\n    colorspace: colorspace, e.g. \"RGB\"\n    height: height of image in pixels, e.g. 462\n    width: width of image in pixels, e.g. 581\n    source_id: original source of the image\n    object_class_text: labels in text format, e.g. [\"person\", \"cat\"]\n    object_class_text: labels in numbers, e.g. [16, 8]\n    object_bbox_xmin: xmin coordinates of groundtruth box, e.g. 10, 30\n    object_bbox_xmax: xmax coordinates of groundtruth box, e.g. 50, 40\n    object_bbox_ymin: ymin coordinates of groundtruth box, e.g. 40, 50\n    object_bbox_ymax: ymax coordinates of groundtruth box, e.g. 80, 70\n    object_view: viewpoint of object, e.g. [\"frontal\", \"left\"]\n    object_truncated: is object truncated, e.g. [true, false]\n    object_occluded: is object occluded, e.g. [true, false]\n    object_difficult: is object difficult, e.g. [true, false]\n    object_is_crowd: is the object a single object or a crowd\n    object_segment_area: the area of the segment.\n    instance_masks: instance segmentation masks.\n    instance_classes: Classes for each instance segmentation mask.\n  \"\"\"\n  image_encoded = 'image/encoded'\n  image_format = 'image/format'  # format is reserved keyword\n  filename = 'image/filename'\n  channels = 'image/channels'\n  colorspace = 'image/colorspace'\n  height = 'image/height'\n  width = 'image/width'\n  source_id = 'image/source_id'\n  object_class_text = 'image/object/class/text'\n  object_class_label = 'image/object/class/label'\n  object_bbox_ymin = 'image/object/bbox/ymin'\n  object_bbox_xmin = 'image/object/bbox/xmin'\n  object_bbox_ymax = 'image/object/bbox/ymax'\n  object_bbox_xmax = 'image/object/bbox/xmax'\n  object_view = 'image/object/view'\n  object_truncated = 'image/object/truncated'\n  object_occluded = 'image/object/occluded'\n  object_difficult = 'image/object/difficult'\n  object_is_crowd = 'image/object/is_crowd'\n  object_segment_area = 'image/object/segment/area'\n  instance_masks = 'image/segmentation/object'\n  instance_classes = 'image/segmentation/object/class'\n"
  },
  {
    "path": "object_detector_app/object_detection/core/target_assigner.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Base target assigner module.\n\nThe job of a TargetAssigner is, for a given set of anchors (bounding boxes) and\ngroundtruth detections (bounding boxes), to assign classification and regression\ntargets to each anchor as well as weights to each anchor (specifying, e.g.,\nwhich anchors should not contribute to training loss).\n\nIt assigns classification/regression targets by performing the following steps:\n1) Computing pairwise similarity between anchors and groundtruth boxes using a\n  provided RegionSimilarity Calculator\n2) Computing a matching based on the similarity matrix using a provided Matcher\n3) Assigning regression targets based on the matching and a provided BoxCoder\n4) Assigning classification targets based on the matching and groundtruth labels\n\nNote that TargetAssigners only operate on detections from a single\nimage at a time, so any logic for applying a TargetAssigner to multiple\nimages must be handled externally.\n\"\"\"\nimport tensorflow as tf\n\nfrom object_detection.box_coders import faster_rcnn_box_coder\nfrom object_detection.box_coders import mean_stddev_box_coder\nfrom object_detection.core import box_coder as bcoder\nfrom object_detection.core import box_list\nfrom object_detection.core import box_list_ops\nfrom object_detection.core import matcher as mat\nfrom object_detection.core import region_similarity_calculator as sim_calc\nfrom object_detection.matchers import argmax_matcher\nfrom object_detection.matchers import bipartite_matcher\n\n\nclass TargetAssigner(object):\n  \"\"\"Target assigner to compute classification and regression targets.\"\"\"\n\n  def __init__(self, similarity_calc, matcher, box_coder,\n               positive_class_weight=1.0, negative_class_weight=1.0,\n               unmatched_cls_target=None):\n    \"\"\"Construct Multibox Target Assigner.\n\n    Args:\n      similarity_calc: a RegionSimilarityCalculator\n      matcher: an object_detection.core.Matcher used to match groundtruth to\n        anchors.\n      box_coder: an object_detection.core.BoxCoder used to encode matching\n        groundtruth boxes with respect to anchors.\n      positive_class_weight: classification weight to be associated to positive\n        anchors (default: 1.0)\n      negative_class_weight: classification weight to be associated to negative\n        anchors (default: 1.0)\n      unmatched_cls_target: a float32 tensor with shape [d_1, d_2, ..., d_k]\n        which is consistent with the classification target for each\n        anchor (and can be empty for scalar targets).  This shape must thus be\n        compatible with the groundtruth labels that are passed to the \"assign\"\n        function (which have shape [num_gt_boxes, d_1, d_2, ..., d_k]).\n        If set to None, unmatched_cls_target is set to be [0] for each anchor.\n\n    Raises:\n      ValueError: if similarity_calc is not a RegionSimilarityCalculator or\n        if matcher is not a Matcher or if box_coder is not a BoxCoder\n    \"\"\"\n    if not isinstance(similarity_calc, sim_calc.RegionSimilarityCalculator):\n      raise ValueError('similarity_calc must be a RegionSimilarityCalculator')\n    if not isinstance(matcher, mat.Matcher):\n      raise ValueError('matcher must be a Matcher')\n    if not isinstance(box_coder, bcoder.BoxCoder):\n      raise ValueError('box_coder must be a BoxCoder')\n    self._similarity_calc = similarity_calc\n    self._matcher = matcher\n    self._box_coder = box_coder\n    self._positive_class_weight = positive_class_weight\n    self._negative_class_weight = negative_class_weight\n    if unmatched_cls_target is None:\n      self._unmatched_cls_target = tf.constant([0], tf.float32)\n    else:\n      self._unmatched_cls_target = unmatched_cls_target\n\n  @property\n  def box_coder(self):\n    return self._box_coder\n\n  def assign(self, anchors, groundtruth_boxes, groundtruth_labels=None,\n             **params):\n    \"\"\"Assign classification and regression targets to each anchor.\n\n    For a given set of anchors and groundtruth detections, match anchors\n    to groundtruth_boxes and assign classification and regression targets to\n    each anchor as well as weights based on the resulting match (specifying,\n    e.g., which anchors should not contribute to training loss).\n\n    Anchors that are not matched to anything are given a classification target\n    of self._unmatched_cls_target which can be specified via the constructor.\n\n    Args:\n      anchors: a BoxList representing N anchors\n      groundtruth_boxes: a BoxList representing M groundtruth boxes\n      groundtruth_labels:  a tensor of shape [num_gt_boxes, d_1, ... d_k]\n        with labels for each of the ground_truth boxes. The subshape\n        [d_1, ... d_k] can be empty (corresponding to scalar inputs).  When set\n        to None, groundtruth_labels assumes a binary problem where all\n        ground_truth boxes get a positive label (of 1).\n      **params: Additional keyword arguments for specific implementations of\n              the Matcher.\n\n    Returns:\n      cls_targets: a float32 tensor with shape [num_anchors, d_1, d_2 ... d_k],\n        where the subshape [d_1, ..., d_k] is compatible with groundtruth_labels\n        which has shape [num_gt_boxes, d_1, d_2, ... d_k].\n      cls_weights: a float32 tensor with shape [num_anchors]\n      reg_targets: a float32 tensor with shape [num_anchors, box_code_dimension]\n      reg_weights: a float32 tensor with shape [num_anchors]\n      match: a matcher.Match object encoding the match between anchors and\n        groundtruth boxes, with rows corresponding to groundtruth boxes\n        and columns corresponding to anchors.\n\n    Raises:\n      ValueError: if anchors or groundtruth_boxes are not of type\n        box_list.BoxList\n    \"\"\"\n    if not isinstance(anchors, box_list.BoxList):\n      raise ValueError('anchors must be an BoxList')\n    if not isinstance(groundtruth_boxes, box_list.BoxList):\n      raise ValueError('groundtruth_boxes must be an BoxList')\n\n    if groundtruth_labels is None:\n      groundtruth_labels = tf.ones(tf.expand_dims(groundtruth_boxes.num_boxes(),\n                                                  0))\n      groundtruth_labels = tf.expand_dims(groundtruth_labels, -1)\n    shape_assert = tf.assert_equal(tf.shape(groundtruth_labels)[1:],\n                                   tf.shape(self._unmatched_cls_target))\n\n    with tf.control_dependencies([shape_assert]):\n      match_quality_matrix = self._similarity_calc.compare(groundtruth_boxes,\n                                                           anchors)\n      match = self._matcher.match(match_quality_matrix, **params)\n      reg_targets = self._create_regression_targets(anchors,\n                                                    groundtruth_boxes,\n                                                    match)\n      cls_targets = self._create_classification_targets(groundtruth_labels,\n                                                        match)\n      reg_weights = self._create_regression_weights(match)\n      cls_weights = self._create_classification_weights(\n          match, self._positive_class_weight, self._negative_class_weight)\n\n      num_anchors = anchors.num_boxes_static()\n      if num_anchors is not None:\n        reg_targets = self._reset_target_shape(reg_targets, num_anchors)\n        cls_targets = self._reset_target_shape(cls_targets, num_anchors)\n        reg_weights = self._reset_target_shape(reg_weights, num_anchors)\n        cls_weights = self._reset_target_shape(cls_weights, num_anchors)\n\n    return cls_targets, cls_weights, reg_targets, reg_weights, match\n\n  def _reset_target_shape(self, target, num_anchors):\n    \"\"\"Sets the static shape of the target.\n\n    Args:\n      target: the target tensor. Its first dimension will be overwritten.\n      num_anchors: the number of anchors, which is used to override the target's\n        first dimension.\n\n    Returns:\n      A tensor with the shape info filled in.\n    \"\"\"\n    target_shape = target.get_shape().as_list()\n    target_shape[0] = num_anchors\n    target.set_shape(target_shape)\n    return target\n\n  def _create_regression_targets(self, anchors, groundtruth_boxes, match):\n    \"\"\"Returns a regression target for each anchor.\n\n    Args:\n      anchors: a BoxList representing N anchors\n      groundtruth_boxes: a BoxList representing M groundtruth_boxes\n      match: a matcher.Match object\n\n    Returns:\n      reg_targets: a float32 tensor with shape [N, box_code_dimension]\n    \"\"\"\n    matched_anchor_indices = match.matched_column_indices()\n    unmatched_ignored_anchor_indices = (match.\n                                        unmatched_or_ignored_column_indices())\n    matched_gt_indices = match.matched_row_indices()\n    matched_anchors = box_list_ops.gather(anchors,\n                                          matched_anchor_indices)\n    matched_gt_boxes = box_list_ops.gather(groundtruth_boxes,\n                                           matched_gt_indices)\n    matched_reg_targets = self._box_coder.encode(matched_gt_boxes,\n                                                 matched_anchors)\n    unmatched_ignored_reg_targets = tf.tile(\n        self._default_regression_target(),\n        tf.stack([tf.size(unmatched_ignored_anchor_indices), 1]))\n    reg_targets = tf.dynamic_stitch(\n        [matched_anchor_indices, unmatched_ignored_anchor_indices],\n        [matched_reg_targets, unmatched_ignored_reg_targets])\n    # TODO: summarize the number of matches on average.\n    return reg_targets\n\n  def _default_regression_target(self):\n    \"\"\"Returns the default target for anchors to regress to.\n\n    Default regression targets are set to zero (though in\n    this implementation what these targets are set to should\n    not matter as the regression weight of any box set to\n    regress to the default target is zero).\n\n    Returns:\n      default_target: a float32 tensor with shape [1, box_code_dimension]\n    \"\"\"\n    return tf.constant([self._box_coder.code_size*[0]], tf.float32)\n\n  def _create_classification_targets(self, groundtruth_labels, match):\n    \"\"\"Create classification targets for each anchor.\n\n    Assign a classification target of for each anchor to the matching\n    groundtruth label that is provided by match.  Anchors that are not matched\n    to anything are given the target self._unmatched_cls_target\n\n    Args:\n      groundtruth_labels:  a tensor of shape [num_gt_boxes, d_1, ... d_k]\n        with labels for each of the ground_truth boxes. The subshape\n        [d_1, ... d_k] can be empty (corresponding to scalar labels).\n      match: a matcher.Match object that provides a matching between anchors\n        and groundtruth boxes.\n\n    Returns:\n      cls_targets: a float32 tensor with shape [num_anchors, d_1, d_2 ... d_k],\n        where the subshape [d_1, ..., d_k] is compatible with groundtruth_labels\n        which has shape [num_gt_boxes, d_1, d_2, ... d_k].\n    \"\"\"\n    matched_anchor_indices = match.matched_column_indices()\n    unmatched_ignored_anchor_indices = (match.\n                                        unmatched_or_ignored_column_indices())\n    matched_gt_indices = match.matched_row_indices()\n    matched_cls_targets = tf.gather(groundtruth_labels, matched_gt_indices)\n\n    ones = self._unmatched_cls_target.shape.ndims * [1]\n    unmatched_ignored_cls_targets = tf.tile(\n        tf.expand_dims(self._unmatched_cls_target, 0),\n        tf.stack([tf.size(unmatched_ignored_anchor_indices)] + ones))\n\n    cls_targets = tf.dynamic_stitch(\n        [matched_anchor_indices, unmatched_ignored_anchor_indices],\n        [matched_cls_targets, unmatched_ignored_cls_targets])\n    return cls_targets\n\n  def _create_regression_weights(self, match):\n    \"\"\"Set regression weight for each anchor.\n\n    Only positive anchors are set to contribute to the regression loss, so this\n    method returns a weight of 1 for every positive anchor and 0 for every\n    negative anchor.\n\n    Args:\n      match: a matcher.Match object that provides a matching between anchors\n        and groundtruth boxes.\n\n    Returns:\n      reg_weights: a float32 tensor with shape [num_anchors] representing\n        regression weights\n    \"\"\"\n    reg_weights = tf.cast(match.matched_column_indicator(), tf.float32)\n    return reg_weights\n\n  def _create_classification_weights(self,\n                                     match,\n                                     positive_class_weight=1.0,\n                                     negative_class_weight=1.0):\n    \"\"\"Create classification weights for each anchor.\n\n    Positive (matched) anchors are associated with a weight of\n    positive_class_weight and negative (unmatched) anchors are associated with\n    a weight of negative_class_weight. When anchors are ignored, weights are set\n    to zero. By default, both positive/negative weights are set to 1.0,\n    but they can be adjusted to handle class imbalance (which is almost always\n    the case in object detection).\n\n    Args:\n      match: a matcher.Match object that provides a matching between anchors\n        and groundtruth boxes.\n      positive_class_weight: weight to be associated to positive anchors\n      negative_class_weight: weight to be associated to negative anchors\n\n    Returns:\n      cls_weights: a float32 tensor with shape [num_anchors] representing\n        classification weights.\n    \"\"\"\n    matched_indicator = tf.cast(match.matched_column_indicator(), tf.float32)\n    ignore_indicator = tf.cast(match.ignored_column_indicator(), tf.float32)\n    unmatched_indicator = 1.0 - matched_indicator - ignore_indicator\n    cls_weights = (positive_class_weight * matched_indicator\n                   + negative_class_weight * unmatched_indicator)\n    return cls_weights\n\n  def get_box_coder(self):\n    \"\"\"Get BoxCoder of this TargetAssigner.\n\n    Returns:\n      BoxCoder: BoxCoder object.\n    \"\"\"\n    return self._box_coder\n\n\n# TODO: This method pulls in all the implementation dependencies into core.\n# Therefore its best to have this factory method outside of core.\ndef create_target_assigner(reference, stage=None,\n                           positive_class_weight=1.0,\n                           negative_class_weight=1.0,\n                           unmatched_cls_target=None):\n  \"\"\"Factory function for creating standard target assigners.\n\n  Args:\n    reference: string referencing the type of TargetAssigner.\n    stage: string denoting stage: {proposal, detection}.\n    positive_class_weight: classification weight to be associated to positive\n      anchors (default: 1.0)\n    negative_class_weight: classification weight to be associated to negative\n      anchors (default: 1.0)\n    unmatched_cls_target: a float32 tensor with shape [d_1, d_2, ..., d_k]\n      which is consistent with the classification target for each\n      anchor (and can be empty for scalar targets).  This shape must thus be\n      compatible with the groundtruth labels that are passed to the Assign\n      function (which have shape [num_gt_boxes, d_1, d_2, ..., d_k]).\n      If set to None, unmatched_cls_target is set to be 0 for each anchor.\n\n  Returns:\n    TargetAssigner: desired target assigner.\n\n  Raises:\n    ValueError: if combination reference+stage is invalid.\n  \"\"\"\n  if reference == 'Multibox' and stage == 'proposal':\n    similarity_calc = sim_calc.NegSqDistSimilarity()\n    matcher = bipartite_matcher.GreedyBipartiteMatcher()\n    box_coder = mean_stddev_box_coder.MeanStddevBoxCoder()\n\n  elif reference == 'FasterRCNN' and stage == 'proposal':\n    similarity_calc = sim_calc.IouSimilarity()\n    matcher = argmax_matcher.ArgMaxMatcher(matched_threshold=0.7,\n                                           unmatched_threshold=0.3,\n                                           force_match_for_each_row=True)\n    box_coder = faster_rcnn_box_coder.FasterRcnnBoxCoder(\n        scale_factors=[10.0, 10.0, 5.0, 5.0])\n\n  elif reference == 'FasterRCNN' and stage == 'detection':\n    similarity_calc = sim_calc.IouSimilarity()\n    # Uses all proposals with IOU < 0.5 as candidate negatives.\n    matcher = argmax_matcher.ArgMaxMatcher(matched_threshold=0.5,\n                                           negatives_lower_than_unmatched=True)\n    box_coder = faster_rcnn_box_coder.FasterRcnnBoxCoder(\n        scale_factors=[10.0, 10.0, 5.0, 5.0])\n\n  elif reference == 'FastRCNN':\n    similarity_calc = sim_calc.IouSimilarity()\n    matcher = argmax_matcher.ArgMaxMatcher(matched_threshold=0.5,\n                                           unmatched_threshold=0.1,\n                                           force_match_for_each_row=False,\n                                           negatives_lower_than_unmatched=False)\n    box_coder = faster_rcnn_box_coder.FasterRcnnBoxCoder()\n\n  else:\n    raise ValueError('No valid combination of reference and stage.')\n\n  return TargetAssigner(similarity_calc, matcher, box_coder,\n                        positive_class_weight=positive_class_weight,\n                        negative_class_weight=negative_class_weight,\n                        unmatched_cls_target=unmatched_cls_target)\n\n\ndef batch_assign_targets(target_assigner,\n                         anchors_batch,\n                         gt_box_batch,\n                         gt_class_targets_batch):\n  \"\"\"Batched assignment of classification and regression targets.\n\n  Args:\n    target_assigner: a target assigner.\n    anchors_batch: BoxList representing N box anchors or list of BoxList objects\n      with length batch_size representing anchor sets.\n    gt_box_batch: a list of BoxList objects with length batch_size\n      representing groundtruth boxes for each image in the batch\n    gt_class_targets_batch: a list of tensors with length batch_size, where\n      each tensor has shape [num_gt_boxes_i, classification_target_size] and\n      num_gt_boxes_i is the number of boxes in the ith boxlist of\n      gt_box_batch.\n\n  Returns:\n    batch_cls_targets: a tensor with shape [batch_size, num_anchors,\n      num_classes],\n    batch_cls_weights: a tensor with shape [batch_size, num_anchors],\n    batch_reg_targets: a tensor with shape [batch_size, num_anchors,\n      box_code_dimension]\n    batch_reg_weights: a tensor with shape [batch_size, num_anchors],\n    match_list: a list of matcher.Match objects encoding the match between\n      anchors and groundtruth boxes for each image of the batch,\n      with rows of the Match objects corresponding to groundtruth boxes\n      and columns corresponding to anchors.\n  Raises:\n    ValueError: if input list lengths are inconsistent, i.e.,\n      batch_size == len(gt_box_batch) == len(gt_class_targets_batch)\n        and batch_size == len(anchors_batch) unless anchors_batch is a single\n        BoxList.\n  \"\"\"\n  if not isinstance(anchors_batch, list):\n    anchors_batch = len(gt_box_batch) * [anchors_batch]\n  if not all(\n      isinstance(anchors, box_list.BoxList) for anchors in anchors_batch):\n    raise ValueError('anchors_batch must be a BoxList or list of BoxLists.')\n  if not (len(anchors_batch)\n          == len(gt_box_batch)\n          == len(gt_class_targets_batch)):\n    raise ValueError('batch size incompatible with lengths of anchors_batch, '\n                     'gt_box_batch and gt_class_targets_batch.')\n  cls_targets_list = []\n  cls_weights_list = []\n  reg_targets_list = []\n  reg_weights_list = []\n  match_list = []\n  for anchors, gt_boxes, gt_class_targets in zip(\n      anchors_batch, gt_box_batch, gt_class_targets_batch):\n    (cls_targets, cls_weights, reg_targets,\n     reg_weights, match) = target_assigner.assign(\n         anchors, gt_boxes, gt_class_targets)\n    cls_targets_list.append(cls_targets)\n    cls_weights_list.append(cls_weights)\n    reg_targets_list.append(reg_targets)\n    reg_weights_list.append(reg_weights)\n    match_list.append(match)\n  batch_cls_targets = tf.stack(cls_targets_list)\n  batch_cls_weights = tf.stack(cls_weights_list)\n  batch_reg_targets = tf.stack(reg_targets_list)\n  batch_reg_weights = tf.stack(reg_weights_list)\n  return (batch_cls_targets, batch_cls_weights, batch_reg_targets,\n          batch_reg_weights, match_list)\n"
  },
  {
    "path": "object_detector_app/object_detection/core/target_assigner_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.core.target_assigner.\"\"\"\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.box_coders import mean_stddev_box_coder\nfrom object_detection.core import box_list\nfrom object_detection.core import region_similarity_calculator\nfrom object_detection.core import target_assigner as targetassigner\nfrom object_detection.matchers import argmax_matcher\nfrom object_detection.matchers import bipartite_matcher\n\n\nclass TargetAssignerTest(tf.test.TestCase):\n\n  def test_assign_agnostic(self):\n    similarity_calc = region_similarity_calculator.NegSqDistSimilarity()\n    matcher = bipartite_matcher.GreedyBipartiteMatcher()\n    box_coder = mean_stddev_box_coder.MeanStddevBoxCoder()\n    target_assigner = targetassigner.TargetAssigner(\n        similarity_calc, matcher, box_coder, unmatched_cls_target=None)\n\n    prior_means = tf.constant([[0.0, 0.0, 0.5, 0.5],\n                               [0.5, 0.5, 1.0, 0.8],\n                               [0, 0.5, .5, 1.0]])\n    prior_stddevs = tf.constant(3 * [4 * [.1]])\n    priors = box_list.BoxList(prior_means)\n    priors.add_field('stddev', prior_stddevs)\n\n    box_corners = [[0.0, 0.0, 0.5, 0.5], [0.5, 0.5, 0.9, 0.9]]\n    boxes = box_list.BoxList(tf.constant(box_corners))\n    exp_cls_targets = [[1], [1], [0]]\n    exp_cls_weights = [1, 1, 1]\n    exp_reg_targets = [[0, 0, 0, 0],\n                       [0, 0, -1, 1],\n                       [0, 0, 0, 0]]\n    exp_reg_weights = [1, 1, 0]\n    exp_matching_anchors = [0, 1]\n\n    result = target_assigner.assign(priors, boxes, num_valid_rows=2)\n    (cls_targets, cls_weights, reg_targets, reg_weights, match) = result\n\n    with self.test_session() as sess:\n      (cls_targets_out, cls_weights_out,\n       reg_targets_out, reg_weights_out, matching_anchors_out) = sess.run(\n           [cls_targets, cls_weights, reg_targets, reg_weights,\n            match.matched_column_indices()])\n\n      self.assertAllClose(cls_targets_out, exp_cls_targets)\n      self.assertAllClose(cls_weights_out, exp_cls_weights)\n      self.assertAllClose(reg_targets_out, exp_reg_targets)\n      self.assertAllClose(reg_weights_out, exp_reg_weights)\n      self.assertAllClose(matching_anchors_out, exp_matching_anchors)\n      self.assertEquals(cls_targets_out.dtype, np.float32)\n      self.assertEquals(cls_weights_out.dtype, np.float32)\n      self.assertEquals(reg_targets_out.dtype, np.float32)\n      self.assertEquals(reg_weights_out.dtype, np.float32)\n      self.assertEquals(matching_anchors_out.dtype, np.int32)\n\n  def test_assign_with_ignored_matches(self):\n    # Note: test is very similar to above. The third box matched with an IOU\n    # of 0.35, which is between the matched and unmatched threshold. This means\n    # That like above the expected classification targets are [1, 1, 0].\n    # Unlike above, the third target is ignored and therefore expected\n    # classification weights are [1, 1, 0].\n    similarity_calc = region_similarity_calculator.IouSimilarity()\n    matcher = argmax_matcher.ArgMaxMatcher(matched_threshold=0.5,\n                                           unmatched_threshold=0.3)\n    box_coder = mean_stddev_box_coder.MeanStddevBoxCoder()\n    target_assigner = targetassigner.TargetAssigner(\n        similarity_calc, matcher, box_coder)\n\n    prior_means = tf.constant([[0.0, 0.0, 0.5, 0.5],\n                               [0.5, 0.5, 1.0, 0.8],\n                               [0.0, 0.5, .9, 1.0]])\n    prior_stddevs = tf.constant(3 * [4 * [.1]])\n    priors = box_list.BoxList(prior_means)\n    priors.add_field('stddev', prior_stddevs)\n\n    box_corners = [[0.0, 0.0, 0.5, 0.5],\n                   [0.5, 0.5, 0.9, 0.9]]\n    boxes = box_list.BoxList(tf.constant(box_corners))\n    exp_cls_targets = [[1], [1], [0]]\n    exp_cls_weights = [1, 1, 0]\n    exp_reg_targets = [[0, 0, 0, 0],\n                       [0, 0, -1, 1],\n                       [0, 0, 0, 0]]\n    exp_reg_weights = [1, 1, 0]\n    exp_matching_anchors = [0, 1]\n\n    result = target_assigner.assign(priors, boxes)\n    (cls_targets, cls_weights, reg_targets, reg_weights, match) = result\n    with self.test_session() as sess:\n      (cls_targets_out, cls_weights_out,\n       reg_targets_out, reg_weights_out, matching_anchors_out) = sess.run(\n           [cls_targets, cls_weights, reg_targets, reg_weights,\n            match.matched_column_indices()])\n\n      self.assertAllClose(cls_targets_out, exp_cls_targets)\n      self.assertAllClose(cls_weights_out, exp_cls_weights)\n      self.assertAllClose(reg_targets_out, exp_reg_targets)\n      self.assertAllClose(reg_weights_out, exp_reg_weights)\n      self.assertAllClose(matching_anchors_out, exp_matching_anchors)\n      self.assertEquals(cls_targets_out.dtype, np.float32)\n      self.assertEquals(cls_weights_out.dtype, np.float32)\n      self.assertEquals(reg_targets_out.dtype, np.float32)\n      self.assertEquals(reg_weights_out.dtype, np.float32)\n      self.assertEquals(matching_anchors_out.dtype, np.int32)\n\n  def test_assign_multiclass(self):\n    similarity_calc = region_similarity_calculator.NegSqDistSimilarity()\n    matcher = bipartite_matcher.GreedyBipartiteMatcher()\n    box_coder = mean_stddev_box_coder.MeanStddevBoxCoder()\n    unmatched_cls_target = tf.constant([1, 0, 0, 0, 0, 0, 0], tf.float32)\n    target_assigner = targetassigner.TargetAssigner(\n        similarity_calc, matcher, box_coder,\n        unmatched_cls_target=unmatched_cls_target)\n\n    prior_means = tf.constant([[0.0, 0.0, 0.5, 0.5],\n                               [0.5, 0.5, 1.0, 0.8],\n                               [0, 0.5, .5, 1.0],\n                               [.75, 0, 1.0, .25]])\n    prior_stddevs = tf.constant(4 * [4 * [.1]])\n    priors = box_list.BoxList(prior_means)\n    priors.add_field('stddev', prior_stddevs)\n\n    box_corners = [[0.0, 0.0, 0.5, 0.5],\n                   [0.5, 0.5, 0.9, 0.9],\n                   [.75, 0, .95, .27]]\n    boxes = box_list.BoxList(tf.constant(box_corners))\n\n    groundtruth_labels = tf.constant([[0, 1, 0, 0, 0, 0, 0],\n                                      [0, 0, 0, 0, 0, 1, 0],\n                                      [0, 0, 0, 1, 0, 0, 0]], tf.float32)\n\n    exp_cls_targets = [[0, 1, 0, 0, 0, 0, 0],\n                       [0, 0, 0, 0, 0, 1, 0],\n                       [1, 0, 0, 0, 0, 0, 0],\n                       [0, 0, 0, 1, 0, 0, 0]]\n    exp_cls_weights = [1, 1, 1, 1]\n    exp_reg_targets = [[0, 0, 0, 0],\n                       [0, 0, -1, 1],\n                       [0, 0, 0, 0],\n                       [0, 0, -.5, .2]]\n    exp_reg_weights = [1, 1, 0, 1]\n    exp_matching_anchors = [0, 1, 3]\n\n    result = target_assigner.assign(priors, boxes, groundtruth_labels,\n                                    num_valid_rows=3)\n    (cls_targets, cls_weights, reg_targets, reg_weights, match) = result\n    with self.test_session() as sess:\n      (cls_targets_out, cls_weights_out,\n       reg_targets_out, reg_weights_out, matching_anchors_out) = sess.run(\n           [cls_targets, cls_weights, reg_targets, reg_weights,\n            match.matched_column_indices()])\n\n      self.assertAllClose(cls_targets_out, exp_cls_targets)\n      self.assertAllClose(cls_weights_out, exp_cls_weights)\n      self.assertAllClose(reg_targets_out, exp_reg_targets)\n      self.assertAllClose(reg_weights_out, exp_reg_weights)\n      self.assertAllClose(matching_anchors_out, exp_matching_anchors)\n      self.assertEquals(cls_targets_out.dtype, np.float32)\n      self.assertEquals(cls_weights_out.dtype, np.float32)\n      self.assertEquals(reg_targets_out.dtype, np.float32)\n      self.assertEquals(reg_weights_out.dtype, np.float32)\n      self.assertEquals(matching_anchors_out.dtype, np.int32)\n\n  def test_assign_multiclass_unequal_class_weights(self):\n    similarity_calc = region_similarity_calculator.NegSqDistSimilarity()\n    matcher = bipartite_matcher.GreedyBipartiteMatcher()\n    box_coder = mean_stddev_box_coder.MeanStddevBoxCoder()\n    unmatched_cls_target = tf.constant([1, 0, 0, 0, 0, 0, 0], tf.float32)\n    target_assigner = targetassigner.TargetAssigner(\n        similarity_calc, matcher, box_coder,\n        positive_class_weight=1.0, negative_class_weight=0.5,\n        unmatched_cls_target=unmatched_cls_target)\n\n    prior_means = tf.constant([[0.0, 0.0, 0.5, 0.5],\n                               [0.5, 0.5, 1.0, 0.8],\n                               [0, 0.5, .5, 1.0],\n                               [.75, 0, 1.0, .25]])\n    prior_stddevs = tf.constant(4 * [4 * [.1]])\n    priors = box_list.BoxList(prior_means)\n    priors.add_field('stddev', prior_stddevs)\n\n    box_corners = [[0.0, 0.0, 0.5, 0.5],\n                   [0.5, 0.5, 0.9, 0.9],\n                   [.75, 0, .95, .27]]\n    boxes = box_list.BoxList(tf.constant(box_corners))\n\n    groundtruth_labels = tf.constant([[0, 1, 0, 0, 0, 0, 0],\n                                      [0, 0, 0, 0, 0, 1, 0],\n                                      [0, 0, 0, 1, 0, 0, 0]], tf.float32)\n\n    exp_cls_weights = [1, 1, .5, 1]\n    result = target_assigner.assign(priors, boxes, groundtruth_labels,\n                                    num_valid_rows=3)\n    (_, cls_weights, _, _, _) = result\n    with self.test_session() as sess:\n      cls_weights_out = sess.run(cls_weights)\n      self.assertAllClose(cls_weights_out, exp_cls_weights)\n\n  def test_assign_multidimensional_class_targets(self):\n    similarity_calc = region_similarity_calculator.NegSqDistSimilarity()\n    matcher = bipartite_matcher.GreedyBipartiteMatcher()\n    box_coder = mean_stddev_box_coder.MeanStddevBoxCoder()\n    unmatched_cls_target = tf.constant([[0, 0], [0, 0]], tf.float32)\n    target_assigner = targetassigner.TargetAssigner(\n        similarity_calc, matcher, box_coder,\n        unmatched_cls_target=unmatched_cls_target)\n\n    prior_means = tf.constant([[0.0, 0.0, 0.5, 0.5],\n                               [0.5, 0.5, 1.0, 0.8],\n                               [0, 0.5, .5, 1.0],\n                               [.75, 0, 1.0, .25]])\n    prior_stddevs = tf.constant(4 * [4 * [.1]])\n    priors = box_list.BoxList(prior_means)\n    priors.add_field('stddev', prior_stddevs)\n\n    box_corners = [[0.0, 0.0, 0.5, 0.5],\n                   [0.5, 0.5, 0.9, 0.9],\n                   [.75, 0, .95, .27]]\n    boxes = box_list.BoxList(tf.constant(box_corners))\n\n    groundtruth_labels = tf.constant([[[0, 1], [1, 0]],\n                                      [[1, 0], [0, 1]],\n                                      [[0, 1], [1, .5]]], tf.float32)\n\n    exp_cls_targets = [[[0, 1], [1, 0]],\n                       [[1, 0], [0, 1]],\n                       [[0, 0], [0, 0]],\n                       [[0, 1], [1, .5]]]\n    exp_cls_weights = [1, 1, 1, 1]\n    exp_reg_targets = [[0, 0, 0, 0],\n                       [0, 0, -1, 1],\n                       [0, 0, 0, 0],\n                       [0, 0, -.5, .2]]\n    exp_reg_weights = [1, 1, 0, 1]\n    exp_matching_anchors = [0, 1, 3]\n\n    result = target_assigner.assign(priors, boxes, groundtruth_labels,\n                                    num_valid_rows=3)\n    (cls_targets, cls_weights, reg_targets, reg_weights, match) = result\n    with self.test_session() as sess:\n      (cls_targets_out, cls_weights_out,\n       reg_targets_out, reg_weights_out, matching_anchors_out) = sess.run(\n           [cls_targets, cls_weights, reg_targets, reg_weights,\n            match.matched_column_indices()])\n\n      self.assertAllClose(cls_targets_out, exp_cls_targets)\n      self.assertAllClose(cls_weights_out, exp_cls_weights)\n      self.assertAllClose(reg_targets_out, exp_reg_targets)\n      self.assertAllClose(reg_weights_out, exp_reg_weights)\n      self.assertAllClose(matching_anchors_out, exp_matching_anchors)\n      self.assertEquals(cls_targets_out.dtype, np.float32)\n      self.assertEquals(cls_weights_out.dtype, np.float32)\n      self.assertEquals(reg_targets_out.dtype, np.float32)\n      self.assertEquals(reg_weights_out.dtype, np.float32)\n      self.assertEquals(matching_anchors_out.dtype, np.int32)\n\n  def test_assign_empty_groundtruth(self):\n    similarity_calc = region_similarity_calculator.NegSqDistSimilarity()\n    matcher = bipartite_matcher.GreedyBipartiteMatcher()\n    box_coder = mean_stddev_box_coder.MeanStddevBoxCoder()\n    unmatched_cls_target = tf.constant([0, 0, 0], tf.float32)\n    target_assigner = targetassigner.TargetAssigner(\n        similarity_calc, matcher, box_coder,\n        unmatched_cls_target=unmatched_cls_target)\n\n    prior_means = tf.constant([[0.0, 0.0, 0.5, 0.5],\n                               [0.5, 0.5, 1.0, 0.8],\n                               [0, 0.5, .5, 1.0],\n                               [.75, 0, 1.0, .25]])\n    prior_stddevs = tf.constant(4 * [4 * [.1]])\n    priors = box_list.BoxList(prior_means)\n    priors.add_field('stddev', prior_stddevs)\n\n    box_corners_expanded = tf.constant([[0.0, 0.0, 0.0, 0.0]])\n    box_corners = tf.slice(box_corners_expanded, [0, 0], [0, 4])\n    boxes = box_list.BoxList(box_corners)\n\n    groundtruth_labels_expanded = tf.constant([[0, 0, 0]], tf.float32)\n    groundtruth_labels = tf.slice(groundtruth_labels_expanded, [0, 0], [0, 3])\n\n    exp_cls_targets = [[0, 0, 0],\n                       [0, 0, 0],\n                       [0, 0, 0],\n                       [0, 0, 0]]\n    exp_cls_weights = [1, 1, 1, 1]\n    exp_reg_targets = [[0, 0, 0, 0],\n                       [0, 0, 0, 0],\n                       [0, 0, 0, 0],\n                       [0, 0, 0, 0]]\n    exp_reg_weights = [0, 0, 0, 0]\n    exp_matching_anchors = []\n\n    result = target_assigner.assign(priors, boxes, groundtruth_labels)\n    (cls_targets, cls_weights, reg_targets, reg_weights, match) = result\n    with self.test_session() as sess:\n      (cls_targets_out, cls_weights_out,\n       reg_targets_out, reg_weights_out, matching_anchors_out) = sess.run(\n           [cls_targets, cls_weights, reg_targets, reg_weights,\n            match.matched_column_indices()])\n\n      self.assertAllClose(cls_targets_out, exp_cls_targets)\n      self.assertAllClose(cls_weights_out, exp_cls_weights)\n      self.assertAllClose(reg_targets_out, exp_reg_targets)\n      self.assertAllClose(reg_weights_out, exp_reg_weights)\n      self.assertAllClose(matching_anchors_out, exp_matching_anchors)\n      self.assertEquals(cls_targets_out.dtype, np.float32)\n      self.assertEquals(cls_weights_out.dtype, np.float32)\n      self.assertEquals(reg_targets_out.dtype, np.float32)\n      self.assertEquals(reg_weights_out.dtype, np.float32)\n      self.assertEquals(matching_anchors_out.dtype, np.int32)\n\n  def test_raises_error_on_invalid_groundtruth_labels(self):\n    similarity_calc = region_similarity_calculator.NegSqDistSimilarity()\n    matcher = bipartite_matcher.GreedyBipartiteMatcher()\n    box_coder = mean_stddev_box_coder.MeanStddevBoxCoder()\n    unmatched_cls_target = tf.constant([[0, 0], [0, 0], [0, 0]], tf.float32)\n    target_assigner = targetassigner.TargetAssigner(\n        similarity_calc, matcher, box_coder,\n        unmatched_cls_target=unmatched_cls_target)\n\n    prior_means = tf.constant([[0.0, 0.0, 0.5, 0.5]])\n    prior_stddevs = tf.constant([[1.0, 1.0, 1.0, 1.0]])\n    priors = box_list.BoxList(prior_means)\n    priors.add_field('stddev', prior_stddevs)\n\n    box_corners = [[0.0, 0.0, 0.5, 0.5],\n                   [0.5, 0.5, 0.9, 0.9],\n                   [.75, 0, .95, .27]]\n    boxes = box_list.BoxList(tf.constant(box_corners))\n\n    groundtruth_labels = tf.constant([[[0, 1], [1, 0]]], tf.float32)\n\n    with self.assertRaises(ValueError):\n      target_assigner.assign(priors, boxes, groundtruth_labels,\n                             num_valid_rows=3)\n\n\nclass BatchTargetAssignerTest(tf.test.TestCase):\n\n  def _get_agnostic_target_assigner(self):\n    similarity_calc = region_similarity_calculator.NegSqDistSimilarity()\n    matcher = bipartite_matcher.GreedyBipartiteMatcher()\n    box_coder = mean_stddev_box_coder.MeanStddevBoxCoder()\n    return targetassigner.TargetAssigner(\n        similarity_calc, matcher, box_coder,\n        positive_class_weight=1.0,\n        negative_class_weight=1.0,\n        unmatched_cls_target=None)\n\n  def _get_multi_class_target_assigner(self, num_classes):\n    similarity_calc = region_similarity_calculator.NegSqDistSimilarity()\n    matcher = bipartite_matcher.GreedyBipartiteMatcher()\n    box_coder = mean_stddev_box_coder.MeanStddevBoxCoder()\n    unmatched_cls_target = tf.constant([1] + num_classes * [0], tf.float32)\n    return targetassigner.TargetAssigner(\n        similarity_calc, matcher, box_coder,\n        positive_class_weight=1.0,\n        negative_class_weight=1.0,\n        unmatched_cls_target=unmatched_cls_target)\n\n  def _get_multi_dimensional_target_assigner(self, target_dimensions):\n    similarity_calc = region_similarity_calculator.NegSqDistSimilarity()\n    matcher = bipartite_matcher.GreedyBipartiteMatcher()\n    box_coder = mean_stddev_box_coder.MeanStddevBoxCoder()\n    unmatched_cls_target = tf.constant(np.zeros(target_dimensions),\n                                       tf.float32)\n    return targetassigner.TargetAssigner(\n        similarity_calc, matcher, box_coder,\n        positive_class_weight=1.0,\n        negative_class_weight=1.0,\n        unmatched_cls_target=unmatched_cls_target)\n\n  def test_batch_assign_targets(self):\n    box_list1 = box_list.BoxList(tf.constant([[0., 0., 0.2, 0.2]]))\n    box_list2 = box_list.BoxList(tf.constant(\n        [[0, 0.25123152, 1, 1],\n         [0.015789, 0.0985, 0.55789, 0.3842]]\n    ))\n\n    gt_box_batch = [box_list1, box_list2]\n    gt_class_targets = [None, None]\n\n    prior_means = tf.constant([[0, 0, .25, .25],\n                               [0, .25, 1, 1],\n                               [0, .1, .5, .5],\n                               [.75, .75, 1, 1]])\n    prior_stddevs = tf.constant([[.1, .1, .1, .1],\n                                 [.1, .1, .1, .1],\n                                 [.1, .1, .1, .1],\n                                 [.1, .1, .1, .1]])\n    priors = box_list.BoxList(prior_means)\n    priors.add_field('stddev', prior_stddevs)\n\n    exp_reg_targets = [[[0, 0, -0.5, -0.5],\n                        [0, 0, 0, 0],\n                        [0, 0, 0, 0,],\n                        [0, 0, 0, 0,],],\n                       [[0, 0, 0, 0,],\n                        [0, 0.01231521, 0, 0],\n                        [0.15789001, -0.01500003, 0.57889998, -1.15799987],\n                        [0, 0, 0, 0]]]\n    exp_cls_weights = [[1, 1, 1, 1],\n                       [1, 1, 1, 1]]\n    exp_cls_targets = [[[1], [0], [0], [0]],\n                       [[0], [1], [1], [0]]]\n    exp_reg_weights = [[1, 0, 0, 0],\n                       [0, 1, 1, 0]]\n    exp_match_0 = [0]\n    exp_match_1 = [1, 2]\n\n    agnostic_target_assigner = self._get_agnostic_target_assigner()\n    (cls_targets, cls_weights, reg_targets, reg_weights,\n     match_list) = targetassigner.batch_assign_targets(\n         agnostic_target_assigner, priors, gt_box_batch, gt_class_targets)\n    self.assertTrue(isinstance(match_list, list) and len(match_list) == 2)\n    with self.test_session() as sess:\n      (cls_targets_out, cls_weights_out, reg_targets_out, reg_weights_out,\n       match_out_0, match_out_1) = sess.run([\n           cls_targets, cls_weights, reg_targets, reg_weights] + [\n               match.matched_column_indices() for match in match_list])\n      self.assertAllClose(cls_targets_out, exp_cls_targets)\n      self.assertAllClose(cls_weights_out, exp_cls_weights)\n      self.assertAllClose(reg_targets_out, exp_reg_targets)\n      self.assertAllClose(reg_weights_out, exp_reg_weights)\n      self.assertAllClose(match_out_0, exp_match_0)\n      self.assertAllClose(match_out_1, exp_match_1)\n\n  def test_batch_assign_multiclass_targets(self):\n    box_list1 = box_list.BoxList(tf.constant([[0., 0., 0.2, 0.2]]))\n\n    box_list2 = box_list.BoxList(tf.constant(\n        [[0, 0.25123152, 1, 1],\n         [0.015789, 0.0985, 0.55789, 0.3842]]\n    ))\n\n    gt_box_batch = [box_list1, box_list2]\n\n    class_targets1 = tf.constant([[0, 1, 0, 0]], tf.float32)\n    class_targets2 = tf.constant([[0, 0, 0, 1],\n                                  [0, 0, 1, 0]], tf.float32)\n\n    gt_class_targets = [class_targets1, class_targets2]\n\n    prior_means = tf.constant([[0, 0, .25, .25],\n                               [0, .25, 1, 1],\n                               [0, .1, .5, .5],\n                               [.75, .75, 1, 1]])\n    prior_stddevs = tf.constant([[.1, .1, .1, .1],\n                                 [.1, .1, .1, .1],\n                                 [.1, .1, .1, .1],\n                                 [.1, .1, .1, .1]])\n    priors = box_list.BoxList(prior_means)\n    priors.add_field('stddev', prior_stddevs)\n\n    exp_reg_targets = [[[0, 0, -0.5, -0.5],\n                        [0, 0, 0, 0],\n                        [0, 0, 0, 0],\n                        [0, 0, 0, 0]],\n                       [[0, 0, 0, 0],\n                        [0, 0.01231521, 0, 0],\n                        [0.15789001, -0.01500003, 0.57889998, -1.15799987],\n                        [0, 0, 0, 0]]]\n    exp_cls_weights = [[1, 1, 1, 1],\n                       [1, 1, 1, 1]]\n    exp_cls_targets = [[[0, 1, 0, 0],\n                        [1, 0, 0, 0],\n                        [1, 0, 0, 0],\n                        [1, 0, 0, 0]],\n                       [[1, 0, 0, 0],\n                        [0, 0, 0, 1],\n                        [0, 0, 1, 0],\n                        [1, 0, 0, 0]]]\n    exp_reg_weights = [[1, 0, 0, 0],\n                       [0, 1, 1, 0]]\n    exp_match_0 = [0]\n    exp_match_1 = [1, 2]\n\n    multiclass_target_assigner = self._get_multi_class_target_assigner(\n        num_classes=3)\n\n    (cls_targets, cls_weights, reg_targets, reg_weights,\n     match_list) = targetassigner.batch_assign_targets(\n         multiclass_target_assigner, priors, gt_box_batch, gt_class_targets)\n    self.assertTrue(isinstance(match_list, list) and len(match_list) == 2)\n    with self.test_session() as sess:\n      (cls_targets_out, cls_weights_out, reg_targets_out, reg_weights_out,\n       match_out_0, match_out_1) = sess.run([\n           cls_targets, cls_weights, reg_targets, reg_weights] + [\n               match.matched_column_indices() for match in match_list])\n      self.assertAllClose(cls_targets_out, exp_cls_targets)\n      self.assertAllClose(cls_weights_out, exp_cls_weights)\n      self.assertAllClose(reg_targets_out, exp_reg_targets)\n      self.assertAllClose(reg_weights_out, exp_reg_weights)\n      self.assertAllClose(match_out_0, exp_match_0)\n      self.assertAllClose(match_out_1, exp_match_1)\n\n  def test_batch_assign_multidimensional_targets(self):\n    box_list1 = box_list.BoxList(tf.constant([[0., 0., 0.2, 0.2]]))\n\n    box_list2 = box_list.BoxList(tf.constant(\n        [[0, 0.25123152, 1, 1],\n         [0.015789, 0.0985, 0.55789, 0.3842]]\n    ))\n\n    gt_box_batch = [box_list1, box_list2]\n    class_targets1 = tf.constant([[[0, 1, 1],\n                                   [1, 1, 0]]], tf.float32)\n    class_targets2 = tf.constant([[[0, 1, 1],\n                                   [1, 1, 0]],\n                                  [[0, 0, 1],\n                                   [0, 0, 1]]], tf.float32)\n\n    gt_class_targets = [class_targets1, class_targets2]\n\n    prior_means = tf.constant([[0, 0, .25, .25],\n                               [0, .25, 1, 1],\n                               [0, .1, .5, .5],\n                               [.75, .75, 1, 1]])\n    prior_stddevs = tf.constant([[.1, .1, .1, .1],\n                                 [.1, .1, .1, .1],\n                                 [.1, .1, .1, .1],\n                                 [.1, .1, .1, .1]])\n    priors = box_list.BoxList(prior_means)\n    priors.add_field('stddev', prior_stddevs)\n\n    exp_reg_targets = [[[0, 0, -0.5, -0.5],\n                        [0, 0, 0, 0],\n                        [0, 0, 0, 0],\n                        [0, 0, 0, 0]],\n                       [[0, 0, 0, 0],\n                        [0, 0.01231521, 0, 0],\n                        [0.15789001, -0.01500003, 0.57889998, -1.15799987],\n                        [0, 0, 0, 0]]]\n    exp_cls_weights = [[1, 1, 1, 1],\n                       [1, 1, 1, 1]]\n\n    exp_cls_targets = [[[[0., 1., 1.],\n                         [1., 1., 0.]],\n                        [[0., 0., 0.],\n                         [0., 0., 0.]],\n                        [[0., 0., 0.],\n                         [0., 0., 0.]],\n                        [[0., 0., 0.],\n                         [0., 0., 0.]]],\n                       [[[0., 0., 0.],\n                         [0., 0., 0.]],\n                        [[0., 1., 1.],\n                         [1., 1., 0.]],\n                        [[0., 0., 1.],\n                         [0., 0., 1.]],\n                        [[0., 0., 0.],\n                         [0., 0., 0.]]]]\n    exp_reg_weights = [[1, 0, 0, 0],\n                       [0, 1, 1, 0]]\n    exp_match_0 = [0]\n    exp_match_1 = [1, 2]\n\n    multiclass_target_assigner = self._get_multi_dimensional_target_assigner(\n        target_dimensions=(2, 3))\n\n    (cls_targets, cls_weights, reg_targets, reg_weights,\n     match_list) = targetassigner.batch_assign_targets(\n         multiclass_target_assigner, priors, gt_box_batch, gt_class_targets)\n    self.assertTrue(isinstance(match_list, list) and len(match_list) == 2)\n    with self.test_session() as sess:\n      (cls_targets_out, cls_weights_out, reg_targets_out, reg_weights_out,\n       match_out_0, match_out_1) = sess.run([\n           cls_targets, cls_weights, reg_targets, reg_weights] + [\n               match.matched_column_indices() for match in match_list])\n      self.assertAllClose(cls_targets_out, exp_cls_targets)\n      self.assertAllClose(cls_weights_out, exp_cls_weights)\n      self.assertAllClose(reg_targets_out, exp_reg_targets)\n      self.assertAllClose(reg_weights_out, exp_reg_weights)\n      self.assertAllClose(match_out_0, exp_match_0)\n      self.assertAllClose(match_out_1, exp_match_1)\n\n  def test_batch_assign_empty_groundtruth(self):\n    box_coords_expanded = tf.zeros((1, 4), tf.float32)\n    box_coords = tf.slice(box_coords_expanded, [0, 0], [0, 4])\n    box_list1 = box_list.BoxList(box_coords)\n    gt_box_batch = [box_list1]\n\n    prior_means = tf.constant([[0, 0, .25, .25],\n                               [0, .25, 1, 1]])\n    prior_stddevs = tf.constant([[.1, .1, .1, .1],\n                                 [.1, .1, .1, .1]])\n    priors = box_list.BoxList(prior_means)\n    priors.add_field('stddev', prior_stddevs)\n\n    exp_reg_targets = [[[0, 0, 0, 0],\n                        [0, 0, 0, 0]]]\n    exp_cls_weights = [[1, 1]]\n    exp_cls_targets = [[[1, 0, 0, 0],\n                        [1, 0, 0, 0]]]\n    exp_reg_weights = [[0, 0]]\n    exp_match_0 = []\n\n    num_classes = 3\n    pad = 1\n    gt_class_targets = tf.zeros((0, num_classes + pad))\n    gt_class_targets_batch = [gt_class_targets]\n\n    multiclass_target_assigner = self._get_multi_class_target_assigner(\n        num_classes=3)\n\n    (cls_targets, cls_weights, reg_targets, reg_weights,\n     match_list) = targetassigner.batch_assign_targets(\n         multiclass_target_assigner, priors,\n         gt_box_batch, gt_class_targets_batch)\n    self.assertTrue(isinstance(match_list, list) and len(match_list) == 1)\n    with self.test_session() as sess:\n      (cls_targets_out, cls_weights_out, reg_targets_out, reg_weights_out,\n       match_out_0) = sess.run([\n           cls_targets, cls_weights, reg_targets, reg_weights] + [\n               match.matched_column_indices() for match in match_list])\n      self.assertAllClose(cls_targets_out, exp_cls_targets)\n      self.assertAllClose(cls_weights_out, exp_cls_weights)\n      self.assertAllClose(reg_targets_out, exp_reg_targets)\n      self.assertAllClose(reg_weights_out, exp_reg_weights)\n      self.assertAllClose(match_out_0, exp_match_0)\n\n\nclass CreateTargetAssignerTest(tf.test.TestCase):\n\n  def test_create_target_assigner(self):\n    \"\"\"Tests that named constructor gives working target assigners.\n\n    TODO: Make this test more general.\n    \"\"\"\n    corners = [[0.0, 0.0, 1.0, 1.0]]\n    groundtruth = box_list.BoxList(tf.constant(corners))\n\n    priors = box_list.BoxList(tf.constant(corners))\n    prior_stddevs = tf.constant([[1.0, 1.0, 1.0, 1.0]])\n    priors.add_field('stddev', prior_stddevs)\n    multibox_ta = (targetassigner\n                   .create_target_assigner('Multibox', stage='proposal'))\n    multibox_ta.assign(priors, groundtruth)\n    # No tests on output, as that may vary arbitrarily as new target assigners\n    # are added. As long as it is constructed correctly and runs without errors,\n    # tests on the individual assigners cover correctness of the assignments.\n\n    anchors = box_list.BoxList(tf.constant(corners))\n    faster_rcnn_proposals_ta = (targetassigner\n                                .create_target_assigner('FasterRCNN',\n                                                        stage='proposal'))\n    faster_rcnn_proposals_ta.assign(anchors, groundtruth)\n\n    fast_rcnn_ta = (targetassigner\n                    .create_target_assigner('FastRCNN'))\n    fast_rcnn_ta.assign(anchors, groundtruth)\n\n    faster_rcnn_detection_ta = (targetassigner\n                                .create_target_assigner('FasterRCNN',\n                                                        stage='detection'))\n    faster_rcnn_detection_ta.assign(anchors, groundtruth)\n\n    with self.assertRaises(ValueError):\n      targetassigner.create_target_assigner('InvalidDetector',\n                                            stage='invalid_stage')\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/create_pascal_tf_record.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\nr\"\"\"Convert raw PASCAL dataset to TFRecord for object_detection.\n\nExample usage:\n    ./create_pascal_tf_record --data_dir=/home/user/VOCdevkit \\\n        --year=VOC2012 \\\n        --output_path=/home/user/pascal.record\n\"\"\"\nfrom __future__ import absolute_import\nfrom __future__ import division\nfrom __future__ import print_function\n\nimport hashlib\nimport io\nimport logging\nimport os\n\nfrom lxml import etree\nimport PIL.Image\nimport tensorflow as tf\n\nfrom object_detection.utils import dataset_util\nfrom object_detection.utils import label_map_util\n\n\nflags = tf.app.flags\nflags.DEFINE_string('data_dir', '', 'Root directory to raw PASCAL VOC dataset.')\nflags.DEFINE_string('set', 'train', 'Convert training set, validation set or '\n                    'merged set.')\nflags.DEFINE_string('annotations_dir', 'Annotations',\n                    '(Relative) path to annotations directory.')\nflags.DEFINE_string('year', 'VOC2007', 'Desired challenge year.')\nflags.DEFINE_string('output_path', '', 'Path to output TFRecord')\nflags.DEFINE_string('label_map_path', 'data/pascal_label_map.pbtxt',\n                    'Path to label map proto')\nflags.DEFINE_boolean('ignore_difficult_instances', False, 'Whether to ignore '\n                     'difficult instances')\nFLAGS = flags.FLAGS\n\nSETS = ['train', 'val', 'trainval', 'test']\nYEARS = ['VOC2007', 'VOC2012', 'merged']\n\n\ndef dict_to_tf_example(data,\n                       dataset_directory,\n                       label_map_dict,\n                       ignore_difficult_instances=False,\n                       image_subdirectory='JPEGImages'):\n  \"\"\"Convert XML derived dict to tf.Example proto.\n\n  Notice that this function normalizes the bounding box coordinates provided\n  by the raw data.\n\n  Args:\n    data: dict holding PASCAL XML fields for a single image (obtained by\n      running dataset_util.recursive_parse_xml_to_dict)\n    dataset_directory: Path to root directory holding PASCAL dataset\n    label_map_dict: A map from string label names to integers ids.\n    ignore_difficult_instances: Whether to skip difficult instances in the\n      dataset  (default: False).\n    image_subdirectory: String specifying subdirectory within the\n      PASCAL dataset directory holding the actual image data.\n\n  Returns:\n    example: The converted tf.Example.\n\n  Raises:\n    ValueError: if the image pointed to by data['filename'] is not a valid JPEG\n  \"\"\"\n  img_path = os.path.join(data['folder'], image_subdirectory, data['filename'])\n  full_path = os.path.join(dataset_directory, img_path)\n  with tf.gfile.GFile(full_path) as fid:\n    encoded_jpg = fid.read()\n  encoded_jpg_io = io.BytesIO(encoded_jpg)\n  image = PIL.Image.open(encoded_jpg_io)\n  if image.format != 'JPEG':\n    raise ValueError('Image format not JPEG')\n  key = hashlib.sha256(encoded_jpg).hexdigest()\n\n  width = int(data['size']['width'])\n  height = int(data['size']['height'])\n\n  xmin = []\n  ymin = []\n  xmax = []\n  ymax = []\n  classes = []\n  classes_text = []\n  truncated = []\n  poses = []\n  difficult_obj = []\n  for obj in data['object']:\n    difficult = bool(int(obj['difficult']))\n    if ignore_difficult_instances and difficult:\n      continue\n\n    difficult_obj.append(int(difficult))\n\n    xmin.append(float(obj['bndbox']['xmin']) / width)\n    ymin.append(float(obj['bndbox']['ymin']) / height)\n    xmax.append(float(obj['bndbox']['xmax']) / width)\n    ymax.append(float(obj['bndbox']['ymax']) / height)\n    classes_text.append(obj['name'])\n    classes.append(label_map_dict[obj['name']])\n    truncated.append(int(obj['truncated']))\n    poses.append(obj['pose'])\n\n  example = tf.train.Example(features=tf.train.Features(feature={\n      'image/height': dataset_util.int64_feature(height),\n      'image/width': dataset_util.int64_feature(width),\n      'image/filename': dataset_util.bytes_feature(data['filename']),\n      'image/source_id': dataset_util.bytes_feature(data['filename']),\n      'image/key/sha256': dataset_util.bytes_feature(key),\n      'image/encoded': dataset_util.bytes_feature(encoded_jpg),\n      'image/format': dataset_util.bytes_feature('jpeg'),\n      'image/object/bbox/xmin': dataset_util.float_list_feature(xmin),\n      'image/object/bbox/xmax': dataset_util.float_list_feature(xmax),\n      'image/object/bbox/ymin': dataset_util.float_list_feature(ymin),\n      'image/object/bbox/ymax': dataset_util.float_list_feature(ymax),\n      'image/object/class/text': dataset_util.bytes_list_feature(classes_text),\n      'image/object/class/label': dataset_util.int64_list_feature(classes),\n      'image/object/difficult': dataset_util.int64_list_feature(difficult_obj),\n      'image/object/truncated': dataset_util.int64_list_feature(truncated),\n      'image/object/view': dataset_util.bytes_list_feature(poses),\n  }))\n  return example\n\n\ndef main(_):\n  if FLAGS.set not in SETS:\n    raise ValueError('set must be in : {}'.format(SETS))\n  if FLAGS.year not in YEARS:\n    raise ValueError('year must be in : {}'.format(YEARS))\n\n  data_dir = FLAGS.data_dir\n  years = ['VOC2007', 'VOC2012']\n  if FLAGS.year != 'merged':\n    years = [FLAGS.year]\n\n  writer = tf.python_io.TFRecordWriter(FLAGS.output_path)\n\n  label_map_dict = label_map_util.get_label_map_dict(FLAGS.label_map_path)\n\n  for year in years:\n    logging.info('Reading from PASCAL %s dataset.', year)\n    examples_path = os.path.join(data_dir, year, 'ImageSets', 'Main',\n                                 'aeroplane_' + FLAGS.set + '.txt')\n    annotations_dir = os.path.join(data_dir, year, FLAGS.annotations_dir)\n    examples_list = dataset_util.read_examples_list(examples_path)\n    for idx, example in enumerate(examples_list):\n      if idx % 100 == 0:\n        logging.info('On image %d of %d', idx, len(examples_list))\n      path = os.path.join(annotations_dir, example + '.xml')\n      with tf.gfile.GFile(path, 'r') as fid:\n        xml_str = fid.read()\n      xml = etree.fromstring(xml_str)\n      data = dataset_util.recursive_parse_xml_to_dict(xml)['annotation']\n\n      tf_example = dict_to_tf_example(data, FLAGS.data_dir, label_map_dict,\n                                      FLAGS.ignore_difficult_instances)\n      writer.write(tf_example.SerializeToString())\n\n  writer.close()\n\n\nif __name__ == '__main__':\n  tf.app.run()\n"
  },
  {
    "path": "object_detector_app/object_detection/create_pascal_tf_record_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Test for create_pascal_tf_record.py.\"\"\"\n\nimport os\n\nimport numpy as np\nimport PIL.Image\nimport tensorflow as tf\n\nfrom object_detection import create_pascal_tf_record\n\n\nclass DictToTFExampleTest(tf.test.TestCase):\n\n  def _assertProtoEqual(self, proto_field, expectation):\n    \"\"\"Helper function to assert if a proto field equals some value.\n\n    Args:\n      proto_field: The protobuf field to compare.\n      expectation: The expected value of the protobuf field.\n    \"\"\"\n    proto_list = [p for p in proto_field]\n    self.assertListEqual(proto_list, expectation)\n\n  def test_dict_to_tf_example(self):\n    image_file_name = 'tmp_image.jpg'\n    image_data = np.random.rand(256, 256, 3)\n    save_path = os.path.join(self.get_temp_dir(), image_file_name)\n    image = PIL.Image.fromarray(image_data, 'RGB')\n    image.save(save_path)\n\n    data = {\n        'folder': '',\n        'filename': image_file_name,\n        'size': {\n            'height': 256,\n            'width': 256,\n        },\n        'object': [\n            {\n                'difficult': 1,\n                'bndbox': {\n                    'xmin': 64,\n                    'ymin': 64,\n                    'xmax': 192,\n                    'ymax': 192,\n                },\n                'name': 'person',\n                'truncated': 0,\n                'pose': '',\n            },\n        ],\n    }\n\n    label_map_dict = {\n        'background': 0,\n        'person': 1,\n        'notperson': 2,\n    }\n\n    example = create_pascal_tf_record.dict_to_tf_example(\n        data, self.get_temp_dir(), label_map_dict, image_subdirectory='')\n    self._assertProtoEqual(\n        example.features.feature['image/height'].int64_list.value, [256])\n    self._assertProtoEqual(\n        example.features.feature['image/width'].int64_list.value, [256])\n    self._assertProtoEqual(\n        example.features.feature['image/filename'].bytes_list.value,\n        [image_file_name])\n    self._assertProtoEqual(\n        example.features.feature['image/source_id'].bytes_list.value,\n        [image_file_name])\n    self._assertProtoEqual(\n        example.features.feature['image/format'].bytes_list.value, ['jpeg'])\n    self._assertProtoEqual(\n        example.features.feature['image/object/bbox/xmin'].float_list.value,\n        [0.25])\n    self._assertProtoEqual(\n        example.features.feature['image/object/bbox/ymin'].float_list.value,\n        [0.25])\n    self._assertProtoEqual(\n        example.features.feature['image/object/bbox/xmax'].float_list.value,\n        [0.75])\n    self._assertProtoEqual(\n        example.features.feature['image/object/bbox/ymax'].float_list.value,\n        [0.75])\n    self._assertProtoEqual(\n        example.features.feature['image/object/class/text'].bytes_list.value,\n        ['person'])\n    self._assertProtoEqual(\n        example.features.feature['image/object/class/label'].int64_list.value,\n        [1])\n    self._assertProtoEqual(\n        example.features.feature['image/object/difficult'].int64_list.value,\n        [1])\n    self._assertProtoEqual(\n        example.features.feature['image/object/truncated'].int64_list.value,\n        [0])\n    self._assertProtoEqual(\n        example.features.feature['image/object/view'].bytes_list.value, [''])\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/create_pet_tf_record.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\nr\"\"\"Convert the Oxford pet dataset to TFRecord for object_detection.\n\nSee: O. M. Parkhi, A. Vedaldi, A. Zisserman, C. V. Jawahar\n     Cats and Dogs\n     IEEE Conference on Computer Vision and Pattern Recognition, 2012\n     http://www.robots.ox.ac.uk/~vgg/data/pets/\n\nExample usage:\n    ./create_pet_tf_record --data_dir=/home/user/pet \\\n        --output_dir=/home/user/pet/output\n\"\"\"\n\nimport hashlib\nimport io\nimport logging\nimport os\nimport random\nimport re\n\nfrom lxml import etree\nimport PIL.Image\nimport tensorflow as tf\n\nfrom object_detection.utils import dataset_util\nfrom object_detection.utils import label_map_util\n\nflags = tf.app.flags\nflags.DEFINE_string('data_dir', '', 'Root directory to raw pet dataset.')\nflags.DEFINE_string('output_dir', '', 'Path to directory to output TFRecords.')\nflags.DEFINE_string('label_map_path', 'data/pet_label_map.pbtxt',\n                    'Path to label map proto')\nFLAGS = flags.FLAGS\n\n\ndef get_class_name_from_filename(file_name):\n  \"\"\"Gets the class name from a file.\n\n  Args:\n    file_name: The file name to get the class name from.\n               ie. \"american_pit_bull_terrier_105.jpg\"\n\n  Returns:\n    example: The converted tf.Example.\n  \"\"\"\n  match = re.match(r'([A-Za-z_]+)(_[0-9]+\\.jpg)', file_name, re.I)\n  return match.groups()[0]\n\n\ndef dict_to_tf_example(data,\n                       label_map_dict,\n                       image_subdirectory,\n                       ignore_difficult_instances=False):\n  \"\"\"Convert XML derived dict to tf.Example proto.\n\n  Notice that this function normalizes the bounding box coordinates provided\n  by the raw data.\n\n  Args:\n    data: dict holding PASCAL XML fields for a single image (obtained by\n      running dataset_util.recursive_parse_xml_to_dict)\n    label_map_dict: A map from string label names to integers ids.\n    image_subdirectory: String specifying subdirectory within the\n      Pascal dataset directory holding the actual image data.\n    ignore_difficult_instances: Whether to skip difficult instances in the\n      dataset  (default: False).\n\n  Returns:\n    example: The converted tf.Example.\n\n  Raises:\n    ValueError: if the image pointed to by data['filename'] is not a valid JPEG\n  \"\"\"\n  img_path = os.path.join(image_subdirectory, data['filename'])\n  with tf.gfile.GFile(img_path) as fid:\n    encoded_jpg = fid.read()\n  encoded_jpg_io = io.BytesIO(encoded_jpg)\n  image = PIL.Image.open(encoded_jpg_io)\n  if image.format != 'JPEG':\n    raise ValueError('Image format not JPEG')\n  key = hashlib.sha256(encoded_jpg).hexdigest()\n\n  width = int(data['size']['width'])\n  height = int(data['size']['height'])\n\n  xmin = []\n  ymin = []\n  xmax = []\n  ymax = []\n  classes = []\n  classes_text = []\n  truncated = []\n  poses = []\n  difficult_obj = []\n  for obj in data['object']:\n    difficult = bool(int(obj['difficult']))\n    if ignore_difficult_instances and difficult:\n      continue\n\n    difficult_obj.append(int(difficult))\n\n    xmin.append(float(obj['bndbox']['xmin']) / width)\n    ymin.append(float(obj['bndbox']['ymin']) / height)\n    xmax.append(float(obj['bndbox']['xmax']) / width)\n    ymax.append(float(obj['bndbox']['ymax']) / height)\n    class_name = get_class_name_from_filename(data['filename'])\n    classes_text.append(class_name)\n    classes.append(label_map_dict[class_name])\n    truncated.append(int(obj['truncated']))\n    poses.append(obj['pose'])\n\n  example = tf.train.Example(features=tf.train.Features(feature={\n      'image/height': dataset_util.int64_feature(height),\n      'image/width': dataset_util.int64_feature(width),\n      'image/filename': dataset_util.bytes_feature(data['filename']),\n      'image/source_id': dataset_util.bytes_feature(data['filename']),\n      'image/key/sha256': dataset_util.bytes_feature(key),\n      'image/encoded': dataset_util.bytes_feature(encoded_jpg),\n      'image/format': dataset_util.bytes_feature('jpeg'),\n      'image/object/bbox/xmin': dataset_util.float_list_feature(xmin),\n      'image/object/bbox/xmax': dataset_util.float_list_feature(xmax),\n      'image/object/bbox/ymin': dataset_util.float_list_feature(ymin),\n      'image/object/bbox/ymax': dataset_util.float_list_feature(ymax),\n      'image/object/class/text': dataset_util.bytes_list_feature(classes_text),\n      'image/object/class/label': dataset_util.int64_list_feature(classes),\n      'image/object/difficult': dataset_util.int64_list_feature(difficult_obj),\n      'image/object/truncated': dataset_util.int64_list_feature(truncated),\n      'image/object/view': dataset_util.bytes_list_feature(poses),\n  }))\n  return example\n\n\ndef create_tf_record(output_filename,\n                     label_map_dict,\n                     annotations_dir,\n                     image_dir,\n                     examples):\n  \"\"\"Creates a TFRecord file from examples.\n\n  Args:\n    output_filename: Path to where output file is saved.\n    label_map_dict: The label map dictionary.\n    annotations_dir: Directory where annotation files are stored.\n    image_dir: Directory where image files are stored.\n    examples: Examples to parse and save to tf record.\n  \"\"\"\n  writer = tf.python_io.TFRecordWriter(output_filename)\n  for idx, example in enumerate(examples):\n    if idx % 100 == 0:\n      logging.info('On image %d of %d', idx, len(examples))\n    path = os.path.join(annotations_dir, 'xmls', example + '.xml')\n\n    if not os.path.exists(path):\n      logging.warning('Could not find %s, ignoring example.', path)\n      continue\n    with tf.gfile.GFile(path, 'r') as fid:\n      xml_str = fid.read()\n    xml = etree.fromstring(xml_str)\n    data = dataset_util.recursive_parse_xml_to_dict(xml)['annotation']\n\n    tf_example = dict_to_tf_example(data, label_map_dict, image_dir)\n    writer.write(tf_example.SerializeToString())\n\n  writer.close()\n\n\n# TODO: Add test for pet/PASCAL main files.\ndef main(_):\n  data_dir = FLAGS.data_dir\n  label_map_dict = label_map_util.get_label_map_dict(FLAGS.label_map_path)\n\n  logging.info('Reading from Pet dataset.')\n  image_dir = os.path.join(data_dir, 'images')\n  annotations_dir = os.path.join(data_dir, 'annotations')\n  examples_path = os.path.join(annotations_dir, 'trainval.txt')\n  examples_list = dataset_util.read_examples_list(examples_path)\n\n  # Test images are not included in the downloaded data set, so we shall perform\n  # our own split.\n  random.seed(42)\n  random.shuffle(examples_list)\n  num_examples = len(examples_list)\n  num_train = int(0.7 * num_examples)\n  train_examples = examples_list[:num_train]\n  val_examples = examples_list[num_train:]\n  logging.info('%d training and %d validation examples.',\n               len(train_examples), len(val_examples))\n\n  train_output_path = os.path.join(FLAGS.output_dir, 'pet_train.record')\n  val_output_path = os.path.join(FLAGS.output_dir, 'pet_val.record')\n  create_tf_record(train_output_path, label_map_dict, annotations_dir,\n                   image_dir, train_examples)\n  create_tf_record(val_output_path, label_map_dict, annotations_dir,\n                   image_dir, val_examples)\n\nif __name__ == '__main__':\n  tf.app.run()\n"
  },
  {
    "path": "object_detector_app/object_detection/data/mscoco_label_map.pbtxt",
    "content": "item {\n  name: \"/m/01g317\"\n  id: 1\n  display_name: \"person\"\n}\nitem {\n  name: \"/m/0199g\"\n  id: 2\n  display_name: \"bicycle\"\n}\nitem {\n  name: \"/m/0k4j\"\n  id: 3\n  display_name: \"car\"\n}\nitem {\n  name: \"/m/04_sv\"\n  id: 4\n  display_name: \"motorcycle\"\n}\nitem {\n  name: \"/m/05czz6l\"\n  id: 5\n  display_name: \"airplane\"\n}\nitem {\n  name: \"/m/01bjv\"\n  id: 6\n  display_name: \"bus\"\n}\nitem {\n  name: \"/m/07jdr\"\n  id: 7\n  display_name: \"train\"\n}\nitem {\n  name: \"/m/07r04\"\n  id: 8\n  display_name: \"truck\"\n}\nitem {\n  name: \"/m/019jd\"\n  id: 9\n  display_name: \"boat\"\n}\nitem {\n  name: \"/m/015qff\"\n  id: 10\n  display_name: \"traffic light\"\n}\nitem {\n  name: \"/m/01pns0\"\n  id: 11\n  display_name: \"fire hydrant\"\n}\nitem {\n  name: \"/m/02pv19\"\n  id: 13\n  display_name: \"stop sign\"\n}\nitem {\n  name: \"/m/015qbp\"\n  id: 14\n  display_name: \"parking meter\"\n}\nitem {\n  name: \"/m/0cvnqh\"\n  id: 15\n  display_name: \"bench\"\n}\nitem {\n  name: \"/m/015p6\"\n  id: 16\n  display_name: \"bird\"\n}\nitem {\n  name: \"/m/01yrx\"\n  id: 17\n  display_name: \"cat\"\n}\nitem {\n  name: \"/m/0bt9lr\"\n  id: 18\n  display_name: \"dog\"\n}\nitem {\n  name: \"/m/03k3r\"\n  id: 19\n  display_name: \"horse\"\n}\nitem {\n  name: \"/m/07bgp\"\n  id: 20\n  display_name: \"sheep\"\n}\nitem {\n  name: \"/m/01xq0k1\"\n  id: 21\n  display_name: \"cow\"\n}\nitem {\n  name: \"/m/0bwd_0j\"\n  id: 22\n  display_name: \"elephant\"\n}\nitem {\n  name: \"/m/01dws\"\n  id: 23\n  display_name: \"bear\"\n}\nitem {\n  name: \"/m/0898b\"\n  id: 24\n  display_name: \"zebra\"\n}\nitem {\n  name: \"/m/03bk1\"\n  id: 25\n  display_name: \"giraffe\"\n}\nitem {\n  name: \"/m/01940j\"\n  id: 27\n  display_name: \"backpack\"\n}\nitem {\n  name: \"/m/0hnnb\"\n  id: 28\n  display_name: \"umbrella\"\n}\nitem {\n  name: \"/m/080hkjn\"\n  id: 31\n  display_name: \"handbag\"\n}\nitem {\n  name: \"/m/01rkbr\"\n  id: 32\n  display_name: \"tie\"\n}\nitem {\n  name: \"/m/01s55n\"\n  id: 33\n  display_name: \"suitcase\"\n}\nitem {\n  name: \"/m/02wmf\"\n  id: 34\n  display_name: \"frisbee\"\n}\nitem {\n  name: \"/m/071p9\"\n  id: 35\n  display_name: \"skis\"\n}\nitem {\n  name: \"/m/06__v\"\n  id: 36\n  display_name: \"snowboard\"\n}\nitem {\n  name: \"/m/018xm\"\n  id: 37\n  display_name: \"sports ball\"\n}\nitem {\n  name: \"/m/02zt3\"\n  id: 38\n  display_name: \"kite\"\n}\nitem {\n  name: \"/m/03g8mr\"\n  id: 39\n  display_name: \"baseball bat\"\n}\nitem {\n  name: \"/m/03grzl\"\n  id: 40\n  display_name: \"baseball glove\"\n}\nitem {\n  name: \"/m/06_fw\"\n  id: 41\n  display_name: \"skateboard\"\n}\nitem {\n  name: \"/m/019w40\"\n  id: 42\n  display_name: \"surfboard\"\n}\nitem {\n  name: \"/m/0dv9c\"\n  id: 43\n  display_name: \"tennis racket\"\n}\nitem {\n  name: \"/m/04dr76w\"\n  id: 44\n  display_name: \"bottle\"\n}\nitem {\n  name: \"/m/09tvcd\"\n  id: 46\n  display_name: \"wine glass\"\n}\nitem {\n  name: \"/m/08gqpm\"\n  id: 47\n  display_name: \"cup\"\n}\nitem {\n  name: \"/m/0dt3t\"\n  id: 48\n  display_name: \"fork\"\n}\nitem {\n  name: \"/m/04ctx\"\n  id: 49\n  display_name: \"knife\"\n}\nitem {\n  name: \"/m/0cmx8\"\n  id: 50\n  display_name: \"spoon\"\n}\nitem {\n  name: \"/m/04kkgm\"\n  id: 51\n  display_name: \"bowl\"\n}\nitem {\n  name: \"/m/09qck\"\n  id: 52\n  display_name: \"banana\"\n}\nitem {\n  name: \"/m/014j1m\"\n  id: 53\n  display_name: \"apple\"\n}\nitem {\n  name: \"/m/0l515\"\n  id: 54\n  display_name: \"sandwich\"\n}\nitem {\n  name: \"/m/0cyhj_\"\n  id: 55\n  display_name: \"orange\"\n}\nitem {\n  name: \"/m/0hkxq\"\n  id: 56\n  display_name: \"broccoli\"\n}\nitem {\n  name: \"/m/0fj52s\"\n  id: 57\n  display_name: \"carrot\"\n}\nitem {\n  name: \"/m/01b9xk\"\n  id: 58\n  display_name: \"hot dog\"\n}\nitem {\n  name: \"/m/0663v\"\n  id: 59\n  display_name: \"pizza\"\n}\nitem {\n  name: \"/m/0jy4k\"\n  id: 60\n  display_name: \"donut\"\n}\nitem {\n  name: \"/m/0fszt\"\n  id: 61\n  display_name: \"cake\"\n}\nitem {\n  name: \"/m/01mzpv\"\n  id: 62\n  display_name: \"chair\"\n}\nitem {\n  name: \"/m/02crq1\"\n  id: 63\n  display_name: \"couch\"\n}\nitem {\n  name: \"/m/03fp41\"\n  id: 64\n  display_name: \"potted plant\"\n}\nitem {\n  name: \"/m/03ssj5\"\n  id: 65\n  display_name: \"bed\"\n}\nitem {\n  name: \"/m/04bcr3\"\n  id: 67\n  display_name: \"dining table\"\n}\nitem {\n  name: \"/m/09g1w\"\n  id: 70\n  display_name: \"toilet\"\n}\nitem {\n  name: \"/m/07c52\"\n  id: 72\n  display_name: \"tv\"\n}\nitem {\n  name: \"/m/01c648\"\n  id: 73\n  display_name: \"laptop\"\n}\nitem {\n  name: \"/m/020lf\"\n  id: 74\n  display_name: \"mouse\"\n}\nitem {\n  name: \"/m/0qjjc\"\n  id: 75\n  display_name: \"remote\"\n}\nitem {\n  name: \"/m/01m2v\"\n  id: 76\n  display_name: \"keyboard\"\n}\nitem {\n  name: \"/m/050k8\"\n  id: 77\n  display_name: \"cell phone\"\n}\nitem {\n  name: \"/m/0fx9l\"\n  id: 78\n  display_name: \"microwave\"\n}\nitem {\n  name: \"/m/029bxz\"\n  id: 79\n  display_name: \"oven\"\n}\nitem {\n  name: \"/m/01k6s3\"\n  id: 80\n  display_name: \"toaster\"\n}\nitem {\n  name: \"/m/0130jx\"\n  id: 81\n  display_name: \"sink\"\n}\nitem {\n  name: \"/m/040b_t\"\n  id: 82\n  display_name: \"refrigerator\"\n}\nitem {\n  name: \"/m/0bt_c3\"\n  id: 84\n  display_name: \"book\"\n}\nitem {\n  name: \"/m/01x3z\"\n  id: 85\n  display_name: \"clock\"\n}\nitem {\n  name: \"/m/02s195\"\n  id: 86\n  display_name: \"vase\"\n}\nitem {\n  name: \"/m/01lsmm\"\n  id: 87\n  display_name: \"scissors\"\n}\nitem {\n  name: \"/m/0kmg4\"\n  id: 88\n  display_name: \"teddy bear\"\n}\nitem {\n  name: \"/m/03wvsk\"\n  id: 89\n  display_name: \"hair drier\"\n}\nitem {\n  name: \"/m/012xff\"\n  id: 90\n  display_name: \"toothbrush\"\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/data/pascal_label_map.pbtxt",
    "content": "item {\n  id: 0\n  name: 'none_of_the_above'\n}\n\nitem {\n  id: 1\n  name: 'aeroplane'\n}\n\nitem {\n  id: 2\n  name: 'bicycle'\n}\n\nitem {\n  id: 3\n  name: 'bird'\n}\n\nitem {\n  id: 4\n  name: 'boat'\n}\n\nitem {\n  id: 5\n  name: 'bottle'\n}\n\nitem {\n  id: 6\n  name: 'bus'\n}\n\nitem {\n  id: 7\n  name: 'car'\n}\n\nitem {\n  id: 8\n  name: 'cat'\n}\n\nitem {\n  id: 9\n  name: 'chair'\n}\n\nitem {\n  id: 10\n  name: 'cow'\n}\n\nitem {\n  id: 11\n  name: 'diningtable'\n}\n\nitem {\n  id: 12\n  name: 'dog'\n}\n\nitem {\n  id: 13\n  name: 'horse'\n}\n\nitem {\n  id: 14\n  name: 'motorbike'\n}\n\nitem {\n  id: 15\n  name: 'person'\n}\n\nitem {\n  id: 16\n  name: 'pottedplant'\n}\n\nitem {\n  id: 17\n  name: 'sheep'\n}\n\nitem {\n  id: 18\n  name: 'sofa'\n}\n\nitem {\n  id: 19\n  name: 'train'\n}\n\nitem {\n  id: 20\n  name: 'tvmonitor'\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/data/pet_label_map.pbtxt",
    "content": "item {\n  id: 0\n  name: 'none_of_the_above'\n}\n\nitem {\n  id: 1\n  name: 'Abyssinian'\n}\n\nitem {\n  id: 2\n  name: 'american_bulldog'\n}\n\nitem {\n  id: 3\n  name: 'american_pit_bull_terrier'\n}\n\nitem {\n  id: 4\n  name: 'basset_hound'\n}\n\nitem {\n  id: 5\n  name: 'beagle'\n}\n\nitem {\n  id: 6\n  name: 'Bengal'\n}\n\nitem {\n  id: 7\n  name: 'Birman'\n}\n\nitem {\n  id: 8\n  name: 'Bombay'\n}\n\nitem {\n  id: 9\n  name: 'boxer'\n}\n\nitem {\n  id: 10\n  name: 'British_Shorthair'\n}\n\nitem {\n  id: 11\n  name: 'chihuahua'\n}\n\nitem {\n  id: 12\n  name: 'Egyptian_Mau'\n}\n\nitem {\n  id: 13\n  name: 'english_cocker_spaniel'\n}\n\nitem {\n  id: 14\n  name: 'english_setter'\n}\n\nitem {\n  id: 15\n  name: 'german_shorthaired'\n}\n\nitem {\n  id: 16\n  name: 'great_pyrenees'\n}\n\nitem {\n  id: 17\n  name: 'havanese'\n}\n\nitem {\n  id: 18\n  name: 'japanese_chin'\n}\n\nitem {\n  id: 19\n  name: 'keeshond'\n}\n\nitem {\n  id: 20\n  name: 'leonberger'\n}\n\nitem {\n  id: 21\n  name: 'Maine_Coon'\n}\n\nitem {\n  id: 22\n  name: 'miniature_pinscher'\n}\n\nitem {\n  id: 23\n  name: 'newfoundland'\n}\n\nitem {\n  id: 24\n  name: 'Persian'\n}\n\nitem {\n  id: 25\n  name: 'pomeranian'\n}\n\nitem {\n  id: 26\n  name: 'pug'\n}\n\nitem {\n  id: 27\n  name: 'Ragdoll'\n}\n\nitem {\n  id: 28\n  name: 'Russian_Blue'\n}\n\nitem {\n  id: 29\n  name: 'saint_bernard'\n}\n\nitem {\n  id: 30\n  name: 'samoyed'\n}\n\nitem {\n  id: 31\n  name: 'scottish_terrier'\n}\n\nitem {\n  id: 32\n  name: 'shiba_inu'\n}\n\nitem {\n  id: 33\n  name: 'Siamese'\n}\n\nitem {\n  id: 34\n  name: 'Sphynx'\n}\n\nitem {\n  id: 35\n  name: 'staffordshire_bull_terrier'\n}\n\nitem {\n  id: 36\n  name: 'wheaten_terrier'\n}\n\nitem {\n  id: 37\n  name: 'yorkshire_terrier'\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/data_decoders/BUILD",
    "content": "# Tensorflow Object Detection API: data decoders.\n\npackage(\n    default_visibility = [\"//visibility:public\"],\n)\n\nlicenses([\"notice\"])\n# Apache 2.0\n\npy_library(\n    name = \"tf_example_decoder\",\n    srcs = [\"tf_example_decoder.py\"],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:data_decoder\",\n        \"//tensorflow_models/object_detection/core:standard_fields\",\n    ],\n)\n\npy_test(\n    name = \"tf_example_decoder_test\",\n    srcs = [\"tf_example_decoder_test.py\"],\n    deps = [\n        \":tf_example_decoder\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:standard_fields\",\n    ],\n)\n"
  },
  {
    "path": "object_detector_app/object_detection/data_decoders/__init__.py",
    "content": ""
  },
  {
    "path": "object_detector_app/object_detection/data_decoders/tf_example_decoder.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tensorflow Example proto decoder for object detection.\n\nA decoder to decode string tensors containing serialized tensorflow.Example\nprotos for object detection.\n\"\"\"\nimport tensorflow as tf\n\nfrom object_detection.core import data_decoder\nfrom object_detection.core import standard_fields as fields\n\nslim_example_decoder = tf.contrib.slim.tfexample_decoder\n\n\nclass TfExampleDecoder(data_decoder.DataDecoder):\n  \"\"\"Tensorflow Example proto decoder.\"\"\"\n\n  def __init__(self):\n    \"\"\"Constructor sets keys_to_features and items_to_handlers.\"\"\"\n    self.keys_to_features = {\n        'image/encoded': tf.FixedLenFeature((), tf.string, default_value=''),\n        'image/format': tf.FixedLenFeature((), tf.string, default_value='jpeg'),\n        'image/filename': tf.FixedLenFeature((), tf.string, default_value=''),\n        'image/key/sha256': tf.FixedLenFeature((), tf.string, default_value=''),\n        'image/source_id': tf.FixedLenFeature((), tf.string, default_value=''),\n        'image/height': tf.FixedLenFeature((), tf.int64, 1),\n        'image/width': tf.FixedLenFeature((), tf.int64, 1),\n        # Object boxes and classes.\n        'image/object/bbox/xmin': tf.VarLenFeature(tf.float32),\n        'image/object/bbox/xmax': tf.VarLenFeature(tf.float32),\n        'image/object/bbox/ymin': tf.VarLenFeature(tf.float32),\n        'image/object/bbox/ymax': tf.VarLenFeature(tf.float32),\n        'image/object/class/label': tf.VarLenFeature(tf.int64),\n        'image/object/area': tf.VarLenFeature(tf.float32),\n        'image/object/is_crowd': tf.VarLenFeature(tf.int64),\n        'image/object/difficult': tf.VarLenFeature(tf.int64),\n        # Instance masks and classes.\n        'image/segmentation/object': tf.VarLenFeature(tf.int64),\n        'image/segmentation/object/class': tf.VarLenFeature(tf.int64)\n    }\n    self.items_to_handlers = {\n        fields.InputDataFields.image: slim_example_decoder.Image(\n            image_key='image/encoded', format_key='image/format', channels=3),\n        fields.InputDataFields.source_id: (\n            slim_example_decoder.Tensor('image/source_id')),\n        fields.InputDataFields.key: (\n            slim_example_decoder.Tensor('image/key/sha256')),\n        fields.InputDataFields.filename: (\n            slim_example_decoder.Tensor('image/filename')),\n        # Object boxes and classes.\n        fields.InputDataFields.groundtruth_boxes: (\n            slim_example_decoder.BoundingBox(\n                ['ymin', 'xmin', 'ymax', 'xmax'], 'image/object/bbox/')),\n        fields.InputDataFields.groundtruth_classes: (\n            slim_example_decoder.Tensor('image/object/class/label')),\n        fields.InputDataFields.groundtruth_area: slim_example_decoder.Tensor(\n            'image/object/area'),\n        fields.InputDataFields.groundtruth_is_crowd: (\n            slim_example_decoder.Tensor('image/object/is_crowd')),\n        fields.InputDataFields.groundtruth_difficult: (\n            slim_example_decoder.Tensor('image/object/difficult')),\n        # Instance masks and classes.\n        fields.InputDataFields.groundtruth_instance_masks: (\n            slim_example_decoder.ItemHandlerCallback(\n                ['image/segmentation/object', 'image/height', 'image/width'],\n                self._reshape_instance_masks)),\n        fields.InputDataFields.groundtruth_instance_classes: (\n            slim_example_decoder.Tensor('image/segmentation/object/class')),\n    }\n\n  def Decode(self, tf_example_string_tensor):\n    \"\"\"Decodes serialized tensorflow example and returns a tensor dictionary.\n\n    Args:\n      tf_example_string_tensor: a string tensor holding a serialized tensorflow\n        example proto.\n\n    Returns:\n      A dictionary of the following tensors.\n      fields.InputDataFields.image - 3D uint8 tensor of shape [None, None, 3]\n        containing image.\n      fields.InputDataFields.source_id - string tensor containing original\n        image id.\n      fields.InputDataFields.key - string tensor with unique sha256 hash key.\n      fields.InputDataFields.filename - string tensor with original dataset\n        filename.\n      fields.InputDataFields.groundtruth_boxes - 2D float32 tensor of shape\n        [None, 4] containing box corners.\n      fields.InputDataFields.groundtruth_classes - 1D int64 tensor of shape\n        [None] containing classes for the boxes.\n      fields.InputDataFields.groundtruth_area - 1D float32 tensor of shape\n        [None] containing containing object mask area in pixel squared.\n      fields.InputDataFields.groundtruth_is_crowd - 1D bool tensor of shape\n        [None] indicating if the boxes enclose a crowd.\n      fields.InputDataFields.groundtruth_difficult - 1D bool tensor of shape\n        [None] indicating if the boxes represent `difficult` instances.\n      fields.InputDataFields.groundtruth_instance_masks - 3D int64 tensor of\n        shape [None, None, None] containing instance masks.\n      fields.InputDataFields.groundtruth_instance_classes - 1D int64 tensor\n        of shape [None] containing classes for the instance masks.\n    \"\"\"\n\n    serialized_example = tf.reshape(tf_example_string_tensor, shape=[])\n    decoder = slim_example_decoder.TFExampleDecoder(self.keys_to_features,\n                                                    self.items_to_handlers)\n    keys = decoder.list_items()\n    tensors = decoder.decode(serialized_example, items=keys)\n    tensor_dict = dict(zip(keys, tensors))\n    is_crowd = fields.InputDataFields.groundtruth_is_crowd\n    tensor_dict[is_crowd] = tf.cast(tensor_dict[is_crowd], dtype=tf.bool)\n    tensor_dict[fields.InputDataFields.image].set_shape([None, None, 3])\n    return tensor_dict\n\n  def _reshape_instance_masks(self, keys_to_tensors):\n    \"\"\"Reshape instance segmentation masks.\n\n    The instance segmentation masks are reshaped to [num_instances, height,\n    width] and cast to boolean type to save memory.\n\n    Args:\n      keys_to_tensors: a dictionary from keys to tensors.\n\n    Returns:\n      A 3-D boolean tensor of shape [num_instances, height, width].\n    \"\"\"\n    masks = keys_to_tensors['image/segmentation/object']\n    if isinstance(masks, tf.SparseTensor):\n      masks = tf.sparse_tensor_to_dense(masks)\n    height = keys_to_tensors['image/height']\n    width = keys_to_tensors['image/width']\n    to_shape = tf.cast(tf.stack([-1, height, width]), tf.int32)\n\n    return tf.cast(tf.reshape(masks, to_shape), tf.bool)\n"
  },
  {
    "path": "object_detector_app/object_detection/data_decoders/tf_example_decoder_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.data_decoders.tf_example_decoder.\"\"\"\n\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.core import standard_fields as fields\nfrom object_detection.data_decoders import tf_example_decoder\n\n\nclass TfExampleDecoderTest(tf.test.TestCase):\n\n  def _EncodeImage(self, image_tensor, encoding_type='jpeg'):\n    with self.test_session():\n      if encoding_type == 'jpeg':\n        image_encoded = tf.image.encode_jpeg(tf.constant(image_tensor)).eval()\n      elif encoding_type == 'png':\n        image_encoded = tf.image.encode_png(tf.constant(image_tensor)).eval()\n      else:\n        raise ValueError('Invalid encoding type.')\n    return image_encoded\n\n  def _DecodeImage(self, image_encoded, encoding_type='jpeg'):\n    with self.test_session():\n      if encoding_type == 'jpeg':\n        image_decoded = tf.image.decode_jpeg(tf.constant(image_encoded)).eval()\n      elif encoding_type == 'png':\n        image_decoded = tf.image.decode_png(tf.constant(image_encoded)).eval()\n      else:\n        raise ValueError('Invalid encoding type.')\n    return image_decoded\n\n  def _Int64Feature(self, value):\n    return tf.train.Feature(int64_list=tf.train.Int64List(value=value))\n\n  def _FloatFeature(self, value):\n    return tf.train.Feature(float_list=tf.train.FloatList(value=value))\n\n  def _BytesFeature(self, value):\n    return tf.train.Feature(bytes_list=tf.train.BytesList(value=[value]))\n\n  def testDecodeJpegImage(self):\n    image_tensor = np.random.randint(255, size=(4, 5, 3)).astype(np.uint8)\n    encoded_jpeg = self._EncodeImage(image_tensor)\n    decoded_jpeg = self._DecodeImage(encoded_jpeg)\n    example = tf.train.Example(features=tf.train.Features(feature={\n        'image/encoded': self._BytesFeature(encoded_jpeg),\n        'image/format': self._BytesFeature('jpeg'),\n        'image/source_id': self._BytesFeature('image_id'),\n    })).SerializeToString()\n\n    example_decoder = tf_example_decoder.TfExampleDecoder()\n    tensor_dict = example_decoder.Decode(tf.convert_to_tensor(example))\n\n    self.assertAllEqual((tensor_dict[fields.InputDataFields.image].\n                         get_shape().as_list()), [None, None, 3])\n    with self.test_session() as sess:\n      tensor_dict = sess.run(tensor_dict)\n\n    self.assertAllEqual(decoded_jpeg, tensor_dict[fields.InputDataFields.image])\n    self.assertEqual('image_id', tensor_dict[fields.InputDataFields.source_id])\n\n  def testDecodeImageKeyAndFilename(self):\n    image_tensor = np.random.randint(255, size=(4, 5, 3)).astype(np.uint8)\n    encoded_jpeg = self._EncodeImage(image_tensor)\n    example = tf.train.Example(features=tf.train.Features(feature={\n        'image/encoded': self._BytesFeature(encoded_jpeg),\n        'image/key/sha256': self._BytesFeature('abc'),\n        'image/filename': self._BytesFeature('filename')\n    })).SerializeToString()\n\n    example_decoder = tf_example_decoder.TfExampleDecoder()\n    tensor_dict = example_decoder.Decode(tf.convert_to_tensor(example))\n\n    with self.test_session() as sess:\n      tensor_dict = sess.run(tensor_dict)\n\n    self.assertEqual('abc', tensor_dict[fields.InputDataFields.key])\n    self.assertEqual('filename', tensor_dict[fields.InputDataFields.filename])\n\n  def testDecodePngImage(self):\n    image_tensor = np.random.randint(255, size=(4, 5, 3)).astype(np.uint8)\n    encoded_png = self._EncodeImage(image_tensor, encoding_type='png')\n    decoded_png = self._DecodeImage(encoded_png, encoding_type='png')\n    example = tf.train.Example(features=tf.train.Features(feature={\n        'image/encoded': self._BytesFeature(encoded_png),\n        'image/format': self._BytesFeature('png'),\n        'image/source_id': self._BytesFeature('image_id')\n    })).SerializeToString()\n\n    example_decoder = tf_example_decoder.TfExampleDecoder()\n    tensor_dict = example_decoder.Decode(tf.convert_to_tensor(example))\n\n    self.assertAllEqual((tensor_dict[fields.InputDataFields.image].\n                         get_shape().as_list()), [None, None, 3])\n    with self.test_session() as sess:\n      tensor_dict = sess.run(tensor_dict)\n\n    self.assertAllEqual(decoded_png, tensor_dict[fields.InputDataFields.image])\n    self.assertEqual('image_id', tensor_dict[fields.InputDataFields.source_id])\n\n  def testDecodeBoundingBox(self):\n    image_tensor = np.random.randint(255, size=(4, 5, 3)).astype(np.uint8)\n    encoded_jpeg = self._EncodeImage(image_tensor)\n    bbox_ymins = [0.0, 4.0]\n    bbox_xmins = [1.0, 5.0]\n    bbox_ymaxs = [2.0, 6.0]\n    bbox_xmaxs = [3.0, 7.0]\n    example = tf.train.Example(features=tf.train.Features(feature={\n        'image/encoded': self._BytesFeature(encoded_jpeg),\n        'image/format': self._BytesFeature('jpeg'),\n        'image/object/bbox/ymin': self._FloatFeature(bbox_ymins),\n        'image/object/bbox/xmin': self._FloatFeature(bbox_xmins),\n        'image/object/bbox/ymax': self._FloatFeature(bbox_ymaxs),\n        'image/object/bbox/xmax': self._FloatFeature(bbox_xmaxs),\n    })).SerializeToString()\n\n    example_decoder = tf_example_decoder.TfExampleDecoder()\n    tensor_dict = example_decoder.Decode(tf.convert_to_tensor(example))\n\n    self.assertAllEqual((tensor_dict[fields.InputDataFields.groundtruth_boxes].\n                         get_shape().as_list()), [None, 4])\n    with self.test_session() as sess:\n      tensor_dict = sess.run(tensor_dict)\n\n    expected_boxes = np.vstack([bbox_ymins, bbox_xmins,\n                                bbox_ymaxs, bbox_xmaxs]).transpose()\n    self.assertAllEqual(expected_boxes,\n                        tensor_dict[fields.InputDataFields.groundtruth_boxes])\n\n  def testDecodeObjectLabel(self):\n    image_tensor = np.random.randint(255, size=(4, 5, 3)).astype(np.uint8)\n    encoded_jpeg = self._EncodeImage(image_tensor)\n    bbox_classes = [0, 1]\n    example = tf.train.Example(features=tf.train.Features(feature={\n        'image/encoded': self._BytesFeature(encoded_jpeg),\n        'image/format': self._BytesFeature('jpeg'),\n        'image/object/class/label': self._Int64Feature(bbox_classes),\n    })).SerializeToString()\n\n    example_decoder = tf_example_decoder.TfExampleDecoder()\n    tensor_dict = example_decoder.Decode(tf.convert_to_tensor(example))\n\n    self.assertAllEqual((tensor_dict[\n        fields.InputDataFields.groundtruth_classes].get_shape().as_list()),\n                        [None])\n\n    with self.test_session() as sess:\n      tensor_dict = sess.run(tensor_dict)\n\n    self.assertAllEqual(bbox_classes,\n                        tensor_dict[fields.InputDataFields.groundtruth_classes])\n\n  def testDecodeObjectArea(self):\n    image_tensor = np.random.randint(255, size=(4, 5, 3)).astype(np.uint8)\n    encoded_jpeg = self._EncodeImage(image_tensor)\n    object_area = [100., 174.]\n    example = tf.train.Example(features=tf.train.Features(feature={\n        'image/encoded': self._BytesFeature(encoded_jpeg),\n        'image/format': self._BytesFeature('jpeg'),\n        'image/object/area': self._FloatFeature(object_area),\n    })).SerializeToString()\n\n    example_decoder = tf_example_decoder.TfExampleDecoder()\n    tensor_dict = example_decoder.Decode(tf.convert_to_tensor(example))\n\n    self.assertAllEqual((tensor_dict[fields.InputDataFields.groundtruth_area].\n                         get_shape().as_list()), [None])\n    with self.test_session() as sess:\n      tensor_dict = sess.run(tensor_dict)\n\n    self.assertAllEqual(object_area,\n                        tensor_dict[fields.InputDataFields.groundtruth_area])\n\n  def testDecodeObjectIsCrowd(self):\n    image_tensor = np.random.randint(255, size=(4, 5, 3)).astype(np.uint8)\n    encoded_jpeg = self._EncodeImage(image_tensor)\n    object_is_crowd = [0, 1]\n    example = tf.train.Example(features=tf.train.Features(feature={\n        'image/encoded': self._BytesFeature(encoded_jpeg),\n        'image/format': self._BytesFeature('jpeg'),\n        'image/object/is_crowd': self._Int64Feature(object_is_crowd),\n    })).SerializeToString()\n\n    example_decoder = tf_example_decoder.TfExampleDecoder()\n    tensor_dict = example_decoder.Decode(tf.convert_to_tensor(example))\n\n    self.assertAllEqual((tensor_dict[\n        fields.InputDataFields.groundtruth_is_crowd].get_shape().as_list()),\n                        [None])\n    with self.test_session() as sess:\n      tensor_dict = sess.run(tensor_dict)\n\n    self.assertAllEqual([bool(item) for item in object_is_crowd],\n                        tensor_dict[\n                            fields.InputDataFields.groundtruth_is_crowd])\n\n  def testDecodeObjectDifficult(self):\n    image_tensor = np.random.randint(255, size=(4, 5, 3)).astype(np.uint8)\n    encoded_jpeg = self._EncodeImage(image_tensor)\n    object_difficult = [0, 1]\n    example = tf.train.Example(features=tf.train.Features(feature={\n        'image/encoded': self._BytesFeature(encoded_jpeg),\n        'image/format': self._BytesFeature('jpeg'),\n        'image/object/difficult': self._Int64Feature(object_difficult),\n    })).SerializeToString()\n\n    example_decoder = tf_example_decoder.TfExampleDecoder()\n    tensor_dict = example_decoder.Decode(tf.convert_to_tensor(example))\n\n    self.assertAllEqual((tensor_dict[\n        fields.InputDataFields.groundtruth_difficult].get_shape().as_list()),\n                        [None])\n    with self.test_session() as sess:\n      tensor_dict = sess.run(tensor_dict)\n\n    self.assertAllEqual([bool(item) for item in object_difficult],\n                        tensor_dict[\n                            fields.InputDataFields.groundtruth_difficult])\n\n  def testDecodeInstanceSegmentation(self):\n    num_instances = 4\n    image_height = 5\n    image_width = 3\n\n    # Randomly generate image.\n    image_tensor = np.random.randint(255, size=(image_height,\n                                                image_width,\n                                                3)).astype(np.uint8)\n    encoded_jpeg = self._EncodeImage(image_tensor)\n\n    # Randomly generate instance segmentation masks.\n    instance_segmentation = (\n        np.random.randint(2, size=(num_instances,\n                                   image_height,\n                                   image_width)).astype(np.int64))\n\n    # Randomly generate class labels for each instance.\n    instance_segmentation_classes = np.random.randint(\n        100, size=(num_instances)).astype(np.int64)\n\n    example = tf.train.Example(features=tf.train.Features(feature={\n        'image/encoded': self._BytesFeature(encoded_jpeg),\n        'image/format': self._BytesFeature('jpeg'),\n        'image/height': self._Int64Feature([image_height]),\n        'image/width': self._Int64Feature([image_width]),\n        'image/segmentation/object': self._Int64Feature(\n            instance_segmentation.flatten()),\n        'image/segmentation/object/class': self._Int64Feature(\n            instance_segmentation_classes)})).SerializeToString()\n    example_decoder = tf_example_decoder.TfExampleDecoder()\n    tensor_dict = example_decoder.Decode(tf.convert_to_tensor(example))\n\n    self.assertAllEqual((\n        tensor_dict[fields.InputDataFields.groundtruth_instance_masks].\n        get_shape().as_list()), [None, None, None])\n\n    self.assertAllEqual((\n        tensor_dict[fields.InputDataFields.groundtruth_instance_classes].\n        get_shape().as_list()), [None])\n\n    with self.test_session() as sess:\n      tensor_dict = sess.run(tensor_dict)\n\n    self.assertAllEqual(\n        instance_segmentation.astype(np.bool),\n        tensor_dict[fields.InputDataFields.groundtruth_instance_masks])\n    self.assertAllEqual(\n        instance_segmentation_classes,\n        tensor_dict[fields.InputDataFields.groundtruth_instance_classes])\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/eval.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\nr\"\"\"Evaluation executable for detection models.\n\nThis executable is used to evaluate DetectionModels. There are two ways of\nconfiguring the eval job.\n\n1) A single pipeline_pb2.TrainEvalPipelineConfig file maybe specified instead.\nIn this mode, the --eval_training_data flag may be given to force the pipeline\nto evaluate on training data instead.\n\nExample usage:\n    ./eval \\\n        --logtostderr \\\n        --checkpoint_dir=path/to/checkpoint_dir \\\n        --eval_dir=path/to/eval_dir \\\n        --pipeline_config_path=pipeline_config.pbtxt\n\n2) Three configuration files may be provided: a model_pb2.DetectionModel\nconfiguration file to define what type of DetectionModel is being evaulated, an\ninput_reader_pb2.InputReader file to specify what data the model is evaluating\nand an eval_pb2.EvalConfig file to configure evaluation parameters.\n\nExample usage:\n    ./eval \\\n        --logtostderr \\\n        --checkpoint_dir=path/to/checkpoint_dir \\\n        --eval_dir=path/to/eval_dir \\\n        --eval_config_path=eval_config.pbtxt \\\n        --model_config_path=model_config.pbtxt \\\n        --input_config_path=eval_input_config.pbtxt\n\"\"\"\nimport functools\nimport tensorflow as tf\n\nfrom google.protobuf import text_format\nfrom object_detection import evaluator\nfrom object_detection.builders import input_reader_builder\nfrom object_detection.builders import model_builder\nfrom object_detection.protos import eval_pb2\nfrom object_detection.protos import input_reader_pb2\nfrom object_detection.protos import model_pb2\nfrom object_detection.protos import pipeline_pb2\nfrom object_detection.utils import label_map_util\n\ntf.logging.set_verbosity(tf.logging.INFO)\n\nflags = tf.app.flags\nflags.DEFINE_boolean('eval_training_data', False,\n                     'If training data should be evaluated for this job.')\nflags.DEFINE_string('checkpoint_dir', '',\n                    'Directory containing checkpoints to evaluate, typically '\n                    'set to `train_dir` used in the training job.')\nflags.DEFINE_string('eval_dir', '',\n                    'Directory to write eval summaries to.')\nflags.DEFINE_string('pipeline_config_path', '',\n                    'Path to a pipeline_pb2.TrainEvalPipelineConfig config '\n                    'file. If provided, other configs are ignored')\nflags.DEFINE_string('eval_config_path', '',\n                    'Path to an eval_pb2.EvalConfig config file.')\nflags.DEFINE_string('input_config_path', '',\n                    'Path to an input_reader_pb2.InputReader config file.')\nflags.DEFINE_string('model_config_path', '',\n                    'Path to a model_pb2.DetectionModel config file.')\n\nFLAGS = flags.FLAGS\n\n\ndef get_configs_from_pipeline_file():\n  \"\"\"Reads evaluation configuration from a pipeline_pb2.TrainEvalPipelineConfig.\n\n  Reads evaluation config from file specified by pipeline_config_path flag.\n\n  Returns:\n    model_config: a model_pb2.DetectionModel\n    eval_config: a eval_pb2.EvalConfig\n    input_config: a input_reader_pb2.InputReader\n  \"\"\"\n  pipeline_config = pipeline_pb2.TrainEvalPipelineConfig()\n  with tf.gfile.GFile(FLAGS.pipeline_config_path, 'r') as f:\n    text_format.Merge(f.read(), pipeline_config)\n\n  model_config = pipeline_config.model\n  if FLAGS.eval_training_data:\n    eval_config = pipeline_config.train_config\n  else:\n    eval_config = pipeline_config.eval_config\n  input_config = pipeline_config.eval_input_reader\n\n  return model_config, eval_config, input_config\n\n\ndef get_configs_from_multiple_files():\n  \"\"\"Reads evaluation configuration from multiple config files.\n\n  Reads the evaluation config from the following files:\n    model_config: Read from --model_config_path\n    eval_config: Read from --eval_config_path\n    input_config: Read from --input_config_path\n\n  Returns:\n    model_config: a model_pb2.DetectionModel\n    eval_config: a eval_pb2.EvalConfig\n    input_config: a input_reader_pb2.InputReader\n  \"\"\"\n  eval_config = eval_pb2.EvalConfig()\n  with tf.gfile.GFile(FLAGS.eval_config_path, 'r') as f:\n    text_format.Merge(f.read(), eval_config)\n\n  model_config = model_pb2.DetectionModel()\n  with tf.gfile.GFile(FLAGS.model_config_path, 'r') as f:\n    text_format.Merge(f.read(), model_config)\n\n  input_config = input_reader_pb2.InputReader()\n  with tf.gfile.GFile(FLAGS.input_config_path, 'r') as f:\n    text_format.Merge(f.read(), input_config)\n\n  return model_config, eval_config, input_config\n\n\ndef main(unused_argv):\n  assert FLAGS.checkpoint_dir, '`checkpoint_dir` is missing.'\n  assert FLAGS.eval_dir, '`eval_dir` is missing.'\n  if FLAGS.pipeline_config_path:\n    model_config, eval_config, input_config = get_configs_from_pipeline_file()\n  else:\n    model_config, eval_config, input_config = get_configs_from_multiple_files()\n\n  model_fn = functools.partial(\n      model_builder.build,\n      model_config=model_config,\n      is_training=False)\n\n  create_input_dict_fn = functools.partial(\n      input_reader_builder.build,\n      input_config)\n\n  label_map = label_map_util.load_labelmap(input_config.label_map_path)\n  max_num_classes = max([item.id for item in label_map.item])\n  categories = label_map_util.convert_label_map_to_categories(\n      label_map, max_num_classes)\n\n  evaluator.evaluate(create_input_dict_fn, model_fn, eval_config, categories,\n                     FLAGS.checkpoint_dir, FLAGS.eval_dir)\n\n\nif __name__ == '__main__':\n  tf.app.run()\n"
  },
  {
    "path": "object_detector_app/object_detection/eval_util.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Common functions for repeatedly evaluating a checkpoint.\n\"\"\"\nimport copy\nimport logging\nimport os\nimport time\n\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.utils import label_map_util\nfrom object_detection.utils import object_detection_evaluation\nfrom object_detection.utils import visualization_utils as vis_utils\n\nslim = tf.contrib.slim\n\n\ndef write_metrics(metrics, global_step, summary_dir):\n  \"\"\"Write metrics to a summary directory.\n\n  Args:\n    metrics: A dictionary containing metric names and values.\n    global_step: Global step at which the metrics are computed.\n    summary_dir: Directory to write tensorflow summaries to.\n  \"\"\"\n  logging.info('Writing metrics to tf summary.')\n  summary_writer = tf.summary.FileWriter(summary_dir)\n  for key in sorted(metrics):\n    summary = tf.Summary(value=[\n        tf.Summary.Value(tag=key, simple_value=metrics[key]),\n    ])\n    summary_writer.add_summary(summary, global_step)\n    logging.info('%s: %f', key, metrics[key])\n  summary_writer.close()\n  logging.info('Metrics written to tf summary.')\n\n\ndef evaluate_detection_results_pascal_voc(result_lists,\n                                          categories,\n                                          label_id_offset=0,\n                                          iou_thres=0.5,\n                                          corloc_summary=False):\n  \"\"\"Computes Pascal VOC detection metrics given groundtruth and detections.\n\n  This function computes Pascal VOC metrics. This function by default\n  takes detections and groundtruth boxes encoded in result_lists and writes\n  evaluation results to tf summaries which can be viewed on tensorboard.\n\n  Args:\n    result_lists: a dictionary holding lists of groundtruth and detection\n      data corresponding to each image being evaluated.  The following keys\n      are required:\n        'image_id': a list of string ids\n        'detection_boxes': a list of float32 numpy arrays of shape [N, 4]\n        'detection_scores': a list of float32 numpy arrays of shape [N]\n        'detection_classes': a list of int32 numpy arrays of shape [N]\n        'groundtruth_boxes': a list of float32 numpy arrays of shape [M, 4]\n        'groundtruth_classes': a list of int32 numpy arrays of shape [M]\n      and the remaining fields below are optional:\n        'difficult': a list of boolean arrays of shape [M] indicating the\n          difficulty of groundtruth boxes. Some datasets like PASCAL VOC provide\n          this information and it is used to remove difficult examples from eval\n          in order to not penalize the models on them.\n      Note that it is okay to have additional fields in result_lists --- they\n      are simply ignored.\n    categories: a list of dictionaries representing all possible categories.\n      Each dict in this list has the following keys:\n          'id': (required) an integer id uniquely identifying this category\n          'name': (required) string representing category name\n            e.g., 'cat', 'dog', 'pizza'\n    label_id_offset: an integer offset for the label space.\n    iou_thres: float determining the IoU threshold at which a box is considered\n        correct. Defaults to the standard 0.5.\n    corloc_summary: boolean. If True, also outputs CorLoc metrics.\n\n  Returns:\n    A dictionary of metric names to scalar values.\n\n  Raises:\n    ValueError: if the set of keys in result_lists is not a superset of the\n      expected list of keys.  Unexpected keys are ignored.\n    ValueError: if the lists in result_lists have inconsistent sizes.\n  \"\"\"\n  # check for expected keys in result_lists\n  expected_keys = [\n      'detection_boxes', 'detection_scores', 'detection_classes', 'image_id'\n  ]\n  expected_keys += ['groundtruth_boxes', 'groundtruth_classes']\n  if not set(expected_keys).issubset(set(result_lists.keys())):\n    raise ValueError('result_lists does not have expected key set.')\n  num_results = len(result_lists[expected_keys[0]])\n  for key in expected_keys:\n    if len(result_lists[key]) != num_results:\n      raise ValueError('Inconsistent list sizes in result_lists')\n\n  # Pascal VOC evaluator assumes foreground index starts from zero.\n  categories = copy.deepcopy(categories)\n  for idx in range(len(categories)):\n    categories[idx]['id'] -= label_id_offset\n\n  # num_classes (maybe encoded as categories)\n  num_classes = max([cat['id'] for cat in categories]) + 1\n  logging.info('Computing Pascal VOC metrics on results.')\n  if all(image_id.isdigit() for image_id in result_lists['image_id']):\n    image_ids = [int(image_id) for image_id in result_lists['image_id']]\n  else:\n    image_ids = range(num_results)\n\n  evaluator = object_detection_evaluation.ObjectDetectionEvaluation(\n      num_classes, matching_iou_threshold=iou_thres)\n\n  difficult_lists = None\n  if 'difficult' in result_lists and result_lists['difficult']:\n    difficult_lists = result_lists['difficult']\n  for idx, image_id in enumerate(image_ids):\n    difficult = None\n    if difficult_lists is not None and difficult_lists[idx].size:\n      difficult = difficult_lists[idx].astype(np.bool)\n    evaluator.add_single_ground_truth_image_info(\n        image_id, result_lists['groundtruth_boxes'][idx],\n        result_lists['groundtruth_classes'][idx] - label_id_offset,\n        difficult)\n    evaluator.add_single_detected_image_info(\n        image_id, result_lists['detection_boxes'][idx],\n        result_lists['detection_scores'][idx],\n        result_lists['detection_classes'][idx] - label_id_offset)\n  per_class_ap, mean_ap, _, _, per_class_corloc, mean_corloc = (\n      evaluator.evaluate())\n\n  metrics = {'Precision/mAP@{}IOU'.format(iou_thres): mean_ap}\n  category_index = label_map_util.create_category_index(categories)\n  for idx in range(per_class_ap.size):\n    if idx in category_index:\n      display_name = ('PerformanceByCategory/mAP@{}IOU/{}'\n                      .format(iou_thres, category_index[idx]['name']))\n      metrics[display_name] = per_class_ap[idx]\n\n  if corloc_summary:\n    metrics['CorLoc/CorLoc@{}IOU'.format(iou_thres)] = mean_corloc\n    for idx in range(per_class_corloc.size):\n      if idx in category_index:\n        display_name = (\n            'PerformanceByCategory/CorLoc@{}IOU/{}'.format(\n                iou_thres, category_index[idx]['name']))\n        metrics[display_name] = per_class_corloc[idx]\n  return metrics\n\n\n# TODO: Add tests.\ndef visualize_detection_results(result_dict,\n                                tag,\n                                global_step,\n                                categories,\n                                summary_dir='',\n                                export_dir='',\n                                agnostic_mode=False,\n                                show_groundtruth=False,\n                                min_score_thresh=.5,\n                                max_num_predictions=20):\n  \"\"\"Visualizes detection results and writes visualizations to image summaries.\n\n  This function visualizes an image with its detected bounding boxes and writes\n  to image summaries which can be viewed on tensorboard.  It optionally also\n  writes images to a directory. In the case of missing entry in the label map,\n  unknown class name in the visualization is shown as \"N/A\".\n\n  Args:\n    result_dict: a dictionary holding groundtruth and detection\n      data corresponding to each image being evaluated.  The following keys\n      are required:\n        'original_image': a numpy array representing the image with shape\n          [1, height, width, 3]\n        'detection_boxes': a numpy array of shape [N, 4]\n        'detection_scores': a numpy array of shape [N]\n        'detection_classes': a numpy array of shape [N]\n      The following keys are optional:\n        'groundtruth_boxes': a numpy array of shape [N, 4]\n        'groundtruth_keypoints': a numpy array of shape [N, num_keypoints, 2]\n      Detections are assumed to be provided in decreasing order of score and for\n      display, and we assume that scores are probabilities between 0 and 1.\n    tag: tensorboard tag (string) to associate with image.\n    global_step: global step at which the visualization are generated.\n    categories: a list of dictionaries representing all possible categories.\n      Each dict in this list has the following keys:\n          'id': (required) an integer id uniquely identifying this category\n          'name': (required) string representing category name\n            e.g., 'cat', 'dog', 'pizza'\n          'supercategory': (optional) string representing the supercategory\n            e.g., 'animal', 'vehicle', 'food', etc\n    summary_dir: the output directory to which the image summaries are written.\n    export_dir: the output directory to which images are written.  If this is\n      empty (default), then images are not exported.\n    agnostic_mode: boolean (default: False) controlling whether to evaluate in\n      class-agnostic mode or not.\n    show_groundtruth: boolean (default: False) controlling whether to show\n      groundtruth boxes in addition to detected boxes\n    min_score_thresh: minimum score threshold for a box to be visualized\n    max_num_predictions: maximum number of detections to visualize\n  Raises:\n    ValueError: if result_dict does not contain the expected keys (i.e.,\n      'original_image', 'detection_boxes', 'detection_scores',\n      'detection_classes')\n  \"\"\"\n  if not set([\n      'original_image', 'detection_boxes', 'detection_scores',\n      'detection_classes'\n  ]).issubset(set(result_dict.keys())):\n    raise ValueError('result_dict does not contain all expected keys.')\n  if show_groundtruth and 'groundtruth_boxes' not in result_dict:\n    raise ValueError('If show_groundtruth is enabled, result_dict must contain '\n                     'groundtruth_boxes.')\n  logging.info('Creating detection visualizations.')\n  category_index = label_map_util.create_category_index(categories)\n\n  image = np.squeeze(result_dict['original_image'], axis=0)\n  detection_boxes = result_dict['detection_boxes']\n  detection_scores = result_dict['detection_scores']\n  detection_classes = np.int32((result_dict['detection_classes']))\n  detection_keypoints = result_dict.get('detection_keypoints', None)\n  detection_masks = result_dict.get('detection_masks', None)\n\n  # Plot groundtruth underneath detections\n  if show_groundtruth:\n    groundtruth_boxes = result_dict['groundtruth_boxes']\n    groundtruth_keypoints = result_dict.get('groundtruth_keypoints', None)\n    vis_utils.visualize_boxes_and_labels_on_image_array(\n        image,\n        groundtruth_boxes,\n        None,\n        None,\n        category_index,\n        keypoints=groundtruth_keypoints,\n        use_normalized_coordinates=False,\n        max_boxes_to_draw=None)\n  vis_utils.visualize_boxes_and_labels_on_image_array(\n      image,\n      detection_boxes,\n      detection_classes,\n      detection_scores,\n      category_index,\n      instance_masks=detection_masks,\n      keypoints=detection_keypoints,\n      use_normalized_coordinates=False,\n      max_boxes_to_draw=max_num_predictions,\n      min_score_thresh=min_score_thresh,\n      agnostic_mode=agnostic_mode)\n\n  if export_dir:\n    export_path = os.path.join(export_dir, 'export-{}.png'.format(tag))\n    vis_utils.save_image_array_as_png(image, export_path)\n\n  summary = tf.Summary(value=[\n      tf.Summary.Value(tag=tag, image=tf.Summary.Image(\n          encoded_image_string=vis_utils.encode_image_array_as_png_str(\n              image)))\n  ])\n  summary_writer = tf.summary.FileWriter(summary_dir)\n  summary_writer.add_summary(summary, global_step)\n  summary_writer.close()\n\n  logging.info('Detection visualizations written to summary with tag %s.', tag)\n\n\n# TODO: Add tests.\n# TODO: Have an argument called `aggregated_processor_tensor_keys` that contains\n# a whitelist of tensors used by the `aggregated_result_processor` instead of a\n# blacklist. This will prevent us from inadvertently adding any evaluated\n# tensors into the `results_list` data structure that are not needed by\n# `aggregated_result_preprocessor`.\ndef run_checkpoint_once(tensor_dict,\n                        update_op,\n                        summary_dir,\n                        aggregated_result_processor=None,\n                        batch_processor=None,\n                        checkpoint_dirs=None,\n                        variables_to_restore=None,\n                        restore_fn=None,\n                        num_batches=1,\n                        master='',\n                        save_graph=False,\n                        save_graph_dir='',\n                        metric_names_to_values=None,\n                        keys_to_exclude_from_results=()):\n  \"\"\"Evaluates both python metrics and tensorflow slim metrics.\n\n  Python metrics are processed in batch by the aggregated_result_processor,\n  while tensorflow slim metrics statistics are computed by running\n  metric_names_to_updates tensors and aggregated using metric_names_to_values\n  tensor.\n\n  Args:\n    tensor_dict: a dictionary holding tensors representing a batch of detections\n      and corresponding groundtruth annotations.\n    update_op: a tensorflow update op that will run for each batch along with\n      the tensors in tensor_dict..\n    summary_dir: a directory to write metrics summaries.\n    aggregated_result_processor: a function taking one arguments:\n      1. result_lists: a dictionary with keys matching those in tensor_dict\n        and corresponding values being the list of results for each tensor\n        in tensor_dict.  The length of each such list is num_batches.\n    batch_processor: a function taking four arguments:\n      1. tensor_dict: the same tensor_dict that is passed in as the first\n        argument to this function.\n      2. sess: a tensorflow session\n      3. batch_index: an integer representing the index of the batch amongst\n        all batches\n      4. update_op: a tensorflow update op that will run for each batch.\n      and returns result_dict, a dictionary of results for that batch.\n      By default, batch_processor is None, which defaults to running:\n        return sess.run(tensor_dict)\n      To skip an image, it suffices to return an empty dictionary in place of\n      result_dict.\n    checkpoint_dirs: list of directories to load into an EnsembleModel. If it\n      has only one directory, EnsembleModel will not be used -- a DetectionModel\n      will be instantiated directly. Not used if restore_fn is set.\n    variables_to_restore: None, or a dictionary mapping variable names found in\n      a checkpoint to model variables. The dictionary would normally be\n      generated by creating a tf.train.ExponentialMovingAverage object and\n      calling its variables_to_restore() method. Not used if restore_fn is set.\n    restore_fn: None, or a function that takes a tf.Session object and correctly\n      restores all necessary variables from the correct checkpoint file. If\n      None, attempts to restore from the first directory in checkpoint_dirs.\n    num_batches: the number of batches to use for evaluation.\n    master: the location of the Tensorflow session.\n    save_graph: whether or not the Tensorflow graph is stored as a pbtxt file.\n    save_graph_dir: where to store the Tensorflow graph on disk. If save_graph\n      is True this must be non-empty.\n    metric_names_to_values: A dictionary containing metric names to tensors\n      which will be evaluated after processing all batches\n      of [tensor_dict, update_op]. If any metrics depend on statistics computed\n      during each batch ensure that `update_op` tensor has a control dependency\n      on the update ops that compute the statistics.\n    keys_to_exclude_from_results: keys in tensor_dict that will be excluded\n      from results_list. Note that the tensors corresponding to these keys will\n      still be evaluated for each batch, but won't be added to results_list.\n\n  Raises:\n    ValueError: if restore_fn is None and checkpoint_dirs doesn't have at least\n      one element.\n    ValueError: if save_graph is True and save_graph_dir is not defined.\n  \"\"\"\n  if save_graph and not save_graph_dir:\n    raise ValueError('`save_graph_dir` must be defined.')\n  sess = tf.Session(master, graph=tf.get_default_graph())\n  sess.run(tf.global_variables_initializer())\n  sess.run(tf.local_variables_initializer())\n  if restore_fn:\n    restore_fn(sess)\n  else:\n    if not checkpoint_dirs:\n      raise ValueError('`checkpoint_dirs` must have at least one entry.')\n    checkpoint_file = tf.train.latest_checkpoint(checkpoint_dirs[0])\n    saver = tf.train.Saver(variables_to_restore)\n    saver.restore(sess, checkpoint_file)\n\n  if save_graph:\n    tf.train.write_graph(sess.graph_def, save_graph_dir, 'eval.pbtxt')\n\n  valid_keys = list(set(tensor_dict.keys()) - set(keys_to_exclude_from_results))\n  result_lists = {key: [] for key in valid_keys}\n  counters = {'skipped': 0, 'success': 0}\n  other_metrics = None\n  with tf.contrib.slim.queues.QueueRunners(sess):\n    try:\n      for batch in range(int(num_batches)):\n        if (batch + 1) % 100 == 0:\n          logging.info('Running eval ops batch %d/%d', batch + 1, num_batches)\n        if not batch_processor:\n          try:\n            (result_dict, _) = sess.run([tensor_dict, update_op])\n            counters['success'] += 1\n          except tf.errors.InvalidArgumentError:\n            logging.info('Skipping image')\n            counters['skipped'] += 1\n            result_dict = {}\n        else:\n          result_dict = batch_processor(\n              tensor_dict, sess, batch, counters, update_op)\n        for key in result_dict:\n          if key in valid_keys:\n            result_lists[key].append(result_dict[key])\n      if metric_names_to_values is not None:\n        other_metrics = sess.run(metric_names_to_values)\n      logging.info('Running eval batches done.')\n    except tf.errors.OutOfRangeError:\n      logging.info('Done evaluating -- epoch limit reached')\n    finally:\n      # When done, ask the threads to stop.\n      metrics = aggregated_result_processor(result_lists)\n      if other_metrics is not None:\n        metrics.update(other_metrics)\n      global_step = tf.train.global_step(sess, slim.get_global_step())\n      write_metrics(metrics, global_step, summary_dir)\n      logging.info('# success: %d', counters['success'])\n      logging.info('# skipped: %d', counters['skipped'])\n  sess.close()\n\n\n# TODO: Add tests.\ndef repeated_checkpoint_run(tensor_dict,\n                            update_op,\n                            summary_dir,\n                            aggregated_result_processor=None,\n                            batch_processor=None,\n                            checkpoint_dirs=None,\n                            variables_to_restore=None,\n                            restore_fn=None,\n                            num_batches=1,\n                            eval_interval_secs=120,\n                            max_number_of_evaluations=None,\n                            master='',\n                            save_graph=False,\n                            save_graph_dir='',\n                            metric_names_to_values=None,\n                            keys_to_exclude_from_results=()):\n  \"\"\"Periodically evaluates desired tensors using checkpoint_dirs or restore_fn.\n\n  This function repeatedly loads a checkpoint and evaluates a desired\n  set of tensors (provided by tensor_dict) and hands the resulting numpy\n  arrays to a function result_processor which can be used to further\n  process/save/visualize the results.\n\n  Args:\n    tensor_dict: a dictionary holding tensors representing a batch of detections\n      and corresponding groundtruth annotations.\n    update_op: a tensorflow update op that will run for each batch along with\n      the tensors in tensor_dict.\n    summary_dir: a directory to write metrics summaries.\n    aggregated_result_processor: a function taking one argument:\n      1. result_lists: a dictionary with keys matching those in tensor_dict\n        and corresponding values being the list of results for each tensor\n        in tensor_dict.  The length of each such list is num_batches.\n    batch_processor: a function taking three arguments:\n      1. tensor_dict: the same tensor_dict that is passed in as the first\n        argument to this function.\n      2. sess: a tensorflow session\n      3. batch_index: an integer representing the index of the batch amongst\n        all batches\n      4. update_op: a tensorflow update op that will run for each batch.\n      and returns result_dict, a dictionary of results for that batch.\n      By default, batch_processor is None, which defaults to running:\n        return sess.run(tensor_dict)\n    checkpoint_dirs: list of directories to load into a DetectionModel or an\n      EnsembleModel if restore_fn isn't set. Also used to determine when to run\n      next evaluation. Must have at least one element.\n    variables_to_restore: None, or a dictionary mapping variable names found in\n      a checkpoint to model variables. The dictionary would normally be\n      generated by creating a tf.train.ExponentialMovingAverage object and\n      calling its variables_to_restore() method. Not used if restore_fn is set.\n    restore_fn: a function that takes a tf.Session object and correctly restores\n      all necessary variables from the correct checkpoint file.\n    num_batches: the number of batches to use for evaluation.\n    eval_interval_secs: the number of seconds between each evaluation run.\n    max_number_of_evaluations: the max number of iterations of the evaluation.\n      If the value is left as None the evaluation continues indefinitely.\n    master: the location of the Tensorflow session.\n    save_graph: whether or not the Tensorflow graph is saved as a pbtxt file.\n    save_graph_dir: where to save on disk the Tensorflow graph. If store_graph\n      is True this must be non-empty.\n    metric_names_to_values: A dictionary containing metric names to tensors\n      which will be evaluated after processing all batches\n      of [tensor_dict, update_op]. If any metrics depend on statistics computed\n      during each batch ensure that `update_op` tensor has a control dependency\n      on the update ops that compute the statistics.\n    keys_to_exclude_from_results: keys in tensor_dict that will be excluded\n      from results_list. Note that the tensors corresponding to these keys will\n      still be evaluated for each batch, but won't be added to results_list.\n\n  Raises:\n    ValueError: if max_num_of_evaluations is not None or a positive number.\n    ValueError: if checkpoint_dirs doesn't have at least one element.\n  \"\"\"\n  if max_number_of_evaluations and max_number_of_evaluations <= 0:\n    raise ValueError(\n        '`number_of_steps` must be either None or a positive number.')\n\n  if not checkpoint_dirs:\n    raise ValueError('`checkpoint_dirs` must have at least one entry.')\n\n  last_evaluated_model_path = None\n  number_of_evaluations = 0\n  while True:\n    start = time.time()\n    logging.info('Starting evaluation at ' + time.strftime('%Y-%m-%d-%H:%M:%S',\n                                                           time.gmtime()))\n    model_path = tf.train.latest_checkpoint(checkpoint_dirs[0])\n    if not model_path:\n      logging.info('No model found in %s. Will try again in %d seconds',\n                   checkpoint_dirs[0], eval_interval_secs)\n    elif model_path == last_evaluated_model_path:\n      logging.info('Found already evaluated checkpoint. Will try again in %d '\n                   'seconds', eval_interval_secs)\n    else:\n      last_evaluated_model_path = model_path\n      run_checkpoint_once(tensor_dict, update_op, summary_dir,\n                          aggregated_result_processor,\n                          batch_processor, checkpoint_dirs,\n                          variables_to_restore, restore_fn, num_batches, master,\n                          save_graph, save_graph_dir, metric_names_to_values,\n                          keys_to_exclude_from_results)\n    number_of_evaluations += 1\n\n    if (max_number_of_evaluations and\n        number_of_evaluations >= max_number_of_evaluations):\n      logging.info('Finished evaluation!')\n      break\n    time_to_next_eval = start + eval_interval_secs - time.time()\n    if time_to_next_eval > 0:\n      time.sleep(time_to_next_eval)\n"
  },
  {
    "path": "object_detector_app/object_detection/evaluator.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Detection model evaluator.\n\nThis file provides a generic evaluation method that can be used to evaluate a\nDetectionModel.\n\"\"\"\nimport logging\nimport tensorflow as tf\n\nfrom object_detection import eval_util\nfrom object_detection.core import box_list\nfrom object_detection.core import box_list_ops\nfrom object_detection.core import prefetcher\nfrom object_detection.core import standard_fields as fields\nfrom object_detection.utils import ops\n\nslim = tf.contrib.slim\n\nEVAL_METRICS_FN_DICT = {\n    'pascal_voc_metrics': eval_util.evaluate_detection_results_pascal_voc\n}\n\n\ndef _extract_prediction_tensors(model,\n                                create_input_dict_fn,\n                                ignore_groundtruth=False):\n  \"\"\"Restores the model in a tensorflow session.\n\n  Args:\n    model: model to perform predictions with.\n    create_input_dict_fn: function to create input tensor dictionaries.\n    ignore_groundtruth: whether groundtruth should be ignored.\n\n  Returns:\n    tensor_dict: A tensor dictionary with evaluations.\n  \"\"\"\n  input_dict = create_input_dict_fn()\n  prefetch_queue = prefetcher.prefetch(input_dict, capacity=500)\n  input_dict = prefetch_queue.dequeue()\n  original_image = tf.expand_dims(input_dict[fields.InputDataFields.image], 0)\n  preprocessed_image = model.preprocess(tf.to_float(original_image))\n  prediction_dict = model.predict(preprocessed_image)\n  detections = model.postprocess(prediction_dict)\n\n  original_image_shape = tf.shape(original_image)\n  absolute_detection_boxlist = box_list_ops.to_absolute_coordinates(\n      box_list.BoxList(tf.squeeze(detections['detection_boxes'], axis=0)),\n      original_image_shape[1], original_image_shape[2])\n  label_id_offset = 1\n  tensor_dict = {\n      'original_image': original_image,\n      'image_id': input_dict[fields.InputDataFields.source_id],\n      'detection_boxes': absolute_detection_boxlist.get(),\n      'detection_scores': tf.squeeze(detections['detection_scores'], axis=0),\n      'detection_classes': (\n          tf.squeeze(detections['detection_classes'], axis=0) +\n          label_id_offset),\n  }\n  if 'detection_masks' in detections:\n    detection_masks = tf.squeeze(detections['detection_masks'],\n                                 axis=0)\n    detection_boxes = tf.squeeze(detections['detection_boxes'],\n                                 axis=0)\n    # TODO: This should be done in model's postprocess function ideally.\n    detection_masks_reframed = ops.reframe_box_masks_to_image_masks(\n        detection_masks,\n        detection_boxes,\n        original_image_shape[1], original_image_shape[2])\n    detection_masks_reframed = tf.to_float(tf.greater(detection_masks_reframed,\n                                                      0.5))\n\n    tensor_dict['detection_masks'] = detection_masks_reframed\n  # load groundtruth fields into tensor_dict\n  if not ignore_groundtruth:\n    normalized_gt_boxlist = box_list.BoxList(\n        input_dict[fields.InputDataFields.groundtruth_boxes])\n    gt_boxlist = box_list_ops.scale(normalized_gt_boxlist,\n                                    tf.shape(original_image)[1],\n                                    tf.shape(original_image)[2])\n    groundtruth_boxes = gt_boxlist.get()\n    groundtruth_classes = input_dict[fields.InputDataFields.groundtruth_classes]\n    tensor_dict['groundtruth_boxes'] = groundtruth_boxes\n    tensor_dict['groundtruth_classes'] = groundtruth_classes\n    tensor_dict['area'] = input_dict[fields.InputDataFields.groundtruth_area]\n    tensor_dict['is_crowd'] = input_dict[\n        fields.InputDataFields.groundtruth_is_crowd]\n    tensor_dict['difficult'] = input_dict[\n        fields.InputDataFields.groundtruth_difficult]\n    if 'detection_masks' in tensor_dict:\n      tensor_dict['groundtruth_instance_masks'] = input_dict[\n          fields.InputDataFields.groundtruth_instance_masks]\n  return tensor_dict\n\n\ndef evaluate(create_input_dict_fn, create_model_fn, eval_config, categories,\n             checkpoint_dir, eval_dir):\n  \"\"\"Evaluation function for detection models.\n\n  Args:\n    create_input_dict_fn: a function to create a tensor input dictionary.\n    create_model_fn: a function that creates a DetectionModel.\n    eval_config: a eval_pb2.EvalConfig protobuf.\n    categories: a list of category dictionaries. Each dict in the list should\n                have an integer 'id' field and string 'name' field.\n    checkpoint_dir: directory to load the checkpoints to evaluate from.\n    eval_dir: directory to write evaluation metrics summary to.\n  \"\"\"\n\n  model = create_model_fn()\n\n  if eval_config.ignore_groundtruth and not eval_config.export_path:\n    logging.fatal('If ignore_groundtruth=True then an export_path is '\n                  'required. Aborting!!!')\n\n  tensor_dict = _extract_prediction_tensors(\n      model=model,\n      create_input_dict_fn=create_input_dict_fn,\n      ignore_groundtruth=eval_config.ignore_groundtruth)\n\n  def _process_batch(tensor_dict, sess, batch_index, counters, update_op):\n    \"\"\"Evaluates tensors in tensor_dict, visualizing the first K examples.\n\n    This function calls sess.run on tensor_dict, evaluating the original_image\n    tensor only on the first K examples and visualizing detections overlaid\n    on this original_image.\n\n    Args:\n      tensor_dict: a dictionary of tensors\n      sess: tensorflow session\n      batch_index: the index of the batch amongst all batches in the run.\n      counters: a dictionary holding 'success' and 'skipped' fields which can\n        be updated to keep track of number of successful and failed runs,\n        respectively.  If these fields are not updated, then the success/skipped\n        counter values shown at the end of evaluation will be incorrect.\n      update_op: An update op that has to be run along with output tensors. For\n        example this could be an op to compute statistics for slim metrics.\n\n    Returns:\n      result_dict: a dictionary of numpy arrays\n    \"\"\"\n    if batch_index >= eval_config.num_visualizations:\n      if 'original_image' in tensor_dict:\n        tensor_dict = {k: v for (k, v) in tensor_dict.iteritems()\n                       if k != 'original_image'}\n    try:\n      (result_dict, _) = sess.run([tensor_dict, update_op])\n      counters['success'] += 1\n    except tf.errors.InvalidArgumentError:\n      logging.info('Skipping image')\n      counters['skipped'] += 1\n      return {}\n    global_step = tf.train.global_step(sess, slim.get_global_step())\n    if batch_index < eval_config.num_visualizations:\n      tag = 'image-{}'.format(batch_index)\n      eval_util.visualize_detection_results(\n          result_dict, tag, global_step, categories=categories,\n          summary_dir=eval_dir,\n          export_dir=eval_config.visualization_export_dir,\n          show_groundtruth=eval_config.visualization_export_dir)\n    return result_dict\n\n  def _process_aggregated_results(result_lists):\n    eval_metric_fn_key = eval_config.metrics_set\n    if eval_metric_fn_key not in EVAL_METRICS_FN_DICT:\n      raise ValueError('Metric not found: {}'.format(eval_metric_fn_key))\n    return EVAL_METRICS_FN_DICT[eval_metric_fn_key](result_lists,\n                                                    categories=categories)\n\n  variables_to_restore = tf.global_variables()\n  global_step = slim.get_or_create_global_step()\n  variables_to_restore.append(global_step)\n  if eval_config.use_moving_averages:\n    variable_averages = tf.train.ExponentialMovingAverage(0.0)\n    variables_to_restore = variable_averages.variables_to_restore()\n  saver = tf.train.Saver(variables_to_restore)\n  def _restore_latest_checkpoint(sess):\n    latest_checkpoint = tf.train.latest_checkpoint(checkpoint_dir)\n    saver.restore(sess, latest_checkpoint)\n\n  eval_util.repeated_checkpoint_run(\n      tensor_dict=tensor_dict,\n      update_op=tf.no_op(),\n      summary_dir=eval_dir,\n      aggregated_result_processor=_process_aggregated_results,\n      batch_processor=_process_batch,\n      checkpoint_dirs=[checkpoint_dir],\n      variables_to_restore=None,\n      restore_fn=_restore_latest_checkpoint,\n      num_batches=eval_config.num_examples,\n      eval_interval_secs=eval_config.eval_interval_secs,\n      max_number_of_evaluations=(\n          1 if eval_config.ignore_groundtruth else\n          eval_config.max_evals if eval_config.max_evals else\n          None),\n      master=eval_config.eval_master,\n      save_graph=eval_config.save_graph,\n      save_graph_dir=(eval_dir if eval_config.save_graph else ''))\n"
  },
  {
    "path": "object_detector_app/object_detection/export_inference_graph.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\nr\"\"\"Tool to export an object detection model for inference.\n\nPrepares an object detection tensorflow graph for inference using model\nconfiguration and an optional trained checkpoint.\n\nThe inference graph contains one of two input nodes depending on the user\nspecified option.\n  * `image_tensor`: Accepts a uint8 4-D tensor of shape [1, None, None, 3]\n  * `tf_example`: Accepts a serialized TFExample proto. The batch size in this\n    case is always 1.\n\nand the following output nodes:\n  * `num_detections` : Outputs float32 tensors of the form [batch]\n      that specifies the number of valid boxes per image in the batch.\n  * `detection_boxes`  : Outputs float32 tensors of the form\n      [batch, num_boxes, 4] containing detected boxes.\n  * `detection_scores` : Outputs float32 tensors of the form\n      [batch, num_boxes] containing class scores for the detections.\n  * `detection_classes`: Outputs float32 tensors of the form\n      [batch, num_boxes] containing classes for the detections.\n\nNote that currently `batch` is always 1, but we will support `batch` > 1 in\nthe future.\n\nOptionally, one can freeze the graph by converting the weights in the provided\ncheckpoint as graph constants thereby eliminating the need to use a checkpoint\nfile during inference.\n\nNote that this tool uses `use_moving_averages` from eval_config to decide\nwhich weights to freeze.\n\nExample Usage:\n--------------\npython export_inference_graph \\\n    --input_type image_tensor \\\n    --pipeline_config_path path/to/ssd_inception_v2.config \\\n    --checkpoint_path path/to/model-ckpt \\\n    --inference_graph_path path/to/inference_graph.pb\n\"\"\"\nimport tensorflow as tf\nfrom google.protobuf import text_format\nfrom object_detection import exporter\nfrom object_detection.protos import pipeline_pb2\n\nslim = tf.contrib.slim\nflags = tf.app.flags\n\nflags.DEFINE_string('input_type', 'image_tensor', 'Type of input node. Can be '\n                    'one of [`image_tensor` `tf_example_proto`]')\nflags.DEFINE_string('pipeline_config_path', '',\n                    'Path to a pipeline_pb2.TrainEvalPipelineConfig config '\n                    'file.')\nflags.DEFINE_string('checkpoint_path', '', 'Optional path to checkpoint file. '\n                    'If provided, bakes the weights from the checkpoint into '\n                    'the graph.')\nflags.DEFINE_string('inference_graph_path', '', 'Path to write the output '\n                    'inference graph.')\n\nFLAGS = flags.FLAGS\n\n\ndef main(_):\n  assert FLAGS.pipeline_config_path, 'TrainEvalPipelineConfig missing.'\n  assert FLAGS.inference_graph_path, 'Inference graph path missing.'\n  assert FLAGS.input_type, 'Input type missing.'\n  pipeline_config = pipeline_pb2.TrainEvalPipelineConfig()\n  with tf.gfile.GFile(FLAGS.pipeline_config_path, 'r') as f:\n    text_format.Merge(f.read(), pipeline_config)\n  exporter.export_inference_graph(FLAGS.input_type, pipeline_config,\n                                  FLAGS.checkpoint_path,\n                                  FLAGS.inference_graph_path)\n\n\nif __name__ == '__main__':\n  tf.app.run()\n"
  },
  {
    "path": "object_detector_app/object_detection/exporter.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Functions to export object detection inference graph.\"\"\"\nimport logging\nimport os\nimport tensorflow as tf\nfrom tensorflow.python import pywrap_tensorflow\nfrom tensorflow.python.client import session\nfrom tensorflow.python.framework import graph_util\nfrom tensorflow.python.framework import importer\nfrom tensorflow.python.platform import gfile\nfrom tensorflow.python.training import saver as saver_lib\nfrom object_detection.builders import model_builder\nfrom object_detection.core import standard_fields as fields\nfrom object_detection.data_decoders import tf_example_decoder\n\nslim = tf.contrib.slim\n\n\n# TODO: Replace with freeze_graph.freeze_graph_with_def_protos when newer\n# version of Tensorflow becomes more common.\ndef freeze_graph_with_def_protos(\n    input_graph_def,\n    input_saver_def,\n    input_checkpoint,\n    output_node_names,\n    restore_op_name,\n    filename_tensor_name,\n    output_graph,\n    clear_devices,\n    initializer_nodes,\n    variable_names_blacklist=''):\n  \"\"\"Converts all variables in a graph and checkpoint into constants.\"\"\"\n  del restore_op_name, filename_tensor_name  # Unused by updated loading code.\n\n  # 'input_checkpoint' may be a prefix if we're using Saver V2 format\n  if not saver_lib.checkpoint_exists(input_checkpoint):\n    logging.info('Input checkpoint \"' + input_checkpoint + '\" does not exist!')\n    return -1\n\n  if not output_node_names:\n    logging.info('You must supply the name of a node to --output_node_names.')\n    return -1\n\n  # Remove all the explicit device specifications for this node. This helps to\n  # make the graph more portable.\n  if clear_devices:\n    for node in input_graph_def.node:\n      node.device = ''\n\n  _ = importer.import_graph_def(input_graph_def, name='')\n\n  with session.Session() as sess:\n    if input_saver_def:\n      saver = saver_lib.Saver(saver_def=input_saver_def)\n      saver.restore(sess, input_checkpoint)\n    else:\n      var_list = {}\n      reader = pywrap_tensorflow.NewCheckpointReader(input_checkpoint)\n      var_to_shape_map = reader.get_variable_to_shape_map()\n      for key in var_to_shape_map:\n        try:\n          tensor = sess.graph.get_tensor_by_name(key + ':0')\n        except KeyError:\n          # This tensor doesn't exist in the graph (for example it's\n          # 'global_step' or a similar housekeeping element) so skip it.\n          continue\n        var_list[key] = tensor\n      saver = saver_lib.Saver(var_list=var_list)\n      saver.restore(sess, input_checkpoint)\n      if initializer_nodes:\n        sess.run(initializer_nodes)\n\n    variable_names_blacklist = (variable_names_blacklist.split(',') if\n                                variable_names_blacklist else None)\n    output_graph_def = graph_util.convert_variables_to_constants(\n        sess,\n        input_graph_def,\n        output_node_names.split(','),\n        variable_names_blacklist=variable_names_blacklist)\n\n  with gfile.GFile(output_graph, 'wb') as f:\n    f.write(output_graph_def.SerializeToString())\n  logging.info('%d ops in the final graph.', len(output_graph_def.node))\n\n\n# TODO: Support batch tf example inputs.\ndef _tf_example_input_placeholder():\n  tf_example_placeholder = tf.placeholder(\n      tf.string, shape=[], name='tf_example')\n  tensor_dict = tf_example_decoder.TfExampleDecoder().Decode(\n      tf_example_placeholder)\n  image = tensor_dict[fields.InputDataFields.image]\n  return tf.expand_dims(image, axis=0)\n\n\ndef _image_tensor_input_placeholder():\n  return tf.placeholder(dtype=tf.uint8,\n                        shape=(1, None, None, 3),\n                        name='image_tensor')\n\ninput_placeholder_fn_map = {\n    'tf_example': _tf_example_input_placeholder,\n    'image_tensor': _image_tensor_input_placeholder\n}\n\n\ndef _add_output_tensor_nodes(postprocessed_tensors):\n  \"\"\"Adds output nodes for detection boxes and scores.\n\n  Adds the following nodes for output tensors -\n    * num_detections: float32 tensor of shape [batch_size].\n    * detection_boxes: float32 tensor of shape [batch_size, num_boxes, 4]\n      containing detected boxes.\n    * detection_scores: float32 tensor of shape [batch_size, num_boxes]\n      containing scores for the detected boxes.\n    * detection_classes: float32 tensor of shape [batch_size, num_boxes]\n      containing class predictions for the detected boxes.\n\n  Args:\n    postprocessed_tensors: a dictionary containing the following fields\n      'detection_boxes': [batch, max_detections, 4]\n      'detection_scores': [batch, max_detections]\n      'detection_classes': [batch, max_detections]\n      'num_detections': [batch]\n  \"\"\"\n  label_id_offset = 1\n  boxes = postprocessed_tensors.get('detection_boxes')\n  scores = postprocessed_tensors.get('detection_scores')\n  classes = postprocessed_tensors.get('detection_classes') + label_id_offset\n  num_detections = postprocessed_tensors.get('num_detections')\n  tf.identity(boxes, name='detection_boxes')\n  tf.identity(scores, name='detection_scores')\n  tf.identity(classes, name='detection_classes')\n  tf.identity(num_detections, name='num_detections')\n\n\ndef _write_inference_graph(inference_graph_path,\n                           checkpoint_path=None,\n                           use_moving_averages=False,\n                           output_node_names=(\n                               'num_detections,detection_scores,'\n                               'detection_boxes,detection_classes')):\n  \"\"\"Writes inference graph to disk with the option to bake in weights.\n\n  If checkpoint_path is not None bakes the weights into the graph thereby\n  eliminating the need of checkpoint files during inference. If the model\n  was trained with moving averages, setting use_moving_averages to true\n  restores the moving averages, otherwise the original set of variables\n  is restored.\n\n  Args:\n    inference_graph_path: Path to write inference graph.\n    checkpoint_path: Optional path to the checkpoint file.\n    use_moving_averages: Whether to export the original or the moving averages\n      of the trainable variables from the checkpoint.\n    output_node_names: Output tensor names, defaults are: num_detections,\n      detection_scores, detection_boxes, detection_classes.\n  \"\"\"\n  inference_graph_def = tf.get_default_graph().as_graph_def()\n  if checkpoint_path:\n    saver = None\n    if use_moving_averages:\n      variable_averages = tf.train.ExponentialMovingAverage(0.0)\n      variables_to_restore = variable_averages.variables_to_restore()\n      saver = tf.train.Saver(variables_to_restore)\n    else:\n      saver = tf.train.Saver()\n    freeze_graph_with_def_protos(\n        input_graph_def=inference_graph_def,\n        input_saver_def=saver.as_saver_def(),\n        input_checkpoint=checkpoint_path,\n        output_node_names=output_node_names,\n        restore_op_name='save/restore_all',\n        filename_tensor_name='save/Const:0',\n        output_graph=inference_graph_path,\n        clear_devices=True,\n        initializer_nodes='')\n    return\n  tf.train.write_graph(inference_graph_def,\n                       os.path.dirname(inference_graph_path),\n                       os.path.basename(inference_graph_path),\n                       as_text=False)\n\n\ndef _export_inference_graph(input_type,\n                            detection_model,\n                            use_moving_averages,\n                            checkpoint_path,\n                            inference_graph_path):\n  if input_type not in input_placeholder_fn_map:\n    raise ValueError('Unknown input type: {}'.format(input_type))\n  inputs = tf.to_float(input_placeholder_fn_map[input_type]())\n  preprocessed_inputs = detection_model.preprocess(inputs)\n  output_tensors = detection_model.predict(preprocessed_inputs)\n  postprocessed_tensors = detection_model.postprocess(output_tensors)\n  _add_output_tensor_nodes(postprocessed_tensors)\n  _write_inference_graph(inference_graph_path, checkpoint_path,\n                         use_moving_averages)\n\n\ndef export_inference_graph(input_type, pipeline_config, checkpoint_path,\n                           inference_graph_path):\n  \"\"\"Exports inference graph for the model specified in the pipeline config.\n\n  Args:\n    input_type: Type of input for the graph. Can be one of [`image_tensor`,\n      `tf_example`].\n    pipeline_config: pipeline_pb2.TrainAndEvalPipelineConfig proto.\n    checkpoint_path: Path to the checkpoint file to freeze.\n    inference_graph_path: Path to write inference graph to.\n  \"\"\"\n  detection_model = model_builder.build(pipeline_config.model,\n                                        is_training=False)\n  _export_inference_graph(input_type, detection_model,\n                          pipeline_config.eval_config.use_moving_averages,\n                          checkpoint_path, inference_graph_path)\n"
  },
  {
    "path": "object_detector_app/object_detection/exporter_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.export_inference_graph.\"\"\"\nimport os\nimport mock\nimport numpy as np\nimport tensorflow as tf\nfrom object_detection import exporter\nfrom object_detection.builders import model_builder\nfrom object_detection.core import model\nfrom object_detection.protos import pipeline_pb2\n\n\nclass FakeModel(model.DetectionModel):\n\n  def preprocess(self, inputs):\n    return (tf.identity(inputs) *\n            tf.get_variable('dummy', shape=(),\n                            initializer=tf.constant_initializer(2),\n                            dtype=tf.float32))\n\n  def predict(self, preprocessed_inputs):\n    return {'image': tf.identity(preprocessed_inputs)}\n\n  def postprocess(self, prediction_dict):\n    with tf.control_dependencies(prediction_dict.values()):\n      return {\n          'detection_boxes': tf.constant([[0.0, 0.0, 0.5, 0.5],\n                                          [0.5, 0.5, 0.8, 0.8]], tf.float32),\n          'detection_scores': tf.constant([[0.7, 0.6]], tf.float32),\n          'detection_classes': tf.constant([[0, 1]], tf.float32),\n          'num_detections': tf.constant([2], tf.float32)\n      }\n\n  def restore_fn(self, checkpoint_path, from_detection_checkpoint):\n    pass\n\n  def loss(self, prediction_dict):\n    pass\n\n\nclass ExportInferenceGraphTest(tf.test.TestCase):\n\n  def _save_checkpoint_from_mock_model(self, checkpoint_path,\n                                       use_moving_averages):\n    g = tf.Graph()\n    with g.as_default():\n      mock_model = FakeModel(num_classes=1)\n      mock_model.preprocess(tf.constant([1, 3, 4, 3], tf.float32))\n      if use_moving_averages:\n        tf.train.ExponentialMovingAverage(0.0).apply()\n      saver = tf.train.Saver()\n      init = tf.global_variables_initializer()\n      with self.test_session() as sess:\n        sess.run(init)\n        saver.save(sess, checkpoint_path)\n\n  def _load_inference_graph(self, inference_graph_path):\n    od_graph = tf.Graph()\n    with od_graph.as_default():\n      od_graph_def = tf.GraphDef()\n      with tf.gfile.GFile(inference_graph_path) as fid:\n        serialized_graph = fid.read()\n        od_graph_def.ParseFromString(serialized_graph)\n        tf.import_graph_def(od_graph_def, name='')\n    return od_graph\n\n  def _create_tf_example(self, image_array):\n    with self.test_session():\n      encoded_image = tf.image.encode_jpeg(tf.constant(image_array)).eval()\n    def _bytes_feature(value):\n      return tf.train.Feature(bytes_list=tf.train.BytesList(value=[value]))\n    example = tf.train.Example(features=tf.train.Features(feature={\n        'image/encoded': _bytes_feature(encoded_image),\n        'image/format': _bytes_feature('jpg'),\n        'image/source_id': _bytes_feature('image_id')\n    })).SerializeToString()\n    return example\n\n  def test_export_graph_with_image_tensor_input(self):\n    with mock.patch.object(\n        model_builder, 'build', autospec=True) as mock_builder:\n      mock_builder.return_value = FakeModel(num_classes=1)\n      inference_graph_path = os.path.join(self.get_temp_dir(),\n                                          'exported_graph.pbtxt')\n\n      pipeline_config = pipeline_pb2.TrainEvalPipelineConfig()\n      pipeline_config.eval_config.use_moving_averages = False\n      exporter.export_inference_graph(\n          input_type='image_tensor',\n          pipeline_config=pipeline_config,\n          checkpoint_path=None,\n          inference_graph_path=inference_graph_path)\n\n  def test_export_graph_with_tf_example_input(self):\n    with mock.patch.object(\n        model_builder, 'build', autospec=True) as mock_builder:\n      mock_builder.return_value = FakeModel(num_classes=1)\n      inference_graph_path = os.path.join(self.get_temp_dir(),\n                                          'exported_graph.pbtxt')\n      pipeline_config = pipeline_pb2.TrainEvalPipelineConfig()\n      pipeline_config.eval_config.use_moving_averages = False\n      exporter.export_inference_graph(\n          input_type='tf_example',\n          pipeline_config=pipeline_config,\n          checkpoint_path=None,\n          inference_graph_path=inference_graph_path)\n\n  def test_export_frozen_graph(self):\n    checkpoint_path = os.path.join(self.get_temp_dir(), 'model-ckpt')\n    self._save_checkpoint_from_mock_model(checkpoint_path,\n                                          use_moving_averages=False)\n    inference_graph_path = os.path.join(self.get_temp_dir(),\n                                        'exported_graph.pb')\n    with mock.patch.object(\n        model_builder, 'build', autospec=True) as mock_builder:\n      mock_builder.return_value = FakeModel(num_classes=1)\n      pipeline_config = pipeline_pb2.TrainEvalPipelineConfig()\n      pipeline_config.eval_config.use_moving_averages = False\n      exporter.export_inference_graph(\n          input_type='image_tensor',\n          pipeline_config=pipeline_config,\n          checkpoint_path=checkpoint_path,\n          inference_graph_path=inference_graph_path)\n\n  def test_export_frozen_graph_with_moving_averages(self):\n    checkpoint_path = os.path.join(self.get_temp_dir(), 'model-ckpt')\n    self._save_checkpoint_from_mock_model(checkpoint_path,\n                                          use_moving_averages=True)\n    inference_graph_path = os.path.join(self.get_temp_dir(),\n                                        'exported_graph.pb')\n    with mock.patch.object(\n        model_builder, 'build', autospec=True) as mock_builder:\n      mock_builder.return_value = FakeModel(num_classes=1)\n      pipeline_config = pipeline_pb2.TrainEvalPipelineConfig()\n      pipeline_config.eval_config.use_moving_averages = True\n      exporter.export_inference_graph(\n          input_type='image_tensor',\n          pipeline_config=pipeline_config,\n          checkpoint_path=checkpoint_path,\n          inference_graph_path=inference_graph_path)\n\n  def test_export_and_run_inference_with_image_tensor(self):\n    checkpoint_path = os.path.join(self.get_temp_dir(), 'model-ckpt')\n    self._save_checkpoint_from_mock_model(checkpoint_path,\n                                          use_moving_averages=False)\n    inference_graph_path = os.path.join(self.get_temp_dir(),\n                                        'exported_graph.pb')\n    with mock.patch.object(\n        model_builder, 'build', autospec=True) as mock_builder:\n      mock_builder.return_value = FakeModel(num_classes=1)\n      pipeline_config = pipeline_pb2.TrainEvalPipelineConfig()\n      pipeline_config.eval_config.use_moving_averages = False\n      exporter.export_inference_graph(\n          input_type='image_tensor',\n          pipeline_config=pipeline_config,\n          checkpoint_path=checkpoint_path,\n          inference_graph_path=inference_graph_path)\n\n    inference_graph = self._load_inference_graph(inference_graph_path)\n    with self.test_session(graph=inference_graph) as sess:\n      image_tensor = inference_graph.get_tensor_by_name('image_tensor:0')\n      boxes = inference_graph.get_tensor_by_name('detection_boxes:0')\n      scores = inference_graph.get_tensor_by_name('detection_scores:0')\n      classes = inference_graph.get_tensor_by_name('detection_classes:0')\n      num_detections = inference_graph.get_tensor_by_name('num_detections:0')\n      (boxes, scores, classes, num_detections) = sess.run(\n          [boxes, scores, classes, num_detections],\n          feed_dict={image_tensor: np.ones((1, 4, 4, 3)).astype(np.uint8)})\n      self.assertAllClose(boxes, [[0.0, 0.0, 0.5, 0.5],\n                                  [0.5, 0.5, 0.8, 0.8]])\n      self.assertAllClose(scores, [[0.7, 0.6]])\n      self.assertAllClose(classes, [[1, 2]])\n      self.assertAllClose(num_detections, [2])\n\n  def test_export_and_run_inference_with_tf_example(self):\n    checkpoint_path = os.path.join(self.get_temp_dir(), 'model-ckpt')\n    self._save_checkpoint_from_mock_model(checkpoint_path,\n                                          use_moving_averages=False)\n    inference_graph_path = os.path.join(self.get_temp_dir(),\n                                        'exported_graph.pb')\n    with mock.patch.object(\n        model_builder, 'build', autospec=True) as mock_builder:\n      mock_builder.return_value = FakeModel(num_classes=1)\n      pipeline_config = pipeline_pb2.TrainEvalPipelineConfig()\n      pipeline_config.eval_config.use_moving_averages = False\n      exporter.export_inference_graph(\n          input_type='tf_example',\n          pipeline_config=pipeline_config,\n          checkpoint_path=checkpoint_path,\n          inference_graph_path=inference_graph_path)\n\n    inference_graph = self._load_inference_graph(inference_graph_path)\n    with self.test_session(graph=inference_graph) as sess:\n      tf_example = inference_graph.get_tensor_by_name('tf_example:0')\n      boxes = inference_graph.get_tensor_by_name('detection_boxes:0')\n      scores = inference_graph.get_tensor_by_name('detection_scores:0')\n      classes = inference_graph.get_tensor_by_name('detection_classes:0')\n      num_detections = inference_graph.get_tensor_by_name('num_detections:0')\n      (boxes, scores, classes, num_detections) = sess.run(\n          [boxes, scores, classes, num_detections],\n          feed_dict={tf_example: self._create_tf_example(\n              np.ones((4, 4, 3)).astype(np.uint8))})\n      self.assertAllClose(boxes, [[0.0, 0.0, 0.5, 0.5],\n                                  [0.5, 0.5, 0.8, 0.8]])\n      self.assertAllClose(scores, [[0.7, 0.6]])\n      self.assertAllClose(classes, [[1, 2]])\n      self.assertAllClose(num_detections, [2])\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/g3doc/configuring_jobs.md",
    "content": "# Configuring the Object Detection Training Pipeline\n\n## Overview\n\nThe Tensorflow Object Detection API uses protobuf files to configure the\ntraining and evaluation process. The schema for the training pipeline can be\nfound in object_detection/protos/pipeline.proto. At a high level, the config\nfile is split into 5 parts:\n\n1. The `model` configuration. This defines what type of model will be trained\n(ie. meta-architecture, feature extractor).\n2. The `train_config`, which decides what parameters should be used to train\nmodel parameters (ie. SGD parameters, input preprocessing and feature extractor\ninitialization values).\n3. The `eval_config`, which determines what set of metrics will be reported for\nevaluation (currently we only support the PASCAL VOC metrics).\n4. The `train_input_config`, which defines what dataset the model should be\ntrained on.\n5. The `eval_input_config`, which defines what dataset the model will be\nevaluated on. Typically this should be different than the training input\ndataset.\n\nA skeleton configuration file is shown below:\n\n```\nmodel {\n(... Add model config here...)\n}\n\ntrain_config : {\n(... Add train_config here...)\n}\n\ntrain_input_reader: {\n(... Add train_input configuration here...)\n}\n\neval_config: {\n}\n\neval_input_reader: {\n(... Add eval_input configuration here...)\n}\n```\n\n## Picking Model Parameters\n\nThere are a large number of model parameters to configure. The best settings\nwill depend on your given application. Faster R-CNN models are better suited to\ncases where high accuracy is desired and latency is of lower priority.\nConversely, if processing time is the most important factor, SSD models are\nrecommended. Read [our paper](https://arxiv.org/abs/1611.10012) for a more\ndetailed discussion on the speed vs accuracy tradeoff.\n\nTo help new users get started, sample model configurations have been provided\nin the object_detection/samples/model_configs folder. The contents of these\nconfiguration files can be pasted into `model` field of the skeleton\nconfiguration. Users should note that the `num_classes` field should be changed\nto a value suited for the dataset the user is training on.\n\n## Defining Inputs\n\nThe Tensorflow Object Detection API accepts inputs in the TFRecord file format.\nUsers must specify the locations of both the training and evaluation files.\nAdditionally, users should also specify a label map, which define the mapping\nbetween a class id and class name. The label map should be identical between\ntraining and evaluation datasets.\n\nAn example input configuration looks as follows:\n\n```\ntf_record_input_reader {\n  input_path: \"/usr/home/username/data/train.record\"\n}\nlabel_map_path: \"/usr/home/username/data/label_map.pbtxt\"\n```\n\nUsers should substitute the `input_path` and `label_map_path` arguments and\ninsert the input configuration into the `train_input_reader` and\n`eval_input_reader` fields in the skeleton configuration. Note that the paths\ncan also point to Google Cloud Storage buckets (ie.\n\"gs://project_bucket/train.record\") for use on Google Cloud.\n\n## Configuring the Trainer\n\nThe `train_config` defines parts of the training process:\n\n1. Model parameter initialization.\n2. Input preprocessing.\n3. SGD parameters.\n\nA sample `train_config` is below:\n\n```\nbatch_size: 1\noptimizer {\n  momentum_optimizer: {\n    learning_rate: {\n      manual_step_learning_rate {\n        initial_learning_rate: 0.0002\n        schedule {\n          step: 0\n          learning_rate: .0002\n        }\n        schedule {\n          step: 900000\n          learning_rate: .00002\n        }\n        schedule {\n          step: 1200000\n          learning_rate: .000002\n        }\n      }\n    }\n    momentum_optimizer_value: 0.9\n  }\n  use_moving_average: false\n}\nfine_tune_checkpoint: \"/usr/home/username/tmp/model.ckpt-#####\"\nfrom_detection_checkpoint: true\ngradient_clipping_by_norm: 10.0\ndata_augmentation_options {\n  random_horizontal_flip {\n  }\n}\n```\n\n### Model Parameter Initialization\n\nWhile optional, it is highly recommended that users utilize other object\ndetection checkpoints. Training an object detector from scratch can take days.\nTo speed up the training process, it is recommended that users re-use the\nfeature extractor parameters from a pre-existing object classification or\ndetection checkpoint. `train_config` provides two fields to specify\npre-existing checkpoints: `fine_tune_checkpoint` and\n`from_detection_checkpoint`. `fine_tune_checkpoint` should provide a path to\nthe pre-existing checkpoint\n(ie:\"/usr/home/username/checkpoint/model.ckpt-#####\").\n`from_detection_checkpoint` is a boolean value. If false, it assumes the\ncheckpoint was from an object classification checkpoint. Note that starting\nfrom a detection checkpoint will usually result in a faster training job than\na classification checkpoint.\n\nThe list of provided checkpoints can be found [here](detection_model_zoo.md).\n\n### Input Preprocessing\n\nThe `data_augmentation_options` in `train_config` can be used to specify\nhow training data can be modified. This field is optional.\n\n### SGD Parameters\n\nThe remainings parameters in `train_config` are hyperparameters for gradient\ndescent. Please note that the optimal learning rates provided in these\nconfiguration files may depend on the specifics of the training setup (e.g.\nnumber of workers, gpu type).\n\n## Configuring the Evaluator\n\nCurrently evaluation is fixed to generating metrics as defined by the PASCAL\nVOC challenge. The parameters for `eval_config` are set to reasonable defaults\nand typically do not need to be configured.\n"
  },
  {
    "path": "object_detector_app/object_detection/g3doc/defining_your_own_model.md",
    "content": "# So you want to create a new model!\n\nIn this section, we discuss some of the abstractions that we use\nfor defining detection models. If you would like to define a new model\narchitecture for detection and use it in the Tensorflow Detection API,\nthen this section should also serve as a high level guide to the files that you\nwill need to edit to get your new model working.\n\n## DetectionModels (`object_detection/core/model.py`)\n\nIn order to be trained, evaluated, and exported for serving  using our\nprovided binaries, all models under the Tensorflow Object Detection API must\nimplement the `DetectionModel` interface (see the full definition in `object_detection/core/model.py`).  In particular,\neach of these models are responsible for implementing 5 functions:\n\n* `preprocess`: Run any preprocessing (e.g., scaling/shifting/reshaping) of\n  input values that is necessary prior to running the detector on an input\n  image.\n* `predict`: Produce “raw” prediction tensors that can be passed to loss or\n  postprocess functions.\n* `postprocess`: Convert predicted output tensors to final detections.\n* `loss`: Compute scalar loss tensors with respect to provided groundtruth.\n* `restore`: Load a checkpoint into the Tensorflow graph.\n\nGiven a `DetectionModel` at training time, we pass each image batch through\nthe following sequence of functions to compute a loss which can be optimized via\nSGD:\n\n```\ninputs (images tensor) -> preprocess -> predict -> loss -> outputs (loss tensor)\n```\n\nAnd at eval time, we pass each image batch through the following sequence of\nfunctions to produce a set of detections:\n\n```\ninputs (images tensor) -> preprocess -> predict -> postprocess ->\n  outputs (boxes tensor, scores tensor, classes tensor, num_detections tensor)\n```\n\nSome conventions to be aware of:\n\n* `DetectionModel`s should make no assumptions about the input size or aspect\n  ratio --- they are responsible for doing any resize/reshaping necessary\n  (see docstring for the `preprocess` function).\n* Output classes are always integers in the range `[0, num_classes)`.\n  Any mapping of these integers to semantic labels is to be handled outside\n  of this class.  We never explicitly emit a “background class” --- thus 0 is\n  the first non-background class and any logic of predicting and removing\n  implicit background classes must be handled internally by the implementation.\n* Detected boxes are to be interpreted as being in\n  `[y_min, x_min, y_max, x_max]` format and normalized relative to the\n  image window.\n* We do not specifically assume any kind of probabilistic interpretation of the\n  scores --- the only important thing is their relative ordering. Thus\n  implementations of the postprocess function are free to output logits,\n  probabilities, calibrated probabilities, or anything else.\n\n## Defining a new Faster R-CNN or SSD Feature Extractor\n\nIn most cases, you probably will not implement a `DetectionModel` from scratch\n--- instead you might create a new feature extractor to be used by one of the\nSSD or Faster R-CNN meta-architectures.  (We think of meta-architectures as\nclasses that define entire families of models using the `DetectionModel`\nabstraction).\n\nNote: For the following discussion to make sense, we recommend first becoming\nfamiliar with the [Faster R-CNN](https://arxiv.org/abs/1506.01497) paper.\n\nLet’s now imagine that you have invented a brand new network architecture\n(say, “InceptionV100”) for classification and want to see how InceptionV100\nwould behave as a feature extractor for detection (say, with Faster R-CNN).\nA similar procedure would hold for SSD models, but we’ll discuss Faster R-CNN.\n\nTo use InceptionV100, we will have to define a new\n`FasterRCNNFeatureExtractor` and pass it to our `FasterRCNNMetaArch`\nconstructor as input.  See\n`object_detection/meta_architectures/faster_rcnn_meta_arch.py` for definitions\nof `FasterRCNNFeatureExtractor` and `FasterRCNNMetaArch`, respectively.\nA `FasterRCNNFeatureExtractor` must define a few\nfunctions:\n\n* `preprocess`: Run any preprocessing of input values that is necessary prior\n  to running the detector on an input image.\n* `_extract_proposal_features`: Extract first stage Region Proposal Network\n  (RPN) features.\n* `_extract_box_classifier_features`: Extract second stage Box Classifier\n  features.\n* `restore_from_classification_checkpoint_fn`: Load a checkpoint into the\n  Tensorflow graph.\n\nSee the `object_detection/models/faster_rcnn_resnet_v1_feature_extractor.py`\ndefinition as one example. Some remarks:\n\n* We typically initialize the weights of this feature extractor\n  using those from the\n  [Slim Resnet-101 classification checkpoint](https://github.com/tensorflow/models/tree/master/slim#pre-trained-models),\n  and we know\n  that images were preprocessed when training this checkpoint\n  by subtracting a channel mean from each input\n  image.  Thus, we implement the preprocess function to replicate the same\n  channel mean subtraction behavior.\n* The “full” resnet classification network defined in slim is cut into two\n  parts --- all but the last “resnet block” is put into the\n  `_extract_proposal_features` function and the final block is separately\n  defined in the `_extract_box_classifier_features function`.  In general,\n  some experimentation may be required to decide on an optimal layer at\n  which to “cut” your feature extractor into these two pieces for Faster R-CNN.\n\n## Register your model for configuration\n\nAssuming that your new feature extractor does not require nonstandard\nconfiguration, you will want to ideally be able to simply change the\n“feature_extractor.type” fields in your configuration protos to point to a\nnew feature extractor.  In order for our API to know how to understand this\nnew type though, you will first have to register your new feature\nextractor with the model builder (`object_detection/builders/model_builder.py`),\nwhose job is to create models from config protos..\n\nRegistration is simple --- just add a pointer to the new Feature Extractor\nclass that you have defined in one of the SSD or Faster R-CNN Feature\nExtractor Class maps at the top of the\n`object_detection/builders/model_builder.py` file.\nWe recommend adding a test in `object_detection/builders/model_builder_test.py`\nto make sure that parsing your proto will work as expected.\n\n## Taking your new model for a spin\n\nAfter registration you are ready to go with your model!  Some final tips:\n\n* To save time debugging, try running your configuration file locally first\n  (both training and evaluation).\n* Do a sweep of learning rates to figure out which learning rate is best\n  for your model.\n* A small but often important detail: you may find it necessary to disable\n  batchnorm training (that is, load the batch norm parameters from the\n  classification checkpoint, but do not update them during gradient descent).\n"
  },
  {
    "path": "object_detector_app/object_detection/g3doc/detection_model_zoo.md",
    "content": "# Tensorflow detection model zoo\n\nWe provide a collection of detection models pre-trained on the\n[COCO dataset](http://mscoco.org).\nThese models can be useful for out-of-the-box inference if you are interested\nin categories already in COCO (e.g., humans, cars, etc).\nThey are also useful for initializing your models when training on novel\ndatasets.\n\nIn the table below, we list each such pre-trained model including:\n\n* a model name that corresponds to a config file that was used to train this\n  model in the `samples/configs` directory,\n* a download link to a tar.gz file containing the pre-trained model,\n* model speed (one of {slow, medium, fast}),\n* detector performance on COCO data as measured by the COCO mAP measure.\n  Here, higher is better, and we only report bounding box mAP rounded to the\n  nearest integer.\n* Output types (currently only `Boxes`)\n\nYou can un-tar each tar.gz file via, e.g.,:\n\n```\ntar -xzvf ssd_mobilenet_v1_coco.tar.gz\n```\n\nInside the un-tar'ed directory, you will find:\n\n* a graph proto (`graph.pbtxt`)\n* a checkpoint\n  (`model.ckpt.data-00000-of-00001`, `model.ckpt.index`, `model.ckpt.meta`)\n* a frozen graph proto with weights baked into the graph as constants\n  (`frozen_inference_graph.pb`) to be used for out of the box inference\n    (try this out in the Jupyter notebook!)\n\n| Model name  | Speed | COCO mAP | Outputs |\n| ------------ | :--------------: | :--------------: | :-------------: |\n| [ssd_mobilenet_v1_coco](http://download.tensorflow.org/models/object_detection/ssd_mobilenet_v1_coco_11_06_2017.tar.gz) | fast | 21 | Boxes |\n| [ssd_inception_v2_coco](http://download.tensorflow.org/models/object_detection/ssd_inception_v2_coco_11_06_2017.tar.gz) | fast | 24 | Boxes |\n| [rfcn_resnet101_coco](http://download.tensorflow.org/models/object_detection/rfcn_resnet101_coco_11_06_2017.tar.gz)  | medium | 30 | Boxes |\n| [faster_rcnn_resnet101_coco](http://download.tensorflow.org/models/object_detection/faster_rcnn_resnet101_coco_11_06_2017.tar.gz) | medium | 32 | Boxes |\n| [faster_rcnn_inception_resnet_v2_atrous_coco](http://download.tensorflow.org/models/object_detection/faster_rcnn_inception_resnet_v2_atrous_coco_11_06_2017.tar.gz) | slow | 37 | Boxes |\n"
  },
  {
    "path": "object_detector_app/object_detection/g3doc/exporting_models.md",
    "content": "# Exporting a trained model for inference\n\nAfter your model has been trained, you should export it to a Tensorflow\ngraph proto. A checkpoint will typically consist of three files:\n\n* model.ckpt-${CHECKPOINT_NUMBER}.data-00000-of-00001,\n* model.ckpt-${CHECKPOINT_NUMBER}.index\n* model.ckpt-${CHECKPOINT_NUMBER}.meta\n\nAfter you've identified a candidate checkpoint to export, run the following\ncommand from tensorflow/models/object_detection:\n\n``` bash\n# From tensorflow/models\npython object_detection/export_inference_graph \\\n    --input_type image_tensor \\\n    --pipeline_config_path ${PIPELINE_CONFIG_PATH} \\\n    --checkpoint_path model.ckpt-${CHECKPOINT_NUMBER} \\\n    --inference_graph_path output_inference_graph.pb\n```\n\nAfterwards, you should see a graph named output_inference_graph.pb.\n"
  },
  {
    "path": "object_detector_app/object_detection/g3doc/installation.md",
    "content": "# Installation\n\n## Dependencies\n\nTensorflow Object Detection API depends on the following libraries:\n\n* Protobuf 2.6\n* Pillow 1.0\n* lxml\n* tf Slim (which is included in the \"tensorflow/models\" checkout)\n* Jupyter notebook\n* Matplotlib\n* Tensorflow\n\nFor detailed steps to install Tensorflow, follow the\n[Tensorflow installation instructions](https://www.tensorflow.org/install/).\nA typically user can install Tensorflow using one of the following commands:\n\n``` bash\n# For CPU\npip install tensorflow\n# For GPU\npip install tensorflow-gpu\n```\n\nThe remaining libraries can be installed on Ubuntu 16.04 using via apt-get:\n\n``` bash\nsudo apt-get install protobuf-compiler python-pil python-lxml\nsudo pip install jupyter\nsudo pip install matplotlib\n```\n\nAlternatively, users can install dependencies using pip:\n\n``` bash\nsudo pip install pillow\nsudo pip install lxml\nsudo pip install jupyter\nsudo pip install matplotlib\n```\n\n## Protobuf Compilation\n\nThe Tensorflow Object Detection API uses Protobufs to configure model and\ntraining parameters. Before the framework can be used, the Protobuf libraries\nmust be compiled. This should be done by running the following command from\nthe tensorflow/models directory:\n\n\n``` bash\n# From tensorflow/models/\nprotoc object_detection/protos/*.proto --python_out=.\n```\n\n## Add Libraries to PYTHONPATH\n\nWhen running locally, the tensorflow/models/ and slim directories should be\nappended to PYTHONPATH. This can be done by running the following from\ntensorflow/models/:\n\n\n``` bash\n# From tensorflow/models/\nexport PYTHONPATH=$PYTHONPATH:`pwd`:`pwd`/slim\n```\n\nNote: This command needs to run from every new terminal you start. If you wish\nto avoid running this manually, you can add it as a new line to the end of your\n~/.bashrc file.\n\n# Testing the Installation\n\nYou can test that you have correctly installed the Tensorflow Object Detection\\\nAPI by running the following command:\n\n``` bash\npython object_detection/builders/model_builder_test.py\n```\n"
  },
  {
    "path": "object_detector_app/object_detection/g3doc/preparing_inputs.md",
    "content": "# Preparing Inputs\n\nTensorflow Object Detection API reads data using the TFRecord file format. Two\nsample scripts (`create_pascal_tf_record.py` and `create_pet_tf_record.py`) are\nprovided to convert from the PASCAL VOC dataset and Oxford-IIT Pet dataset to\nTFRecords.\n\n## Generating the PASCAL VOC TFRecord files.\n\nThe raw 2012 PASCAL VOC data set can be downloaded\n[here](http://host.robots.ox.ac.uk/pascal/VOC/voc2012/VOCtrainval_11-May-2012.tar).\nExtract the tar file and run the `create_pascal_tf_record` script:\n\n```\n# From tensorflow/models/object_detection\ntar -xvf VOCtrainval_11-May-2012.tar\n./create_pascal_tf_record --data_dir=VOCdevkit \\\n    --year=VOC2012 --set=train --output_path=pascal_train.record\n./create_pascal_tf_record --data_dir=/home/user/VOCdevkit \\\n    --year=VOC2012 --set=val --output_path=pascal_val.record\n```\n\nYou should end up with two TFRecord files named pascal_train.record and\npascal_val.record in the tensorflow/models/object_detection directory.\n\nThe label map for the PASCAL VOC data set can be found at\ndata/pascal_label_map.pbtxt.\n\n## Generation the Oxford-IIT Pet TFRecord files.\n\nThe Oxford-IIT Pet data set can be downloaded from\n[their website](http://www.robots.ox.ac.uk/~vgg/data/pets/). Extract the tar\nfile and run the `create_pet_tf_record` script to generate TFRecords.\n\n```\n# From tensorflow/models/object_detection\ntar -xvf annotations.tar.gz\ntar -xvf images.tar.gz\n./create_pet_tf_record --data_dir=`pwd` --output_dir=`pwd`\n```\n\nYou should end up with two TFRecord files named pet_train.record and\npet_val.record in the tensorflow/models/object_detection directory.\n\nThe label map for the Pet dataset can be found at data/pet_label_map.pbtxt.\n"
  },
  {
    "path": "object_detector_app/object_detection/g3doc/running_locally.md",
    "content": "# Running Locally\n\nThis page walks through the steps required to train an object detection model\non a local machine. It assumes the reader has completed the\nfollowing prerequisites:\n\n1. The Tensorflow Object Detection API has been installed as documented in the\n[installation instructions](installation.md). This includes installing library\ndependencies, compiling the configuration protobufs and setting up the Python\nenvironment.\n2. A valid data set has been created. See [this page](preparing_inputs.md) for\ninstructions on how to generate a dataset for the PASCAL VOC challenge or the\nOxford-IIT Pet dataset.\n3. A Object Detection pipeline configuration has been written. See\n[this page](configuring_jobs.md) for details on how to write a pipeline configuration.\n\n## Recommended Directory Structure for Training and Evaluation\n\n```\n+data\n  -label_map file\n  -train TFRecord file\n  -eval TFRecord file\n+models\n  + model\n    -pipeline config file\n    +train\n    +eval\n```\n\n## Running the Training Job\n\nA local training job can be run with the following command:\n\n```bash\n# From the tensorflow/models/ directory\npython object_detection/train.py \\\n    --logtostderr \\\n    --pipeline_config_path=${PATH_TO_YOUR_PIPELINE_CONFIG} \\\n    --train_dir=${PATH_TO_TRAIN_DIR}\n```\n\nwhere `${PATH_TO_YOUR_PIPELINE_CONFIG}` points to the pipeline config and\n`${PATH_TO_TRAIN_DIR}` points to the directory in which training checkpoints\nand events will be written to. By default, the training job will\nrun indefinitely until the user kills it.\n\n## Running the Evaluation Job\n\nEvaluation is run as a separate job. The eval job will periodically poll the\ntrain directory for new checkpoints and evaluate them on a test dataset. The\njob can be run using the following command:\n\n```bash\n# From the tensorflow/models/ directory\npython object_detection/eval.py \\\n    --logtostderr \\\n    --pipeline_config_path=${PATH_TO_YOUR_PIPELINE_CONFIG} \\\n    --checkpoint_dir=${PATH_TO_TRAIN_DIR} \\\n    --eval_dir=${PATH_TO_EVAL_DIR}\n```\n\nwhere `${PATH_TO_YOUR_PIPELINE_CONFIG}` points to the pipeline config,\n`${PATH_TO_TRAIN_DIR}` points to the directory in which training checkpoints\nwere saved (same as the training job) and `${PATH_TO_EVAL_DIR}` points to the\ndirectory in which evaluation events will be saved. As with the training job,\nthe eval job run until terminated by default.\n\n## Running Tensorboard\n\nProgress for training and eval jobs can be inspected using Tensorboard. If\nusing the recommended directory structure, Tensorboard can be run using the\nfollowing command:\n\n```bash\ntensorboard --logdir=${PATH_TO_MODEL_DIRECTORY}\n```\n\nwhere `${PATH_TO_MODEL_DIRECTORY}` points to the directory that contains the\ntrain and eval directories. Please note it make take Tensorboard a couple\nminutes to populate with data.\n"
  },
  {
    "path": "object_detector_app/object_detection/g3doc/running_notebook.md",
    "content": "# Quick Start: Jupyter notebook for off-the-shelf inference\n\nIf you'd like to hit the ground running and run detection on a few example\nimages right out of the box, we recommend trying out the Jupyter notebook demo.\nTo run the Jupyter notebook, run the following command from\n`tensorflow/models/object_detection`:\n\n```\n# From tensorflow/models/object_detection\njupyter notebook\n```\n\nThe notebook should open in your favorite web browser. Click the\n[`object_detection_tutorial.ipynb`](../object_detection_tutorial.ipynb) link\nto open the demo.\n"
  },
  {
    "path": "object_detector_app/object_detection/g3doc/running_on_cloud.md",
    "content": "# Running on Google Cloud Platform\n\nThe Tensorflow Object Detection API supports distributed training on Google\nCloud ML Engine. This section documents instructions on how to train and\nevaluate your model using Cloud ML. The reader should complete the following\nprerequistes:\n\n1. The reader has created and configured a project on Google Cloud Platform.\nSee [the Cloud ML quick start guide](https://cloud.google.com/ml-engine/docs/quickstarts/command-line).\n2. The reader has installed the Tensorflow Object Detection API as documented\nin the [installation instructions](installation.md).\n3. The reader has a valid data set and stored it in a Google Cloud Storage\nbucket. See [this page](preparing_inputs.md) for instructions on how to generate\na dataset for the PASCAL VOC challenge or the Oxford-IIT Pet dataset.\n4. The reader has configured a valid Object Detection pipeline, and stored it\nin a Google Cloud Storage bucket. See [this page](configuring_jobs.md) for\ndetails on how to write a pipeline configuration.\n\nAdditionally, it is recommended users test their job by running training and\nevaluation jobs for a few iterations\n[locally on their own machines](running_locally.md).\n\n## Packaging\n\nIn order to run the Tensorflow Object Detection API on Cloud ML, it must be\npackaged (along with it's TF-Slim dependency). The required packages can be\ncreated with the following command\n\n``` bash\n# From tensorflow/models/\npython setup.py sdist\n(cd slim && python setup.py sdist)\n```\n\nThis will create python packages in dist/object_detection-0.1.tar.gz and\nslim/dist/slim-0.1.tar.gz.\n\n## Running a Multiworker Training Job\n\nGoogle Cloud ML requires a YAML configuration file for a multiworker training\njob using GPUs. A sample YAML file is given below:\n\n```\ntrainingInput:\n  runtimeVersion: \"1.0\"\n  scaleTier: CUSTOM\n  masterType: standard_gpu\n  workerCount: 9\n  workerType: standard_gpu\n  parameterServerCount: 3\n  parameterServerType: standard\n\n\n```\n\nPlease keep the following guidelines in mind when writing the YAML\nconfiguration:\n\n* A job with n workers will have n + 1 training machines (n workers + 1 master).\n* The number of parameters servers used should be an odd number to prevent\n  a parameter server from storing only weight variables or only bias variables\n  (due to round robin parameter scheduling).\n* The learning rate in the training config should be decreased when using a\n  larger number of workers. Some experimentation is required to find the\n  optimal learning rate.\n\nThe YAML file should be saved on the local machine (not on GCP). Once it has\nbeen written, a user can start a training job on Cloud ML Engine using the\nfollowing command:\n\n``` bash\n# From tensorflow/models/\ngcloud ml-engine jobs submit training object_detection_`date +%s` \\\n    --job-dir=gs://${TRAIN_DIR} \\\n    --packages dist/object_detection-0.1.tar.gz,slim/dist/slim-0.1.tar.gz \\\n    --module-name object_detection.train \\\n    --region us-central1 \\\n    --config ${PATH_TO_LOCAL_YAML_FILE} \\\n    -- \\\n    --train_dir=gs://${TRAIN_DIR} \\\n    --pipeline_config_path=gs://${PIPELINE_CONFIG_PATH}\n```\n\nWhere `${PATH_TO_LOCAL_YAML_FILE}` is the local path to the YAML configuration,\n`gs://${TRAIN_DIR}` specifies the directory on Google Cloud Storage where the\ntraining checkpoints and events will be written to and\n`gs://${PIPELINE_CONFIG_PATH}` points to the pipeline configuration stored on\nGoogle Cloud Storage.\n\nUsers can monitor the progress of their training job on the [ML Engine\nDasboard](https://pantheon.corp.google.com/mlengine/jobs).\n\n## Running an Evaluation Job on Cloud\n\nEvaluation jobs run on a single machine, so it is not necessary to write a YAML\nconfiguration for evaluation. Run the following command to start the evaluation\njob:\n\n``` bash\ngcloud ml-engine jobs submit training object_detection_eval_`date +%s` \\\n    --job-dir=gs://${TRAIN_DIR} \\\n    --packages dist/object_detection-0.1.tar.gz,slim/dist/slim-0.1.tar.gz \\\n    --module-name object_detection.eval \\\n    --region us-central1 \\\n    --scale-tier BASIC_GPU \\\n    -- \\\n    --checkpoint_dir=gs://${TRAIN_DIR} \\\n    --eval_dir=gs://${EVAL_DIR} \\\n    --pipeline_config_path=gs://${PIPELINE_CONFIG_PATH}\n```\n\nWhere `gs://${TRAIN_DIR}` points to the directory on Google Cloud Storage where\ntraining checkpoints are saved (same as the training job), `gs://${EVAL_DIR}`\npoints to where evaluation events will be saved on Google Cloud Storage and\n`gs://${PIPELINE_CONFIG_PATH}` points to where the pipeline configuration is\nstored on Google Cloud Storage.\n\n## Running Tensorboard\n\nYou can run Tensorboard locally on your own machine to view progress of your\ntraining and eval jobs on Google Cloud ML. Run the following command to start\nTensorboard:\n\n``` bash\ntensorboard --logdir=gs://${YOUR_CLOUD_BUCKET}\n```\n\nNote it may Tensorboard a few minutes to populate with results.\n"
  },
  {
    "path": "object_detector_app/object_detection/g3doc/running_pets.md",
    "content": "# Quick Start: Distributed Training on the Oxford-IIT Pets Dataset on Google Cloud\n\nThis page is a walkthrough for training an object detector using the Tensorflow\nObject Detection API. In this tutorial, we'll be training on the Oxford-IIT Pets\ndataset to build a system to detect various breeds of cats and dogs. The output\nof the detector will look like the following:\n\n![](img/oxford_pet.png)\n\n## Setting up a Project on Google Cloud\n\nTo accelerate the process, we'll run training and evaluation on [Google Cloud\nML Engine](https://cloud.google.com/ml-engine/) to leverage multiple GPUs. To\nbegin, you will have to set up Google Cloud via the following steps (if you have\nalready done this, feel free to skip to the next section):\n\n1. [Create a GCP project](https://cloud.google.com/resource-manager/docs/creating-managing-projects).\n2. [Install the Google Cloud SDK](https://cloud.google.com/sdk/downloads) on\nyour workstation or laptop.\nThis will provide the tools you need to upload files to Google Cloud Storage and\nstart ML training jobs.\n3. [Enable the ML Engine\nAPIs](https://console.cloud.google.com/flows/enableapi?apiid=ml.googleapis.com,compute_component&_ga=1.73374291.1570145678.1496689256).\nBy default, a new GCP project does not enable APIs to start ML Engine training\njobs. Use the above link to explicitly enable them.\n4. [Set up a Google Cloud Storage (GCS)\nbucket](https://cloud.google.com/storage/docs/creating-buckets). ML Engine\ntraining jobs can only access files on a Google Cloud Storage bucket. In this\ntutorial, we'll be required to upload our dataset and configuration to GCS.\n\nPlease remember the name of your GCS bucket, as we will reference it multiple\ntimes in this document. Substitute `${YOUR_GCS_BUCKET}` with the name of\nyour bucket in this document. For your convenience, you should define the\nenvironment variable below:\n\n``` bash\nexport YOUR_GCS_BUCKET=${YOUR_GCS_BUCKET}\n```\n\n## Installing Tensorflow and the Tensorflow Object Detection API\n\nPlease run through the [installation instructions](installation.md) to install\nTensorflow and all it dependencies. Ensure the Protobuf libraries are\ncompiled and the library directories are added to `PYTHONPATH`.\n\n## Getting the Oxford-IIT Pets Dataset and Uploading it to Google Cloud Storage\n\nIn order to train a detector, we require a dataset of images, bounding boxes and\nclassifications. For this demo, we'll use the Oxford-IIT Pets dataset. The raw\ndataset for Oxford-IIT Pets lives\n[here](http://www.robots.ox.ac.uk/~vgg/data/pets/). You will need to download\nboth the image dataset [`images.tar.gz`](http://www.robots.ox.ac.uk/~vgg/data/pets/data/images.tar.gz)\nand the groundtruth data [`annotations.tar.gz`](http://www.robots.ox.ac.uk/~vgg/data/pets/data/annotations.tar.gz)\nto the tensorflow/models directory. This may take some time. After downloading\nthe tarballs, your object_detection directory should appear as follows:\n\n```lang-none\n+ object_detection/\n  + data/\n  - images.tar.gz\n  - annotations.tar.gz\n  - create_pet_tf_record.py\n  ... other files and directories\n```\n\nThe Tensorflow Object Detection API expects data to be in the TFRecord format,\nso we'll now run the _create_pet_tf_record_ script to convert from the raw\nOxford-IIT Pet dataset into TFRecords. Run the following commands from the\nobject_detection directory:\n\n``` bash\n# From tensorflow/models/\nwget http://www.robots.ox.ac.uk/~vgg/data/pets/data/images.tar.gz\nwget http://www.robots.ox.ac.uk/~vgg/data/pets/data/annotations.tar.gz\ntar -xvf annotations.tar.gz\ntar -xvf images.tar.gz\npython object_detection/create_pet_tf_record.py \\\n    --label_map_path=object_detection/data/pet_label_map.pbtxt \\\n    --data_dir=`pwd` \\\n    --output_dir=`pwd`\n```\n\nNote: It is normal to see some warnings when running this script. You may ignore\nthem.\n\nTwo TFRecord files named pet_train.record and pet_val.record should be generated\nin the object_detection/ directory.\n\nNow that the data has been generated, we'll need to upload it to Google Cloud\nStorage so the data can be accessed by ML Engine. Run the following command to\ncopy the files into your GCS bucket (substituting ${YOUR_GCS_BUCKET}):\n\n``` bash\n# From tensorflow/models/\ngsutil cp pet_train.record gs://${YOUR_GCS_BUCKET}/data/pet_train.record\ngsutil cp pet_val.record gs://${YOUR_GCS_BUCKET}/data/pet_val.record\ngsutil cp object_detection/data/pet_label_map.pbtxt gs://${YOUR_GCS_BUCKET}/data/pet_label_map.pbtxt\n```\n\nPlease remember the path where you upload the data to, as we will need this\ninformation when configuring the pipeline in a following step.\n\n## Downloading a COCO-pretrained Model for Transfer Learning\n\nTraining a state of the art object detector from scratch can take days, even\nwhen using multiple GPUs! In order to speed up training, we'll take an object\ndetector trained on a different dataset (COCO), and reuse some of it's\nparameters to initialize our new model.\n\nDownload our [COCO-pretrained Faster R-CNN with Resnet-101\nmodel](http://storage.googleapis.com/download.tensorflow.org/models/object_detection/faster_rcnn_resnet101_coco_11_06_2017.tar.gz).\nUnzip the contents of the folder and copy the model.ckpt* files into your GCS\nBucket.\n\n``` bash\nwget http://storage.googleapis.com/download.tensorflow.org/models/object_detection/faster_rcnn_resnet101_coco_11_06_2017.tar.gz\ntar -xvf faster_rcnn_resnet101_coco_11_06_2017.tar.gz\ngsutil cp faster_rcnn_resnet101_coco_11_06_2017/model.ckpt.* gs://${YOUR_GCS_BUCKET}/data/\n```\n\nRemember the path where you uploaded the model checkpoint to, as we will need it\nin the following step.\n\n## Configuring the Object Detection Pipeline\n\nIn the Tensorflow Object Detection API, the model parameters, training\nparameters and eval parameters are all defined by a config file. More details\ncan be found [here](configuring_jobs.md). For this tutorial, we will use some\npredefined templates provided with the source code. In the\nobject_detection/samples/configs folder, there are skeleton object_detection\nconfiguration files. We will use `faster_rcnn_resnet101_pets.config` as a\nstarting point for configuring the pipeline. Open the file with your favourite\ntext editor.\n\nWe'll need to configure some paths in order for the template to work. Search the\nfile for instances of `PATH_TO_BE_CONFIGURED` and replace them with the\nappropriate value (typically \"gs://${YOUR_GCS_BUCKET}/data/\"). Afterwards\nupload your edited file onto GCS, making note of the path it was uploaded to\n(we'll need it when starting the training/eval jobs).\n\n``` bash\n# From tensorflow/models/\n\n# Edit the faster_rcnn_resnet101_pets.config template. Please note that there\n# are multiple places where PATH_TO_BE_CONFIGURED needs to be set.\nsed -i \"s|PATH_TO_BE_CONFIGURED|\"gs://${YOUR_GCS_BUCKET}\"/data|g\" \\\n    object_detection/samples/configs/faster_rcnn_resnet101_pets.config\n\n# Copy editted template to cloud.\ngsutil cp object_detection/samples/configs/faster_rcnn_resnet101_pets.config \\\n    gs://${YOUR_GCS_BUCKET}/data/faster_rcnn_resnet101_pets.config\n```\n\n## Checking Your Google Cloud Storage Bucket\n\nAt this point in the tutorial, you should have uploaded the training/validation\ndatasets (including label map), our COCO trained FasterRCNN finetune checkpoint and your job\nconfiguration to your Google Cloud Storage Bucket. Your bucket should look like\nthe following:\n\n```lang-none\n+ ${YOUR_GCS_BUCKET}/\n  + data/\n    - faster_rcnn_resnet101_pets.config\n    - model.ckpt.index\n    - model.ckpt.meta\n    - model.ckpt.data-00000-of-00001\n    - pet_label_map.pbtxt\n    - pet_train.record\n    - pet_val.record\n```\n\nYou can inspect your bucket using the [Google Cloud Storage\nbrowser](pantheon.corp.google.com/storage).\n\n## Starting Training and Evaluation Jobs on Google Cloud ML Engine\n\nBefore we can start a job on Google Cloud ML Engine, we must:\n\n1. Package the Tensorflow Object Detection code.\n2. Write a cluster configuration for our Google Cloud ML job.\n\nTo package the Tensorflow Object Detection code, run the following commands from\nthe tensorflow/models/ directory:\n\n``` bash\n# From tensorflow/models/\npython setup.py sdist\n(cd slim && python setup.py sdist)\n```\n\nYou should see two tar.gz files created at `dist/object_detection-0.1.tar.gz`\nand `slim/dist/slim-0.1.tar.gz`.\n\nFor running the training Cloud ML job, we'll configure the cluster to use 10\ntraining jobs (1 master + 9 workers) and three parameters servers. The\nconfiguration file can be found at object_detection/samples/cloud/cloud.yml.\n\nTo start training, execute the following command from the tensorflow/models/\ndirectory:\n\n``` bash\n# From tensorflow/models/\ngcloud ml-engine jobs submit training `whoami`_object_detection_`date +%s` \\\n    --job-dir=gs://${YOUR_GCS_BUCKET}/train \\\n    --packages dist/object_detection-0.1.tar.gz,slim/dist/slim-0.1.tar.gz \\\n    --module-name object_detection.train \\\n    --region us-central1 \\\n    --config object_detection/samples/cloud/cloud.yml \\\n    -- \\\n    --train_dir=gs://${YOUR_GCS_BUCKET}/train \\\n    --pipeline_config_path=gs://${YOUR_GCS_BUCKET}/data/faster_rcnn_resnet101_pets.config\n```\n\nOnce training has started, we can run an evaluation concurrently:\n\n``` bash\n# From tensorflow/models/\ngcloud ml-engine jobs submit training `whoami`_object_detection_eval_`date +%s` \\\n    --job-dir=gs://${YOUR_GCS_BUCKET}/train \\\n    --packages dist/object_detection-0.1.tar.gz,slim/dist/slim-0.1.tar.gz \\\n    --module-name object_detection.eval \\\n    --region us-central1 \\\n    --scale-tier BASIC_GPU \\\n    -- \\\n    --checkpoint_dir=gs://${YOUR_GCS_BUCKET}/train \\\n    --eval_dir=gs://${YOUR_GCS_BUCKET}/eval \\\n    --pipeline_config_path=gs://${YOUR_GCS_BUCKET}/data/faster_rcnn_resnet101_pets.config\n```\n\nNote: Even though we're running an evaluation job, the `gcloud ml-engine jobs\nsubmit training` command is correct. ML Engine does not distinguish between\ntraining and evaluation jobs.\n\nUsers can monitor and stop training and evaluation jobs on the [ML Engine\nDasboard](https://pantheon.corp.google.com/mlengine/jobs).\n\n## Monitoring Progress with Tensorboard\n\nYou can monitor progress of the training and eval jobs by running Tensorboard on\nyour local machine:\n\n``` bash\n# This command needs to be run once to allow your local machine to access your\n# GCS bucket.\ngcloud auth application-default login\n\ntensorboard --logdir=gs://${YOUR_GCS_BUCKET}\n```\n\nOnce Tensorboard is running, navigate to `localhost:6006` from your favourite\nweb browser. You should something similar see the following:\n\n![](img/tensorboard.png)\n\nYou will also want to click on the images tab to see example detections made by\nthe model while it trains. After about an hour and a half of training, you can\nexpect to see something like this:\n\n![](img/tensorboard2.png)\n\nNote: It takes roughly 10 minutes for a job to get started on ML Engine, and\nroughly an hour for the system to evaluate the validation dataset. It may take\nsome time to populate the dashboards. If you do not see any entries after half\nan hour, check the logs from the [ML Engine\nDasboard](https://pantheon.corp.google.com/mlengine/jobs).\n\n## Exporting the Tensorflow Graph\n\nAfter your model has been trained, you should export it to a Tensorflow\ngraph proto. First, you need to identify a candidate checkpoint to export. You\ncan search your bucket using the [Google Cloud Storage\nBrowser](https://pantheon.corp.google.com/storage/browser). The file should be\nstored under ${YOUR_GCS_BUCKET}/train. The checkpoint will typically consist of\nthree files:\n\n* model.ckpt-${CHECKPOINT_NUMBER}.data-00000-of-00001,\n* model.ckpt-${CHECKPOINT_NUMBER}.index\n* model.ckpt-${CHECKPOINT_NUMBER}.meta\n\nAfter you've identified a candidate checkpoint to export, run the following\ncommand from tensorflow/models/object_detection:\n\n``` bash\n# From tensorflow/models\ngsutil cp gs://${YOUR_GCS_BUCKET}/train/model.ckpt-${CHECKPOINT_NUMBER}.* .\npython object_detection/export_inference_graph \\\n    --input_type image_tensor \\\n    --pipeline_config_path object_detection/samples/configs/faster_rcnn_resnet101_pets.config \\\n    --checkpoint_path model.ckpt-${CHECKPOINT_NUMBER} \\\n    --inference_graph_path output_inference_graph.pb\n```\n\nAfterwards, you should see a graph named output_inference_graph.pb.\n\n## What's Next\n\nCongratulations, you have now trained an object detector for various cats and\ndogs! There different things you can do now:\n\n1. [Test your exported model using the provided Jupyter notebook.](running_notebook.md)\n2. [Experiment with different model configurations.](configuring_jobs.md)\n3. Train an object detector using your own data.\n"
  },
  {
    "path": "object_detector_app/object_detection/matchers/BUILD",
    "content": "# Tensorflow Object Detection API: Matcher implementations.\n\npackage(\n    default_visibility = [\"//visibility:public\"],\n)\n\nlicenses([\"notice\"])\n\n# Apache 2.0\npy_library(\n    name = \"argmax_matcher\",\n    srcs = [\n        \"argmax_matcher.py\",\n    ],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:matcher\",\n    ],\n)\n\npy_test(\n    name = \"argmax_matcher_test\",\n    srcs = [\"argmax_matcher_test.py\"],\n    deps = [\n        \":argmax_matcher\",\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"bipartite_matcher\",\n    srcs = [\n        \"bipartite_matcher.py\",\n    ],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow/contrib/image:image_py\",\n        \"//tensorflow_models/object_detection/core:matcher\",\n    ],\n)\n\npy_test(\n    name = \"bipartite_matcher_test\",\n    srcs = [\n        \"bipartite_matcher_test.py\",\n    ],\n    deps = [\n        \":bipartite_matcher\",\n        \"//tensorflow\",\n    ],\n)\n"
  },
  {
    "path": "object_detector_app/object_detection/matchers/__init__.py",
    "content": ""
  },
  {
    "path": "object_detector_app/object_detection/matchers/argmax_matcher.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Argmax matcher implementation.\n\nThis class takes a similarity matrix and matches columns to rows based on the\nmaximum value per column. One can specify matched_thresholds and\nto prevent columns from matching to rows (generally resulting in a negative\ntraining example) and unmatched_theshold to ignore the match (generally\nresulting in neither a positive or negative training example).\n\nThis matcher is used in Fast(er)-RCNN.\n\nNote: matchers are used in TargetAssigners. There is a create_target_assigner\nfactory function for popular implementations.\n\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.core import matcher\n\n\nclass ArgMaxMatcher(matcher.Matcher):\n  \"\"\"Matcher based on highest value.\n\n  This class computes matches from a similarity matrix. Each column is matched\n  to a single row.\n\n  To support object detection target assignment this class enables setting both\n  matched_threshold (upper threshold) and unmatched_threshold (lower thresholds)\n  defining three categories of similarity which define whether examples are\n  positive, negative, or ignored:\n  (1) similarity >= matched_threshold: Highest similarity. Matched/Positive!\n  (2) matched_threshold > similarity >= unmatched_threshold: Medium similarity.\n          Depending on negatives_lower_than_unmatched, this is either\n          Unmatched/Negative OR Ignore.\n  (3) unmatched_threshold > similarity: Lowest similarity. Depending on flag\n          negatives_lower_than_unmatched, either Unmatched/Negative OR Ignore.\n  For ignored matches this class sets the values in the Match object to -2.\n  \"\"\"\n\n  def __init__(self,\n               matched_threshold,\n               unmatched_threshold=None,\n               negatives_lower_than_unmatched=True,\n               force_match_for_each_row=False):\n    \"\"\"Construct ArgMaxMatcher.\n\n    Args:\n      matched_threshold: Threshold for positive matches. Positive if\n        sim >= matched_threshold, where sim is the maximum value of the\n        similarity matrix for a given column. Set to None for no threshold.\n      unmatched_threshold: Threshold for negative matches. Negative if\n        sim < unmatched_threshold. Defaults to matched_threshold\n        when set to None.\n      negatives_lower_than_unmatched: Boolean which defaults to True. If True\n        then negative matches are the ones below the unmatched_threshold,\n        whereas ignored matches are in between the matched and umatched\n        threshold. If False, then negative matches are in between the matched\n        and unmatched threshold, and everything lower than unmatched is ignored.\n      force_match_for_each_row: If True, ensures that each row is matched to\n        at least one column (which is not guaranteed otherwise if the\n        matched_threshold is high). Defaults to False. See\n        argmax_matcher_test.testMatcherForceMatch() for an example.\n\n    Raises:\n      ValueError: if unmatched_threshold is set but matched_threshold is not set\n        or if unmatched_threshold > matched_threshold.\n    \"\"\"\n    if (matched_threshold is None) and (unmatched_threshold is not None):\n      raise ValueError('Need to also define matched_threshold when'\n                       'unmatched_threshold is defined')\n    self._matched_threshold = matched_threshold\n    if unmatched_threshold is None:\n      self._unmatched_threshold = matched_threshold\n    else:\n      if unmatched_threshold > matched_threshold:\n        raise ValueError('unmatched_threshold needs to be smaller or equal'\n                         'to matched_threshold')\n      self._unmatched_threshold = unmatched_threshold\n    if not negatives_lower_than_unmatched:\n      if self._unmatched_threshold == self._matched_threshold:\n        raise ValueError('When negatives are in between matched and '\n                         'unmatched thresholds, these cannot be of equal '\n                         'value. matched: %s, unmatched: %s',\n                         self._matched_threshold, self._unmatched_threshold)\n    self._force_match_for_each_row = force_match_for_each_row\n    self._negatives_lower_than_unmatched = negatives_lower_than_unmatched\n\n  def _match(self, similarity_matrix):\n    \"\"\"Tries to match each column of the similarity matrix to a row.\n\n    Args:\n      similarity_matrix: tensor of shape [N, M] representing any similarity\n        metric.\n\n    Returns:\n      Match object with corresponding matches for each of M columns.\n    \"\"\"\n\n    def _match_when_rows_are_empty():\n      \"\"\"Performs matching when the rows of similarity matrix are empty.\n\n      When the rows are empty, all detections are false positives. So we return\n      a tensor of -1's to indicate that the columns do not match to any rows.\n\n      Returns:\n        matches:  int32 tensor indicating the row each column matches to.\n      \"\"\"\n      return -1 * tf.ones([tf.shape(similarity_matrix)[1]], dtype=tf.int32)\n\n    def _match_when_rows_are_non_empty():\n      \"\"\"Performs matching when the rows of similarity matrix are non empty.\n\n      Returns:\n        matches:  int32 tensor indicating the row each column matches to.\n      \"\"\"\n      # Matches for each column\n      matches = tf.argmax(similarity_matrix, 0)\n\n      # Deal with matched and unmatched threshold\n      if self._matched_threshold is not None:\n        # Get logical indices of ignored and unmatched columns as tf.int64\n        matched_vals = tf.reduce_max(similarity_matrix, 0)\n        below_unmatched_threshold = tf.greater(self._unmatched_threshold,\n                                               matched_vals)\n        between_thresholds = tf.logical_and(\n            tf.greater_equal(matched_vals, self._unmatched_threshold),\n            tf.greater(self._matched_threshold, matched_vals))\n\n        if self._negatives_lower_than_unmatched:\n          matches = self._set_values_using_indicator(matches,\n                                                     below_unmatched_threshold,\n                                                     -1)\n          matches = self._set_values_using_indicator(matches,\n                                                     between_thresholds,\n                                                     -2)\n        else:\n          matches = self._set_values_using_indicator(matches,\n                                                     below_unmatched_threshold,\n                                                     -2)\n          matches = self._set_values_using_indicator(matches,\n                                                     between_thresholds,\n                                                     -1)\n\n      if self._force_match_for_each_row:\n        forced_matches_ids = tf.cast(tf.argmax(similarity_matrix, 1), tf.int32)\n\n        # Set matches[forced_matches_ids] = [0, ..., R], R is number of rows.\n        row_range = tf.range(tf.shape(similarity_matrix)[0])\n        col_range = tf.range(tf.shape(similarity_matrix)[1])\n        forced_matches_values = tf.cast(row_range, matches.dtype)\n        keep_matches_ids, _ = tf.setdiff1d(col_range, forced_matches_ids)\n        keep_matches_values = tf.gather(matches, keep_matches_ids)\n        matches = tf.dynamic_stitch(\n            [forced_matches_ids,\n             keep_matches_ids], [forced_matches_values, keep_matches_values])\n\n      return tf.cast(matches, tf.int32)\n\n    return tf.cond(\n        tf.greater(tf.shape(similarity_matrix)[0], 0),\n        _match_when_rows_are_non_empty, _match_when_rows_are_empty)\n\n  def _set_values_using_indicator(self, x, indicator, val):\n    \"\"\"Set the indicated fields of x to val.\n\n    Args:\n      x: tensor.\n      indicator: boolean with same shape as x.\n      val: scalar with value to set.\n\n    Returns:\n      modified tensor.\n    \"\"\"\n    indicator = tf.cast(indicator, x.dtype)\n    return tf.add(tf.multiply(x, 1 - indicator), val * indicator)\n"
  },
  {
    "path": "object_detector_app/object_detection/matchers/argmax_matcher_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.matchers.argmax_matcher.\"\"\"\n\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.matchers import argmax_matcher\n\n\nclass ArgMaxMatcherTest(tf.test.TestCase):\n\n  def test_return_correct_matches_with_default_thresholds(self):\n    similarity = np.array([[1., 1, 1, 3, 1],\n                           [2, -1, 2, 0, 4],\n                           [3, 0, -1, 0, 0]])\n\n    matcher = argmax_matcher.ArgMaxMatcher(matched_threshold=None)\n    expected_matched_rows = np.array([2, 0, 1, 0, 1])\n\n    sim = tf.constant(similarity)\n    match = matcher.match(sim)\n    matched_cols = match.matched_column_indices()\n    matched_rows = match.matched_row_indices()\n    unmatched_cols = match.unmatched_column_indices()\n\n    with self.test_session() as sess:\n      res_matched_cols = sess.run(matched_cols)\n      res_matched_rows = sess.run(matched_rows)\n      res_unmatched_cols = sess.run(unmatched_cols)\n\n    self.assertAllEqual(res_matched_rows, expected_matched_rows)\n    self.assertAllEqual(res_matched_cols, np.arange(similarity.shape[1]))\n    self.assertEmpty(res_unmatched_cols)\n\n  def test_return_correct_matches_with_empty_rows(self):\n\n    matcher = argmax_matcher.ArgMaxMatcher(matched_threshold=None)\n    sim = 0.2*tf.ones([0, 5])\n    match = matcher.match(sim)\n    unmatched_cols = match.unmatched_column_indices()\n\n    with self.test_session() as sess:\n      res_unmatched_cols = sess.run(unmatched_cols)\n      self.assertAllEqual(res_unmatched_cols, np.arange(5))\n\n  def test_return_correct_matches_with_matched_threshold(self):\n    similarity = np.array([[1, 1, 1, 3, 1],\n                           [2, -1, 2, 0, 4],\n                           [3, 0, -1, 0, 0]], dtype=np.int32)\n\n    matcher = argmax_matcher.ArgMaxMatcher(matched_threshold=3)\n    expected_matched_cols = np.array([0, 3, 4])\n    expected_matched_rows = np.array([2, 0, 1])\n    expected_unmatched_cols = np.array([1, 2])\n\n    sim = tf.constant(similarity)\n    match = matcher.match(sim)\n    matched_cols = match.matched_column_indices()\n    matched_rows = match.matched_row_indices()\n    unmatched_cols = match.unmatched_column_indices()\n\n    init_op = tf.global_variables_initializer()\n\n    with self.test_session() as sess:\n      sess.run(init_op)\n      res_matched_cols = sess.run(matched_cols)\n      res_matched_rows = sess.run(matched_rows)\n      res_unmatched_cols = sess.run(unmatched_cols)\n\n    self.assertAllEqual(res_matched_rows, expected_matched_rows)\n    self.assertAllEqual(res_matched_cols, expected_matched_cols)\n    self.assertAllEqual(res_unmatched_cols, expected_unmatched_cols)\n\n  def test_return_correct_matches_with_matched_and_unmatched_threshold(self):\n    similarity = np.array([[1, 1, 1, 3, 1],\n                           [2, -1, 2, 0, 4],\n                           [3, 0, -1, 0, 0]], dtype=np.int32)\n\n    matcher = argmax_matcher.ArgMaxMatcher(matched_threshold=3,\n                                           unmatched_threshold=2)\n    expected_matched_cols = np.array([0, 3, 4])\n    expected_matched_rows = np.array([2, 0, 1])\n    expected_unmatched_cols = np.array([1])  # col 2 has too high maximum val\n\n    sim = tf.constant(similarity)\n    match = matcher.match(sim)\n    matched_cols = match.matched_column_indices()\n    matched_rows = match.matched_row_indices()\n    unmatched_cols = match.unmatched_column_indices()\n\n    with self.test_session() as sess:\n      res_matched_cols = sess.run(matched_cols)\n      res_matched_rows = sess.run(matched_rows)\n      res_unmatched_cols = sess.run(unmatched_cols)\n\n    self.assertAllEqual(res_matched_rows, expected_matched_rows)\n    self.assertAllEqual(res_matched_cols, expected_matched_cols)\n    self.assertAllEqual(res_unmatched_cols, expected_unmatched_cols)\n\n  def test_return_correct_matches_negatives_lower_than_unmatched_false(self):\n    similarity = np.array([[1, 1, 1, 3, 1],\n                           [2, -1, 2, 0, 4],\n                           [3, 0, -1, 0, 0]], dtype=np.int32)\n\n    matcher = argmax_matcher.ArgMaxMatcher(matched_threshold=3,\n                                           unmatched_threshold=2,\n                                           negatives_lower_than_unmatched=False)\n    expected_matched_cols = np.array([0, 3, 4])\n    expected_matched_rows = np.array([2, 0, 1])\n    expected_unmatched_cols = np.array([2])  # col 1 has too low maximum val\n\n    sim = tf.constant(similarity)\n    match = matcher.match(sim)\n    matched_cols = match.matched_column_indices()\n    matched_rows = match.matched_row_indices()\n    unmatched_cols = match.unmatched_column_indices()\n\n    with self.test_session() as sess:\n      res_matched_cols = sess.run(matched_cols)\n      res_matched_rows = sess.run(matched_rows)\n      res_unmatched_cols = sess.run(unmatched_cols)\n\n    self.assertAllEqual(res_matched_rows, expected_matched_rows)\n    self.assertAllEqual(res_matched_cols, expected_matched_cols)\n    self.assertAllEqual(res_unmatched_cols, expected_unmatched_cols)\n\n  def test_return_correct_matches_unmatched_row_not_using_force_match(self):\n    similarity = np.array([[1, 1, 1, 3, 1],\n                           [-1, 0, -2, -2, -1],\n                           [3, 0, -1, 2, 0]], dtype=np.int32)\n\n    matcher = argmax_matcher.ArgMaxMatcher(matched_threshold=3,\n                                           unmatched_threshold=2)\n    expected_matched_cols = np.array([0, 3])\n    expected_matched_rows = np.array([2, 0])\n    expected_unmatched_cols = np.array([1, 2, 4])\n\n    sim = tf.constant(similarity)\n    match = matcher.match(sim)\n    matched_cols = match.matched_column_indices()\n    matched_rows = match.matched_row_indices()\n    unmatched_cols = match.unmatched_column_indices()\n\n    with self.test_session() as sess:\n      res_matched_cols = sess.run(matched_cols)\n      res_matched_rows = sess.run(matched_rows)\n      res_unmatched_cols = sess.run(unmatched_cols)\n\n    self.assertAllEqual(res_matched_rows, expected_matched_rows)\n    self.assertAllEqual(res_matched_cols, expected_matched_cols)\n    self.assertAllEqual(res_unmatched_cols, expected_unmatched_cols)\n\n  def test_return_correct_matches_unmatched_row_while_using_force_match(self):\n    similarity = np.array([[1, 1, 1, 3, 1],\n                           [-1, 0, -2, -2, -1],\n                           [3, 0, -1, 2, 0]], dtype=np.int32)\n\n    matcher = argmax_matcher.ArgMaxMatcher(matched_threshold=3,\n                                           unmatched_threshold=2,\n                                           force_match_for_each_row=True)\n    expected_matched_cols = np.array([0, 1, 3])\n    expected_matched_rows = np.array([2, 1, 0])\n    expected_unmatched_cols = np.array([2, 4])  # col 2 has too high max val\n\n    sim = tf.constant(similarity)\n    match = matcher.match(sim)\n    matched_cols = match.matched_column_indices()\n    matched_rows = match.matched_row_indices()\n    unmatched_cols = match.unmatched_column_indices()\n\n    with self.test_session() as sess:\n      res_matched_cols = sess.run(matched_cols)\n      res_matched_rows = sess.run(matched_rows)\n      res_unmatched_cols = sess.run(unmatched_cols)\n\n    self.assertAllEqual(res_matched_rows, expected_matched_rows)\n    self.assertAllEqual(res_matched_cols, expected_matched_cols)\n    self.assertAllEqual(res_unmatched_cols, expected_unmatched_cols)\n\n  def test_valid_arguments_corner_case(self):\n    argmax_matcher.ArgMaxMatcher(matched_threshold=1,\n                                 unmatched_threshold=1)\n\n  def test_invalid_arguments_corner_case_negatives_lower_than_thres_false(self):\n    with self.assertRaises(ValueError):\n      argmax_matcher.ArgMaxMatcher(matched_threshold=1,\n                                   unmatched_threshold=1,\n                                   negatives_lower_than_unmatched=False)\n\n  def test_invalid_arguments_no_matched_threshold(self):\n    with self.assertRaises(ValueError):\n      argmax_matcher.ArgMaxMatcher(matched_threshold=None,\n                                   unmatched_threshold=4)\n\n  def test_invalid_arguments_unmatched_thres_larger_than_matched_thres(self):\n    with self.assertRaises(ValueError):\n      argmax_matcher.ArgMaxMatcher(matched_threshold=1,\n                                   unmatched_threshold=2)\n\n  def test_set_values_using_indicator(self):\n    input_a = np.array([3, 4, 5, 1, 4, 3, 2])\n    expected_b = np.array([3, 0, 0, 1, 0, 3, 2])  # Set a>3 to 0\n    expected_c = np.array(\n        [3., 4., 5., -1., 4., 3., -1.])  # Set a<3 to -1. Float32\n    idxb_ = input_a > 3\n    idxc_ = input_a < 3\n\n    matcher = argmax_matcher.ArgMaxMatcher(matched_threshold=None)\n\n    a = tf.constant(input_a)\n    idxb = tf.constant(idxb_)\n    idxc = tf.constant(idxc_)\n    b = matcher._set_values_using_indicator(a, idxb, 0)\n    c = matcher._set_values_using_indicator(tf.cast(a, tf.float32), idxc, -1)\n    with self.test_session() as sess:\n      res_b = sess.run(b)\n      res_c = sess.run(c)\n      self.assertAllEqual(res_b, expected_b)\n      self.assertAllEqual(res_c, expected_c)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/matchers/bipartite_matcher.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Bipartite matcher implementation.\"\"\"\n\nimport tensorflow as tf\n\nfrom tensorflow.contrib.image.python.ops import image_ops\nfrom object_detection.core import matcher\n\n\nclass GreedyBipartiteMatcher(matcher.Matcher):\n  \"\"\"Wraps a Tensorflow greedy bipartite matcher.\"\"\"\n\n  def _match(self, similarity_matrix, num_valid_rows=-1):\n    \"\"\"Bipartite matches a collection rows and columns. A greedy bi-partite.\n\n    TODO: Add num_valid_columns options to match only that many columns with\n        all the rows.\n\n    Args:\n      similarity_matrix: Float tensor of shape [N, M] with pairwise similarity\n        where higher values mean more similar.\n      num_valid_rows: A scalar or a 1-D tensor with one element describing the\n        number of valid rows of similarity_matrix to consider for the bipartite\n        matching. If set to be negative, then all rows from similarity_matrix\n        are used.\n\n    Returns:\n      match_results: int32 tensor of shape [M] with match_results[i]=-1\n        meaning that column i is not matched and otherwise that it is matched to\n        row match_results[i].\n    \"\"\"\n    # Convert similarity matrix to distance matrix as tf.image.bipartite tries\n    # to find minimum distance matches.\n    distance_matrix = -1 * similarity_matrix\n    _, match_results = image_ops.bipartite_match(\n        distance_matrix, num_valid_rows)\n    match_results = tf.reshape(match_results, [-1])\n    match_results = tf.cast(match_results, tf.int32)\n    return match_results\n"
  },
  {
    "path": "object_detector_app/object_detection/matchers/bipartite_matcher_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.core.bipartite_matcher.\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.matchers import bipartite_matcher\n\n\nclass GreedyBipartiteMatcherTest(tf.test.TestCase):\n\n  def test_get_expected_matches_when_all_rows_are_valid(self):\n    similarity_matrix = tf.constant([[0.50, 0.1, 0.8], [0.15, 0.2, 0.3]])\n    num_valid_rows = 2\n    expected_match_results = [-1, 1, 0]\n\n    matcher = bipartite_matcher.GreedyBipartiteMatcher()\n    match = matcher.match(similarity_matrix, num_valid_rows=num_valid_rows)\n    with self.test_session() as sess:\n      match_results_out = sess.run(match._match_results)\n      self.assertAllEqual(match_results_out, expected_match_results)\n\n  def test_get_expected_matches_with_valid_rows_set_to_minus_one(self):\n    similarity_matrix = tf.constant([[0.50, 0.1, 0.8], [0.15, 0.2, 0.3]])\n    num_valid_rows = -1\n    expected_match_results = [-1, 1, 0]\n\n    matcher = bipartite_matcher.GreedyBipartiteMatcher()\n    match = matcher.match(similarity_matrix, num_valid_rows=num_valid_rows)\n    with self.test_session() as sess:\n      match_results_out = sess.run(match._match_results)\n      self.assertAllEqual(match_results_out, expected_match_results)\n\n  def test_get_no_matches_with_zero_valid_rows(self):\n    similarity_matrix = tf.constant([[0.50, 0.1, 0.8], [0.15, 0.2, 0.3]])\n    num_valid_rows = 0\n    expected_match_results = [-1, -1, -1]\n\n    matcher = bipartite_matcher.GreedyBipartiteMatcher()\n    match = matcher.match(similarity_matrix, num_valid_rows=num_valid_rows)\n    with self.test_session() as sess:\n      match_results_out = sess.run(match._match_results)\n      self.assertAllEqual(match_results_out, expected_match_results)\n\n  def test_get_expected_matches_with_only_one_valid_row(self):\n    similarity_matrix = tf.constant([[0.50, 0.1, 0.8], [0.15, 0.2, 0.3]])\n    num_valid_rows = 1\n    expected_match_results = [-1, -1, 0]\n\n    matcher = bipartite_matcher.GreedyBipartiteMatcher()\n    match = matcher.match(similarity_matrix, num_valid_rows=num_valid_rows)\n    with self.test_session() as sess:\n      match_results_out = sess.run(match._match_results)\n      self.assertAllEqual(match_results_out, expected_match_results)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/meta_architectures/BUILD",
    "content": "# Tensorflow Object Detection API: Meta-architectures.\n\npackage(\n    default_visibility = [\"//visibility:public\"],\n)\n\nlicenses([\"notice\"])\n\n# Apache 2.0\n\npy_library(\n    name = \"ssd_meta_arch\",\n    srcs = [\"ssd_meta_arch.py\"],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:box_coder\",\n        \"//tensorflow_models/object_detection/core:box_list\",\n        \"//tensorflow_models/object_detection/core:box_predictor\",\n        \"//tensorflow_models/object_detection/core:model\",\n        \"//tensorflow_models/object_detection/core:target_assigner\",\n        \"//tensorflow_models/object_detection/utils:variables_helper\",\n    ],\n)\n\npy_test(\n    name = \"ssd_meta_arch_test\",\n    srcs = [\"ssd_meta_arch_test.py\"],\n    deps = [\n        \":ssd_meta_arch\",\n        \"//tensorflow\",\n        \"//tensorflow/python:training\",\n        \"//tensorflow_models/object_detection/core:anchor_generator\",\n        \"//tensorflow_models/object_detection/core:box_list\",\n        \"//tensorflow_models/object_detection/core:losses\",\n        \"//tensorflow_models/object_detection/core:post_processing\",\n        \"//tensorflow_models/object_detection/core:region_similarity_calculator\",\n        \"//tensorflow_models/object_detection/utils:test_utils\",\n    ],\n)\n\npy_library(\n    name = \"faster_rcnn_meta_arch\",\n    srcs = [\n        \"faster_rcnn_meta_arch.py\",\n    ],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/anchor_generators:grid_anchor_generator\",\n        \"//tensorflow_models/object_detection/core:balanced_positive_negative_sampler\",\n        \"//tensorflow_models/object_detection/core:box_list\",\n        \"//tensorflow_models/object_detection/core:box_list_ops\",\n        \"//tensorflow_models/object_detection/core:box_predictor\",\n        \"//tensorflow_models/object_detection/core:losses\",\n        \"//tensorflow_models/object_detection/core:model\",\n        \"//tensorflow_models/object_detection/core:post_processing\",\n        \"//tensorflow_models/object_detection/core:standard_fields\",\n        \"//tensorflow_models/object_detection/core:target_assigner\",\n        \"//tensorflow_models/object_detection/utils:ops\",\n        \"//tensorflow_models/object_detection/utils:variables_helper\",\n    ],\n)\n\npy_library(\n    name = \"faster_rcnn_meta_arch_test_lib\",\n    srcs = [\n        \"faster_rcnn_meta_arch_test_lib.py\",\n    ],\n    deps = [\n        \":faster_rcnn_meta_arch\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/anchor_generators:grid_anchor_generator\",\n        \"//tensorflow_models/object_detection/builders:box_predictor_builder\",\n        \"//tensorflow_models/object_detection/builders:hyperparams_builder\",\n        \"//tensorflow_models/object_detection/builders:post_processing_builder\",\n        \"//tensorflow_models/object_detection/core:losses\",\n        \"//tensorflow_models/object_detection/protos:box_predictor_py_pb2\",\n        \"//tensorflow_models/object_detection/protos:hyperparams_py_pb2\",\n        \"//tensorflow_models/object_detection/protos:post_processing_py_pb2\",\n    ],\n)\n\npy_test(\n    name = \"faster_rcnn_meta_arch_test\",\n    srcs = [\"faster_rcnn_meta_arch_test.py\"],\n    deps = [\n        \":faster_rcnn_meta_arch_test_lib\",\n    ],\n)\n\npy_library(\n    name = \"rfcn_meta_arch\",\n    srcs = [\"rfcn_meta_arch.py\"],\n    deps = [\n        \":faster_rcnn_meta_arch\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:box_predictor\",\n        \"//tensorflow_models/object_detection/utils:ops\",\n    ],\n)\n\npy_test(\n    name = \"rfcn_meta_arch_test\",\n    srcs = [\"rfcn_meta_arch_test.py\"],\n    deps = [\n        \":faster_rcnn_meta_arch_test_lib\",\n        \":rfcn_meta_arch\",\n        \"//tensorflow\",\n    ],\n)\n"
  },
  {
    "path": "object_detector_app/object_detection/meta_architectures/__init__.py",
    "content": ""
  },
  {
    "path": "object_detector_app/object_detection/meta_architectures/faster_rcnn_meta_arch.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Faster R-CNN meta-architecture definition.\n\nGeneral tensorflow implementation of Faster R-CNN detection models.\n\nSee Faster R-CNN: Ren, Shaoqing, et al.\n\"Faster R-CNN: Towards real-time object detection with region proposal\nnetworks.\" Advances in neural information processing systems. 2015.\n\nWe allow for two modes: first_stage_only=True and first_stage_only=False.  In\nthe former setting, all of the user facing methods (e.g., predict, postprocess,\nloss) can be used as if the model consisted only of the RPN, returning class\nagnostic proposals (these can be thought of as approximate detections with no\nassociated class information).  In the latter setting, proposals are computed,\nthen passed through a second stage \"box classifier\" to yield (multi-class)\ndetections.\n\nImplementations of Faster R-CNN models must define a new\nFasterRCNNFeatureExtractor and override three methods: `preprocess`,\n`_extract_proposal_features` (the first stage of the model), and\n`_extract_box_classifier_features` (the second stage of the model). Optionally,\nthe `restore_fn` method can be overridden.  See tests for an example.\n\nA few important notes:\n+ Batching conventions:  We support batched inference and training where\nall images within a batch have the same resolution.  Batch sizes are determined\ndynamically via the shape of the input tensors (rather than being specified\ndirectly as, e.g., a model constructor).\n\nA complication is that due to non-max suppression, we are not guaranteed to get\nthe same number of proposals from the first stage RPN (region proposal network)\nfor each image (though in practice, we should often get the same number of\nproposals).  For this reason we pad to a max number of proposals per image\nwithin a batch. This `self.max_num_proposals` property is set to the\n`first_stage_max_proposals` parameter at inference time and the\n`second_stage_batch_size` at training time since we subsample the batch to\nbe sent through the box classifier during training.\n\nFor the second stage of the pipeline, we arrange the proposals for all images\nwithin the batch along a single batch dimension.  For example, the input to\n_extract_box_classifier_features is a tensor of shape\n`[total_num_proposals, crop_height, crop_width, depth]` where\ntotal_num_proposals is batch_size * self.max_num_proposals.  (And note that per\nthe above comment, a subset of these entries correspond to zero paddings.)\n\n+ Coordinate representations:\nFollowing the API (see model.DetectionModel definition), our outputs after\npostprocessing operations are always normalized boxes however, internally, we\nsometimes convert to absolute --- e.g. for loss computation.  In particular,\nanchors and proposal_boxes are both represented as absolute coordinates.\n\nTODO: Support TPU implementations and sigmoid loss.\n\"\"\"\nfrom abc import abstractmethod\nfrom functools import partial\nimport tensorflow as tf\n\nfrom object_detection.anchor_generators import grid_anchor_generator\nfrom object_detection.core import balanced_positive_negative_sampler as sampler\nfrom object_detection.core import box_list\nfrom object_detection.core import box_list_ops\nfrom object_detection.core import box_predictor\nfrom object_detection.core import losses\nfrom object_detection.core import model\nfrom object_detection.core import post_processing\nfrom object_detection.core import standard_fields as fields\nfrom object_detection.core import target_assigner\nfrom object_detection.utils import ops\nfrom object_detection.utils import variables_helper\n\nslim = tf.contrib.slim\n\n\nclass FasterRCNNFeatureExtractor(object):\n  \"\"\"Faster R-CNN Feature Extractor definition.\"\"\"\n\n  def __init__(self,\n               is_training,\n               first_stage_features_stride,\n               reuse_weights=None,\n               weight_decay=0.0):\n    \"\"\"Constructor.\n\n    Args:\n      is_training: A boolean indicating whether the training version of the\n        computation graph should be constructed.\n      first_stage_features_stride: Output stride of extracted RPN feature map.\n      reuse_weights: Whether to reuse variables. Default is None.\n      weight_decay: float weight decay for feature extractor (default: 0.0).\n    \"\"\"\n    self._is_training = is_training\n    self._first_stage_features_stride = first_stage_features_stride\n    self._reuse_weights = reuse_weights\n    self._weight_decay = weight_decay\n\n  @abstractmethod\n  def preprocess(self, resized_inputs):\n    \"\"\"Feature-extractor specific preprocessing (minus image resizing).\"\"\"\n    pass\n\n  def extract_proposal_features(self, preprocessed_inputs, scope):\n    \"\"\"Extracts first stage RPN features.\n\n    This function is responsible for extracting feature maps from preprocessed\n    images.  These features are used by the region proposal network (RPN) to\n    predict proposals.\n\n    Args:\n      preprocessed_inputs: A [batch, height, width, channels] float tensor\n        representing a batch of images.\n      scope: A scope name.\n\n    Returns:\n      rpn_feature_map: A tensor with shape [batch, height, width, depth]\n    \"\"\"\n    with tf.variable_scope(scope, values=[preprocessed_inputs]):\n      return self._extract_proposal_features(preprocessed_inputs, scope)\n\n  @abstractmethod\n  def _extract_proposal_features(self, preprocessed_inputs, scope):\n    \"\"\"Extracts first stage RPN features, to be overridden.\"\"\"\n    pass\n\n  def extract_box_classifier_features(self, proposal_feature_maps, scope):\n    \"\"\"Extracts second stage box classifier features.\n\n    Args:\n      proposal_feature_maps: A 4-D float tensor with shape\n        [batch_size * self.max_num_proposals, crop_height, crop_width, depth]\n        representing the feature map cropped to each proposal.\n      scope: A scope name.\n\n    Returns:\n      proposal_classifier_features: A 4-D float tensor with shape\n        [batch_size * self.max_num_proposals, height, width, depth]\n        representing box classifier features for each proposal.\n    \"\"\"\n    with tf.variable_scope(scope, values=[proposal_feature_maps]):\n      return self._extract_box_classifier_features(proposal_feature_maps, scope)\n\n  @abstractmethod\n  def _extract_box_classifier_features(self, proposal_feature_maps, scope):\n    \"\"\"Extracts second stage box classifier features, to be overridden.\"\"\"\n    pass\n\n  def restore_from_classification_checkpoint_fn(\n      self,\n      checkpoint_path,\n      first_stage_feature_extractor_scope,\n      second_stage_feature_extractor_scope):\n    \"\"\"Returns callable for loading a checkpoint into the tensorflow graph.\n\n    Args:\n      checkpoint_path: path to checkpoint to restore.\n      first_stage_feature_extractor_scope: A scope name for the first stage\n        feature extractor.\n      second_stage_feature_extractor_scope: A scope name for the second stage\n        feature extractor.\n\n    Returns:\n      a callable which takes a tf.Session as input and loads a checkpoint when\n        run.\n    \"\"\"\n    variables_to_restore = {}\n    for variable in tf.global_variables():\n      for scope_name in [first_stage_feature_extractor_scope,\n                         second_stage_feature_extractor_scope]:\n        if variable.op.name.startswith(scope_name):\n          var_name = variable.op.name.replace(scope_name + '/', '')\n          variables_to_restore[var_name] = variable\n    variables_to_restore = (\n        variables_helper.get_variables_available_in_checkpoint(\n            variables_to_restore, checkpoint_path))\n    saver = tf.train.Saver(variables_to_restore)\n    def restore(sess):\n      saver.restore(sess, checkpoint_path)\n    return restore\n\n\nclass FasterRCNNMetaArch(model.DetectionModel):\n  \"\"\"Faster R-CNN Meta-architecture definition.\"\"\"\n\n  def __init__(self,\n               is_training,\n               num_classes,\n               image_resizer_fn,\n               feature_extractor,\n               first_stage_only,\n               first_stage_anchor_generator,\n               first_stage_atrous_rate,\n               first_stage_box_predictor_arg_scope,\n               first_stage_box_predictor_kernel_size,\n               first_stage_box_predictor_depth,\n               first_stage_minibatch_size,\n               first_stage_positive_balance_fraction,\n               first_stage_nms_score_threshold,\n               first_stage_nms_iou_threshold,\n               first_stage_max_proposals,\n               first_stage_localization_loss_weight,\n               first_stage_objectness_loss_weight,\n               initial_crop_size,\n               maxpool_kernel_size,\n               maxpool_stride,\n               second_stage_mask_rcnn_box_predictor,\n               second_stage_batch_size,\n               second_stage_balance_fraction,\n               second_stage_non_max_suppression_fn,\n               second_stage_score_conversion_fn,\n               second_stage_localization_loss_weight,\n               second_stage_classification_loss_weight,\n               hard_example_miner,\n               parallel_iterations=16):\n    \"\"\"FasterRCNNMetaArch Constructor.\n\n    Args:\n      is_training: A boolean indicating whether the training version of the\n        computation graph should be constructed.\n      num_classes: Number of classes.  Note that num_classes *does not*\n        include the background category, so if groundtruth labels take values\n        in {0, 1, .., K-1}, num_classes=K (and not K+1, even though the\n        assigned classification targets can range from {0,... K}).\n      image_resizer_fn: A callable for image resizing.  This callable always\n        takes a rank-3 image tensor (corresponding to a single image) and\n        returns a rank-3 image tensor, possibly with new spatial dimensions.\n        See builders/image_resizer_builder.py.\n      feature_extractor: A FasterRCNNFeatureExtractor object.\n      first_stage_only:  Whether to construct only the Region Proposal Network\n        (RPN) part of the model.\n      first_stage_anchor_generator: An anchor_generator.AnchorGenerator object\n        (note that currently we only support\n        grid_anchor_generator.GridAnchorGenerator objects)\n      first_stage_atrous_rate: A single integer indicating the atrous rate for\n        the single convolution op which is applied to the `rpn_features_to_crop`\n        tensor to obtain a tensor to be used for box prediction. Some feature\n        extractors optionally allow for producing feature maps computed at\n        denser resolutions.  The atrous rate is used to compensate for the\n        denser feature maps by using an effectively larger receptive field.\n        (This should typically be set to 1).\n      first_stage_box_predictor_arg_scope: Slim arg_scope for conv2d,\n        separable_conv2d and fully_connected ops for the RPN box predictor.\n      first_stage_box_predictor_kernel_size: Kernel size to use for the\n        convolution op just prior to RPN box predictions.\n      first_stage_box_predictor_depth: Output depth for the convolution op\n        just prior to RPN box predictions.\n      first_stage_minibatch_size: The \"batch size\" to use for computing the\n        objectness and location loss of the region proposal network. This\n        \"batch size\" refers to the number of anchors selected as contributing\n        to the loss function for any given image within the image batch and is\n        only called \"batch_size\" due to terminology from the Faster R-CNN paper.\n      first_stage_positive_balance_fraction: Fraction of positive examples\n        per image for the RPN. The recommended value for Faster RCNN is 0.5.\n      first_stage_nms_score_threshold: Score threshold for non max suppression\n        for the Region Proposal Network (RPN).  This value is expected to be in\n        [0, 1] as it is applied directly after a softmax transformation.  The\n        recommended value for Faster R-CNN is 0.\n      first_stage_nms_iou_threshold: The Intersection Over Union (IOU) threshold\n        for performing Non-Max Suppression (NMS) on the boxes predicted by the\n        Region Proposal Network (RPN).\n      first_stage_max_proposals: Maximum number of boxes to retain after\n        performing Non-Max Suppression (NMS) on the boxes predicted by the\n        Region Proposal Network (RPN).\n      first_stage_localization_loss_weight: A float\n      first_stage_objectness_loss_weight: A float\n      initial_crop_size: A single integer indicating the output size\n        (width and height are set to be the same) of the initial bilinear\n        interpolation based cropping during ROI pooling.\n      maxpool_kernel_size: A single integer indicating the kernel size of the\n        max pool op on the cropped feature map during ROI pooling.\n      maxpool_stride: A single integer indicating the stride of the max pool\n        op on the cropped feature map during ROI pooling.\n      second_stage_mask_rcnn_box_predictor: Mask R-CNN box predictor to use for\n        the second stage.\n      second_stage_batch_size: The batch size used for computing the\n        classification and refined location loss of the box classifier.  This\n        \"batch size\" refers to the number of proposals selected as contributing\n        to the loss function for any given image within the image batch and is\n        only called \"batch_size\" due to terminology from the Faster R-CNN paper.\n      second_stage_balance_fraction: Fraction of positive examples to use\n        per image for the box classifier. The recommended value for Faster RCNN\n        is 0.25.\n      second_stage_non_max_suppression_fn: batch_multiclass_non_max_suppression\n        callable that takes `boxes`, `scores`, optional `clip_window` and\n        optional (kwarg) `mask` inputs (with all other inputs already set)\n        and returns a dictionary containing tensors with keys:\n        `detection_boxes`, `detection_scores`, `detection_classes`,\n        `num_detections`, and (optionally) `detection_masks`. See\n        `post_processing.batch_multiclass_non_max_suppression` for the type and\n        shape of these tensors.\n      second_stage_score_conversion_fn: Callable elementwise nonlinearity\n        (that takes tensors as inputs and returns tensors).  This is usually\n        used to convert logits to probabilities.\n      second_stage_localization_loss_weight: A float\n      second_stage_classification_loss_weight: A float\n      hard_example_miner:  A losses.HardExampleMiner object (can be None).\n      parallel_iterations: (Optional) The number of iterations allowed to run\n        in parallel for calls to tf.map_fn.\n    Raises:\n      ValueError: If `second_stage_batch_size` > `first_stage_max_proposals`\n      ValueError: If first_stage_anchor_generator is not of type\n        grid_anchor_generator.GridAnchorGenerator.\n    \"\"\"\n    super(FasterRCNNMetaArch, self).__init__(num_classes=num_classes)\n\n    if second_stage_batch_size > first_stage_max_proposals:\n      raise ValueError('second_stage_batch_size should be no greater than '\n                       'first_stage_max_proposals.')\n    if not isinstance(first_stage_anchor_generator,\n                      grid_anchor_generator.GridAnchorGenerator):\n      raise ValueError('first_stage_anchor_generator must be of type '\n                       'grid_anchor_generator.GridAnchorGenerator.')\n\n    self._is_training = is_training\n    self._image_resizer_fn = image_resizer_fn\n    self._feature_extractor = feature_extractor\n    self._first_stage_only = first_stage_only\n\n    # The first class is reserved as background.\n    unmatched_cls_target = tf.constant(\n        [1] + self._num_classes * [0], dtype=tf.float32)\n    self._proposal_target_assigner = target_assigner.create_target_assigner(\n        'FasterRCNN', 'proposal')\n    self._detector_target_assigner = target_assigner.create_target_assigner(\n        'FasterRCNN', 'detection', unmatched_cls_target=unmatched_cls_target)\n    # Both proposal and detector target assigners use the same box coder\n    self._box_coder = self._proposal_target_assigner.box_coder\n\n    # (First stage) Region proposal network parameters\n    self._first_stage_anchor_generator = first_stage_anchor_generator\n    self._first_stage_atrous_rate = first_stage_atrous_rate\n    self._first_stage_box_predictor_arg_scope = (\n        first_stage_box_predictor_arg_scope)\n    self._first_stage_box_predictor_kernel_size = (\n        first_stage_box_predictor_kernel_size)\n    self._first_stage_box_predictor_depth = first_stage_box_predictor_depth\n    self._first_stage_minibatch_size = first_stage_minibatch_size\n    self._first_stage_sampler = sampler.BalancedPositiveNegativeSampler(\n        positive_fraction=first_stage_positive_balance_fraction)\n    self._first_stage_box_predictor = box_predictor.ConvolutionalBoxPredictor(\n        self._is_training, num_classes=1,\n        conv_hyperparams=self._first_stage_box_predictor_arg_scope,\n        min_depth=0, max_depth=0, num_layers_before_predictor=0,\n        use_dropout=False, dropout_keep_prob=1.0, kernel_size=1,\n        box_code_size=self._box_coder.code_size)\n\n    self._first_stage_nms_score_threshold = first_stage_nms_score_threshold\n    self._first_stage_nms_iou_threshold = first_stage_nms_iou_threshold\n    self._first_stage_max_proposals = first_stage_max_proposals\n\n    self._first_stage_localization_loss = (\n        losses.WeightedSmoothL1LocalizationLoss(anchorwise_output=True))\n    self._first_stage_objectness_loss = (\n        losses.WeightedSoftmaxClassificationLoss(anchorwise_output=True))\n    self._first_stage_loc_loss_weight = first_stage_localization_loss_weight\n    self._first_stage_obj_loss_weight = first_stage_objectness_loss_weight\n\n    # Per-region cropping parameters\n    self._initial_crop_size = initial_crop_size\n    self._maxpool_kernel_size = maxpool_kernel_size\n    self._maxpool_stride = maxpool_stride\n\n    self._mask_rcnn_box_predictor = second_stage_mask_rcnn_box_predictor\n\n    self._second_stage_batch_size = second_stage_batch_size\n    self._second_stage_sampler = sampler.BalancedPositiveNegativeSampler(\n        positive_fraction=second_stage_balance_fraction)\n\n    self._second_stage_nms_fn = second_stage_non_max_suppression_fn\n    self._second_stage_score_conversion_fn = second_stage_score_conversion_fn\n\n    self._second_stage_localization_loss = (\n        losses.WeightedSmoothL1LocalizationLoss(anchorwise_output=True))\n    self._second_stage_classification_loss = (\n        losses.WeightedSoftmaxClassificationLoss(anchorwise_output=True))\n    self._second_stage_loc_loss_weight = second_stage_localization_loss_weight\n    self._second_stage_cls_loss_weight = second_stage_classification_loss_weight\n    self._hard_example_miner = hard_example_miner\n    self._parallel_iterations = parallel_iterations\n\n  @property\n  def first_stage_feature_extractor_scope(self):\n    return 'FirstStageFeatureExtractor'\n\n  @property\n  def second_stage_feature_extractor_scope(self):\n    return 'SecondStageFeatureExtractor'\n\n  @property\n  def first_stage_box_predictor_scope(self):\n    return 'FirstStageBoxPredictor'\n\n  @property\n  def second_stage_box_predictor_scope(self):\n    return 'SecondStageBoxPredictor'\n\n  @property\n  def max_num_proposals(self):\n    \"\"\"Max number of proposals (to pad to) for each image in the input batch.\n\n    At training time, this is set to be the `second_stage_batch_size` if hard\n    example miner is not configured, else it is set to\n    `first_stage_max_proposals`. At inference time, this is always set to\n    `first_stage_max_proposals`.\n\n    Returns:\n      A positive integer.\n    \"\"\"\n    if self._is_training and not self._hard_example_miner:\n      return self._second_stage_batch_size\n    return self._first_stage_max_proposals\n\n  def preprocess(self, inputs):\n    \"\"\"Feature-extractor specific preprocessing.\n\n    See base class.\n\n    For Faster R-CNN, we perform image resizing in the base class --- each\n    class subclassing FasterRCNNMetaArch is responsible for any additional\n    preprocessing (e.g., scaling pixel values to be in [-1, 1]).\n\n    Args:\n      inputs: a [batch, height_in, width_in, channels] float tensor representing\n        a batch of images with values between 0 and 255.0.\n\n    Returns:\n      preprocessed_inputs: a [batch, height_out, width_out, channels] float\n        tensor representing a batch of images.\n    Raises:\n      ValueError: if inputs tensor does not have type tf.float32\n    \"\"\"\n    if inputs.dtype is not tf.float32:\n      raise ValueError('`preprocess` expects a tf.float32 tensor')\n    with tf.name_scope('Preprocessor'):\n      resized_inputs = tf.map_fn(self._image_resizer_fn,\n                                 elems=inputs,\n                                 dtype=tf.float32,\n                                 parallel_iterations=self._parallel_iterations)\n      return self._feature_extractor.preprocess(resized_inputs)\n\n  def predict(self, preprocessed_inputs):\n    \"\"\"Predicts unpostprocessed tensors from input tensor.\n\n    This function takes an input batch of images and runs it through the\n    forward pass of the network to yield \"raw\" un-postprocessed predictions.\n    If `first_stage_only` is True, this function only returns first stage\n    RPN predictions (un-postprocessed).  Otherwise it returns both\n    first stage RPN predictions as well as second stage box classifier\n    predictions.\n\n    Other remarks:\n    + Anchor pruning vs. clipping: following the recommendation of the Faster\n    R-CNN paper, we prune anchors that venture outside the image window at\n    training time and clip anchors to the image window at inference time.\n    + Proposal padding: as described at the top of the file, proposals are\n    padded to self._max_num_proposals and flattened so that proposals from all\n    images within the input batch are arranged along the same batch dimension.\n\n    Args:\n      preprocessed_inputs: a [batch, height, width, channels] float tensor\n        representing a batch of images.\n\n    Returns:\n      prediction_dict: a dictionary holding \"raw\" prediction tensors:\n        1) rpn_box_predictor_features: A 4-D float32 tensor with shape\n          [batch_size, height, width, depth] to be used for predicting proposal\n          boxes and corresponding objectness scores.\n        2) rpn_features_to_crop: A 4-D float32 tensor with shape\n          [batch_size, height, width, depth] representing image features to crop\n          using the proposal boxes predicted by the RPN.\n        3) image_shape: a 1-D tensor of shape [4] representing the input\n          image shape.\n        4) rpn_box_encodings:  3-D float tensor of shape\n          [batch_size, num_anchors, self._box_coder.code_size] containing\n          predicted boxes.\n        5) rpn_objectness_predictions_with_background: 3-D float tensor of shape\n          [batch_size, num_anchors, 2] containing class\n          predictions (logits) for each of the anchors.  Note that this\n          tensor *includes* background class predictions (at class index 0).\n        6) anchors: A 2-D tensor of shape [num_anchors, 4] representing anchors\n          for the first stage RPN (in absolute coordinates).  Note that\n          `num_anchors` can differ depending on whether the model is created in\n          training or inference mode.\n\n        (and if first_stage_only=False):\n        7) refined_box_encodings: a 3-D tensor with shape\n          [total_num_proposals, num_classes, 4] representing predicted\n          (final) refined box encodings, where\n          total_num_proposals=batch_size*self._max_num_proposals\n        8) class_predictions_with_background: a 3-D tensor with shape\n          [total_num_proposals, num_classes + 1] containing class\n          predictions (logits) for each of the anchors, where\n          total_num_proposals=batch_size*self._max_num_proposals.\n          Note that this tensor *includes* background class predictions\n          (at class index 0).\n        9) num_proposals: An int32 tensor of shape [batch_size] representing the\n          number of proposals generated by the RPN.  `num_proposals` allows us\n          to keep track of which entries are to be treated as zero paddings and\n          which are not since we always pad the number of proposals to be\n          `self.max_num_proposals` for each image.\n        10) proposal_boxes: A float32 tensor of shape\n          [batch_size, self.max_num_proposals, 4] representing\n          decoded proposal bounding boxes (in absolute coordinates).\n        11) mask_predictions: (optional) a 4-D tensor with shape\n          [total_num_padded_proposals, num_classes, mask_height, mask_width]\n          containing instance mask predictions.\n    \"\"\"\n    (rpn_box_predictor_features, rpn_features_to_crop, anchors_boxlist,\n     image_shape) = self._extract_rpn_feature_maps(preprocessed_inputs)\n    (rpn_box_encodings, rpn_objectness_predictions_with_background\n    ) = self._predict_rpn_proposals(rpn_box_predictor_features)\n\n    # The Faster R-CNN paper recommends pruning anchors that venture outside\n    # the image window at training time and clipping at inference time.\n    clip_window = tf.to_float(tf.stack([0, 0, image_shape[1], image_shape[2]]))\n    if self._is_training:\n      (rpn_box_encodings, rpn_objectness_predictions_with_background,\n       anchors_boxlist) = self._remove_invalid_anchors_and_predictions(\n           rpn_box_encodings, rpn_objectness_predictions_with_background,\n           anchors_boxlist, clip_window)\n    else:\n      anchors_boxlist = box_list_ops.clip_to_window(\n          anchors_boxlist, clip_window)\n\n    anchors = anchors_boxlist.get()\n    prediction_dict = {\n        'rpn_box_predictor_features': rpn_box_predictor_features,\n        'rpn_features_to_crop': rpn_features_to_crop,\n        'image_shape': image_shape,\n        'rpn_box_encodings': rpn_box_encodings,\n        'rpn_objectness_predictions_with_background':\n        rpn_objectness_predictions_with_background,\n        'anchors': anchors\n    }\n\n    if not self._first_stage_only:\n      prediction_dict.update(self._predict_second_stage(\n          rpn_box_encodings,\n          rpn_objectness_predictions_with_background,\n          rpn_features_to_crop,\n          anchors, image_shape))\n    return prediction_dict\n\n  def _predict_second_stage(self, rpn_box_encodings,\n                            rpn_objectness_predictions_with_background,\n                            rpn_features_to_crop,\n                            anchors,\n                            image_shape):\n    \"\"\"Predicts the output tensors from second stage of Faster R-CNN.\n\n    Args:\n      rpn_box_encodings: 4-D float tensor of shape\n        [batch_size, num_valid_anchors, self._box_coder.code_size] containing\n        predicted boxes.\n      rpn_objectness_predictions_with_background: 2-D float tensor of shape\n        [batch_size, num_valid_anchors, 2] containing class\n        predictions (logits) for each of the anchors.  Note that this\n        tensor *includes* background class predictions (at class index 0).\n      rpn_features_to_crop: A 4-D float32 tensor with shape\n        [batch_size, height, width, depth] representing image features to crop\n        using the proposal boxes predicted by the RPN.\n      anchors: 2-D float tensor of shape\n        [num_anchors, self._box_coder.code_size].\n      image_shape: A 1D int32 tensors of size [4] containing the image shape.\n\n    Returns:\n      prediction_dict: a dictionary holding \"raw\" prediction tensors:\n        1) refined_box_encodings: a 3-D tensor with shape\n          [total_num_proposals, num_classes, 4] representing predicted\n          (final) refined box encodings, where\n          total_num_proposals=batch_size*self._max_num_proposals\n        2) class_predictions_with_background: a 3-D tensor with shape\n          [total_num_proposals, num_classes + 1] containing class\n          predictions (logits) for each of the anchors, where\n          total_num_proposals=batch_size*self._max_num_proposals.\n          Note that this tensor *includes* background class predictions\n          (at class index 0).\n        3) num_proposals: An int32 tensor of shape [batch_size] representing the\n          number of proposals generated by the RPN.  `num_proposals` allows us\n          to keep track of which entries are to be treated as zero paddings and\n          which are not since we always pad the number of proposals to be\n          `self.max_num_proposals` for each image.\n        4) proposal_boxes: A float32 tensor of shape\n          [batch_size, self.max_num_proposals, 4] representing\n          decoded proposal bounding boxes (in absolute coordinates).\n        5) mask_predictions: (optional) a 4-D tensor with shape\n          [total_num_padded_proposals, num_classes, mask_height, mask_width]\n          containing instance mask predictions.\n    \"\"\"\n    proposal_boxes_normalized, _, num_proposals = self._postprocess_rpn(\n        rpn_box_encodings, rpn_objectness_predictions_with_background,\n        anchors, image_shape)\n\n    flattened_proposal_feature_maps = (\n        self._compute_second_stage_input_feature_maps(\n            rpn_features_to_crop, proposal_boxes_normalized))\n\n    box_classifier_features = (\n        self._feature_extractor.extract_box_classifier_features(\n            flattened_proposal_feature_maps,\n            scope=self.second_stage_feature_extractor_scope))\n\n    box_predictions = self._mask_rcnn_box_predictor.predict(\n        box_classifier_features,\n        num_predictions_per_location=1,\n        scope=self.second_stage_box_predictor_scope)\n    refined_box_encodings = tf.squeeze(\n        box_predictions[box_predictor.BOX_ENCODINGS], axis=1)\n    class_predictions_with_background = tf.squeeze(box_predictions[\n        box_predictor.CLASS_PREDICTIONS_WITH_BACKGROUND], axis=1)\n\n    absolute_proposal_boxes = ops.normalized_to_image_coordinates(\n        proposal_boxes_normalized, image_shape, self._parallel_iterations)\n\n    prediction_dict = {\n        'refined_box_encodings': refined_box_encodings,\n        'class_predictions_with_background':\n        class_predictions_with_background,\n        'num_proposals': num_proposals,\n        'proposal_boxes': absolute_proposal_boxes,\n    }\n    return prediction_dict\n\n  def _extract_rpn_feature_maps(self, preprocessed_inputs):\n    \"\"\"Extracts RPN features.\n\n    This function extracts two feature maps: a feature map to be directly\n    fed to a box predictor (to predict location and objectness scores for\n    proposals) and a feature map from which to crop regions which will then\n    be sent to the second stage box classifier.\n\n    Args:\n      preprocessed_inputs: a [batch, height, width, channels] image tensor.\n\n    Returns:\n      rpn_box_predictor_features: A 4-D float32 tensor with shape\n        [batch, height, width, depth] to be used for predicting proposal boxes\n        and corresponding objectness scores.\n      rpn_features_to_crop: A 4-D float32 tensor with shape\n        [batch, height, width, depth] representing image features to crop using\n        the proposals boxes.\n      anchors: A BoxList representing anchors (for the RPN) in\n        absolute coordinates.\n      image_shape: A 1-D tensor representing the input image shape.\n    \"\"\"\n    image_shape = tf.shape(preprocessed_inputs)\n    rpn_features_to_crop = self._feature_extractor.extract_proposal_features(\n        preprocessed_inputs, scope=self.first_stage_feature_extractor_scope)\n\n    feature_map_shape = tf.shape(rpn_features_to_crop)\n    anchors = self._first_stage_anchor_generator.generate(\n        [(feature_map_shape[1], feature_map_shape[2])])\n    with slim.arg_scope(self._first_stage_box_predictor_arg_scope):\n      kernel_size = self._first_stage_box_predictor_kernel_size\n      rpn_box_predictor_features = slim.conv2d(\n          rpn_features_to_crop,\n          self._first_stage_box_predictor_depth,\n          kernel_size=[kernel_size, kernel_size],\n          rate=self._first_stage_atrous_rate,\n          activation_fn=tf.nn.relu6)\n    return (rpn_box_predictor_features, rpn_features_to_crop,\n            anchors, image_shape)\n\n  def _predict_rpn_proposals(self, rpn_box_predictor_features):\n    \"\"\"Adds box predictors to RPN feature map to predict proposals.\n\n    Note resulting tensors will not have been postprocessed.\n\n    Args:\n      rpn_box_predictor_features: A 4-D float32 tensor with shape\n        [batch, height, width, depth] to be used for predicting proposal boxes\n        and corresponding objectness scores.\n\n    Returns:\n      box_encodings: 3-D float tensor of shape\n        [batch_size, num_anchors, self._box_coder.code_size] containing\n        predicted boxes.\n      objectness_predictions_with_background: 3-D float tensor of shape\n        [batch_size, num_anchors, 2] containing class\n        predictions (logits) for each of the anchors.  Note that this\n        tensor *includes* background class predictions (at class index 0).\n\n    Raises:\n      RuntimeError: if the anchor generator generates anchors corresponding to\n        multiple feature maps.  We currently assume that a single feature map\n        is generated for the RPN.\n    \"\"\"\n    num_anchors_per_location = (\n        self._first_stage_anchor_generator.num_anchors_per_location())\n    if len(num_anchors_per_location) != 1:\n      raise RuntimeError('anchor_generator is expected to generate anchors '\n                         'corresponding to a single feature map.')\n    box_predictions = self._first_stage_box_predictor.predict(\n        rpn_box_predictor_features,\n        num_anchors_per_location[0],\n        scope=self.first_stage_box_predictor_scope)\n\n    box_encodings = box_predictions[box_predictor.BOX_ENCODINGS]\n    objectness_predictions_with_background = box_predictions[\n        box_predictor.CLASS_PREDICTIONS_WITH_BACKGROUND]\n    return (tf.squeeze(box_encodings, axis=2),\n            objectness_predictions_with_background)\n\n  def _remove_invalid_anchors_and_predictions(\n      self,\n      box_encodings,\n      objectness_predictions_with_background,\n      anchors_boxlist,\n      clip_window):\n    \"\"\"Removes anchors that (partially) fall outside an image.\n\n    Also removes associated box encodings and objectness predictions.\n\n    Args:\n      box_encodings: 3-D float tensor of shape\n        [batch_size, num_anchors, self._box_coder.code_size] containing\n        predicted boxes.\n      objectness_predictions_with_background: 3-D float tensor of shape\n        [batch_size, num_anchors, 2] containing class\n        predictions (logits) for each of the anchors.  Note that this\n        tensor *includes* background class predictions (at class index 0).\n      anchors_boxlist: A BoxList representing num_anchors anchors (for the RPN)\n        in absolute coordinates.\n      clip_window: a 1-D tensor representing the [ymin, xmin, ymax, xmax]\n        extent of the window to clip/prune to.\n\n    Returns:\n      box_encodings: 4-D float tensor of shape\n        [batch_size, num_valid_anchors, self._box_coder.code_size] containing\n        predicted boxes, where num_valid_anchors <= num_anchors\n      objectness_predictions_with_background: 2-D float tensor of shape\n        [batch_size, num_valid_anchors, 2] containing class\n        predictions (logits) for each of the anchors, where\n        num_valid_anchors <= num_anchors.  Note that this\n        tensor *includes* background class predictions (at class index 0).\n      anchors: A BoxList representing num_valid_anchors anchors (for the RPN) in\n        absolute coordinates.\n    \"\"\"\n    pruned_anchors_boxlist, keep_indices = box_list_ops.prune_outside_window(\n        anchors_boxlist, clip_window)\n    def _batch_gather_kept_indices(predictions_tensor):\n      return tf.map_fn(\n          partial(tf.gather, indices=keep_indices),\n          elems=predictions_tensor,\n          dtype=tf.float32,\n          parallel_iterations=self._parallel_iterations,\n          back_prop=True)\n    return (_batch_gather_kept_indices(box_encodings),\n            _batch_gather_kept_indices(objectness_predictions_with_background),\n            pruned_anchors_boxlist)\n\n  def _flatten_first_two_dimensions(self, inputs):\n    \"\"\"Flattens `K-d` tensor along batch dimension to be a `(K-1)-d` tensor.\n\n    Converts `inputs` with shape [A, B, ..., depth] into a tensor of shape\n    [A * B, ..., depth].\n\n    Args:\n      inputs: A float tensor with shape [A, B, ..., depth].  Note that the first\n        two and last dimensions must be statically defined.\n    Returns:\n      A float tensor with shape [A * B, ..., depth] (where the first and last\n        dimension are statically defined.\n    \"\"\"\n    inputs_shape = inputs.get_shape().as_list()\n    flattened_shape = tf.concat([\n        [inputs_shape[0]*inputs_shape[1]], tf.shape(inputs)[2:-1],\n        [inputs_shape[-1]]], 0)\n    return tf.reshape(inputs, flattened_shape)\n\n  def postprocess(self, prediction_dict):\n    \"\"\"Convert prediction tensors to final detections.\n\n    This function converts raw predictions tensors to final detection results.\n    See base class for output format conventions.  Note also that by default,\n    scores are to be interpreted as logits, but if a score_converter is used,\n    then scores are remapped (and may thus have a different interpretation).\n\n    If first_stage_only=True, the returned results represent proposals from the\n    first stage RPN and are padded to have self.max_num_proposals for each\n    image; otherwise, the results can be interpreted as multiclass detections\n    from the full two-stage model and are padded to self._max_detections.\n\n    Args:\n      prediction_dict: a dictionary holding prediction tensors (see the\n        documentation for the predict method.  If first_stage_only=True, we\n        expect prediction_dict to contain `rpn_box_encodings`,\n        `rpn_objectness_predictions_with_background`, `rpn_features_to_crop`,\n        `image_shape`, and `anchors` fields.  Otherwise we expect\n        prediction_dict to additionally contain `refined_box_encodings`,\n        `class_predictions_with_background`, `num_proposals`,\n        `proposal_boxes` and, optionally, `mask_predictions` fields.\n\n    Returns:\n      detections: a dictionary containing the following fields\n        detection_boxes: [batch, max_detection, 4]\n        detection_scores: [batch, max_detections]\n        detection_classes: [batch, max_detections]\n          (this entry is only created if rpn_mode=False)\n        num_detections: [batch]\n    \"\"\"\n    with tf.name_scope('FirstStagePostprocessor'):\n      image_shape = prediction_dict['image_shape']\n      if self._first_stage_only:\n        proposal_boxes, proposal_scores, num_proposals = self._postprocess_rpn(\n            prediction_dict['rpn_box_encodings'],\n            prediction_dict['rpn_objectness_predictions_with_background'],\n            prediction_dict['anchors'],\n            image_shape)\n        return {\n            'detection_boxes': proposal_boxes,\n            'detection_scores': proposal_scores,\n            'num_detections': num_proposals\n        }\n    with tf.name_scope('SecondStagePostprocessor'):\n      mask_predictions = prediction_dict.get(box_predictor.MASK_PREDICTIONS)\n      detections_dict = self._postprocess_box_classifier(\n          prediction_dict['refined_box_encodings'],\n          prediction_dict['class_predictions_with_background'],\n          prediction_dict['proposal_boxes'],\n          prediction_dict['num_proposals'],\n          image_shape,\n          mask_predictions=mask_predictions)\n      return detections_dict\n\n  def _postprocess_rpn(self,\n                       rpn_box_encodings_batch,\n                       rpn_objectness_predictions_with_background_batch,\n                       anchors,\n                       image_shape):\n    \"\"\"Converts first stage prediction tensors from the RPN to proposals.\n\n    This function decodes the raw RPN predictions, runs non-max suppression\n    on the result.\n\n    Note that the behavior of this function is slightly modified during\n    training --- specifically, we stop the gradient from passing through the\n    proposal boxes and we only return a balanced sampled subset of proposals\n    with size `second_stage_batch_size`.\n\n    Args:\n      rpn_box_encodings_batch: A 3-D float32 tensor of shape\n        [batch_size, num_anchors, self._box_coder.code_size] containing\n        predicted proposal box encodings.\n      rpn_objectness_predictions_with_background_batch: A 3-D float tensor of\n        shape [batch_size, num_anchors, 2] containing objectness predictions\n        (logits) for each of the anchors with 0 corresponding to background\n        and 1 corresponding to object.\n      anchors: A 2-D tensor of shape [num_anchors, 4] representing anchors\n        for the first stage RPN.  Note that `num_anchors` can differ depending\n        on whether the model is created in training or inference mode.\n      image_shape: A 1-D tensor representing the input image shape.\n\n    Returns:\n      proposal_boxes: A float tensor with shape\n        [batch_size, max_num_proposals, 4] representing the (potentially zero\n        padded) proposal boxes for all images in the batch.  These boxes are\n        represented as normalized coordinates.\n      proposal_scores:  A float tensor with shape\n        [batch_size, max_num_proposals] representing the (potentially zero\n        padded) proposal objectness scores for all images in the batch.\n      num_proposals: A Tensor of type `int32`. A 1-D tensor of shape [batch]\n        representing the number of proposals predicted for each image in\n        the batch.\n    \"\"\"\n    clip_window = tf.to_float(tf.stack([0, 0, image_shape[1], image_shape[2]]))\n    if self._is_training:\n      (groundtruth_boxlists, groundtruth_classes_with_background_list\n      ) = self._format_groundtruth_data(image_shape)\n\n    proposal_boxes_list = []\n    proposal_scores_list = []\n    num_proposals_list = []\n    for (batch_index,\n         (rpn_box_encodings,\n          rpn_objectness_predictions_with_background)) in enumerate(zip(\n              tf.unstack(rpn_box_encodings_batch),\n              tf.unstack(rpn_objectness_predictions_with_background_batch))):\n      decoded_boxes = self._box_coder.decode(\n          rpn_box_encodings, box_list.BoxList(anchors))\n      objectness_scores = tf.unstack(\n          tf.nn.softmax(rpn_objectness_predictions_with_background), axis=1)[1]\n      proposal_boxlist = post_processing.multiclass_non_max_suppression(\n          tf.expand_dims(decoded_boxes.get(), 1),\n          tf.expand_dims(objectness_scores, 1),\n          self._first_stage_nms_score_threshold,\n          self._first_stage_nms_iou_threshold, self._first_stage_max_proposals,\n          clip_window=clip_window)\n\n      if self._is_training:\n        proposal_boxlist.set(tf.stop_gradient(proposal_boxlist.get()))\n        if not self._hard_example_miner:\n          proposal_boxlist = self._sample_box_classifier_minibatch(\n              proposal_boxlist, groundtruth_boxlists[batch_index],\n              groundtruth_classes_with_background_list[batch_index])\n\n      normalized_proposals = box_list_ops.to_normalized_coordinates(\n          proposal_boxlist, image_shape[1], image_shape[2],\n          check_range=False)\n\n      # pad proposals to max_num_proposals\n      padded_proposals = box_list_ops.pad_or_clip_box_list(\n          normalized_proposals, num_boxes=self.max_num_proposals)\n      proposal_boxes_list.append(padded_proposals.get())\n      proposal_scores_list.append(\n          padded_proposals.get_field(fields.BoxListFields.scores))\n      num_proposals_list.append(tf.minimum(normalized_proposals.num_boxes(),\n                                           self.max_num_proposals))\n\n    return (tf.stack(proposal_boxes_list), tf.stack(proposal_scores_list),\n            tf.stack(num_proposals_list))\n\n  def _format_groundtruth_data(self, image_shape):\n    \"\"\"Helper function for preparing groundtruth data for target assignment.\n\n    In order to be consistent with the model.DetectionModel interface,\n    groundtruth boxes are specified in normalized coordinates and classes are\n    specified as label indices with no assumed background category.  To prepare\n    for target assignment, we:\n    1) convert boxes to absolute coordinates,\n    2) add a background class at class index 0\n\n    Args:\n      image_shape: A 1-D int32 tensor of shape [4] representing the shape of the\n        input image batch.\n\n    Returns:\n      groundtruth_boxlists: A list of BoxLists containing (absolute) coordinates\n        of the groundtruth boxes.\n      groundtruth_classes_with_background_list: A list of 2-D one-hot\n        (or k-hot) tensors of shape [num_boxes, num_classes+1] containing the\n        class targets with the 0th index assumed to map to the background class.\n    \"\"\"\n    groundtruth_boxlists = [\n        box_list_ops.to_absolute_coordinates(\n            box_list.BoxList(boxes), image_shape[1], image_shape[2])\n        for boxes in self.groundtruth_lists(fields.BoxListFields.boxes)]\n    groundtruth_classes_with_background_list = [\n        tf.to_float(\n            tf.pad(one_hot_encoding, [[0, 0], [1, 0]], mode='CONSTANT'))\n        for one_hot_encoding in self.groundtruth_lists(\n            fields.BoxListFields.classes)]\n    return groundtruth_boxlists, groundtruth_classes_with_background_list\n\n  def _sample_box_classifier_minibatch(self,\n                                       proposal_boxlist,\n                                       groundtruth_boxlist,\n                                       groundtruth_classes_with_background):\n    \"\"\"Samples a mini-batch of proposals to be sent to the box classifier.\n\n    Helper function for self._postprocess_rpn.\n\n    Args:\n      proposal_boxlist: A BoxList containing K proposal boxes in absolute\n        coordinates.\n      groundtruth_boxlist: A Boxlist containing N groundtruth object boxes in\n        absolute coordinates.\n      groundtruth_classes_with_background: A tensor with shape\n        `[N, self.num_classes + 1]` representing groundtruth classes. The\n        classes are assumed to be k-hot encoded, and include background as the\n        zero-th class.\n\n    Returns:\n      a BoxList contained sampled proposals.\n    \"\"\"\n    (cls_targets, cls_weights, _, _, _) = self._detector_target_assigner.assign(\n        proposal_boxlist, groundtruth_boxlist,\n        groundtruth_classes_with_background)\n    # Selects all boxes as candidates if none of them is selected according\n    # to cls_weights. This could happen as boxes within certain IOU ranges\n    # are ignored. If triggered, the selected boxes will still be ignored\n    # during loss computation.\n    cls_weights += tf.to_float(tf.equal(tf.reduce_sum(cls_weights), 0))\n    positive_indicator = tf.greater(tf.argmax(cls_targets, axis=1), 0)\n    sampled_indices = self._second_stage_sampler.subsample(\n        tf.cast(cls_weights, tf.bool),\n        self._second_stage_batch_size,\n        positive_indicator)\n    return box_list_ops.boolean_mask(proposal_boxlist, sampled_indices)\n\n  def _compute_second_stage_input_feature_maps(self, features_to_crop,\n                                               proposal_boxes_normalized):\n    \"\"\"Crops to a set of proposals from the feature map for a batch of images.\n\n    Helper function for self._postprocess_rpn. This function calls\n    `tf.image.crop_and_resize` to create the feature map to be passed to the\n    second stage box classifier for each proposal.\n\n    Args:\n      features_to_crop: A float32 tensor with shape\n        [batch_size, height, width, depth]\n      proposal_boxes_normalized: A float32 tensor with shape [batch_size,\n        num_proposals, box_code_size] containing proposal boxes in\n        normalized coordinates.\n\n    Returns:\n      A float32 tensor with shape [K, new_height, new_width, depth].\n    \"\"\"\n    def get_box_inds(proposals):\n      proposals_shape = proposals.get_shape().as_list()\n      if any(dim is None for dim in proposals_shape):\n        proposals_shape = tf.shape(proposals)\n      ones_mat = tf.ones(proposals_shape[:2], dtype=tf.int32)\n      multiplier = tf.expand_dims(\n          tf.range(start=0, limit=proposals_shape[0]), 1)\n      return tf.reshape(ones_mat * multiplier, [-1])\n\n    cropped_regions = tf.image.crop_and_resize(\n        features_to_crop,\n        self._flatten_first_two_dimensions(proposal_boxes_normalized),\n        get_box_inds(proposal_boxes_normalized),\n        (self._initial_crop_size, self._initial_crop_size))\n    return slim.max_pool2d(\n        cropped_regions,\n        [self._maxpool_kernel_size, self._maxpool_kernel_size],\n        stride=self._maxpool_stride)\n\n  def _postprocess_box_classifier(self,\n                                  refined_box_encodings,\n                                  class_predictions_with_background,\n                                  proposal_boxes,\n                                  num_proposals,\n                                  image_shape,\n                                  mask_predictions=None,\n                                  mask_threshold=0.5):\n    \"\"\"Converts predictions from the second stage box classifier to detections.\n\n    Args:\n      refined_box_encodings: a 3-D tensor with shape\n        [total_num_padded_proposals, num_classes, 4] representing predicted\n        (final) refined box encodings.\n      class_predictions_with_background: a 3-D tensor with shape\n        [total_num_padded_proposals, num_classes + 1] containing class\n        predictions (logits) for each of the proposals.  Note that this tensor\n        *includes* background class predictions (at class index 0).\n      proposal_boxes: [batch_size, self.max_num_proposals, 4] representing\n        decoded proposal bounding boxes.\n      num_proposals: A Tensor of type `int32`. A 1-D tensor of shape [batch]\n        representing the number of proposals predicted for each image in\n        the batch.\n      image_shape: a 1-D tensor representing the input image shape.\n      mask_predictions: (optional) a 4-D tensor with shape\n        [total_num_padded_proposals, num_classes, mask_height, mask_width]\n        containing instance mask predictions.\n      mask_threshold: a scalar threshold determining which mask values are\n        rounded to 0 or 1.\n\n    Returns:\n      A dictionary containing:\n        `detection_boxes`: [batch, max_detection, 4]\n        `detection_scores`: [batch, max_detections]\n        `detection_classes`: [batch, max_detections]\n        `num_detections`: [batch]\n        `detection_masks`:\n          (optional) [batch, max_detections, mask_height, mask_width]\n    \"\"\"\n    refined_box_encodings_batch = tf.reshape(refined_box_encodings,\n                                             [-1, self.max_num_proposals,\n                                              self.num_classes,\n                                              self._box_coder.code_size])\n    class_predictions_with_background_batch = tf.reshape(\n        class_predictions_with_background,\n        [-1, self.max_num_proposals, self.num_classes + 1]\n    )\n    refined_decoded_boxes_batch = self._batch_decode_refined_boxes(\n        refined_box_encodings_batch, proposal_boxes)\n    class_predictions_with_background_batch = (\n        self._second_stage_score_conversion_fn(\n            class_predictions_with_background_batch))\n    class_predictions_batch = tf.reshape(\n        tf.slice(class_predictions_with_background_batch,\n                 [0, 0, 1], [-1, -1, -1]),\n        [-1, self.max_num_proposals, self.num_classes])\n    clip_window = tf.to_float(tf.stack([0, 0, image_shape[1], image_shape[2]]))\n\n    mask_predictions_batch = None\n    if mask_predictions is not None:\n      mask_height = mask_predictions.shape[2].value\n      mask_width = mask_predictions.shape[3].value\n      mask_predictions_batch = tf.reshape(\n          mask_predictions, [-1, self.max_num_proposals,\n                             self.num_classes, mask_height, mask_width])\n    detections = self._second_stage_nms_fn(\n        refined_decoded_boxes_batch,\n        class_predictions_batch,\n        clip_window=clip_window,\n        change_coordinate_frame=True,\n        num_valid_boxes=num_proposals,\n        masks=mask_predictions_batch)\n    if mask_predictions is not None:\n      detections['detection_masks'] = tf.to_float(\n          tf.greater_equal(detections['detection_masks'], mask_threshold))\n    return detections\n\n  def _batch_decode_refined_boxes(self, refined_box_encodings, proposal_boxes):\n    \"\"\"Decode tensor of refined box encodings.\n\n    Args:\n      refined_box_encodings: a 3-D tensor with shape\n        [batch_size, max_num_proposals, num_classes, self._box_coder.code_size]\n        representing predicted (final) refined box encodings.\n      proposal_boxes: [batch_size, self.max_num_proposals, 4] representing\n        decoded proposal bounding boxes.\n\n    Returns:\n      refined_box_predictions: a [batch_size, max_num_proposals, num_classes, 4]\n        float tensor representing (padded) refined bounding box predictions\n        (for each image in batch, proposal and class).\n    \"\"\"\n    tiled_proposal_boxes = tf.tile(\n        tf.expand_dims(proposal_boxes, 2), [1, 1, self.num_classes, 1])\n    tiled_proposals_boxlist = box_list.BoxList(\n        tf.reshape(tiled_proposal_boxes, [-1, 4]))\n    decoded_boxes = self._box_coder.decode(\n        tf.reshape(refined_box_encodings, [-1, self._box_coder.code_size]),\n        tiled_proposals_boxlist)\n    return tf.reshape(decoded_boxes.get(),\n                      [-1, self.max_num_proposals, self.num_classes, 4])\n\n  def loss(self, prediction_dict, scope=None):\n    \"\"\"Compute scalar loss tensors given prediction tensors.\n\n    If first_stage_only=True, only RPN related losses are computed (i.e.,\n    `rpn_localization_loss` and `rpn_objectness_loss`).  Otherwise all\n    losses are computed.\n\n    Args:\n      prediction_dict: a dictionary holding prediction tensors (see the\n        documentation for the predict method.  If first_stage_only=True, we\n        expect prediction_dict to contain `rpn_box_encodings`,\n        `rpn_objectness_predictions_with_background`, `rpn_features_to_crop`,\n        `image_shape`, and `anchors` fields.  Otherwise we expect\n        prediction_dict to additionally contain `refined_box_encodings`,\n        `class_predictions_with_background`, `num_proposals`, and\n        `proposal_boxes` fields.\n      scope: Optional scope name.\n\n    Returns:\n      a dictionary mapping loss keys (`first_stage_localization_loss`,\n        `first_stage_objectness_loss`, 'second_stage_localization_loss',\n        'second_stage_classification_loss') to scalar tensors representing\n        corresponding loss values.\n    \"\"\"\n    with tf.name_scope(scope, 'Loss', prediction_dict.values()):\n      (groundtruth_boxlists, groundtruth_classes_with_background_list\n      ) = self._format_groundtruth_data(prediction_dict['image_shape'])\n      loss_dict = self._loss_rpn(\n          prediction_dict['rpn_box_encodings'],\n          prediction_dict['rpn_objectness_predictions_with_background'],\n          prediction_dict['anchors'],\n          groundtruth_boxlists,\n          groundtruth_classes_with_background_list)\n      if not self._first_stage_only:\n        loss_dict.update(\n            self._loss_box_classifier(\n                prediction_dict['refined_box_encodings'],\n                prediction_dict['class_predictions_with_background'],\n                prediction_dict['proposal_boxes'],\n                prediction_dict['num_proposals'],\n                groundtruth_boxlists,\n                groundtruth_classes_with_background_list))\n    return loss_dict\n\n  def _loss_rpn(self,\n                rpn_box_encodings,\n                rpn_objectness_predictions_with_background,\n                anchors,\n                groundtruth_boxlists,\n                groundtruth_classes_with_background_list):\n    \"\"\"Computes scalar RPN loss tensors.\n\n    Uses self._proposal_target_assigner to obtain regression and classification\n    targets for the first stage RPN, samples a \"minibatch\" of anchors to\n    participate in the loss computation, and returns the RPN losses.\n\n    Args:\n      rpn_box_encodings: A 4-D float tensor of shape\n        [batch_size, num_anchors, self._box_coder.code_size] containing\n        predicted proposal box encodings.\n      rpn_objectness_predictions_with_background: A 2-D float tensor of shape\n        [batch_size, num_anchors, 2] containing objectness predictions\n        (logits) for each of the anchors with 0 corresponding to background\n        and 1 corresponding to object.\n      anchors: A 2-D tensor of shape [num_anchors, 4] representing anchors\n        for the first stage RPN.  Note that `num_anchors` can differ depending\n        on whether the model is created in training or inference mode.\n      groundtruth_boxlists: A list of BoxLists containing coordinates of the\n        groundtruth boxes.\n      groundtruth_classes_with_background_list: A list of 2-D one-hot\n        (or k-hot) tensors of shape [num_boxes, num_classes+1] containing the\n        class targets with the 0th index assumed to map to the background class.\n\n    Returns:\n      a dictionary mapping loss keys (`first_stage_localization_loss`,\n        `first_stage_objectness_loss`) to scalar tensors representing\n        corresponding loss values.\n    \"\"\"\n    with tf.name_scope('RPNLoss'):\n      (batch_cls_targets, batch_cls_weights, batch_reg_targets,\n       batch_reg_weights, _) = target_assigner.batch_assign_targets(\n           self._proposal_target_assigner, box_list.BoxList(anchors),\n           groundtruth_boxlists, len(groundtruth_boxlists)*[None])\n      batch_cls_targets = tf.squeeze(batch_cls_targets, axis=2)\n\n      def _minibatch_subsample_fn(inputs):\n        cls_targets, cls_weights = inputs\n        return self._first_stage_sampler.subsample(\n            tf.cast(cls_weights, tf.bool),\n            self._first_stage_minibatch_size, tf.cast(cls_targets, tf.bool))\n      batch_sampled_indices = tf.to_float(tf.map_fn(\n          _minibatch_subsample_fn,\n          [batch_cls_targets, batch_cls_weights],\n          dtype=tf.bool,\n          parallel_iterations=self._parallel_iterations,\n          back_prop=True))\n\n      # Normalize by number of examples in sampled minibatch\n      normalizer = tf.reduce_sum(batch_sampled_indices, axis=1)\n      batch_one_hot_targets = tf.one_hot(\n          tf.to_int32(batch_cls_targets), depth=2)\n      sampled_reg_indices = tf.multiply(batch_sampled_indices,\n                                        batch_reg_weights)\n\n      localization_losses = self._first_stage_localization_loss(\n          rpn_box_encodings, batch_reg_targets, weights=sampled_reg_indices)\n      objectness_losses = self._first_stage_objectness_loss(\n          rpn_objectness_predictions_with_background,\n          batch_one_hot_targets, weights=batch_sampled_indices)\n      localization_loss = tf.reduce_mean(\n          tf.reduce_sum(localization_losses, axis=1) / normalizer)\n      objectness_loss = tf.reduce_mean(\n          tf.reduce_sum(objectness_losses, axis=1) / normalizer)\n      loss_dict = {\n          'first_stage_localization_loss':\n          self._first_stage_loc_loss_weight * localization_loss,\n          'first_stage_objectness_loss':\n          self._first_stage_obj_loss_weight * objectness_loss,\n      }\n    return loss_dict\n\n  def _loss_box_classifier(self,\n                           refined_box_encodings,\n                           class_predictions_with_background,\n                           proposal_boxes,\n                           num_proposals,\n                           groundtruth_boxlists,\n                           groundtruth_classes_with_background_list):\n    \"\"\"Computes scalar box classifier loss tensors.\n\n    Uses self._detector_target_assigner to obtain regression and classification\n    targets for the second stage box classifier, optionally performs\n    hard mining, and returns losses.  All losses are computed independently\n    for each image and then averaged across the batch.\n\n    This function assumes that the proposal boxes in the \"padded\" regions are\n    actually zero (and thus should not be matched to).\n\n    Args:\n      refined_box_encodings: a 3-D tensor with shape\n        [total_num_proposals, num_classes, box_coder.code_size] representing\n        predicted (final) refined box encodings.\n      class_predictions_with_background: a 3-D tensor with shape\n        [total_num_proposals, num_classes + 1] containing class\n        predictions (logits) for each of the anchors.  Note that this tensor\n        *includes* background class predictions (at class index 0).\n      proposal_boxes: [batch_size, self.max_num_proposals, 4] representing\n        decoded proposal bounding boxes.\n      num_proposals: A Tensor of type `int32`. A 1-D tensor of shape [batch]\n        representing the number of proposals predicted for each image in\n        the batch.\n      groundtruth_boxlists: a list of BoxLists containing coordinates of the\n        groundtruth boxes.\n      groundtruth_classes_with_background_list: a list of 2-D one-hot\n        (or k-hot) tensors of shape [num_boxes, num_classes + 1] containing the\n        class targets with the 0th index assumed to map to the background class.\n\n    Returns:\n      a dictionary mapping loss keys ('second_stage_localization_loss',\n        'second_stage_classification_loss') to scalar tensors representing\n        corresponding loss values.\n    \"\"\"\n    with tf.name_scope('BoxClassifierLoss'):\n      paddings_indicator = self._padded_batched_proposals_indicator(\n          num_proposals, self.max_num_proposals)\n      proposal_boxlists = [\n          box_list.BoxList(proposal_boxes_single_image)\n          for proposal_boxes_single_image in tf.unstack(proposal_boxes)]\n      batch_size = len(proposal_boxlists)\n\n      num_proposals_or_one = tf.to_float(tf.expand_dims(\n          tf.maximum(num_proposals, tf.ones_like(num_proposals)), 1))\n      normalizer = tf.tile(num_proposals_or_one,\n                           [1, self.max_num_proposals]) * batch_size\n\n      (batch_cls_targets_with_background, batch_cls_weights, batch_reg_targets,\n       batch_reg_weights, _) = target_assigner.batch_assign_targets(\n           self._detector_target_assigner, proposal_boxlists,\n           groundtruth_boxlists, groundtruth_classes_with_background_list)\n\n      # We only predict refined location encodings for the non background\n      # classes, but we now pad it to make it compatible with the class\n      # predictions\n      flat_cls_targets_with_background = tf.reshape(\n          batch_cls_targets_with_background,\n          [batch_size * self.max_num_proposals, -1])\n      refined_box_encodings_with_background = tf.pad(\n          refined_box_encodings, [[0, 0], [1, 0], [0, 0]])\n      refined_box_encodings_masked_by_class_targets = tf.boolean_mask(\n          refined_box_encodings_with_background,\n          tf.greater(flat_cls_targets_with_background, 0))\n      reshaped_refined_box_encodings = tf.reshape(\n          refined_box_encodings_masked_by_class_targets,\n          [batch_size, -1, 4])\n\n      second_stage_loc_losses = self._second_stage_localization_loss(\n          reshaped_refined_box_encodings,\n          batch_reg_targets, weights=batch_reg_weights) / normalizer\n      second_stage_cls_losses = self._second_stage_classification_loss(\n          class_predictions_with_background,\n          batch_cls_targets_with_background,\n          weights=batch_cls_weights) / normalizer\n      second_stage_loc_loss = tf.reduce_sum(\n          tf.boolean_mask(second_stage_loc_losses, paddings_indicator))\n      second_stage_cls_loss = tf.reduce_sum(\n          tf.boolean_mask(second_stage_cls_losses, paddings_indicator))\n\n      if self._hard_example_miner:\n        (second_stage_loc_loss, second_stage_cls_loss\n        ) = self._unpad_proposals_and_apply_hard_mining(\n            proposal_boxlists, second_stage_loc_losses,\n            second_stage_cls_losses, num_proposals)\n      loss_dict = {\n          'second_stage_localization_loss':\n          (self._second_stage_loc_loss_weight * second_stage_loc_loss),\n          'second_stage_classification_loss':\n          (self._second_stage_cls_loss_weight * second_stage_cls_loss),\n      }\n    return loss_dict\n\n  def _padded_batched_proposals_indicator(self,\n                                          num_proposals,\n                                          max_num_proposals):\n    \"\"\"Creates indicator matrix of non-pad elements of padded batch proposals.\n\n    Args:\n      num_proposals: Tensor of type tf.int32 with shape [batch_size].\n      max_num_proposals: Maximum number of proposals per image (integer).\n\n    Returns:\n      A Tensor of type tf.bool with shape [batch_size, max_num_proposals].\n    \"\"\"\n    batch_size = tf.size(num_proposals)\n    tiled_num_proposals = tf.tile(\n        tf.expand_dims(num_proposals, 1), [1, max_num_proposals])\n    tiled_proposal_index = tf.tile(\n        tf.expand_dims(tf.range(max_num_proposals), 0), [batch_size, 1])\n    return tf.greater(tiled_num_proposals, tiled_proposal_index)\n\n  def _unpad_proposals_and_apply_hard_mining(self,\n                                             proposal_boxlists,\n                                             second_stage_loc_losses,\n                                             second_stage_cls_losses,\n                                             num_proposals):\n    \"\"\"Unpads proposals and applies hard mining.\n\n    Args:\n      proposal_boxlists: A list of `batch_size` BoxLists each representing\n        `self.max_num_proposals` representing decoded proposal bounding boxes\n        for each image.\n      second_stage_loc_losses: A Tensor of type `float32`. A tensor of shape\n        `[batch_size, self.max_num_proposals]` representing per-anchor\n        second stage localization loss values.\n      second_stage_cls_losses: A Tensor of type `float32`. A tensor of shape\n        `[batch_size, self.max_num_proposals]` representing per-anchor\n        second stage classification loss values.\n      num_proposals: A Tensor of type `int32`. A 1-D tensor of shape [batch]\n        representing the number of proposals predicted for each image in\n        the batch.\n\n    Returns:\n      second_stage_loc_loss: A scalar float32 tensor representing the second\n        stage localization loss.\n      second_stage_cls_loss: A scalar float32 tensor representing the second\n        stage classification loss.\n    \"\"\"\n    for (proposal_boxlist, single_image_loc_loss, single_image_cls_loss,\n         single_image_num_proposals) in zip(\n             proposal_boxlists,\n             tf.unstack(second_stage_loc_losses),\n             tf.unstack(second_stage_cls_losses),\n             tf.unstack(num_proposals)):\n      proposal_boxlist = box_list.BoxList(\n          tf.slice(proposal_boxlist.get(),\n                   [0, 0], [single_image_num_proposals, -1]))\n      single_image_loc_loss = tf.slice(single_image_loc_loss,\n                                       [0], [single_image_num_proposals])\n      single_image_cls_loss = tf.slice(single_image_cls_loss,\n                                       [0], [single_image_num_proposals])\n      return self._hard_example_miner(\n          location_losses=tf.expand_dims(single_image_loc_loss, 0),\n          cls_losses=tf.expand_dims(single_image_cls_loss, 0),\n          decoded_boxlist_list=[proposal_boxlist])\n\n  def restore_fn(self, checkpoint_path, from_detection_checkpoint=True):\n    \"\"\"Returns callable for loading a checkpoint into the tensorflow graph.\n\n    Args:\n      checkpoint_path: path to checkpoint to restore.\n      from_detection_checkpoint: whether to restore from a detection checkpoint\n        (with compatible variable names) or to restore from a classification\n        checkpoint for initialization prior to training.  Note that when\n        from_detection_checkpoint=True, the current implementation only\n        supports restoration from an (exactly) identical model (with exception\n        of the num_classes parameter).\n\n    Returns:\n      a callable which takes a tf.Session as input and loads a checkpoint when\n        run.\n    \"\"\"\n    if not from_detection_checkpoint:\n      return self._feature_extractor.restore_from_classification_checkpoint_fn(\n          checkpoint_path,\n          self.first_stage_feature_extractor_scope,\n          self.second_stage_feature_extractor_scope)\n\n    variables_to_restore = tf.global_variables()\n    variables_to_restore.append(slim.get_or_create_global_step())\n    # Only load feature extractor variables to be consistent with loading from\n    # a classification checkpoint.\n    first_stage_variables = tf.contrib.framework.filter_variables(\n        variables_to_restore,\n        include_patterns=[self.first_stage_feature_extractor_scope,\n                          self.second_stage_feature_extractor_scope])\n\n    saver = tf.train.Saver(first_stage_variables)\n\n    def restore(sess):\n      saver.restore(sess, checkpoint_path)\n    return restore\n"
  },
  {
    "path": "object_detector_app/object_detection/meta_architectures/faster_rcnn_meta_arch_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.meta_architectures.faster_rcnn_meta_arch.\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.meta_architectures import faster_rcnn_meta_arch_test_lib\n\n\nclass FasterRCNNMetaArchTest(\n    faster_rcnn_meta_arch_test_lib.FasterRCNNMetaArchTestBase):\n\n  def test_postprocess_second_stage_only_inference_mode_with_masks(self):\n    model = self._build_model(\n        is_training=False, first_stage_only=False, second_stage_batch_size=6)\n\n    batch_size = 2\n    total_num_padded_proposals = batch_size * model.max_num_proposals\n    proposal_boxes = tf.constant(\n        [[[1, 1, 2, 3],\n          [0, 0, 1, 1],\n          [.5, .5, .6, .6],\n          4*[0], 4*[0], 4*[0], 4*[0], 4*[0]],\n         [[2, 3, 6, 8],\n          [1, 2, 5, 3],\n          4*[0], 4*[0], 4*[0], 4*[0], 4*[0], 4*[0]]], dtype=tf.float32)\n    num_proposals = tf.constant([3, 2], dtype=tf.int32)\n    refined_box_encodings = tf.zeros(\n        [total_num_padded_proposals, model.num_classes, 4], dtype=tf.float32)\n    class_predictions_with_background = tf.ones(\n        [total_num_padded_proposals, model.num_classes+1], dtype=tf.float32)\n    image_shape = tf.constant([batch_size, 36, 48, 3], dtype=tf.int32)\n\n    mask_height = 2\n    mask_width = 2\n    mask_predictions = .6 * tf.ones(\n        [total_num_padded_proposals, model.num_classes,\n         mask_height, mask_width], dtype=tf.float32)\n    exp_detection_masks = [[[[1, 1], [1, 1]],\n                            [[1, 1], [1, 1]],\n                            [[1, 1], [1, 1]],\n                            [[1, 1], [1, 1]],\n                            [[1, 1], [1, 1]]],\n                           [[[1, 1], [1, 1]],\n                            [[1, 1], [1, 1]],\n                            [[1, 1], [1, 1]],\n                            [[1, 1], [1, 1]],\n                            [[0, 0], [0, 0]]]]\n\n    detections = model.postprocess({\n        'refined_box_encodings': refined_box_encodings,\n        'class_predictions_with_background': class_predictions_with_background,\n        'num_proposals': num_proposals,\n        'proposal_boxes': proposal_boxes,\n        'image_shape': image_shape,\n        'mask_predictions': mask_predictions\n    })\n    with self.test_session() as sess:\n      detections_out = sess.run(detections)\n      self.assertAllEqual(detections_out['detection_boxes'].shape, [2, 5, 4])\n      self.assertAllClose(detections_out['detection_scores'],\n                          [[1, 1, 1, 1, 1], [1, 1, 1, 1, 0]])\n      self.assertAllClose(detections_out['detection_classes'],\n                          [[0, 0, 0, 1, 1], [0, 0, 1, 1, 0]])\n      self.assertAllClose(detections_out['num_detections'], [5, 4])\n      self.assertAllClose(detections_out['detection_masks'],\n                          exp_detection_masks)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/meta_architectures/faster_rcnn_meta_arch_test_lib.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.meta_architectures.faster_rcnn_meta_arch.\"\"\"\nimport numpy as np\nimport tensorflow as tf\nfrom google.protobuf import text_format\nfrom object_detection.anchor_generators import grid_anchor_generator\nfrom object_detection.builders import box_predictor_builder\nfrom object_detection.builders import hyperparams_builder\nfrom object_detection.builders import post_processing_builder\nfrom object_detection.core import losses\nfrom object_detection.meta_architectures import faster_rcnn_meta_arch\nfrom object_detection.protos import box_predictor_pb2\nfrom object_detection.protos import hyperparams_pb2\nfrom object_detection.protos import post_processing_pb2\n\nslim = tf.contrib.slim\nBOX_CODE_SIZE = 4\n\n\nclass FakeFasterRCNNFeatureExtractor(\n    faster_rcnn_meta_arch.FasterRCNNFeatureExtractor):\n  \"\"\"Fake feature extracture to use in tests.\"\"\"\n\n  def __init__(self):\n    super(FakeFasterRCNNFeatureExtractor, self).__init__(\n        is_training=False,\n        first_stage_features_stride=32,\n        reuse_weights=None,\n        weight_decay=0.0)\n\n  def preprocess(self, resized_inputs):\n    return tf.identity(resized_inputs)\n\n  def _extract_proposal_features(self, preprocessed_inputs, scope):\n    with tf.variable_scope('mock_model'):\n      return 0 * slim.conv2d(preprocessed_inputs,\n                             num_outputs=3, kernel_size=1, scope='layer1')\n\n  def _extract_box_classifier_features(self, proposal_feature_maps, scope):\n    with tf.variable_scope('mock_model'):\n      return 0 * slim.conv2d(proposal_feature_maps,\n                             num_outputs=3, kernel_size=1, scope='layer2')\n\n\nclass FasterRCNNMetaArchTestBase(tf.test.TestCase):\n  \"\"\"Base class to test Faster R-CNN and R-FCN meta architectures.\"\"\"\n\n  def _build_arg_scope_with_hyperparams(self,\n                                        hyperparams_text_proto,\n                                        is_training):\n    hyperparams = hyperparams_pb2.Hyperparams()\n    text_format.Merge(hyperparams_text_proto, hyperparams)\n    return hyperparams_builder.build(hyperparams, is_training=is_training)\n\n  def _get_second_stage_box_predictor_text_proto(self):\n    box_predictor_text_proto = \"\"\"\n      mask_rcnn_box_predictor {\n        fc_hyperparams {\n          op: FC\n          activation: NONE\n          regularizer {\n            l2_regularizer {\n              weight: 0.0005\n            }\n          }\n          initializer {\n            variance_scaling_initializer {\n              factor: 1.0\n              uniform: true\n              mode: FAN_AVG\n            }\n          }\n        }\n      }\n    \"\"\"\n    return box_predictor_text_proto\n\n  def _get_second_stage_box_predictor(self, num_classes, is_training):\n    box_predictor_proto = box_predictor_pb2.BoxPredictor()\n    text_format.Merge(self._get_second_stage_box_predictor_text_proto(),\n                      box_predictor_proto)\n    return box_predictor_builder.build(\n        hyperparams_builder.build,\n        box_predictor_proto,\n        num_classes=num_classes,\n        is_training=is_training)\n\n  def _get_model(self, box_predictor, **common_kwargs):\n    return faster_rcnn_meta_arch.FasterRCNNMetaArch(\n        initial_crop_size=3,\n        maxpool_kernel_size=1,\n        maxpool_stride=1,\n        second_stage_mask_rcnn_box_predictor=box_predictor,\n        **common_kwargs)\n\n  def _build_model(self,\n                   is_training,\n                   first_stage_only,\n                   second_stage_batch_size,\n                   first_stage_max_proposals=8,\n                   num_classes=2,\n                   hard_mining=False):\n\n    def image_resizer_fn(image):\n      return tf.identity(image)\n\n    # anchors in this test are designed so that a subset of anchors are inside\n    # the image and a subset of anchors are outside.\n    first_stage_anchor_scales = (0.001, 0.005, 0.1)\n    first_stage_anchor_aspect_ratios = (0.5, 1.0, 2.0)\n    first_stage_anchor_strides = (1, 1)\n    first_stage_anchor_generator = grid_anchor_generator.GridAnchorGenerator(\n        first_stage_anchor_scales,\n        first_stage_anchor_aspect_ratios,\n        anchor_stride=first_stage_anchor_strides)\n\n    fake_feature_extractor = FakeFasterRCNNFeatureExtractor()\n\n    first_stage_box_predictor_hyperparams_text_proto = \"\"\"\n      op: CONV\n      activation: RELU\n      regularizer {\n        l2_regularizer {\n          weight: 0.00004\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n          stddev: 0.03\n        }\n      }\n    \"\"\"\n    first_stage_box_predictor_arg_scope = (\n        self._build_arg_scope_with_hyperparams(\n            first_stage_box_predictor_hyperparams_text_proto, is_training))\n\n    first_stage_box_predictor_kernel_size = 3\n    first_stage_atrous_rate = 1\n    first_stage_box_predictor_depth = 512\n    first_stage_minibatch_size = 3\n    first_stage_positive_balance_fraction = .5\n\n    first_stage_nms_score_threshold = -1.0\n    first_stage_nms_iou_threshold = 1.0\n    first_stage_max_proposals = first_stage_max_proposals\n\n    first_stage_localization_loss_weight = 1.0\n    first_stage_objectness_loss_weight = 1.0\n\n    post_processing_text_proto = \"\"\"\n      batch_non_max_suppression {\n        score_threshold: -20.0\n        iou_threshold: 1.0\n        max_detections_per_class: 5\n        max_total_detections: 5\n      }\n    \"\"\"\n    post_processing_config = post_processing_pb2.PostProcessing()\n    text_format.Merge(post_processing_text_proto, post_processing_config)\n    second_stage_non_max_suppression_fn, _ = post_processing_builder.build(\n        post_processing_config)\n    second_stage_balance_fraction = 1.0\n\n    second_stage_score_conversion_fn = tf.identity\n    second_stage_localization_loss_weight = 1.0\n    second_stage_classification_loss_weight = 1.0\n\n    hard_example_miner = None\n    if hard_mining:\n      hard_example_miner = losses.HardExampleMiner(\n          num_hard_examples=1,\n          iou_threshold=0.99,\n          loss_type='both',\n          cls_loss_weight=second_stage_classification_loss_weight,\n          loc_loss_weight=second_stage_localization_loss_weight,\n          max_negatives_per_positive=None)\n\n    common_kwargs = {\n        'is_training': is_training,\n        'num_classes': num_classes,\n        'image_resizer_fn': image_resizer_fn,\n        'feature_extractor': fake_feature_extractor,\n        'first_stage_only': first_stage_only,\n        'first_stage_anchor_generator': first_stage_anchor_generator,\n        'first_stage_atrous_rate': first_stage_atrous_rate,\n        'first_stage_box_predictor_arg_scope':\n        first_stage_box_predictor_arg_scope,\n        'first_stage_box_predictor_kernel_size':\n        first_stage_box_predictor_kernel_size,\n        'first_stage_box_predictor_depth': first_stage_box_predictor_depth,\n        'first_stage_minibatch_size': first_stage_minibatch_size,\n        'first_stage_positive_balance_fraction':\n        first_stage_positive_balance_fraction,\n        'first_stage_nms_score_threshold': first_stage_nms_score_threshold,\n        'first_stage_nms_iou_threshold': first_stage_nms_iou_threshold,\n        'first_stage_max_proposals': first_stage_max_proposals,\n        'first_stage_localization_loss_weight':\n        first_stage_localization_loss_weight,\n        'first_stage_objectness_loss_weight':\n        first_stage_objectness_loss_weight,\n        'second_stage_batch_size': second_stage_batch_size,\n        'second_stage_balance_fraction': second_stage_balance_fraction,\n        'second_stage_non_max_suppression_fn':\n        second_stage_non_max_suppression_fn,\n        'second_stage_score_conversion_fn': second_stage_score_conversion_fn,\n        'second_stage_localization_loss_weight':\n        second_stage_localization_loss_weight,\n        'second_stage_classification_loss_weight':\n        second_stage_classification_loss_weight,\n        'hard_example_miner': hard_example_miner}\n\n    return self._get_model(self._get_second_stage_box_predictor(\n        num_classes=num_classes, is_training=is_training), **common_kwargs)\n\n  def test_predict_gives_correct_shapes_in_inference_mode_first_stage_only(\n      self):\n    test_graph = tf.Graph()\n    with test_graph.as_default():\n      model = self._build_model(\n          is_training=False, first_stage_only=True, second_stage_batch_size=2)\n      batch_size = 2\n      height = 10\n      width = 12\n      input_image_shape = (batch_size, height, width, 3)\n\n      preprocessed_inputs = tf.placeholder(dtype=tf.float32,\n                                           shape=(batch_size, None, None, 3))\n      prediction_dict = model.predict(preprocessed_inputs)\n\n      # In inference mode, anchors are clipped to the image window, but not\n      # pruned.  Since MockFasterRCNN.extract_proposal_features returns a\n      # tensor with the same shape as its input, the expected number of anchors\n      # is height * width * the number of anchors per location (i.e. 3x3).\n      expected_num_anchors = height * width * 3 * 3\n      expected_output_keys = set([\n          'rpn_box_predictor_features', 'rpn_features_to_crop', 'image_shape',\n          'rpn_box_encodings', 'rpn_objectness_predictions_with_background',\n          'anchors'])\n      expected_output_shapes = {\n          'rpn_box_predictor_features': (batch_size, height, width, 512),\n          'rpn_features_to_crop': (batch_size, height, width, 3),\n          'rpn_box_encodings': (batch_size, expected_num_anchors, 4),\n          'rpn_objectness_predictions_with_background':\n          (batch_size, expected_num_anchors, 2),\n          'anchors': (expected_num_anchors, 4)\n      }\n\n      init_op = tf.global_variables_initializer()\n      with self.test_session() as sess:\n        sess.run(init_op)\n        prediction_out = sess.run(prediction_dict,\n                                  feed_dict={\n                                      preprocessed_inputs:\n                                      np.zeros(input_image_shape)\n                                  })\n\n        self.assertEqual(set(prediction_out.keys()), expected_output_keys)\n\n        self.assertAllEqual(prediction_out['image_shape'], input_image_shape)\n        for output_key, expected_shape in expected_output_shapes.iteritems():\n          self.assertAllEqual(prediction_out[output_key].shape, expected_shape)\n\n        # Check that anchors are clipped to window.\n        anchors = prediction_out['anchors']\n        self.assertTrue(np.all(np.greater_equal(anchors, 0)))\n        self.assertTrue(np.all(np.less_equal(anchors[:, 0], height)))\n        self.assertTrue(np.all(np.less_equal(anchors[:, 1], width)))\n        self.assertTrue(np.all(np.less_equal(anchors[:, 2], height)))\n        self.assertTrue(np.all(np.less_equal(anchors[:, 3], width)))\n\n  def test_predict_gives_valid_anchors_in_training_mode_first_stage_only(self):\n    test_graph = tf.Graph()\n    with test_graph.as_default():\n      model = self._build_model(\n          is_training=True, first_stage_only=True, second_stage_batch_size=2)\n      batch_size = 2\n      height = 10\n      width = 12\n      input_image_shape = (batch_size, height, width, 3)\n      preprocessed_inputs = tf.placeholder(dtype=tf.float32,\n                                           shape=(batch_size, None, None, 3))\n      prediction_dict = model.predict(preprocessed_inputs)\n\n      expected_output_keys = set([\n          'rpn_box_predictor_features', 'rpn_features_to_crop', 'image_shape',\n          'rpn_box_encodings', 'rpn_objectness_predictions_with_background',\n          'anchors'])\n      # At training time, anchors that exceed image bounds are pruned.  Thus\n      # the `expected_num_anchors` in the above inference mode test is now\n      # a strict upper bound on the number of anchors.\n      num_anchors_strict_upper_bound = height * width * 3 * 3\n\n      init_op = tf.global_variables_initializer()\n      with self.test_session() as sess:\n        sess.run(init_op)\n        prediction_out = sess.run(prediction_dict,\n                                  feed_dict={\n                                      preprocessed_inputs:\n                                      np.zeros(input_image_shape)\n                                  })\n\n        self.assertEqual(set(prediction_out.keys()), expected_output_keys)\n        self.assertAllEqual(prediction_out['image_shape'], input_image_shape)\n\n        # Check that anchors have less than the upper bound and\n        # are clipped to window.\n        anchors = prediction_out['anchors']\n        self.assertTrue(len(anchors.shape) == 2 and anchors.shape[1] == 4)\n        num_anchors_out = anchors.shape[0]\n        self.assertTrue(num_anchors_out < num_anchors_strict_upper_bound)\n\n        self.assertTrue(np.all(np.greater_equal(anchors, 0)))\n        self.assertTrue(np.all(np.less_equal(anchors[:, 0], height)))\n        self.assertTrue(np.all(np.less_equal(anchors[:, 1], width)))\n        self.assertTrue(np.all(np.less_equal(anchors[:, 2], height)))\n        self.assertTrue(np.all(np.less_equal(anchors[:, 3], width)))\n\n        self.assertAllEqual(prediction_out['rpn_box_encodings'].shape,\n                            (batch_size, num_anchors_out, 4))\n        self.assertAllEqual(\n            prediction_out['rpn_objectness_predictions_with_background'].shape,\n            (batch_size, num_anchors_out, 2))\n\n  def test_predict_gives_correct_shapes_in_inference_mode_both_stages(self):\n    test_graph = tf.Graph()\n    with test_graph.as_default():\n      model = self._build_model(\n          is_training=False, first_stage_only=False, second_stage_batch_size=2)\n      batch_size = 2\n      image_size = 10\n      image_shape = (batch_size, image_size, image_size, 3)\n      preprocessed_inputs = tf.zeros(image_shape, dtype=tf.float32)\n      result_tensor_dict = model.predict(preprocessed_inputs)\n      expected_num_anchors = image_size * image_size * 3 * 3\n\n      expected_shapes = {\n          'rpn_box_predictor_features':\n          (2, image_size, image_size, 512),\n          'rpn_features_to_crop': (2, image_size, image_size, 3),\n          'image_shape': (4,),\n          'rpn_box_encodings': (2, expected_num_anchors, 4),\n          'rpn_objectness_predictions_with_background':\n          (2, expected_num_anchors, 2),\n          'anchors': (expected_num_anchors, 4),\n          'refined_box_encodings': (2 * 8, 2, 4),\n          'class_predictions_with_background': (2 * 8, 2 + 1),\n          'num_proposals': (2,),\n          'proposal_boxes': (2, 8, 4),\n      }\n      init_op = tf.global_variables_initializer()\n      with self.test_session() as sess:\n        sess.run(init_op)\n        tensor_dict_out = sess.run(result_tensor_dict)\n        self.assertEqual(set(tensor_dict_out.keys()),\n                         set(expected_shapes.keys()))\n        for key in expected_shapes:\n          self.assertAllEqual(tensor_dict_out[key].shape, expected_shapes[key])\n\n  def test_predict_gives_correct_shapes_in_train_mode_both_stages(self):\n    test_graph = tf.Graph()\n    with test_graph.as_default():\n      model = self._build_model(\n          is_training=True, first_stage_only=False, second_stage_batch_size=7)\n      batch_size = 2\n      image_size = 10\n      image_shape = (batch_size, image_size, image_size, 3)\n      preprocessed_inputs = tf.zeros(image_shape, dtype=tf.float32)\n      groundtruth_boxes_list = [\n          tf.constant([[0, 0, .5, .5], [.5, .5, 1, 1]], dtype=tf.float32),\n          tf.constant([[0, .5, .5, 1], [.5, 0, 1, .5]], dtype=tf.float32)]\n      groundtruth_classes_list = [\n          tf.constant([[1, 0], [0, 1]], dtype=tf.float32),\n          tf.constant([[1, 0], [1, 0]], dtype=tf.float32)]\n\n      model.provide_groundtruth(groundtruth_boxes_list,\n                                groundtruth_classes_list)\n\n      result_tensor_dict = model.predict(preprocessed_inputs)\n      expected_shapes = {\n          'rpn_box_predictor_features':\n          (2, image_size, image_size, 512),\n          'rpn_features_to_crop': (2, image_size, image_size, 3),\n          'image_shape': (4,),\n          'refined_box_encodings': (2 * 7, 2, 4),\n          'class_predictions_with_background': (2 * 7, 2 + 1),\n          'num_proposals': (2,),\n          'proposal_boxes': (2, 7, 4),\n      }\n      init_op = tf.global_variables_initializer()\n      with self.test_session() as sess:\n        sess.run(init_op)\n        tensor_dict_out = sess.run(result_tensor_dict)\n        self.assertEqual(set(tensor_dict_out.keys()),\n                         set(expected_shapes.keys()).union(set([\n                             'rpn_box_encodings',\n                             'rpn_objectness_predictions_with_background',\n                             'anchors'])))\n        for key in expected_shapes:\n          self.assertAllEqual(tensor_dict_out[key].shape, expected_shapes[key])\n\n        anchors_shape_out = tensor_dict_out['anchors'].shape\n        self.assertEqual(2, len(anchors_shape_out))\n        self.assertEqual(4, anchors_shape_out[1])\n        num_anchors_out = anchors_shape_out[0]\n        self.assertAllEqual(tensor_dict_out['rpn_box_encodings'].shape,\n                            (2, num_anchors_out, 4))\n        self.assertAllEqual(\n            tensor_dict_out['rpn_objectness_predictions_with_background'].shape,\n            (2, num_anchors_out, 2))\n\n  def test_postprocess_first_stage_only_inference_mode(self):\n    model = self._build_model(\n        is_training=False, first_stage_only=True, second_stage_batch_size=6)\n    batch_size = 2\n    anchors = tf.constant(\n        [[0, 0, 16, 16],\n         [0, 16, 16, 32],\n         [16, 0, 32, 16],\n         [16, 16, 32, 32]], dtype=tf.float32)\n    rpn_box_encodings = tf.zeros(\n        [batch_size, anchors.get_shape().as_list()[0],\n         BOX_CODE_SIZE], dtype=tf.float32)\n    # use different numbers for the objectness category to break ties in\n    # order of boxes returned by NMS\n    rpn_objectness_predictions_with_background = tf.constant([\n        [[-10, 13],\n         [10, -10],\n         [10, -11],\n         [-10, 12]],\n        [[10, -10],\n         [-10, 13],\n         [-10, 12],\n         [10, -11]]], dtype=tf.float32)\n    rpn_features_to_crop = tf.ones((batch_size, 8, 8, 10), dtype=tf.float32)\n    image_shape = tf.constant([batch_size, 32, 32, 3], dtype=tf.int32)\n    proposals = model.postprocess({\n        'rpn_box_encodings': rpn_box_encodings,\n        'rpn_objectness_predictions_with_background':\n        rpn_objectness_predictions_with_background,\n        'rpn_features_to_crop': rpn_features_to_crop,\n        'anchors': anchors,\n        'image_shape': image_shape})\n    expected_proposal_boxes = [\n        [[0, 0, .5, .5], [.5, .5, 1, 1], [0, .5, .5, 1], [.5, 0, 1.0, .5]]\n        + 4 * [4 * [0]],\n        [[0, .5, .5, 1], [.5, 0, 1.0, .5], [0, 0, .5, .5], [.5, .5, 1, 1]]\n        + 4 * [4 * [0]]]\n    expected_proposal_scores = [[1, 1, 0, 0, 0, 0, 0, 0],\n                                [1, 1, 0, 0, 0, 0, 0, 0]]\n    expected_num_proposals = [4, 4]\n\n    expected_output_keys = set(['detection_boxes', 'detection_scores',\n                                'num_detections'])\n    self.assertEqual(set(proposals.keys()), expected_output_keys)\n    with self.test_session() as sess:\n      proposals_out = sess.run(proposals)\n      self.assertAllClose(proposals_out['detection_boxes'],\n                          expected_proposal_boxes)\n      self.assertAllClose(proposals_out['detection_scores'],\n                          expected_proposal_scores)\n      self.assertAllEqual(proposals_out['num_detections'],\n                          expected_num_proposals)\n\n  def test_postprocess_first_stage_only_train_mode(self):\n    model = self._build_model(\n        is_training=True, first_stage_only=True, second_stage_batch_size=2)\n    batch_size = 2\n    anchors = tf.constant(\n        [[0, 0, 16, 16],\n         [0, 16, 16, 32],\n         [16, 0, 32, 16],\n         [16, 16, 32, 32]], dtype=tf.float32)\n    rpn_box_encodings = tf.zeros(\n        [batch_size, anchors.get_shape().as_list()[0],\n         BOX_CODE_SIZE], dtype=tf.float32)\n    # use different numbers for the objectness category to break ties in\n    # order of boxes returned by NMS\n    rpn_objectness_predictions_with_background = tf.constant([\n        [[-10, 13],\n         [-10, 12],\n         [-10, 11],\n         [-10, 10]],\n        [[-10, 13],\n         [-10, 12],\n         [-10, 11],\n         [-10, 10]]], dtype=tf.float32)\n    rpn_features_to_crop = tf.ones((batch_size, 8, 8, 10), dtype=tf.float32)\n    image_shape = tf.constant([batch_size, 32, 32, 3], dtype=tf.int32)\n    groundtruth_boxes_list = [\n        tf.constant([[0, 0, .5, .5], [.5, .5, 1, 1]], dtype=tf.float32),\n        tf.constant([[0, .5, .5, 1], [.5, 0, 1, .5]], dtype=tf.float32)]\n    groundtruth_classes_list = [tf.constant([[1, 0], [0, 1]], dtype=tf.float32),\n                                tf.constant([[1, 0], [1, 0]], dtype=tf.float32)]\n\n    model.provide_groundtruth(groundtruth_boxes_list,\n                              groundtruth_classes_list)\n    proposals = model.postprocess({\n        'rpn_box_encodings': rpn_box_encodings,\n        'rpn_objectness_predictions_with_background':\n        rpn_objectness_predictions_with_background,\n        'rpn_features_to_crop': rpn_features_to_crop,\n        'anchors': anchors,\n        'image_shape': image_shape})\n    expected_proposal_boxes = [\n        [[0, 0, .5, .5], [.5, .5, 1, 1]], [[0, .5, .5, 1], [.5, 0, 1, .5]]]\n    expected_proposal_scores = [[1, 1],\n                                [1, 1]]\n    expected_num_proposals = [2, 2]\n\n    expected_output_keys = set(['detection_boxes', 'detection_scores',\n                                'num_detections'])\n    self.assertEqual(set(proposals.keys()), expected_output_keys)\n\n    with self.test_session() as sess:\n      proposals_out = sess.run(proposals)\n      self.assertAllClose(proposals_out['detection_boxes'],\n                          expected_proposal_boxes)\n      self.assertAllClose(proposals_out['detection_scores'],\n                          expected_proposal_scores)\n      self.assertAllEqual(proposals_out['num_detections'],\n                          expected_num_proposals)\n\n  def test_postprocess_second_stage_only_inference_mode(self):\n    model = self._build_model(\n        is_training=False, first_stage_only=False, second_stage_batch_size=6)\n\n    batch_size = 2\n    total_num_padded_proposals = batch_size * model.max_num_proposals\n    proposal_boxes = tf.constant(\n        [[[1, 1, 2, 3],\n          [0, 0, 1, 1],\n          [.5, .5, .6, .6],\n          4*[0], 4*[0], 4*[0], 4*[0], 4*[0]],\n         [[2, 3, 6, 8],\n          [1, 2, 5, 3],\n          4*[0], 4*[0], 4*[0], 4*[0], 4*[0], 4*[0]]], dtype=tf.float32)\n    num_proposals = tf.constant([3, 2], dtype=tf.int32)\n    refined_box_encodings = tf.zeros(\n        [total_num_padded_proposals, model.num_classes, 4], dtype=tf.float32)\n    class_predictions_with_background = tf.ones(\n        [total_num_padded_proposals, model.num_classes+1], dtype=tf.float32)\n    image_shape = tf.constant([batch_size, 36, 48, 3], dtype=tf.int32)\n\n    detections = model.postprocess({\n        'refined_box_encodings': refined_box_encodings,\n        'class_predictions_with_background': class_predictions_with_background,\n        'num_proposals': num_proposals,\n        'proposal_boxes': proposal_boxes,\n        'image_shape': image_shape\n    })\n    with self.test_session() as sess:\n      detections_out = sess.run(detections)\n      self.assertAllEqual(detections_out['detection_boxes'].shape, [2, 5, 4])\n      self.assertAllClose(detections_out['detection_scores'],\n                          [[1, 1, 1, 1, 1], [1, 1, 1, 1, 0]])\n      self.assertAllClose(detections_out['detection_classes'],\n                          [[0, 0, 0, 1, 1], [0, 0, 1, 1, 0]])\n      self.assertAllClose(detections_out['num_detections'], [5, 4])\n\n  def test_loss_first_stage_only_mode(self):\n    model = self._build_model(\n        is_training=True, first_stage_only=True, second_stage_batch_size=6)\n    batch_size = 2\n    anchors = tf.constant(\n        [[0, 0, 16, 16],\n         [0, 16, 16, 32],\n         [16, 0, 32, 16],\n         [16, 16, 32, 32]], dtype=tf.float32)\n\n    rpn_box_encodings = tf.zeros(\n        [batch_size,\n         anchors.get_shape().as_list()[0],\n         BOX_CODE_SIZE], dtype=tf.float32)\n    # use different numbers for the objectness category to break ties in\n    # order of boxes returned by NMS\n    rpn_objectness_predictions_with_background = tf.constant([\n        [[-10, 13],\n         [10, -10],\n         [10, -11],\n         [-10, 12]],\n        [[10, -10],\n         [-10, 13],\n         [-10, 12],\n         [10, -11]]], dtype=tf.float32)\n    image_shape = tf.constant([batch_size, 32, 32, 3], dtype=tf.int32)\n\n    groundtruth_boxes_list = [\n        tf.constant([[0, 0, .5, .5], [.5, .5, 1, 1]], dtype=tf.float32),\n        tf.constant([[0, .5, .5, 1], [.5, 0, 1, .5]], dtype=tf.float32)]\n    groundtruth_classes_list = [tf.constant([[1, 0], [0, 1]], dtype=tf.float32),\n                                tf.constant([[1, 0], [1, 0]], dtype=tf.float32)]\n\n    prediction_dict = {\n        'rpn_box_encodings': rpn_box_encodings,\n        'rpn_objectness_predictions_with_background':\n        rpn_objectness_predictions_with_background,\n        'image_shape': image_shape,\n        'anchors': anchors\n    }\n    model.provide_groundtruth(groundtruth_boxes_list,\n                              groundtruth_classes_list)\n    loss_dict = model.loss(prediction_dict)\n    with self.test_session() as sess:\n      loss_dict_out = sess.run(loss_dict)\n      self.assertAllClose(loss_dict_out['first_stage_localization_loss'], 0)\n      self.assertAllClose(loss_dict_out['first_stage_objectness_loss'], 0)\n      self.assertTrue('second_stage_localization_loss' not in loss_dict_out)\n      self.assertTrue('second_stage_classification_loss' not in loss_dict_out)\n\n  def test_loss_full(self):\n    model = self._build_model(\n        is_training=True, first_stage_only=False, second_stage_batch_size=6)\n    batch_size = 2\n    anchors = tf.constant(\n        [[0, 0, 16, 16],\n         [0, 16, 16, 32],\n         [16, 0, 32, 16],\n         [16, 16, 32, 32]], dtype=tf.float32)\n    rpn_box_encodings = tf.zeros(\n        [batch_size,\n         anchors.get_shape().as_list()[0],\n         BOX_CODE_SIZE], dtype=tf.float32)\n    # use different numbers for the objectness category to break ties in\n    # order of boxes returned by NMS\n    rpn_objectness_predictions_with_background = tf.constant([\n        [[-10, 13],\n         [10, -10],\n         [10, -11],\n         [-10, 12]],\n        [[10, -10],\n         [-10, 13],\n         [-10, 12],\n         [10, -11]]], dtype=tf.float32)\n    image_shape = tf.constant([batch_size, 32, 32, 3], dtype=tf.int32)\n\n    num_proposals = tf.constant([6, 6], dtype=tf.int32)\n    proposal_boxes = tf.constant(\n        2 * [[[0, 0, 16, 16],\n              [0, 16, 16, 32],\n              [16, 0, 32, 16],\n              [16, 16, 32, 32],\n              [0, 0, 16, 16],\n              [0, 16, 16, 32]]], dtype=tf.float32)\n    refined_box_encodings = tf.zeros(\n        (batch_size * model.max_num_proposals,\n         model.num_classes,\n         BOX_CODE_SIZE), dtype=tf.float32)\n    class_predictions_with_background = tf.constant(\n        [[-10, 10, -10],  # first image\n         [10, -10, -10],\n         [10, -10, -10],\n         [-10, -10, 10],\n         [-10, 10, -10],\n         [10, -10, -10],\n         [10, -10, -10],  # second image\n         [-10, 10, -10],\n         [-10, 10, -10],\n         [10, -10, -10],\n         [10, -10, -10],\n         [-10, 10, -10]], dtype=tf.float32)\n\n    groundtruth_boxes_list = [\n        tf.constant([[0, 0, .5, .5], [.5, .5, 1, 1]], dtype=tf.float32),\n        tf.constant([[0, .5, .5, 1], [.5, 0, 1, .5]], dtype=tf.float32)]\n    groundtruth_classes_list = [tf.constant([[1, 0], [0, 1]], dtype=tf.float32),\n                                tf.constant([[1, 0], [1, 0]], dtype=tf.float32)]\n\n    prediction_dict = {\n        'rpn_box_encodings': rpn_box_encodings,\n        'rpn_objectness_predictions_with_background':\n        rpn_objectness_predictions_with_background,\n        'image_shape': image_shape,\n        'anchors': anchors,\n        'refined_box_encodings': refined_box_encodings,\n        'class_predictions_with_background': class_predictions_with_background,\n        'proposal_boxes': proposal_boxes,\n        'num_proposals': num_proposals\n    }\n    model.provide_groundtruth(groundtruth_boxes_list,\n                              groundtruth_classes_list)\n    loss_dict = model.loss(prediction_dict)\n\n    with self.test_session() as sess:\n      loss_dict_out = sess.run(loss_dict)\n      self.assertAllClose(loss_dict_out['first_stage_localization_loss'], 0)\n      self.assertAllClose(loss_dict_out['first_stage_objectness_loss'], 0)\n      self.assertAllClose(loss_dict_out['second_stage_localization_loss'], 0)\n      self.assertAllClose(loss_dict_out['second_stage_classification_loss'], 0)\n\n  def test_loss_full_zero_padded_proposals(self):\n    model = self._build_model(\n        is_training=True, first_stage_only=False, second_stage_batch_size=6)\n    batch_size = 1\n    anchors = tf.constant(\n        [[0, 0, 16, 16],\n         [0, 16, 16, 32],\n         [16, 0, 32, 16],\n         [16, 16, 32, 32]], dtype=tf.float32)\n    rpn_box_encodings = tf.zeros(\n        [batch_size,\n         anchors.get_shape().as_list()[0],\n         BOX_CODE_SIZE], dtype=tf.float32)\n    # use different numbers for the objectness category to break ties in\n    # order of boxes returned by NMS\n    rpn_objectness_predictions_with_background = tf.constant([\n        [[-10, 13],\n         [10, -10],\n         [10, -11],\n         [10, -12]],], dtype=tf.float32)\n    image_shape = tf.constant([batch_size, 32, 32, 3], dtype=tf.int32)\n\n    # box_classifier_batch_size is 6, but here we assume that the number of\n    # actual proposals (not counting zero paddings) is fewer (3).\n    num_proposals = tf.constant([3], dtype=tf.int32)\n    proposal_boxes = tf.constant(\n        [[[0, 0, 16, 16],\n          [0, 16, 16, 32],\n          [16, 0, 32, 16],\n          [0, 0, 0, 0],  # begin paddings\n          [0, 0, 0, 0],\n          [0, 0, 0, 0]]], dtype=tf.float32)\n\n    refined_box_encodings = tf.zeros(\n        (batch_size * model.max_num_proposals,\n         model.num_classes,\n         BOX_CODE_SIZE), dtype=tf.float32)\n    class_predictions_with_background = tf.constant(\n        [[-10, 10, -10],\n         [10, -10, -10],\n         [10, -10, -10],\n         [0, 0, 0],  # begin paddings\n         [0, 0, 0],\n         [0, 0, 0]], dtype=tf.float32)\n\n    groundtruth_boxes_list = [\n        tf.constant([[0, 0, .5, .5]], dtype=tf.float32)]\n    groundtruth_classes_list = [tf.constant([[1, 0]], dtype=tf.float32)]\n\n    prediction_dict = {\n        'rpn_box_encodings': rpn_box_encodings,\n        'rpn_objectness_predictions_with_background':\n        rpn_objectness_predictions_with_background,\n        'image_shape': image_shape,\n        'anchors': anchors,\n        'refined_box_encodings': refined_box_encodings,\n        'class_predictions_with_background': class_predictions_with_background,\n        'proposal_boxes': proposal_boxes,\n        'num_proposals': num_proposals\n    }\n    model.provide_groundtruth(groundtruth_boxes_list,\n                              groundtruth_classes_list)\n    loss_dict = model.loss(prediction_dict)\n\n    with self.test_session() as sess:\n      loss_dict_out = sess.run(loss_dict)\n      self.assertAllClose(loss_dict_out['first_stage_localization_loss'], 0)\n      self.assertAllClose(loss_dict_out['first_stage_objectness_loss'], 0)\n      self.assertAllClose(loss_dict_out['second_stage_localization_loss'], 0)\n      self.assertAllClose(loss_dict_out['second_stage_classification_loss'], 0)\n\n  def test_loss_full_zero_padded_proposals_nonzero_loss_with_two_images(self):\n    model = self._build_model(\n        is_training=True, first_stage_only=False, second_stage_batch_size=6)\n    batch_size = 2\n    anchors = tf.constant(\n        [[0, 0, 16, 16],\n         [0, 16, 16, 32],\n         [16, 0, 32, 16],\n         [16, 16, 32, 32]], dtype=tf.float32)\n    rpn_box_encodings = tf.zeros(\n        [batch_size,\n         anchors.get_shape().as_list()[0],\n         BOX_CODE_SIZE], dtype=tf.float32)\n    # use different numbers for the objectness category to break ties in\n    # order of boxes returned by NMS\n    rpn_objectness_predictions_with_background = tf.constant(\n        [[[-10, 13],\n          [10, -10],\n          [10, -11],\n          [10, -12]],\n         [[-10, 13],\n          [10, -10],\n          [10, -11],\n          [10, -12]]], dtype=tf.float32)\n    image_shape = tf.constant([batch_size, 32, 32, 3], dtype=tf.int32)\n\n    # box_classifier_batch_size is 6, but here we assume that the number of\n    # actual proposals (not counting zero paddings) is fewer (3).\n    num_proposals = tf.constant([3, 2], dtype=tf.int32)\n    proposal_boxes = tf.constant(\n        [[[0, 0, 16, 16],\n          [0, 16, 16, 32],\n          [16, 0, 32, 16],\n          [0, 0, 0, 0],  # begin paddings\n          [0, 0, 0, 0],\n          [0, 0, 0, 0]],\n         [[0, 0, 16, 16],\n          [0, 16, 16, 32],\n          [0, 0, 0, 0],\n          [0, 0, 0, 0],  # begin paddings\n          [0, 0, 0, 0],\n          [0, 0, 0, 0]]], dtype=tf.float32)\n\n    refined_box_encodings = tf.zeros(\n        (batch_size * model.max_num_proposals,\n         model.num_classes,\n         BOX_CODE_SIZE), dtype=tf.float32)\n    class_predictions_with_background = tf.constant(\n        [[-10, 10, -10],  # first image\n         [10, -10, -10],\n         [10, -10, -10],\n         [0, 0, 0],  # begin paddings\n         [0, 0, 0],\n         [0, 0, 0],\n         [-10, -10, 10],  # second image\n         [10, -10, -10],\n         [0, 0, 0],  # begin paddings\n         [0, 0, 0],\n         [0, 0, 0],\n         [0, 0, 0],], dtype=tf.float32)\n\n    # The first groundtruth box is 4/5 of the anchor size in both directions\n    # experiencing a loss of:\n    # 2 * SmoothL1(5 * log(4/5)) / num_proposals\n    #   = 2 * (abs(5 * log(1/2)) - .5) / 3\n    # The second groundtruth box is identical to the prediction and thus\n    # experiences zero loss.\n    # Total average loss is (abs(5 * log(1/2)) - .5) / 3.\n    groundtruth_boxes_list = [\n        tf.constant([[0.05, 0.05, 0.45, 0.45]], dtype=tf.float32),\n        tf.constant([[0.0, 0.0, 0.5, 0.5]], dtype=tf.float32)]\n    groundtruth_classes_list = [tf.constant([[1, 0]], dtype=tf.float32),\n                                tf.constant([[0, 1]], dtype=tf.float32)]\n    exp_loc_loss = (-5 * np.log(.8) - 0.5) / 3.0\n\n    prediction_dict = {\n        'rpn_box_encodings': rpn_box_encodings,\n        'rpn_objectness_predictions_with_background':\n        rpn_objectness_predictions_with_background,\n        'image_shape': image_shape,\n        'anchors': anchors,\n        'refined_box_encodings': refined_box_encodings,\n        'class_predictions_with_background': class_predictions_with_background,\n        'proposal_boxes': proposal_boxes,\n        'num_proposals': num_proposals\n    }\n    model.provide_groundtruth(groundtruth_boxes_list,\n                              groundtruth_classes_list)\n    loss_dict = model.loss(prediction_dict)\n\n    with self.test_session() as sess:\n      loss_dict_out = sess.run(loss_dict)\n      self.assertAllClose(loss_dict_out['first_stage_localization_loss'],\n                          exp_loc_loss)\n      self.assertAllClose(loss_dict_out['first_stage_objectness_loss'], 0)\n      self.assertAllClose(loss_dict_out['second_stage_localization_loss'],\n                          exp_loc_loss)\n      self.assertAllClose(loss_dict_out['second_stage_classification_loss'], 0)\n\n  def test_loss_with_hard_mining(self):\n    model = self._build_model(is_training=True,\n                              first_stage_only=False,\n                              second_stage_batch_size=None,\n                              first_stage_max_proposals=6,\n                              hard_mining=True)\n    batch_size = 1\n    anchors = tf.constant(\n        [[0, 0, 16, 16],\n         [0, 16, 16, 32],\n         [16, 0, 32, 16],\n         [16, 16, 32, 32]], dtype=tf.float32)\n    rpn_box_encodings = tf.zeros(\n        [batch_size,\n         anchors.get_shape().as_list()[0],\n         BOX_CODE_SIZE], dtype=tf.float32)\n    # use different numbers for the objectness category to break ties in\n    # order of boxes returned by NMS\n    rpn_objectness_predictions_with_background = tf.constant(\n        [[[-10, 13],\n          [-10, 12],\n          [10, -11],\n          [10, -12]]], dtype=tf.float32)\n    image_shape = tf.constant([batch_size, 32, 32, 3], dtype=tf.int32)\n\n    # box_classifier_batch_size is 6, but here we assume that the number of\n    # actual proposals (not counting zero paddings) is fewer (3).\n    num_proposals = tf.constant([3], dtype=tf.int32)\n    proposal_boxes = tf.constant(\n        [[[0, 0, 16, 16],\n          [0, 16, 16, 32],\n          [16, 0, 32, 16],\n          [0, 0, 0, 0],  # begin paddings\n          [0, 0, 0, 0],\n          [0, 0, 0, 0]]], dtype=tf.float32)\n\n    refined_box_encodings = tf.zeros(\n        (batch_size * model.max_num_proposals,\n         model.num_classes,\n         BOX_CODE_SIZE), dtype=tf.float32)\n    class_predictions_with_background = tf.constant(\n        [[-10, 10, -10],  # first image\n         [-10, -10, 10],\n         [10, -10, -10],\n         [0, 0, 0],  # begin paddings\n         [0, 0, 0],\n         [0, 0, 0]], dtype=tf.float32)\n\n    # The first groundtruth box is 4/5 of the anchor size in both directions\n    # experiencing a loss of:\n    # 2 * SmoothL1(5 * log(4/5)) / num_proposals\n    #   = 2 * (abs(5 * log(1/2)) - .5) / 3\n    # The second groundtruth box is 46/50 of the anchor size in both directions\n    # experiencing a loss of:\n    # 2 * SmoothL1(5 * log(42/50)) / num_proposals\n    #   = 2 * (.5(5 * log(.92))^2 - .5) / 3.\n    # Since the first groundtruth box experiences greater loss, and we have\n    # set num_hard_examples=1 in the HardMiner, the final localization loss\n    # corresponds to that of the first groundtruth box.\n    groundtruth_boxes_list = [\n        tf.constant([[0.05, 0.05, 0.45, 0.45],\n                     [0.02, 0.52, 0.48, 0.98],], dtype=tf.float32)]\n    groundtruth_classes_list = [tf.constant([[1, 0], [0, 1]], dtype=tf.float32)]\n    exp_loc_loss = 2 * (-5 * np.log(.8) - 0.5) / 3.0\n\n    prediction_dict = {\n        'rpn_box_encodings': rpn_box_encodings,\n        'rpn_objectness_predictions_with_background':\n        rpn_objectness_predictions_with_background,\n        'image_shape': image_shape,\n        'anchors': anchors,\n        'refined_box_encodings': refined_box_encodings,\n        'class_predictions_with_background': class_predictions_with_background,\n        'proposal_boxes': proposal_boxes,\n        'num_proposals': num_proposals\n    }\n    model.provide_groundtruth(groundtruth_boxes_list,\n                              groundtruth_classes_list)\n    loss_dict = model.loss(prediction_dict)\n\n    with self.test_session() as sess:\n      loss_dict_out = sess.run(loss_dict)\n      self.assertAllClose(loss_dict_out['second_stage_localization_loss'],\n                          exp_loc_loss)\n      self.assertAllClose(loss_dict_out['second_stage_classification_loss'], 0)\n\n  def test_restore_fn_classification(self):\n    # Define mock tensorflow classification graph and save variables.\n    test_graph_classification = tf.Graph()\n    with test_graph_classification.as_default():\n      image = tf.placeholder(dtype=tf.float32, shape=[1, 20, 20, 3])\n      with tf.variable_scope('mock_model'):\n        net = slim.conv2d(image, num_outputs=3, kernel_size=1, scope='layer1')\n        slim.conv2d(net, num_outputs=3, kernel_size=1, scope='layer2')\n\n      init_op = tf.global_variables_initializer()\n      saver = tf.train.Saver()\n      save_path = self.get_temp_dir()\n      with self.test_session() as sess:\n        sess.run(init_op)\n        saved_model_path = saver.save(sess, save_path)\n\n    # Create tensorflow detection graph and load variables from\n    # classification checkpoint.\n    test_graph_detection = tf.Graph()\n    with test_graph_detection.as_default():\n      model = self._build_model(\n          is_training=False, first_stage_only=False, second_stage_batch_size=6)\n\n      inputs_shape = (2, 20, 20, 3)\n      inputs = tf.to_float(tf.random_uniform(\n          inputs_shape, minval=0, maxval=255, dtype=tf.int32))\n      preprocessed_inputs = model.preprocess(inputs)\n      prediction_dict = model.predict(preprocessed_inputs)\n      model.postprocess(prediction_dict)\n      restore_fn = model.restore_fn(saved_model_path,\n                                    from_detection_checkpoint=False)\n      with self.test_session() as sess:\n        restore_fn(sess)\n\n  def test_restore_fn_detection(self):\n    # Define first detection graph and save variables.\n    test_graph_detection1 = tf.Graph()\n    with test_graph_detection1.as_default():\n      model = self._build_model(\n          is_training=False, first_stage_only=False, second_stage_batch_size=6)\n      inputs_shape = (2, 20, 20, 3)\n      inputs = tf.to_float(tf.random_uniform(\n          inputs_shape, minval=0, maxval=255, dtype=tf.int32))\n      preprocessed_inputs = model.preprocess(inputs)\n      prediction_dict = model.predict(preprocessed_inputs)\n      model.postprocess(prediction_dict)\n      init_op = tf.global_variables_initializer()\n      saver = tf.train.Saver()\n      save_path = self.get_temp_dir()\n      with self.test_session() as sess:\n        sess.run(init_op)\n        saved_model_path = saver.save(sess, save_path)\n\n    # Define second detection graph and restore variables.\n    test_graph_detection2 = tf.Graph()\n    with test_graph_detection2.as_default():\n      model2 = self._build_model(is_training=False, first_stage_only=False,\n                                 second_stage_batch_size=6, num_classes=42)\n\n      inputs_shape2 = (2, 20, 20, 3)\n      inputs2 = tf.to_float(tf.random_uniform(\n          inputs_shape2, minval=0, maxval=255, dtype=tf.int32))\n      preprocessed_inputs2 = model2.preprocess(inputs2)\n      prediction_dict2 = model2.predict(preprocessed_inputs2)\n      model2.postprocess(prediction_dict2)\n      restore_fn = model2.restore_fn(saved_model_path,\n                                     from_detection_checkpoint=True)\n      with self.test_session() as sess:\n        restore_fn(sess)\n        for var in sess.run(tf.report_uninitialized_variables()):\n          self.assertNotIn(model2.first_stage_feature_extractor_scope, var.name)\n          self.assertNotIn(model2.second_stage_feature_extractor_scope,\n                           var.name)\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/meta_architectures/rfcn_meta_arch.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\"\"\"R-FCN meta-architecture definition.\n\nR-FCN: Dai, Jifeng, et al. \"R-FCN: Object Detection via Region-based\nFully Convolutional Networks.\" arXiv preprint arXiv:1605.06409 (2016).\n\nThe R-FCN meta architecture is similar to Faster R-CNN and only differs in the\nsecond stage. Hence this class inherits FasterRCNNMetaArch and overrides only\nthe `_predict_second_stage` method.\n\nSimilar to Faster R-CNN we allow for two modes: first_stage_only=True and\nfirst_stage_only=False.  In the former setting, all of the user facing methods\n(e.g., predict, postprocess, loss) can be used as if the model consisted\nonly of the RPN, returning class agnostic proposals (these can be thought of as\napproximate detections with no associated class information).  In the latter\nsetting, proposals are computed, then passed through a second stage\n\"box classifier\" to yield (multi-class) detections.\n\nImplementations of R-FCN models must define a new FasterRCNNFeatureExtractor and\noverride three methods: `preprocess`, `_extract_proposal_features` (the first\nstage of the model), and `_extract_box_classifier_features` (the second stage of\nthe model). Optionally, the `restore_fn` method can be overridden.  See tests\nfor an example.\n\nSee notes in the documentation of Faster R-CNN meta-architecture as they all\napply here.\n\"\"\"\nimport tensorflow as tf\n\nfrom object_detection.core import box_predictor\nfrom object_detection.meta_architectures import faster_rcnn_meta_arch\nfrom object_detection.utils import ops\n\n\nclass RFCNMetaArch(faster_rcnn_meta_arch.FasterRCNNMetaArch):\n  \"\"\"R-FCN Meta-architecture definition.\"\"\"\n\n  def __init__(self,\n               is_training,\n               num_classes,\n               image_resizer_fn,\n               feature_extractor,\n               first_stage_only,\n               first_stage_anchor_generator,\n               first_stage_atrous_rate,\n               first_stage_box_predictor_arg_scope,\n               first_stage_box_predictor_kernel_size,\n               first_stage_box_predictor_depth,\n               first_stage_minibatch_size,\n               first_stage_positive_balance_fraction,\n               first_stage_nms_score_threshold,\n               first_stage_nms_iou_threshold,\n               first_stage_max_proposals,\n               first_stage_localization_loss_weight,\n               first_stage_objectness_loss_weight,\n               second_stage_rfcn_box_predictor,\n               second_stage_batch_size,\n               second_stage_balance_fraction,\n               second_stage_non_max_suppression_fn,\n               second_stage_score_conversion_fn,\n               second_stage_localization_loss_weight,\n               second_stage_classification_loss_weight,\n               hard_example_miner,\n               parallel_iterations=16):\n    \"\"\"RFCNMetaArch Constructor.\n\n    Args:\n      is_training: A boolean indicating whether the training version of the\n        computation graph should be constructed.\n      num_classes: Number of classes.  Note that num_classes *does not*\n        include the background category, so if groundtruth labels take values\n        in {0, 1, .., K-1}, num_classes=K (and not K+1, even though the\n        assigned classification targets can range from {0,... K}).\n      image_resizer_fn: A callable for image resizing.  This callable always\n        takes a rank-3 image tensor (corresponding to a single image) and\n        returns a rank-3 image tensor, possibly with new spatial dimensions.\n        See builders/image_resizer_builder.py.\n      feature_extractor: A FasterRCNNFeatureExtractor object.\n      first_stage_only:  Whether to construct only the Region Proposal Network\n        (RPN) part of the model.\n      first_stage_anchor_generator: An anchor_generator.AnchorGenerator object\n        (note that currently we only support\n        grid_anchor_generator.GridAnchorGenerator objects)\n      first_stage_atrous_rate: A single integer indicating the atrous rate for\n        the single convolution op which is applied to the `rpn_features_to_crop`\n        tensor to obtain a tensor to be used for box prediction. Some feature\n        extractors optionally allow for producing feature maps computed at\n        denser resolutions.  The atrous rate is used to compensate for the\n        denser feature maps by using an effectively larger receptive field.\n        (This should typically be set to 1).\n      first_stage_box_predictor_arg_scope: Slim arg_scope for conv2d,\n        separable_conv2d and fully_connected ops for the RPN box predictor.\n      first_stage_box_predictor_kernel_size: Kernel size to use for the\n        convolution op just prior to RPN box predictions.\n      first_stage_box_predictor_depth: Output depth for the convolution op\n        just prior to RPN box predictions.\n      first_stage_minibatch_size: The \"batch size\" to use for computing the\n        objectness and location loss of the region proposal network. This\n        \"batch size\" refers to the number of anchors selected as contributing\n        to the loss function for any given image within the image batch and is\n        only called \"batch_size\" due to terminology from the Faster R-CNN paper.\n      first_stage_positive_balance_fraction: Fraction of positive examples\n        per image for the RPN. The recommended value for Faster RCNN is 0.5.\n      first_stage_nms_score_threshold: Score threshold for non max suppression\n        for the Region Proposal Network (RPN).  This value is expected to be in\n        [0, 1] as it is applied directly after a softmax transformation.  The\n        recommended value for Faster R-CNN is 0.\n      first_stage_nms_iou_threshold: The Intersection Over Union (IOU) threshold\n        for performing Non-Max Suppression (NMS) on the boxes predicted by the\n        Region Proposal Network (RPN).\n      first_stage_max_proposals: Maximum number of boxes to retain after\n        performing Non-Max Suppression (NMS) on the boxes predicted by the\n        Region Proposal Network (RPN).\n      first_stage_localization_loss_weight: A float\n      first_stage_objectness_loss_weight: A float\n      second_stage_rfcn_box_predictor: RFCN box predictor to use for\n        second stage.\n      second_stage_batch_size: The batch size used for computing the\n        classification and refined location loss of the box classifier.  This\n        \"batch size\" refers to the number of proposals selected as contributing\n        to the loss function for any given image within the image batch and is\n        only called \"batch_size\" due to terminology from the Faster R-CNN paper.\n      second_stage_balance_fraction: Fraction of positive examples to use\n        per image for the box classifier. The recommended value for Faster RCNN\n        is 0.25.\n      second_stage_non_max_suppression_fn: batch_multiclass_non_max_suppression\n        callable that takes `boxes`, `scores`, optional `clip_window` and\n        optional (kwarg) `mask` inputs (with all other inputs already set)\n        and returns a dictionary containing tensors with keys:\n        `detection_boxes`, `detection_scores`, `detection_classes`,\n        `num_detections`, and (optionally) `detection_masks`. See\n        `post_processing.batch_multiclass_non_max_suppression` for the type and\n        shape of these tensors.\n      second_stage_score_conversion_fn: Callable elementwise nonlinearity\n        (that takes tensors as inputs and returns tensors).  This is usually\n        used to convert logits to probabilities.\n      second_stage_localization_loss_weight: A float\n      second_stage_classification_loss_weight: A float\n      hard_example_miner:  A losses.HardExampleMiner object (can be None).\n      parallel_iterations: (Optional) The number of iterations allowed to run\n        in parallel for calls to tf.map_fn.\n    Raises:\n      ValueError: If `second_stage_batch_size` > `first_stage_max_proposals`\n      ValueError: If first_stage_anchor_generator is not of type\n        grid_anchor_generator.GridAnchorGenerator.\n    \"\"\"\n    super(RFCNMetaArch, self).__init__(\n        is_training,\n        num_classes,\n        image_resizer_fn,\n        feature_extractor,\n        first_stage_only,\n        first_stage_anchor_generator,\n        first_stage_atrous_rate,\n        first_stage_box_predictor_arg_scope,\n        first_stage_box_predictor_kernel_size,\n        first_stage_box_predictor_depth,\n        first_stage_minibatch_size,\n        first_stage_positive_balance_fraction,\n        first_stage_nms_score_threshold,\n        first_stage_nms_iou_threshold,\n        first_stage_max_proposals,\n        first_stage_localization_loss_weight,\n        first_stage_objectness_loss_weight,\n        None,  # initial_crop_size is not used in R-FCN\n        None,  # maxpool_kernel_size is not use in R-FCN\n        None,  # maxpool_stride is not use in R-FCN\n        None,  # fully_connected_box_predictor is not used in R-FCN.\n        second_stage_batch_size,\n        second_stage_balance_fraction,\n        second_stage_non_max_suppression_fn,\n        second_stage_score_conversion_fn,\n        second_stage_localization_loss_weight,\n        second_stage_classification_loss_weight,\n        hard_example_miner,\n        parallel_iterations)\n\n    self._rfcn_box_predictor = second_stage_rfcn_box_predictor\n\n  def _predict_second_stage(self, rpn_box_encodings,\n                            rpn_objectness_predictions_with_background,\n                            rpn_features,\n                            anchors,\n                            image_shape):\n    \"\"\"Predicts the output tensors from 2nd stage of FasterRCNN.\n\n    Args:\n      rpn_box_encodings: 4-D float tensor of shape\n        [batch_size, num_valid_anchors, self._box_coder.code_size] containing\n        predicted boxes.\n      rpn_objectness_predictions_with_background: 2-D float tensor of shape\n        [batch_size, num_valid_anchors, 2] containing class\n        predictions (logits) for each of the anchors.  Note that this\n        tensor *includes* background class predictions (at class index 0).\n      rpn_features: A 4-D float32 tensor with shape\n        [batch_size, height, width, depth] representing image features from the\n        RPN.\n      anchors: 2-D float tensor of shape\n        [num_anchors, self._box_coder.code_size].\n      image_shape: A 1D int32 tensors of size [4] containing the image shape.\n\n    Returns:\n      prediction_dict: a dictionary holding \"raw\" prediction tensors:\n        1) refined_box_encodings: a 3-D tensor with shape\n          [total_num_proposals, num_classes, 4] representing predicted\n          (final) refined box encodings, where\n          total_num_proposals=batch_size*self._max_num_proposals\n        2) class_predictions_with_background: a 3-D tensor with shape\n          [total_num_proposals, num_classes + 1] containing class\n          predictions (logits) for each of the anchors, where\n          total_num_proposals=batch_size*self._max_num_proposals.\n          Note that this tensor *includes* background class predictions\n          (at class index 0).\n        3) num_proposals: An int32 tensor of shape [batch_size] representing the\n          number of proposals generated by the RPN.  `num_proposals` allows us\n          to keep track of which entries are to be treated as zero paddings and\n          which are not since we always pad the number of proposals to be\n          `self.max_num_proposals` for each image.\n        4) proposal_boxes: A float32 tensor of shape\n          [batch_size, self.max_num_proposals, 4] representing\n          decoded proposal bounding boxes (in absolute coordinates).\n    \"\"\"\n    proposal_boxes_normalized, _, num_proposals = self._postprocess_rpn(\n        rpn_box_encodings, rpn_objectness_predictions_with_background,\n        anchors, image_shape)\n\n    box_classifier_features = (\n        self._feature_extractor.extract_box_classifier_features(\n            rpn_features,\n            scope=self.second_stage_feature_extractor_scope))\n\n    box_predictions = self._rfcn_box_predictor.predict(\n        box_classifier_features,\n        num_predictions_per_location=1,\n        scope=self.second_stage_box_predictor_scope,\n        proposal_boxes=proposal_boxes_normalized)\n    refined_box_encodings = tf.squeeze(\n        box_predictions[box_predictor.BOX_ENCODINGS], axis=1)\n    class_predictions_with_background = tf.squeeze(\n        box_predictions[box_predictor.CLASS_PREDICTIONS_WITH_BACKGROUND],\n        axis=1)\n\n    absolute_proposal_boxes = ops.normalized_to_image_coordinates(\n        proposal_boxes_normalized, image_shape,\n        parallel_iterations=self._parallel_iterations)\n\n    prediction_dict = {\n        'refined_box_encodings': refined_box_encodings,\n        'class_predictions_with_background':\n        class_predictions_with_background,\n        'num_proposals': num_proposals,\n        'proposal_boxes': absolute_proposal_boxes,\n    }\n    return prediction_dict\n"
  },
  {
    "path": "object_detector_app/object_detection/meta_architectures/rfcn_meta_arch_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.meta_architectures.rfcn_meta_arch.\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.meta_architectures import faster_rcnn_meta_arch_test_lib\nfrom object_detection.meta_architectures import rfcn_meta_arch\n\n\nclass RFCNMetaArchTest(\n    faster_rcnn_meta_arch_test_lib.FasterRCNNMetaArchTestBase):\n\n  def _get_second_stage_box_predictor_text_proto(self):\n    box_predictor_text_proto = \"\"\"\n      rfcn_box_predictor {\n        conv_hyperparams {\n          op: CONV\n          activation: NONE\n          regularizer {\n            l2_regularizer {\n              weight: 0.0005\n            }\n          }\n          initializer {\n            variance_scaling_initializer {\n              factor: 1.0\n              uniform: true\n              mode: FAN_AVG\n            }\n          }\n        }\n      }\n    \"\"\"\n    return box_predictor_text_proto\n\n  def _get_model(self, box_predictor, **common_kwargs):\n    return rfcn_meta_arch.RFCNMetaArch(\n        second_stage_rfcn_box_predictor=box_predictor, **common_kwargs)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/meta_architectures/ssd_meta_arch.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"SSD Meta-architecture definition.\n\nGeneral tensorflow implementation of convolutional Multibox/SSD detection\nmodels.\n\"\"\"\nfrom abc import abstractmethod\n\nimport re\nimport tensorflow as tf\n\nfrom object_detection.core import box_coder as bcoder\nfrom object_detection.core import box_list\nfrom object_detection.core import box_predictor as bpredictor\nfrom object_detection.core import model\nfrom object_detection.core import standard_fields as fields\nfrom object_detection.core import target_assigner\nfrom object_detection.utils import variables_helper\n\nslim = tf.contrib.slim\n\n\nclass SSDFeatureExtractor(object):\n  \"\"\"SSD Feature Extractor definition.\"\"\"\n\n  def __init__(self,\n               depth_multiplier,\n               min_depth,\n               conv_hyperparams,\n               reuse_weights=None):\n    self._depth_multiplier = depth_multiplier\n    self._min_depth = min_depth\n    self._conv_hyperparams = conv_hyperparams\n    self._reuse_weights = reuse_weights\n\n  @abstractmethod\n  def preprocess(self, resized_inputs):\n    \"\"\"Preprocesses images for feature extraction (minus image resizing).\n\n    Args:\n      resized_inputs: a [batch, height, width, channels] float tensor\n        representing a batch of images.\n\n    Returns:\n      preprocessed_inputs: a [batch, height, width, channels] float tensor\n        representing a batch of images.\n    \"\"\"\n    pass\n\n  @abstractmethod\n  def extract_features(self, preprocessed_inputs):\n    \"\"\"Extracts features from preprocessed inputs.\n\n    This function is responsible for extracting feature maps from preprocessed\n    images.\n\n    Args:\n      preprocessed_inputs: a [batch, height, width, channels] float tensor\n        representing a batch of images.\n\n    Returns:\n      feature_maps: a list of tensors where the ith tensor has shape\n        [batch, height_i, width_i, depth_i]\n    \"\"\"\n    pass\n\n\nclass SSDMetaArch(model.DetectionModel):\n  \"\"\"SSD Meta-architecture definition.\"\"\"\n\n  def __init__(self,\n               is_training,\n               anchor_generator,\n               box_predictor,\n               box_coder,\n               feature_extractor,\n               matcher,\n               region_similarity_calculator,\n               image_resizer_fn,\n               non_max_suppression_fn,\n               score_conversion_fn,\n               classification_loss,\n               localization_loss,\n               classification_loss_weight,\n               localization_loss_weight,\n               normalize_loss_by_num_matches,\n               hard_example_miner,\n               add_summaries=True):\n    \"\"\"SSDMetaArch Constructor.\n\n    TODO: group NMS parameters + score converter into\n    a class and loss parameters into a class and write config protos for\n    postprocessing and losses.\n\n    Args:\n      is_training: A boolean indicating whether the training version of the\n        computation graph should be constructed.\n      anchor_generator: an anchor_generator.AnchorGenerator object.\n      box_predictor: a box_predictor.BoxPredictor object.\n      box_coder: a box_coder.BoxCoder object.\n      feature_extractor: a SSDFeatureExtractor object.\n      matcher: a matcher.Matcher object.\n      region_similarity_calculator: a\n        region_similarity_calculator.RegionSimilarityCalculator object.\n      image_resizer_fn: a callable for image resizing.  This callable always\n        takes a rank-3 image tensor (corresponding to a single image) and\n        returns a rank-3 image tensor, possibly with new spatial dimensions.\n        See builders/image_resizer_builder.py.\n      non_max_suppression_fn: batch_multiclass_non_max_suppression\n        callable that takes `boxes`, `scores` and optional `clip_window`\n        inputs (with all other inputs already set) and returns a dictionary\n        hold tensors with keys: `detection_boxes`, `detection_scores`,\n        `detection_classes` and `num_detections`. See `post_processing.\n        batch_multiclass_non_max_suppression` for the type and shape of these\n        tensors.\n      score_conversion_fn: callable elementwise nonlinearity (that takes tensors\n        as inputs and returns tensors).  This is usually used to convert logits\n        to probabilities.\n      classification_loss: an object_detection.core.losses.Loss object.\n      localization_loss: a object_detection.core.losses.Loss object.\n      classification_loss_weight: float\n      localization_loss_weight: float\n      normalize_loss_by_num_matches: boolean\n      hard_example_miner: a losses.HardExampleMiner object (can be None)\n      add_summaries: boolean (default: True) controlling whether summary ops\n        should be added to tensorflow graph.\n    \"\"\"\n    super(SSDMetaArch, self).__init__(num_classes=box_predictor.num_classes)\n    self._is_training = is_training\n\n    # Needed for fine-tuning from classification checkpoints whose\n    # variables do not have the feature extractor scope.\n    self._extract_features_scope = 'FeatureExtractor'\n\n    self._anchor_generator = anchor_generator\n    self._box_predictor = box_predictor\n\n    self._box_coder = box_coder\n    self._feature_extractor = feature_extractor\n    self._matcher = matcher\n    self._region_similarity_calculator = region_similarity_calculator\n\n    # TODO: handle agnostic mode and positive/negative class weights\n    unmatched_cls_target = None\n    unmatched_cls_target = tf.constant([1] + self.num_classes * [0], tf.float32)\n    self._target_assigner = target_assigner.TargetAssigner(\n        self._region_similarity_calculator,\n        self._matcher,\n        self._box_coder,\n        positive_class_weight=1.0,\n        negative_class_weight=1.0,\n        unmatched_cls_target=unmatched_cls_target)\n\n    self._classification_loss = classification_loss\n    self._localization_loss = localization_loss\n    self._classification_loss_weight = classification_loss_weight\n    self._localization_loss_weight = localization_loss_weight\n    self._normalize_loss_by_num_matches = normalize_loss_by_num_matches\n    self._hard_example_miner = hard_example_miner\n\n    self._image_resizer_fn = image_resizer_fn\n    self._non_max_suppression_fn = non_max_suppression_fn\n    self._score_conversion_fn = score_conversion_fn\n\n    self._anchors = None\n    self._add_summaries = add_summaries\n\n  @property\n  def anchors(self):\n    if not self._anchors:\n      raise RuntimeError('anchors have not been constructed yet!')\n    if not isinstance(self._anchors, box_list.BoxList):\n      raise RuntimeError('anchors should be a BoxList object, but is not.')\n    return self._anchors\n\n  def preprocess(self, inputs):\n    \"\"\"Feature-extractor specific preprocessing.\n\n    See base class.\n\n    Args:\n      inputs: a [batch, height_in, width_in, channels] float tensor representing\n        a batch of images with values between 0 and 255.0.\n\n    Returns:\n      preprocessed_inputs: a [batch, height_out, width_out, channels] float\n        tensor representing a batch of images.\n    Raises:\n      ValueError: if inputs tensor does not have type tf.float32\n    \"\"\"\n    if inputs.dtype is not tf.float32:\n      raise ValueError('`preprocess` expects a tf.float32 tensor')\n    with tf.name_scope('Preprocessor'):\n      # TODO: revisit whether to always use batch size as  the number of\n      # parallel iterations vs allow for dynamic batching.\n      resized_inputs = tf.map_fn(self._image_resizer_fn,\n                                 elems=inputs,\n                                 dtype=tf.float32)\n      return self._feature_extractor.preprocess(resized_inputs)\n\n  def predict(self, preprocessed_inputs):\n    \"\"\"Predicts unpostprocessed tensors from input tensor.\n\n    This function takes an input batch of images and runs it through the forward\n    pass of the network to yield unpostprocessesed predictions.\n\n    A side effect of calling the predict method is that self._anchors is\n    populated with a box_list.BoxList of anchors.  These anchors must be\n    constructed before the postprocess or loss functions can be called.\n\n    Args:\n      preprocessed_inputs: a [batch, height, width, channels] image tensor.\n\n    Returns:\n      prediction_dict: a dictionary holding \"raw\" prediction tensors:\n        1) box_encodings: 4-D float tensor of shape [batch_size, num_anchors,\n          box_code_dimension] containing predicted boxes.\n        2) class_predictions_with_background: 3-D float tensor of shape\n          [batch_size, num_anchors, num_classes+1] containing class predictions\n          (logits) for each of the anchors.  Note that this tensor *includes*\n          background class predictions (at class index 0).\n        3) feature_maps: a list of tensors where the ith tensor has shape\n          [batch, height_i, width_i, depth_i].\n    \"\"\"\n    with tf.variable_scope(None, self._extract_features_scope,\n                           [preprocessed_inputs]):\n      feature_maps = self._feature_extractor.extract_features(\n          preprocessed_inputs)\n    feature_map_spatial_dims = self._get_feature_map_spatial_dims(feature_maps)\n    self._anchors = self._anchor_generator.generate(feature_map_spatial_dims)\n    (box_encodings, class_predictions_with_background\n    ) = self._add_box_predictions_to_feature_maps(feature_maps)\n    predictions_dict = {\n        'box_encodings': box_encodings,\n        'class_predictions_with_background': class_predictions_with_background,\n        'feature_maps': feature_maps\n    }\n    return predictions_dict\n\n  def _add_box_predictions_to_feature_maps(self, feature_maps):\n    \"\"\"Adds box predictors to each feature map and returns concatenated results.\n\n    Args:\n      feature_maps: a list of tensors where the ith tensor has shape\n        [batch, height_i, width_i, depth_i]\n\n    Returns:\n      box_encodings: 4-D float tensor of shape [batch_size, num_anchors,\n          box_code_dimension] containing predicted boxes.\n      class_predictions_with_background: 2-D float tensor of shape\n          [batch_size, num_anchors, num_classes+1] containing class predictions\n          (logits) for each of the anchors.  Note that this tensor *includes*\n          background class predictions (at class index 0).\n\n    Raises:\n      RuntimeError: if the number of feature maps extracted via the\n        extract_features method does not match the length of the\n        num_anchors_per_locations list that was passed to the constructor.\n      RuntimeError: if box_encodings from the box_predictor does not have\n        shape of the form  [batch_size, num_anchors, 1, code_size].\n    \"\"\"\n    num_anchors_per_location_list = (\n        self._anchor_generator.num_anchors_per_location())\n    if len(feature_maps) != len(num_anchors_per_location_list):\n      raise RuntimeError('the number of feature maps must match the '\n                         'length of self.anchors.NumAnchorsPerLocation().')\n    box_encodings_list = []\n    cls_predictions_with_background_list = []\n    for idx, (feature_map, num_anchors_per_location\n             ) in enumerate(zip(feature_maps, num_anchors_per_location_list)):\n      box_predictor_scope = 'BoxPredictor_{}'.format(idx)\n      box_predictions = self._box_predictor.predict(feature_map,\n                                                    num_anchors_per_location,\n                                                    box_predictor_scope)\n      box_encodings = box_predictions[bpredictor.BOX_ENCODINGS]\n      cls_predictions_with_background = box_predictions[\n          bpredictor.CLASS_PREDICTIONS_WITH_BACKGROUND]\n\n      box_encodings_shape = box_encodings.get_shape().as_list()\n      if len(box_encodings_shape) != 4 or box_encodings_shape[2] != 1:\n        raise RuntimeError('box_encodings from the box_predictor must be of '\n                           'shape `[batch_size, num_anchors, 1, code_size]`; '\n                           'actual shape', box_encodings_shape)\n      box_encodings = tf.squeeze(box_encodings, axis=2)\n      box_encodings_list.append(box_encodings)\n      cls_predictions_with_background_list.append(\n          cls_predictions_with_background)\n\n    num_predictions = sum(\n        [tf.shape(box_encodings)[1] for box_encodings in box_encodings_list])\n    num_anchors = self.anchors.num_boxes()\n    anchors_assert = tf.assert_equal(num_anchors, num_predictions, [\n        'Mismatch: number of anchors vs number of predictions', num_anchors,\n        num_predictions\n    ])\n    with tf.control_dependencies([anchors_assert]):\n      box_encodings = tf.concat(box_encodings_list, 1)\n      class_predictions_with_background = tf.concat(\n          cls_predictions_with_background_list, 1)\n    return box_encodings, class_predictions_with_background\n\n  def _get_feature_map_spatial_dims(self, feature_maps):\n    \"\"\"Return list of spatial dimensions for each feature map in a list.\n\n    Args:\n      feature_maps: a list of tensors where the ith tensor has shape\n          [batch, height_i, width_i, depth_i].\n\n    Returns:\n      a list of pairs (height, width) for each feature map in feature_maps\n    \"\"\"\n    feature_map_shapes = [\n        feature_map.get_shape().as_list() for feature_map in feature_maps\n    ]\n    return [(shape[1], shape[2]) for shape in feature_map_shapes]\n\n  def postprocess(self, prediction_dict):\n    \"\"\"Converts prediction tensors to final detections.\n\n    This function converts raw predictions tensors to final detection results by\n    slicing off the background class, decoding box predictions and applying\n    non max suppression and clipping to the image window.\n\n    See base class for output format conventions.  Note also that by default,\n    scores are to be interpreted as logits, but if a score_conversion_fn is\n    used, then scores are remapped (and may thus have a different\n    interpretation).\n\n    Args:\n      prediction_dict: a dictionary holding prediction tensors with\n        1) box_encodings: 4-D float tensor of shape [batch_size, num_anchors,\n          box_code_dimension] containing predicted boxes.\n        2) class_predictions_with_background: 2-D float tensor of shape\n          [batch_size, num_anchors, num_classes+1] containing class predictions\n          (logits) for each of the anchors.  Note that this tensor *includes*\n          background class predictions.\n\n    Returns:\n      detections: a dictionary containing the following fields\n        detection_boxes: [batch, max_detection, 4]\n        detection_scores: [batch, max_detections]\n        detection_classes: [batch, max_detections]\n        num_detections: [batch]\n    Raises:\n      ValueError: if prediction_dict does not contain `box_encodings` or\n        `class_predictions_with_background` fields.\n    \"\"\"\n    if ('box_encodings' not in prediction_dict or\n        'class_predictions_with_background' not in prediction_dict):\n      raise ValueError('prediction_dict does not contain expected entries.')\n    with tf.name_scope('Postprocessor'):\n      box_encodings = prediction_dict['box_encodings']\n      class_predictions = prediction_dict['class_predictions_with_background']\n      detection_boxes = bcoder.batch_decode(box_encodings, self._box_coder,\n                                            self.anchors)\n      detection_boxes = tf.expand_dims(detection_boxes, axis=2)\n\n      class_predictions_without_background = tf.slice(class_predictions,\n                                                      [0, 0, 1],\n                                                      [-1, -1, -1])\n      detection_scores = self._score_conversion_fn(\n          class_predictions_without_background)\n      clip_window = tf.constant([0, 0, 1, 1], tf.float32)\n      detections = self._non_max_suppression_fn(detection_boxes,\n                                                detection_scores,\n                                                clip_window=clip_window)\n    return detections\n\n  def loss(self, prediction_dict, scope=None):\n    \"\"\"Compute scalar loss tensors with respect to provided groundtruth.\n\n    Calling this function requires that groundtruth tensors have been\n    provided via the provide_groundtruth function.\n\n    Args:\n      prediction_dict: a dictionary holding prediction tensors with\n        1) box_encodings: 4-D float tensor of shape [batch_size, num_anchors,\n          box_code_dimension] containing predicted boxes.\n        2) class_predictions_with_background: 2-D float tensor of shape\n          [batch_size, num_anchors, num_classes+1] containing class predictions\n          (logits) for each of the anchors.  Note that this tensor *includes*\n          background class predictions.\n      scope: Optional scope name.\n\n    Returns:\n      a dictionary mapping loss keys (`localization_loss` and\n        `classification_loss`) to scalar tensors representing corresponding loss\n        values.\n    \"\"\"\n    with tf.name_scope(scope, 'Loss', prediction_dict.values()):\n      (batch_cls_targets, batch_cls_weights, batch_reg_targets,\n       batch_reg_weights, match_list) = self._assign_targets(\n           self.groundtruth_lists(fields.BoxListFields.boxes),\n           self.groundtruth_lists(fields.BoxListFields.classes))\n      if self._add_summaries:\n        self._summarize_input(\n            self.groundtruth_lists(fields.BoxListFields.boxes), match_list)\n      num_matches = tf.stack(\n          [match.num_matched_columns() for match in match_list])\n      location_losses = self._localization_loss(\n          prediction_dict['box_encodings'],\n          batch_reg_targets,\n          weights=batch_reg_weights)\n      cls_losses = self._classification_loss(\n          prediction_dict['class_predictions_with_background'],\n          batch_cls_targets,\n          weights=batch_cls_weights)\n\n      # Optionally apply hard mining on top of loss values\n      localization_loss = tf.reduce_sum(location_losses)\n      classification_loss = tf.reduce_sum(cls_losses)\n      if self._hard_example_miner:\n        (localization_loss, classification_loss) = self._apply_hard_mining(\n            location_losses, cls_losses, prediction_dict, match_list)\n        if self._add_summaries:\n          self._hard_example_miner.summarize()\n\n      # Optionally normalize by number of positive matches\n      normalizer = tf.constant(1.0, dtype=tf.float32)\n      if self._normalize_loss_by_num_matches:\n        normalizer = tf.maximum(tf.to_float(tf.reduce_sum(num_matches)), 1.0)\n\n      loss_dict = {\n          'localization_loss': (self._localization_loss_weight / normalizer) *\n                               localization_loss,\n          'classification_loss': (self._classification_loss_weight /\n                                  normalizer) * classification_loss\n      }\n    return loss_dict\n\n  def _assign_targets(self, groundtruth_boxes_list, groundtruth_classes_list):\n    \"\"\"Assign groundtruth targets.\n\n    Adds a background class to each one-hot encoding of groundtruth classes\n    and uses target assigner to obtain regression and classification targets.\n\n    Args:\n      groundtruth_boxes_list: a list of 2-D tensors of shape [num_boxes, 4]\n        containing coordinates of the groundtruth boxes.\n          Groundtruth boxes are provided in [y_min, x_min, y_max, x_max]\n          format and assumed to be normalized and clipped\n          relative to the image window with y_min <= y_max and x_min <= x_max.\n      groundtruth_classes_list: a list of 2-D one-hot (or k-hot) tensors of\n        shape [num_boxes, num_classes] containing the class targets with the 0th\n        index assumed to map to the first non-background class.\n\n    Returns:\n      batch_cls_targets: a tensor with shape [batch_size, num_anchors,\n        num_classes],\n      batch_cls_weights: a tensor with shape [batch_size, num_anchors],\n      batch_reg_targets: a tensor with shape [batch_size, num_anchors,\n        box_code_dimension]\n      batch_reg_weights: a tensor with shape [batch_size, num_anchors],\n      match_list: a list of matcher.Match objects encoding the match between\n        anchors and groundtruth boxes for each image of the batch,\n        with rows of the Match objects corresponding to groundtruth boxes\n        and columns corresponding to anchors.\n    \"\"\"\n    groundtruth_boxlists = [\n        box_list.BoxList(boxes) for boxes in groundtruth_boxes_list\n    ]\n    groundtruth_classes_with_background_list = [\n        tf.pad(one_hot_encoding, [[0, 0], [1, 0]], mode='CONSTANT')\n        for one_hot_encoding in groundtruth_classes_list\n    ]\n    return target_assigner.batch_assign_targets(\n        self._target_assigner, self.anchors, groundtruth_boxlists,\n        groundtruth_classes_with_background_list)\n\n  def _summarize_input(self, groundtruth_boxes_list, match_list):\n    \"\"\"Creates tensorflow summaries for the input boxes and anchors.\n\n    This function creates four summaries corresponding to the average\n    number (over images in a batch) of (1) groundtruth boxes, (2) anchors\n    marked as positive, (3) anchors marked as negative, and (4) anchors marked\n    as ignored.\n\n    Args:\n      groundtruth_boxes_list: a list of 2-D tensors of shape [num_boxes, 4]\n        containing corners of the groundtruth boxes.\n      match_list: a list of matcher.Match objects encoding the match between\n        anchors and groundtruth boxes for each image of the batch,\n        with rows of the Match objects corresponding to groundtruth boxes\n        and columns corresponding to anchors.\n    \"\"\"\n    num_boxes_per_image = tf.stack(\n        [tf.shape(x)[0] for x in groundtruth_boxes_list])\n    pos_anchors_per_image = tf.stack(\n        [match.num_matched_columns() for match in match_list])\n    neg_anchors_per_image = tf.stack(\n        [match.num_unmatched_columns() for match in match_list])\n    ignored_anchors_per_image = tf.stack(\n        [match.num_ignored_columns() for match in match_list])\n    tf.summary.scalar('Input/AvgNumGroundtruthBoxesPerImage',\n                      tf.reduce_mean(tf.to_float(num_boxes_per_image)))\n    tf.summary.scalar('Input/AvgNumPositiveAnchorsPerImage',\n                      tf.reduce_mean(tf.to_float(pos_anchors_per_image)))\n    tf.summary.scalar('Input/AvgNumNegativeAnchorsPerImage',\n                      tf.reduce_mean(tf.to_float(neg_anchors_per_image)))\n    tf.summary.scalar('Input/AvgNumIgnoredAnchorsPerImage',\n                      tf.reduce_mean(tf.to_float(ignored_anchors_per_image)))\n\n  def _apply_hard_mining(self, location_losses, cls_losses, prediction_dict,\n                         match_list):\n    \"\"\"Applies hard mining to anchorwise losses.\n\n    Args:\n      location_losses: Float tensor of shape [batch_size, num_anchors]\n        representing anchorwise location losses.\n      cls_losses: Float tensor of shape [batch_size, num_anchors]\n        representing anchorwise classification losses.\n      prediction_dict: p a dictionary holding prediction tensors with\n        1) box_encodings: 4-D float tensor of shape [batch_size, num_anchors,\n          box_code_dimension] containing predicted boxes.\n        2) class_predictions_with_background: 2-D float tensor of shape\n          [batch_size, num_anchors, num_classes+1] containing class predictions\n          (logits) for each of the anchors.  Note that this tensor *includes*\n          background class predictions.\n      match_list: a list of matcher.Match objects encoding the match between\n        anchors and groundtruth boxes for each image of the batch,\n        with rows of the Match objects corresponding to groundtruth boxes\n        and columns corresponding to anchors.\n\n    Returns:\n      mined_location_loss: a float scalar with sum of localization losses from\n        selected hard examples.\n      mined_cls_loss: a float scalar with sum of classification losses from\n        selected hard examples.\n    \"\"\"\n    class_pred_shape = [-1, self.anchors.num_boxes_static(), self.num_classes]\n    class_predictions = tf.reshape(\n        tf.slice(prediction_dict['class_predictions_with_background'],\n                 [0, 0, 1], class_pred_shape), class_pred_shape)\n\n    decoded_boxes = bcoder.batch_decode(prediction_dict['box_encodings'],\n                                        self._box_coder, self.anchors)\n    decoded_box_tensors_list = tf.unstack(decoded_boxes)\n    class_prediction_list = tf.unstack(class_predictions)\n    decoded_boxlist_list = []\n    for box_location, box_score in zip(decoded_box_tensors_list,\n                                       class_prediction_list):\n      decoded_boxlist = box_list.BoxList(box_location)\n      decoded_boxlist.add_field('scores', box_score)\n      decoded_boxlist_list.append(decoded_boxlist)\n    return self._hard_example_miner(\n        location_losses=location_losses,\n        cls_losses=cls_losses,\n        decoded_boxlist_list=decoded_boxlist_list,\n        match_list=match_list)\n\n  def restore_fn(self, checkpoint_path, from_detection_checkpoint=True):\n    \"\"\"Return callable for loading a checkpoint into the tensorflow graph.\n\n    Args:\n      checkpoint_path: path to checkpoint to restore.\n      from_detection_checkpoint: whether to restore from a full detection\n        checkpoint (with compatible variable names) or to restore from a\n        classification checkpoint for initialization prior to training.\n\n    Returns:\n      a callable which takes a tf.Session as input and loads a checkpoint when\n        run.\n    \"\"\"\n    variables_to_restore = {}\n    for variable in tf.all_variables():\n      if variable.op.name.startswith(self._extract_features_scope):\n        var_name = variable.op.name\n        if not from_detection_checkpoint:\n          var_name = (\n              re.split('^' + self._extract_features_scope + '/', var_name)[-1])\n        variables_to_restore[var_name] = variable\n    # TODO: Load variables selectively using scopes.\n    variables_to_restore = (\n        variables_helper.get_variables_available_in_checkpoint(\n            variables_to_restore, checkpoint_path))\n    saver = tf.train.Saver(variables_to_restore)\n\n    def restore(sess):\n      saver.restore(sess, checkpoint_path)\n    return restore\n"
  },
  {
    "path": "object_detector_app/object_detection/meta_architectures/ssd_meta_arch_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.meta_architectures.ssd_meta_arch.\"\"\"\nimport functools\nimport numpy as np\nimport tensorflow as tf\n\nfrom tensorflow.python.training import saver as tf_saver\nfrom object_detection.core import anchor_generator\nfrom object_detection.core import box_list\nfrom object_detection.core import losses\nfrom object_detection.core import post_processing\nfrom object_detection.core import region_similarity_calculator as sim_calc\nfrom object_detection.meta_architectures import ssd_meta_arch\nfrom object_detection.utils import test_utils\n\nslim = tf.contrib.slim\n\n\nclass FakeSSDFeatureExtractor(ssd_meta_arch.SSDFeatureExtractor):\n\n  def __init__(self):\n    super(FakeSSDFeatureExtractor, self).__init__(\n        depth_multiplier=0, min_depth=0, conv_hyperparams=None)\n\n  def preprocess(self, resized_inputs):\n    return tf.identity(resized_inputs)\n\n  def extract_features(self, preprocessed_inputs):\n    with tf.variable_scope('mock_model'):\n      features = slim.conv2d(inputs=preprocessed_inputs, num_outputs=32,\n                             kernel_size=[1, 1], scope='layer1')\n      return [features]\n\n\nclass MockAnchorGenerator2x2(anchor_generator.AnchorGenerator):\n  \"\"\"Sets up a simple 2x2 anchor grid on the unit square.\"\"\"\n\n  def name_scope(self):\n    return 'MockAnchorGenerator'\n\n  def num_anchors_per_location(self):\n    return [1]\n\n  def _generate(self, feature_map_shape_list):\n    return box_list.BoxList(\n        tf.constant([[0, 0, .5, .5],\n                     [0, .5, .5, 1],\n                     [.5, 0, 1, .5],\n                     [.5, .5, 1, 1]], tf.float32))\n\n\nclass SsdMetaArchTest(tf.test.TestCase):\n\n  def setUp(self):\n    \"\"\"Set up mock SSD model.\n\n    Here we set up a simple mock SSD model that will always predict 4\n    detections that happen to always be exactly the anchors that are set up\n    in the above MockAnchorGenerator.  Because we let max_detections=5,\n    we will also always end up with an extra padded row in the detection\n    results.\n    \"\"\"\n    is_training = False\n    self._num_classes = 1\n    mock_anchor_generator = MockAnchorGenerator2x2()\n    mock_box_predictor = test_utils.MockBoxPredictor(\n        is_training, self._num_classes)\n    mock_box_coder = test_utils.MockBoxCoder()\n    fake_feature_extractor = FakeSSDFeatureExtractor()\n    mock_matcher = test_utils.MockMatcher()\n    region_similarity_calculator = sim_calc.IouSimilarity()\n\n    def image_resizer_fn(image):\n      return tf.identity(image)\n\n    classification_loss = losses.WeightedSigmoidClassificationLoss(\n        anchorwise_output=True)\n    localization_loss = losses.WeightedSmoothL1LocalizationLoss(\n        anchorwise_output=True)\n    non_max_suppression_fn = functools.partial(\n        post_processing.batch_multiclass_non_max_suppression,\n        score_thresh=-20.0,\n        iou_thresh=1.0,\n        max_size_per_class=5,\n        max_total_size=5)\n    classification_loss_weight = 1.0\n    localization_loss_weight = 1.0\n    normalize_loss_by_num_matches = False\n\n    # This hard example miner is expected to be a no-op.\n    hard_example_miner = losses.HardExampleMiner(\n        num_hard_examples=None,\n        iou_threshold=1.0)\n\n    self._num_anchors = 4\n    self._code_size = 4\n    self._model = ssd_meta_arch.SSDMetaArch(\n        is_training, mock_anchor_generator, mock_box_predictor, mock_box_coder,\n        fake_feature_extractor, mock_matcher, region_similarity_calculator,\n        image_resizer_fn, non_max_suppression_fn, tf.identity,\n        classification_loss, localization_loss, classification_loss_weight,\n        localization_loss_weight, normalize_loss_by_num_matches,\n        hard_example_miner)\n\n  def test_predict_results_have_correct_keys_and_shapes(self):\n    batch_size = 3\n    preprocessed_input = tf.random_uniform((batch_size, 2, 2, 3),\n                                           dtype=tf.float32)\n    prediction_dict = self._model.predict(preprocessed_input)\n\n    self.assertTrue('box_encodings' in prediction_dict)\n    self.assertTrue('class_predictions_with_background' in prediction_dict)\n    self.assertTrue('feature_maps' in prediction_dict)\n\n    expected_box_encodings_shape_out = (\n        batch_size, self._num_anchors, self._code_size)\n    expected_class_predictions_with_background_shape_out = (\n        batch_size, self._num_anchors, self._num_classes+1)\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      prediction_out = sess.run(prediction_dict)\n      self.assertAllEqual(prediction_out['box_encodings'].shape,\n                          expected_box_encodings_shape_out)\n      self.assertAllEqual(\n          prediction_out['class_predictions_with_background'].shape,\n          expected_class_predictions_with_background_shape_out)\n\n  def test_postprocess_results_are_correct(self):\n    batch_size = 2\n    preprocessed_input = tf.random_uniform((batch_size, 2, 2, 3),\n                                           dtype=tf.float32)\n    prediction_dict = self._model.predict(preprocessed_input)\n    detections = self._model.postprocess(prediction_dict)\n\n    expected_boxes = np.array([[[0, 0, .5, .5],\n                                [0, .5, .5, 1],\n                                [.5, 0, 1, .5],\n                                [.5, .5, 1, 1],\n                                [0, 0, 0, 0]],\n                               [[0, 0, .5, .5],\n                                [0, .5, .5, 1],\n                                [.5, 0, 1, .5],\n                                [.5, .5, 1, 1],\n                                [0, 0, 0, 0]]])\n    expected_scores = np.array([[0, 0, 0, 0, 0],\n                                [0, 0, 0, 0, 0]])\n    expected_classes = np.array([[0, 0, 0, 0, 0],\n                                 [0, 0, 0, 0, 0]])\n    expected_num_detections = np.array([4, 4])\n\n    self.assertTrue('detection_boxes' in detections)\n    self.assertTrue('detection_scores' in detections)\n    self.assertTrue('detection_classes' in detections)\n    self.assertTrue('num_detections' in detections)\n\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      detections_out = sess.run(detections)\n      self.assertAllClose(detections_out['detection_boxes'], expected_boxes)\n      self.assertAllClose(detections_out['detection_scores'], expected_scores)\n      self.assertAllClose(detections_out['detection_classes'], expected_classes)\n      self.assertAllClose(detections_out['num_detections'],\n                          expected_num_detections)\n\n  def test_loss_results_are_correct(self):\n    batch_size = 2\n    preprocessed_input = tf.random_uniform((batch_size, 2, 2, 3),\n                                           dtype=tf.float32)\n    groundtruth_boxes_list = [tf.constant([[0, 0, .5, .5]], dtype=tf.float32),\n                              tf.constant([[0, 0, .5, .5]], dtype=tf.float32)]\n    groundtruth_classes_list = [tf.constant([[1]], dtype=tf.float32),\n                                tf.constant([[1]], dtype=tf.float32)]\n    self._model.provide_groundtruth(groundtruth_boxes_list,\n                                    groundtruth_classes_list)\n    prediction_dict = self._model.predict(preprocessed_input)\n    loss_dict = self._model.loss(prediction_dict)\n\n    self.assertTrue('localization_loss' in loss_dict)\n    self.assertTrue('classification_loss' in loss_dict)\n\n    expected_localization_loss = 0.0\n    expected_classification_loss = (batch_size * self._num_anchors\n                                    * (self._num_classes+1) * np.log(2.0))\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      losses_out = sess.run(loss_dict)\n\n      self.assertAllClose(losses_out['localization_loss'],\n                          expected_localization_loss)\n      self.assertAllClose(losses_out['classification_loss'],\n                          expected_classification_loss)\n\n  def test_restore_fn_detection(self):\n    init_op = tf.global_variables_initializer()\n    saver = tf_saver.Saver()\n    save_path = self.get_temp_dir()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      saved_model_path = saver.save(sess, save_path)\n      restore_fn = self._model.restore_fn(saved_model_path,\n                                          from_detection_checkpoint=True)\n      restore_fn(sess)\n      for var in sess.run(tf.report_uninitialized_variables()):\n        self.assertNotIn('FeatureExtractor', var.name)\n\n  def test_restore_fn_classification(self):\n    # Define mock tensorflow classification graph and save variables.\n    test_graph_classification = tf.Graph()\n    with test_graph_classification.as_default():\n      image = tf.placeholder(dtype=tf.float32, shape=[1, 20, 20, 3])\n      with tf.variable_scope('mock_model'):\n        net = slim.conv2d(image, num_outputs=32, kernel_size=1, scope='layer1')\n        slim.conv2d(net, num_outputs=3, kernel_size=1, scope='layer2')\n\n      init_op = tf.global_variables_initializer()\n      saver = tf.train.Saver()\n      save_path = self.get_temp_dir()\n      with self.test_session() as sess:\n        sess.run(init_op)\n        saved_model_path = saver.save(sess, save_path)\n\n    # Create tensorflow detection graph and load variables from\n    # classification checkpoint.\n    test_graph_detection = tf.Graph()\n    with test_graph_detection.as_default():\n      inputs_shape = [2, 2, 2, 3]\n      inputs = tf.to_float(tf.random_uniform(\n          inputs_shape, minval=0, maxval=255, dtype=tf.int32))\n      preprocessed_inputs = self._model.preprocess(inputs)\n      prediction_dict = self._model.predict(preprocessed_inputs)\n      self._model.postprocess(prediction_dict)\n      restore_fn = self._model.restore_fn(saved_model_path,\n                                          from_detection_checkpoint=False)\n      with self.test_session() as sess:\n        restore_fn(sess)\n        for var in sess.run(tf.report_uninitialized_variables()):\n          self.assertNotIn('FeatureExtractor', var.name)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/models/BUILD",
    "content": "# Tensorflow Object Detection API: Models.\n\npackage(\n    default_visibility = [\"//visibility:public\"],\n)\n\nlicenses([\"notice\"])\n\n# Apache 2.0\n\npy_library(\n    name = \"feature_map_generators\",\n    srcs = [\n        \"feature_map_generators.py\",\n    ],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/utils:ops\",\n    ],\n)\n\npy_test(\n    name = \"feature_map_generators_test\",\n    srcs = [\n        \"feature_map_generators_test.py\",\n    ],\n    deps = [\n        \":feature_map_generators\",\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"ssd_feature_extractor_test\",\n    srcs = [\n        \"ssd_feature_extractor_test.py\",\n    ],\n    deps = [\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"ssd_inception_v2_feature_extractor\",\n    srcs = [\n        \"ssd_inception_v2_feature_extractor.py\",\n    ],\n    deps = [\n        \":feature_map_generators\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/meta_architectures:ssd_meta_arch\",\n        \"//tensorflow_models/slim:inception_v2\",\n    ],\n)\n\npy_library(\n    name = \"ssd_mobilenet_v1_feature_extractor\",\n    srcs = [\"ssd_mobilenet_v1_feature_extractor.py\"],\n    deps = [\n        \":feature_map_generators\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/meta_architectures:ssd_meta_arch\",\n        \"//tensorflow_models/slim:mobilenet_v1\",\n    ],\n)\n\npy_test(\n    name = \"ssd_inception_v2_feature_extractor_test\",\n    srcs = [\n        \"ssd_inception_v2_feature_extractor_test.py\",\n    ],\n    deps = [\n        \":ssd_feature_extractor_test\",\n        \":ssd_inception_v2_feature_extractor\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"ssd_mobilenet_v1_feature_extractor_test\",\n    srcs = [\"ssd_mobilenet_v1_feature_extractor_test.py\"],\n    deps = [\n        \":ssd_feature_extractor_test\",\n        \":ssd_mobilenet_v1_feature_extractor\",\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"faster_rcnn_inception_resnet_v2_feature_extractor\",\n    srcs = [\n        \"faster_rcnn_inception_resnet_v2_feature_extractor.py\",\n    ],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/meta_architectures:faster_rcnn_meta_arch\",\n        \"//tensorflow_models/object_detection/utils:variables_helper\",\n        \"//tensorflow_models/slim:inception_resnet_v2\",\n    ],\n)\n\npy_test(\n    name = \"faster_rcnn_inception_resnet_v2_feature_extractor_test\",\n    srcs = [\n        \"faster_rcnn_inception_resnet_v2_feature_extractor_test.py\",\n    ],\n    deps = [\n        \":faster_rcnn_inception_resnet_v2_feature_extractor\",\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"faster_rcnn_resnet_v1_feature_extractor\",\n    srcs = [\n        \"faster_rcnn_resnet_v1_feature_extractor.py\",\n    ],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/meta_architectures:faster_rcnn_meta_arch\",\n        \"//tensorflow_models/slim:resnet_utils\",\n        \"//tensorflow_models/slim:resnet_v1\",\n    ],\n)\n\npy_test(\n    name = \"faster_rcnn_resnet_v1_feature_extractor_test\",\n    srcs = [\n        \"faster_rcnn_resnet_v1_feature_extractor_test.py\",\n    ],\n    deps = [\n        \":faster_rcnn_resnet_v1_feature_extractor\",\n        \"//tensorflow\",\n    ],\n)\n"
  },
  {
    "path": "object_detector_app/object_detection/models/__init__.py",
    "content": ""
  },
  {
    "path": "object_detector_app/object_detection/models/faster_rcnn_inception_resnet_v2_feature_extractor.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Inception Resnet v2 Faster R-CNN implementation.\n\nSee \"Inception-v4, Inception-ResNet and the Impact of Residual Connections on\nLearning\" by Szegedy et al. (https://arxiv.org/abs/1602.07261)\nas well as\n\"Speed/accuracy trade-offs for modern convolutional object detectors\" by\nHuang et al. (https://arxiv.org/abs/1611.10012)\n\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.meta_architectures import faster_rcnn_meta_arch\nfrom object_detection.utils import variables_helper\nfrom nets import inception_resnet_v2\n\nslim = tf.contrib.slim\n\n\nclass FasterRCNNInceptionResnetV2FeatureExtractor(\n    faster_rcnn_meta_arch.FasterRCNNFeatureExtractor):\n  \"\"\"Faster R-CNN with Inception Resnet v2 feature extractor implementation.\"\"\"\n\n  def __init__(self,\n               is_training,\n               first_stage_features_stride,\n               reuse_weights=None,\n               weight_decay=0.0):\n    \"\"\"Constructor.\n\n    Args:\n      is_training: See base class.\n      first_stage_features_stride: See base class.\n      reuse_weights: See base class.\n      weight_decay: See base class.\n\n    Raises:\n      ValueError: If `first_stage_features_stride` is not 8 or 16.\n    \"\"\"\n    if first_stage_features_stride != 8 and first_stage_features_stride != 16:\n      raise ValueError('`first_stage_features_stride` must be 8 or 16.')\n    super(FasterRCNNInceptionResnetV2FeatureExtractor, self).__init__(\n        is_training, first_stage_features_stride, reuse_weights, weight_decay)\n\n  def preprocess(self, resized_inputs):\n    \"\"\"Faster R-CNN with Inception Resnet v2 preprocessing.\n\n    Maps pixel values to the range [-1, 1].\n\n    Args:\n      resized_inputs: A [batch, height_in, width_in, channels] float32 tensor\n        representing a batch of images with values between 0 and 255.0.\n\n    Returns:\n      preprocessed_inputs: A [batch, height_out, width_out, channels] float32\n        tensor representing a batch of images.\n\n    \"\"\"\n    return (2.0 / 255.0) * resized_inputs - 1.0\n\n  def _extract_proposal_features(self, preprocessed_inputs, scope):\n    \"\"\"Extracts first stage RPN features.\n\n    Extracts features using the first half of the Inception Resnet v2 network.\n    We construct the network in `align_feature_maps=True` mode, which means\n    that all VALID paddings in the network are changed to SAME padding so that\n    the feature maps are aligned.\n\n    Args:\n      preprocessed_inputs: A [batch, height, width, channels] float32 tensor\n        representing a batch of images.\n      scope: A scope name.\n\n    Returns:\n      rpn_feature_map: A tensor with shape [batch, height, width, depth]\n    Raises:\n      InvalidArgumentError: If the spatial size of `preprocessed_inputs`\n        (height or width) is less than 33.\n      ValueError: If the created network is missing the required activation.\n    \"\"\"\n    if len(preprocessed_inputs.get_shape().as_list()) != 4:\n      raise ValueError('`preprocessed_inputs` must be 4 dimensional, got a '\n                       'tensor of shape %s' % preprocessed_inputs.get_shape())\n\n    with slim.arg_scope(inception_resnet_v2.inception_resnet_v2_arg_scope(\n        weight_decay=self._weight_decay)):\n      # Forces is_training to False to disable batch norm update.\n      with slim.arg_scope([slim.batch_norm], is_training=False):\n        with tf.variable_scope('InceptionResnetV2',\n                               reuse=self._reuse_weights) as scope:\n          rpn_feature_map, _ = (\n              inception_resnet_v2.inception_resnet_v2_base(\n                  preprocessed_inputs, final_endpoint='PreAuxLogits',\n                  scope=scope, output_stride=self._first_stage_features_stride,\n                  align_feature_maps=True))\n    return rpn_feature_map\n\n  def _extract_box_classifier_features(self, proposal_feature_maps, scope):\n    \"\"\"Extracts second stage box classifier features.\n\n    This function reconstructs the \"second half\" of the Inception ResNet v2\n    network after the part defined in `_extract_proposal_features`.\n\n    Args:\n      proposal_feature_maps: A 4-D float tensor with shape\n        [batch_size * self.max_num_proposals, crop_height, crop_width, depth]\n        representing the feature map cropped to each proposal.\n      scope: A scope name.\n\n    Returns:\n      proposal_classifier_features: A 4-D float tensor with shape\n        [batch_size * self.max_num_proposals, height, width, depth]\n        representing box classifier features for each proposal.\n    \"\"\"\n    with tf.variable_scope('InceptionResnetV2', reuse=self._reuse_weights):\n      with slim.arg_scope(inception_resnet_v2.inception_resnet_v2_arg_scope(\n          weight_decay=self._weight_decay)):\n        # Forces is_training to False to disable batch norm update.\n        with slim.arg_scope([slim.batch_norm], is_training=False):\n          with slim.arg_scope([slim.conv2d, slim.max_pool2d, slim.avg_pool2d],\n                              stride=1, padding='SAME'):\n            with tf.variable_scope('Mixed_7a'):\n              with tf.variable_scope('Branch_0'):\n                tower_conv = slim.conv2d(proposal_feature_maps,\n                                         256, 1, scope='Conv2d_0a_1x1')\n                tower_conv_1 = slim.conv2d(\n                    tower_conv, 384, 3, stride=2,\n                    padding='VALID', scope='Conv2d_1a_3x3')\n              with tf.variable_scope('Branch_1'):\n                tower_conv1 = slim.conv2d(\n                    proposal_feature_maps, 256, 1, scope='Conv2d_0a_1x1')\n                tower_conv1_1 = slim.conv2d(\n                    tower_conv1, 288, 3, stride=2,\n                    padding='VALID', scope='Conv2d_1a_3x3')\n              with tf.variable_scope('Branch_2'):\n                tower_conv2 = slim.conv2d(\n                    proposal_feature_maps, 256, 1, scope='Conv2d_0a_1x1')\n                tower_conv2_1 = slim.conv2d(tower_conv2, 288, 3,\n                                            scope='Conv2d_0b_3x3')\n                tower_conv2_2 = slim.conv2d(\n                    tower_conv2_1, 320, 3, stride=2,\n                    padding='VALID', scope='Conv2d_1a_3x3')\n              with tf.variable_scope('Branch_3'):\n                tower_pool = slim.max_pool2d(\n                    proposal_feature_maps, 3, stride=2, padding='VALID',\n                    scope='MaxPool_1a_3x3')\n              net = tf.concat(\n                  [tower_conv_1, tower_conv1_1, tower_conv2_2, tower_pool], 3)\n            net = slim.repeat(net, 9, inception_resnet_v2.block8, scale=0.20)\n            net = inception_resnet_v2.block8(net, activation_fn=None)\n            proposal_classifier_features = slim.conv2d(\n                net, 1536, 1, scope='Conv2d_7b_1x1')\n        return proposal_classifier_features\n\n  def restore_from_classification_checkpoint_fn(\n      self,\n      checkpoint_path,\n      first_stage_feature_extractor_scope,\n      second_stage_feature_extractor_scope):\n    \"\"\"Returns callable for loading a checkpoint into the tensorflow graph.\n\n    Note that this overrides the default implementation in\n    faster_rcnn_meta_arch.FasterRCNNFeatureExtractor which does not work for\n    InceptionResnetV2 checkpoints.\n\n    TODO: revisit whether it's possible to force the `Repeat` namescope as\n    created in `_extract_box_classifier_features` to start counting at 2 (e.g.\n    `Repeat_2`) so that the default restore_fn can be used.\n\n    Args:\n      checkpoint_path: Path to checkpoint to restore.\n      first_stage_feature_extractor_scope: A scope name for the first stage\n        feature extractor.\n      second_stage_feature_extractor_scope: A scope name for the second stage\n        feature extractor.\n\n    Returns:\n      a callable which takes a tf.Session as input and loads a checkpoint when\n        run.\n    \"\"\"\n    variables_to_restore = {}\n    for variable in tf.global_variables():\n      if variable.op.name.startswith(\n          first_stage_feature_extractor_scope):\n        var_name = variable.op.name.replace(\n            first_stage_feature_extractor_scope + '/', '')\n        variables_to_restore[var_name] = variable\n      if variable.op.name.startswith(\n          second_stage_feature_extractor_scope):\n        var_name = variable.op.name.replace(\n            second_stage_feature_extractor_scope\n            + '/InceptionResnetV2/Repeat', 'InceptionResnetV2/Repeat_2')\n        var_name = var_name.replace(\n            second_stage_feature_extractor_scope + '/', '')\n        variables_to_restore[var_name] = variable\n    variables_to_restore = (\n        variables_helper.get_variables_available_in_checkpoint(\n            variables_to_restore, checkpoint_path))\n    saver = tf.train.Saver(variables_to_restore)\n    def restore(sess):\n      saver.restore(sess, checkpoint_path)\n    return restore\n"
  },
  {
    "path": "object_detector_app/object_detection/models/faster_rcnn_inception_resnet_v2_feature_extractor_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for models.faster_rcnn_inception_resnet_v2_feature_extractor.\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.models import faster_rcnn_inception_resnet_v2_feature_extractor as frcnn_inc_res\n\n\nclass FasterRcnnInceptionResnetV2FeatureExtractorTest(tf.test.TestCase):\n\n  def _build_feature_extractor(self, first_stage_features_stride):\n    return frcnn_inc_res.FasterRCNNInceptionResnetV2FeatureExtractor(\n        is_training=False,\n        first_stage_features_stride=first_stage_features_stride,\n        reuse_weights=None,\n        weight_decay=0.0)\n\n  def test_extract_proposal_features_returns_expected_size(self):\n    feature_extractor = self._build_feature_extractor(\n        first_stage_features_stride=16)\n    preprocessed_inputs = tf.random_uniform(\n        [1, 299, 299, 3], maxval=255, dtype=tf.float32)\n    rpn_feature_map = feature_extractor.extract_proposal_features(\n        preprocessed_inputs, scope='TestScope')\n    features_shape = tf.shape(rpn_feature_map)\n\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      features_shape_out = sess.run(features_shape)\n      self.assertAllEqual(features_shape_out, [1, 19, 19, 1088])\n\n  def test_extract_proposal_features_stride_eight(self):\n    feature_extractor = self._build_feature_extractor(\n        first_stage_features_stride=8)\n    preprocessed_inputs = tf.random_uniform(\n        [1, 224, 224, 3], maxval=255, dtype=tf.float32)\n    rpn_feature_map = feature_extractor.extract_proposal_features(\n        preprocessed_inputs, scope='TestScope')\n    features_shape = tf.shape(rpn_feature_map)\n\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      features_shape_out = sess.run(features_shape)\n      self.assertAllEqual(features_shape_out, [1, 28, 28, 1088])\n\n  def test_extract_proposal_features_half_size_input(self):\n    feature_extractor = self._build_feature_extractor(\n        first_stage_features_stride=16)\n    preprocessed_inputs = tf.random_uniform(\n        [1, 112, 112, 3], maxval=255, dtype=tf.float32)\n    rpn_feature_map = feature_extractor.extract_proposal_features(\n        preprocessed_inputs, scope='TestScope')\n    features_shape = tf.shape(rpn_feature_map)\n\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      features_shape_out = sess.run(features_shape)\n      self.assertAllEqual(features_shape_out, [1, 7, 7, 1088])\n\n  def test_extract_proposal_features_dies_on_invalid_stride(self):\n    with self.assertRaises(ValueError):\n      self._build_feature_extractor(first_stage_features_stride=99)\n\n  def test_extract_proposal_features_dies_with_incorrect_rank_inputs(self):\n    feature_extractor = self._build_feature_extractor(\n        first_stage_features_stride=16)\n    preprocessed_inputs = tf.random_uniform(\n        [224, 224, 3], maxval=255, dtype=tf.float32)\n    with self.assertRaises(ValueError):\n      feature_extractor.extract_proposal_features(\n          preprocessed_inputs, scope='TestScope')\n\n  def test_extract_box_classifier_features_returns_expected_size(self):\n    feature_extractor = self._build_feature_extractor(\n        first_stage_features_stride=16)\n    proposal_feature_maps = tf.random_uniform(\n        [2, 17, 17, 1088], maxval=255, dtype=tf.float32)\n    proposal_classifier_features = (\n        feature_extractor.extract_box_classifier_features(\n            proposal_feature_maps, scope='TestScope'))\n    features_shape = tf.shape(proposal_classifier_features)\n\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      features_shape_out = sess.run(features_shape)\n      self.assertAllEqual(features_shape_out, [2, 8, 8, 1536])\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/models/faster_rcnn_resnet_v1_feature_extractor.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Resnet V1 Faster R-CNN implementation.\n\nSee \"Deep Residual Learning for Image Recognition\" by He et al., 2015.\nhttps://arxiv.org/abs/1512.03385\n\nNote: this implementation assumes that the classification checkpoint used\nto finetune this model is trained using the same configuration as that of\nthe MSRA provided checkpoints\n(see https://github.com/KaimingHe/deep-residual-networks), e.g., with\nsame preprocessing, batch norm scaling, etc.\n\"\"\"\nimport tensorflow as tf\n\nfrom object_detection.meta_architectures import faster_rcnn_meta_arch\nfrom nets import resnet_utils\nfrom nets import resnet_v1\n\nslim = tf.contrib.slim\n\n\nclass FasterRCNNResnetV1FeatureExtractor(\n    faster_rcnn_meta_arch.FasterRCNNFeatureExtractor):\n  \"\"\"Faster R-CNN Resnet V1 feature extractor implementation.\"\"\"\n\n  def __init__(self,\n               architecture,\n               resnet_model,\n               is_training,\n               first_stage_features_stride,\n               reuse_weights=None,\n               weight_decay=0.0):\n    \"\"\"Constructor.\n\n    Args:\n      architecture: Architecture name of the Resnet V1 model.\n      resnet_model: Definition of the Resnet V1 model.\n      is_training: See base class.\n      first_stage_features_stride: See base class.\n      reuse_weights: See base class.\n      weight_decay: See base class.\n\n    Raises:\n      ValueError: If `first_stage_features_stride` is not 8 or 16.\n    \"\"\"\n    if first_stage_features_stride != 8 and first_stage_features_stride != 16:\n      raise ValueError('`first_stage_features_stride` must be 8 or 16.')\n    self._architecture = architecture\n    self._resnet_model = resnet_model\n    super(FasterRCNNResnetV1FeatureExtractor, self).__init__(\n        is_training, first_stage_features_stride, reuse_weights, weight_decay)\n\n  def preprocess(self, resized_inputs):\n    \"\"\"Faster R-CNN Resnet V1 preprocessing.\n\n    VGG style channel mean subtraction as described here:\n    https://gist.github.com/ksimonyan/211839e770f7b538e2d8#file-readme-md\n\n    Args:\n      resized_inputs: A [batch, height_in, width_in, channels] float32 tensor\n        representing a batch of images with values between 0 and 255.0.\n\n    Returns:\n      preprocessed_inputs: A [batch, height_out, width_out, channels] float32\n        tensor representing a batch of images.\n\n    \"\"\"\n    channel_means = [123.68, 116.779, 103.939]\n    return resized_inputs - [[channel_means]]\n\n  def _extract_proposal_features(self, preprocessed_inputs, scope):\n    \"\"\"Extracts first stage RPN features.\n\n    Args:\n      preprocessed_inputs: A [batch, height, width, channels] float32 tensor\n        representing a batch of images.\n      scope: A scope name.\n\n    Returns:\n      rpn_feature_map: A tensor with shape [batch, height, width, depth]\n    Raises:\n      InvalidArgumentError: If the spatial size of `preprocessed_inputs`\n        (height or width) is less than 33.\n      ValueError: If the created network is missing the required activation.\n    \"\"\"\n    if len(preprocessed_inputs.get_shape().as_list()) != 4:\n      raise ValueError('`preprocessed_inputs` must be 4 dimensional, got a '\n                       'tensor of shape %s' % preprocessed_inputs.get_shape())\n    shape_assert = tf.Assert(\n        tf.logical_and(\n            tf.greater_equal(tf.shape(preprocessed_inputs)[1], 33),\n            tf.greater_equal(tf.shape(preprocessed_inputs)[2], 33)),\n        ['image size must at least be 33 in both height and width.'])\n\n    with tf.control_dependencies([shape_assert]):\n      # Disables batchnorm for fine-tuning with smaller batch sizes.\n      # TODO: Figure out if it is needed when image batch size is bigger.\n      with slim.arg_scope(\n          resnet_utils.resnet_arg_scope(\n              batch_norm_epsilon=1e-5,\n              batch_norm_scale=True,\n              weight_decay=self._weight_decay)):\n        with tf.variable_scope(\n            self._architecture, reuse=self._reuse_weights) as var_scope:\n          _, activations = self._resnet_model(\n              preprocessed_inputs,\n              num_classes=None,\n              is_training=False,\n              global_pool=False,\n              output_stride=self._first_stage_features_stride,\n              spatial_squeeze=False,\n              scope=var_scope)\n\n    handle = scope + '/%s/block3' % self._architecture\n    return activations[handle]\n\n  def _extract_box_classifier_features(self, proposal_feature_maps, scope):\n    \"\"\"Extracts second stage box classifier features.\n\n    Args:\n      proposal_feature_maps: A 4-D float tensor with shape\n        [batch_size * self.max_num_proposals, crop_height, crop_width, depth]\n        representing the feature map cropped to each proposal.\n      scope: A scope name (unused).\n\n    Returns:\n      proposal_classifier_features: A 4-D float tensor with shape\n        [batch_size * self.max_num_proposals, height, width, depth]\n        representing box classifier features for each proposal.\n    \"\"\"\n    with tf.variable_scope(self._architecture, reuse=self._reuse_weights):\n      with slim.arg_scope(\n          resnet_utils.resnet_arg_scope(\n              batch_norm_epsilon=1e-5,\n              batch_norm_scale=True,\n              weight_decay=self._weight_decay)):\n        with slim.arg_scope([slim.batch_norm], is_training=False):\n          blocks = [\n              resnet_utils.Block('block4', resnet_v1.bottleneck, [{\n                  'depth': 2048,\n                  'depth_bottleneck': 512,\n                  'stride': 1\n              }] * 3)\n          ]\n          proposal_classifier_features = resnet_utils.stack_blocks_dense(\n              proposal_feature_maps, blocks)\n    return proposal_classifier_features\n\n\nclass FasterRCNNResnet50FeatureExtractor(FasterRCNNResnetV1FeatureExtractor):\n  \"\"\"Faster R-CNN Resnet 50 feature extractor implementation.\"\"\"\n\n  def __init__(self,\n               is_training,\n               first_stage_features_stride,\n               reuse_weights=None,\n               weight_decay=0.0):\n    \"\"\"Constructor.\n\n    Args:\n      is_training: See base class.\n      first_stage_features_stride: See base class.\n      reuse_weights: See base class.\n      weight_decay: See base class.\n\n    Raises:\n      ValueError: If `first_stage_features_stride` is not 8 or 16,\n        or if `architecture` is not supported.\n    \"\"\"\n    super(FasterRCNNResnet50FeatureExtractor, self).__init__(\n        'resnet_v1_50', resnet_v1.resnet_v1_50, is_training,\n        first_stage_features_stride, reuse_weights, weight_decay)\n\n\nclass FasterRCNNResnet101FeatureExtractor(FasterRCNNResnetV1FeatureExtractor):\n  \"\"\"Faster R-CNN Resnet 101 feature extractor implementation.\"\"\"\n\n  def __init__(self,\n               is_training,\n               first_stage_features_stride,\n               reuse_weights=None,\n               weight_decay=0.0):\n    \"\"\"Constructor.\n\n    Args:\n      is_training: See base class.\n      first_stage_features_stride: See base class.\n      reuse_weights: See base class.\n      weight_decay: See base class.\n\n    Raises:\n      ValueError: If `first_stage_features_stride` is not 8 or 16,\n        or if `architecture` is not supported.\n    \"\"\"\n    super(FasterRCNNResnet101FeatureExtractor, self).__init__(\n        'resnet_v1_101', resnet_v1.resnet_v1_101, is_training,\n        first_stage_features_stride, reuse_weights, weight_decay)\n\n\nclass FasterRCNNResnet152FeatureExtractor(FasterRCNNResnetV1FeatureExtractor):\n  \"\"\"Faster R-CNN Resnet 152 feature extractor implementation.\"\"\"\n\n  def __init__(self,\n               is_training,\n               first_stage_features_stride,\n               reuse_weights=None,\n               weight_decay=0.0):\n    \"\"\"Constructor.\n\n    Args:\n      is_training: See base class.\n      first_stage_features_stride: See base class.\n      reuse_weights: See base class.\n      weight_decay: See base class.\n\n    Raises:\n      ValueError: If `first_stage_features_stride` is not 8 or 16,\n        or if `architecture` is not supported.\n    \"\"\"\n    super(FasterRCNNResnet152FeatureExtractor, self).__init__(\n        'resnet_v1_152', resnet_v1.resnet_v1_152, is_training,\n        first_stage_features_stride, reuse_weights, weight_decay)\n"
  },
  {
    "path": "object_detector_app/object_detection/models/faster_rcnn_resnet_v1_feature_extractor_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.models.faster_rcnn_resnet_v1_feature_extractor.\"\"\"\n\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.models import faster_rcnn_resnet_v1_feature_extractor as faster_rcnn_resnet_v1\n\n\nclass FasterRcnnResnetV1FeatureExtractorTest(tf.test.TestCase):\n\n  def _build_feature_extractor(self,\n                               first_stage_features_stride,\n                               architecture='resnet_v1_101'):\n    feature_extractor_map = {\n        'resnet_v1_50':\n            faster_rcnn_resnet_v1.FasterRCNNResnet50FeatureExtractor,\n        'resnet_v1_101':\n            faster_rcnn_resnet_v1.FasterRCNNResnet101FeatureExtractor,\n        'resnet_v1_152':\n            faster_rcnn_resnet_v1.FasterRCNNResnet152FeatureExtractor\n    }\n    return feature_extractor_map[architecture](\n        is_training=False,\n        first_stage_features_stride=first_stage_features_stride,\n        reuse_weights=None,\n        weight_decay=0.0)\n\n  def test_extract_proposal_features_returns_expected_size(self):\n    for architecture in ['resnet_v1_50', 'resnet_v1_101', 'resnet_v1_152']:\n      feature_extractor = self._build_feature_extractor(\n          first_stage_features_stride=16, architecture=architecture)\n      preprocessed_inputs = tf.random_uniform(\n          [4, 224, 224, 3], maxval=255, dtype=tf.float32)\n      rpn_feature_map = feature_extractor.extract_proposal_features(\n          preprocessed_inputs, scope='TestScope')\n      features_shape = tf.shape(rpn_feature_map)\n\n      init_op = tf.global_variables_initializer()\n      with self.test_session() as sess:\n        sess.run(init_op)\n        features_shape_out = sess.run(features_shape)\n        self.assertAllEqual(features_shape_out, [4, 14, 14, 1024])\n\n  def test_extract_proposal_features_stride_eight(self):\n    feature_extractor = self._build_feature_extractor(\n        first_stage_features_stride=8)\n    preprocessed_inputs = tf.random_uniform(\n        [4, 224, 224, 3], maxval=255, dtype=tf.float32)\n    rpn_feature_map = feature_extractor.extract_proposal_features(\n        preprocessed_inputs, scope='TestScope')\n    features_shape = tf.shape(rpn_feature_map)\n\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      features_shape_out = sess.run(features_shape)\n      self.assertAllEqual(features_shape_out, [4, 28, 28, 1024])\n\n  def test_extract_proposal_features_half_size_input(self):\n    feature_extractor = self._build_feature_extractor(\n        first_stage_features_stride=16)\n    preprocessed_inputs = tf.random_uniform(\n        [1, 112, 112, 3], maxval=255, dtype=tf.float32)\n    rpn_feature_map = feature_extractor.extract_proposal_features(\n        preprocessed_inputs, scope='TestScope')\n    features_shape = tf.shape(rpn_feature_map)\n\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      features_shape_out = sess.run(features_shape)\n      self.assertAllEqual(features_shape_out, [1, 7, 7, 1024])\n\n  def test_extract_proposal_features_dies_on_invalid_stride(self):\n    with self.assertRaises(ValueError):\n      self._build_feature_extractor(first_stage_features_stride=99)\n\n  def test_extract_proposal_features_dies_on_very_small_images(self):\n    feature_extractor = self._build_feature_extractor(\n        first_stage_features_stride=16)\n    preprocessed_inputs = tf.placeholder(tf.float32, (4, None, None, 3))\n    rpn_feature_map = feature_extractor.extract_proposal_features(\n        preprocessed_inputs, scope='TestScope')\n    features_shape = tf.shape(rpn_feature_map)\n\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      with self.assertRaises(tf.errors.InvalidArgumentError):\n        sess.run(\n            features_shape,\n            feed_dict={preprocessed_inputs: np.random.rand(4, 32, 32, 3)})\n\n  def test_extract_proposal_features_dies_with_incorrect_rank_inputs(self):\n    feature_extractor = self._build_feature_extractor(\n        first_stage_features_stride=16)\n    preprocessed_inputs = tf.random_uniform(\n        [224, 224, 3], maxval=255, dtype=tf.float32)\n    with self.assertRaises(ValueError):\n      feature_extractor.extract_proposal_features(\n          preprocessed_inputs, scope='TestScope')\n\n  def test_extract_box_classifier_features_returns_expected_size(self):\n    feature_extractor = self._build_feature_extractor(\n        first_stage_features_stride=16)\n    proposal_feature_maps = tf.random_uniform(\n        [3, 7, 7, 1024], maxval=255, dtype=tf.float32)\n    proposal_classifier_features = (\n        feature_extractor.extract_box_classifier_features(\n            proposal_feature_maps, scope='TestScope'))\n    features_shape = tf.shape(proposal_classifier_features)\n\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      features_shape_out = sess.run(features_shape)\n      self.assertAllEqual(features_shape_out, [3, 7, 7, 2048])\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/models/feature_map_generators.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Functions to generate a list of feature maps based on image features.\n\nProvides several feature map generators that can be used to build object\ndetection feature extractors.\n\nObject detection feature extractors usually are built by stacking two components\n- A base feature extractor such as Inception V3 and a feature map generator.\nFeature map generators build on the base feature extractors and produce a list\nof final feature maps.\n\"\"\"\nimport collections\nimport tensorflow as tf\nfrom object_detection.utils import ops\nslim = tf.contrib.slim\n\n\ndef get_depth_fn(depth_multiplier, min_depth):\n  \"\"\"Builds a callable to compute depth (output channels) of conv filters.\n\n  Args:\n    depth_multiplier: a multiplier for the nominal depth.\n    min_depth: a lower bound on the depth of filters.\n\n  Returns:\n    A callable that takes in a nominal depth and returns the depth to use.\n  \"\"\"\n  def multiply_depth(depth):\n    new_depth = int(depth * depth_multiplier)\n    return max(new_depth, min_depth)\n  return multiply_depth\n\n\ndef multi_resolution_feature_maps(feature_map_layout, depth_multiplier,\n                                  min_depth, insert_1x1_conv, image_features):\n  \"\"\"Generates multi resolution feature maps from input image features.\n\n  Generates multi-scale feature maps for detection as in the SSD papers by\n  Liu et al: https://arxiv.org/pdf/1512.02325v2.pdf, See Sec 2.1.\n\n  More specifically, it performs the following two tasks:\n  1) If a layer name is provided in the configuration, returns that layer as a\n     feature map.\n  2) If a layer name is left as an empty string, constructs a new feature map\n     based on the spatial shape and depth configuration. Note that the current\n     implementation only supports generating new layers using convolution of\n     stride 2 resulting in a spatial resolution reduction by a factor of 2.\n\n  An example of the configuration for Inception V3:\n  {\n    'from_layer': ['Mixed_5d', 'Mixed_6e', 'Mixed_7c', '', '', ''],\n    'layer_depth': [-1, -1, -1, 512, 256, 128],\n    'anchor_strides': [16, 32, 64, -1, -1, -1]\n  }\n\n  Args:\n    feature_map_layout: Dictionary of specifications for the feature map\n      layouts in the following format (Inception V2/V3 respectively):\n      {\n        'from_layer': ['Mixed_3c', 'Mixed_4c', 'Mixed_5c', '', '', ''],\n        'layer_depth': [-1, -1, -1, 512, 256, 128],\n        'anchor_strides': [16, 32, 64, -1, -1, -1]\n      }\n      or\n      {\n        'from_layer': ['Mixed_5d', 'Mixed_6e', 'Mixed_7c', '', '', '', ''],\n        'layer_depth': [-1, -1, -1, 512, 256, 128],\n        'anchor_strides': [16, 32, 64, -1, -1, -1]\n      }\n      If 'from_layer' is specified, the specified feature map is directly used\n      as a box predictor layer, and the layer_depth is directly infered from the\n      feature map (instead of using the provided 'layer_depth' parameter). In\n      this case, our convention is to set 'layer_depth' to -1 for clarity.\n      Otherwise, if 'from_layer' is an empty string, then the box predictor\n      layer will be built from the previous layer using convolution operations.\n      Note that the current implementation only supports generating new layers\n      using convolutions of stride 2 (resulting in a spatial resolution\n      reduction by a factor of 2), and will be extended to a more flexible\n      design. Finally, the optional 'anchor_strides' can be used to specify the\n      anchor stride at each layer where 'from_layer' is specified. Our\n      convention is to set 'anchor_strides' to -1 whenever at the positions that\n      'from_layer' is an empty string, and anchor strides at these layers will\n      be inferred from the previous layer's anchor strides and the current\n      layer's stride length. In the case where 'anchor_strides' is not\n      specified, the anchor strides will default to the image width and height\n      divided by the number of anchors.\n    depth_multiplier: Depth multiplier for convolutional layers.\n    min_depth: Minimum depth for convolutional layers.\n    insert_1x1_conv: A boolean indicating whether an additional 1x1 convolution\n      should be inserted before shrinking the feature map.\n    image_features: A dictionary of handles to activation tensors from the\n      base feature extractor.\n\n  Returns:\n    feature_maps: an OrderedDict mapping keys (feature map names) to\n      tensors where each tensor has shape [batch, height_i, width_i, depth_i].\n\n  Raises:\n    ValueError: if the number entries in 'from_layer' and\n      'layer_depth' do not match.\n    ValueError: if the generated layer does not have the same resolution\n      as specified.\n  \"\"\"\n  depth_fn = get_depth_fn(depth_multiplier, min_depth)\n\n  feature_map_keys = []\n  feature_maps = []\n  base_from_layer = ''\n  feature_map_strides = None\n  use_depthwise = False\n  if 'anchor_strides' in feature_map_layout:\n    feature_map_strides = (feature_map_layout['anchor_strides'])\n  if 'use_depthwise' in feature_map_layout:\n    use_depthwise = feature_map_layout['use_depthwise']\n  for index, (from_layer, layer_depth) in enumerate(\n      zip(feature_map_layout['from_layer'], feature_map_layout['layer_depth'])):\n    if from_layer:\n      feature_map = image_features[from_layer]\n      base_from_layer = from_layer\n      feature_map_keys.append(from_layer)\n    else:\n      pre_layer = feature_maps[-1]\n      intermediate_layer = pre_layer\n      if insert_1x1_conv:\n        layer_name = '{}_1_Conv2d_{}_1x1_{}'.format(\n            base_from_layer, index, depth_fn(layer_depth / 2))\n        intermediate_layer = slim.conv2d(\n            pre_layer,\n            depth_fn(layer_depth / 2), [1, 1],\n            padding='SAME',\n            stride=1,\n            scope=layer_name)\n      stride = 2\n      layer_name = '{}_2_Conv2d_{}_3x3_s2_{}'.format(\n          base_from_layer, index, depth_fn(layer_depth))\n      if use_depthwise:\n        feature_map = slim.separable_conv2d(\n            ops.pad_to_multiple(intermediate_layer, stride),\n            None, [3, 3],\n            depth_multiplier=1,\n            padding='SAME',\n            stride=stride,\n            scope=layer_name + '_depthwise')\n        feature_map = slim.conv2d(\n            feature_map,\n            depth_fn(layer_depth), [1, 1],\n            padding='SAME',\n            stride=1,\n            scope=layer_name)\n      else:\n        feature_map = slim.conv2d(\n            ops.pad_to_multiple(intermediate_layer, stride),\n            depth_fn(layer_depth), [3, 3],\n            padding='SAME',\n            stride=stride,\n            scope=layer_name)\n\n      if (index > 0 and feature_map_strides and\n          feature_map_strides[index - 1] > 0):\n        feature_map_strides[index] = (\n            stride * feature_map_strides[index - 1])\n      feature_map_keys.append(layer_name)\n    feature_maps.append(feature_map)\n  return collections.OrderedDict(\n      [(x, y) for (x, y) in zip(feature_map_keys, feature_maps)])\n"
  },
  {
    "path": "object_detector_app/object_detection/models/feature_map_generators_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for feature map generators.\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.models import feature_map_generators\n\nINCEPTION_V2_LAYOUT = {\n    'from_layer': ['Mixed_3c', 'Mixed_4c', 'Mixed_5c', '', '', ''],\n    'layer_depth': [-1, -1, -1, 512, 256, 256],\n    'anchor_strides': [16, 32, 64, -1, -1, -1],\n    'layer_target_norm': [20.0, -1, -1, -1, -1, -1],\n}\n\nINCEPTION_V3_LAYOUT = {\n    'from_layer': ['Mixed_5d', 'Mixed_6e', 'Mixed_7c', '', '', ''],\n    'layer_depth': [-1, -1, -1, 512, 256, 128],\n    'anchor_strides': [16, 32, 64, -1, -1, -1],\n    'aspect_ratios': [1.0, 2.0, 1.0/2, 3.0, 1.0/3]\n}\n\n\n# TODO: add tests with different anchor strides.\nclass MultiResolutionFeatureMapGeneratorTest(tf.test.TestCase):\n\n  def test_get_expected_feature_map_shapes_with_inception_v2(self):\n    image_features = {\n        'Mixed_3c': tf.random_uniform([4, 28, 28, 256], dtype=tf.float32),\n        'Mixed_4c': tf.random_uniform([4, 14, 14, 576], dtype=tf.float32),\n        'Mixed_5c': tf.random_uniform([4, 7, 7, 1024], dtype=tf.float32)\n    }\n    feature_maps = feature_map_generators.multi_resolution_feature_maps(\n        feature_map_layout=INCEPTION_V2_LAYOUT,\n        depth_multiplier=1,\n        min_depth=32,\n        insert_1x1_conv=True,\n        image_features=image_features)\n\n    expected_feature_map_shapes = {\n        'Mixed_3c': (4, 28, 28, 256),\n        'Mixed_4c': (4, 14, 14, 576),\n        'Mixed_5c': (4, 7, 7, 1024),\n        'Mixed_5c_2_Conv2d_3_3x3_s2_512': (4, 4, 4, 512),\n        'Mixed_5c_2_Conv2d_4_3x3_s2_256': (4, 2, 2, 256),\n        'Mixed_5c_2_Conv2d_5_3x3_s2_256': (4, 1, 1, 256)}\n\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      out_feature_maps = sess.run(feature_maps)\n      out_feature_map_shapes = dict(\n          (key, value.shape) for key, value in out_feature_maps.iteritems())\n      self.assertDictEqual(out_feature_map_shapes, expected_feature_map_shapes)\n\n  def test_get_expected_feature_map_shapes_with_inception_v3(self):\n    image_features = {\n        'Mixed_5d': tf.random_uniform([4, 35, 35, 256], dtype=tf.float32),\n        'Mixed_6e': tf.random_uniform([4, 17, 17, 576], dtype=tf.float32),\n        'Mixed_7c': tf.random_uniform([4, 8, 8, 1024], dtype=tf.float32)\n    }\n\n    feature_maps = feature_map_generators.multi_resolution_feature_maps(\n        feature_map_layout=INCEPTION_V3_LAYOUT,\n        depth_multiplier=1,\n        min_depth=32,\n        insert_1x1_conv=True,\n        image_features=image_features)\n\n    expected_feature_map_shapes = {\n        'Mixed_5d': (4, 35, 35, 256),\n        'Mixed_6e': (4, 17, 17, 576),\n        'Mixed_7c': (4, 8, 8, 1024),\n        'Mixed_7c_2_Conv2d_3_3x3_s2_512': (4, 4, 4, 512),\n        'Mixed_7c_2_Conv2d_4_3x3_s2_256': (4, 2, 2, 256),\n        'Mixed_7c_2_Conv2d_5_3x3_s2_128': (4, 1, 1, 128)}\n\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      out_feature_maps = sess.run(feature_maps)\n      out_feature_map_shapes = dict(\n          (key, value.shape) for key, value in out_feature_maps.iteritems())\n      self.assertDictEqual(out_feature_map_shapes, expected_feature_map_shapes)\n\n\nclass GetDepthFunctionTest(tf.test.TestCase):\n\n  def test_return_min_depth_when_multiplier_is_small(self):\n    depth_fn = feature_map_generators.get_depth_fn(depth_multiplier=0.5,\n                                                   min_depth=16)\n    self.assertEqual(depth_fn(16), 16)\n\n  def test_return_correct_depth_with_multiplier(self):\n    depth_fn = feature_map_generators.get_depth_fn(depth_multiplier=0.5,\n                                                   min_depth=16)\n    self.assertEqual(depth_fn(64), 32)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/models/ssd_feature_extractor_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Base test class SSDFeatureExtractors.\"\"\"\n\nfrom abc import abstractmethod\n\nimport numpy as np\nimport tensorflow as tf\n\n\nclass SsdFeatureExtractorTestBase(object):\n\n  def _validate_features_shape(self,\n                               feature_extractor,\n                               preprocessed_inputs,\n                               expected_feature_map_shapes):\n    \"\"\"Checks the extracted features are of correct shape.\n\n    Args:\n      feature_extractor: The feature extractor to test.\n      preprocessed_inputs: A [batch, height, width, 3] tensor to extract\n                           features with.\n      expected_feature_map_shapes: The expected shape of the extracted features.\n    \"\"\"\n    feature_maps = feature_extractor.extract_features(preprocessed_inputs)\n    feature_map_shapes = [tf.shape(feature_map) for feature_map in feature_maps]\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      feature_map_shapes_out = sess.run(feature_map_shapes)\n      for shape_out, exp_shape_out in zip(\n          feature_map_shapes_out, expected_feature_map_shapes):\n        self.assertAllEqual(shape_out, exp_shape_out)\n\n  @abstractmethod\n  def _create_feature_extractor(self, depth_multiplier):\n    \"\"\"Constructs a new feature extractor.\n\n    Args:\n      depth_multiplier: float depth multiplier for feature extractor\n    Returns:\n      an ssd_meta_arch.SSDFeatureExtractor object.\n    \"\"\"\n    pass\n\n  def check_extract_features_returns_correct_shape(\n      self,\n      image_height,\n      image_width,\n      depth_multiplier,\n      expected_feature_map_shapes_out):\n    feature_extractor = self._create_feature_extractor(depth_multiplier)\n    preprocessed_inputs = tf.random_uniform(\n        [4, image_height, image_width, 3], dtype=tf.float32)\n    self._validate_features_shape(\n        feature_extractor, preprocessed_inputs, expected_feature_map_shapes_out)\n\n  def check_extract_features_raises_error_with_invalid_image_size(\n      self,\n      image_height,\n      image_width,\n      depth_multiplier):\n    feature_extractor = self._create_feature_extractor(depth_multiplier)\n    preprocessed_inputs = tf.placeholder(tf.float32, (4, None, None, 3))\n    feature_maps = feature_extractor.extract_features(preprocessed_inputs)\n    test_preprocessed_image = np.random.rand(4, image_height, image_width, 3)\n    with self.test_session() as sess:\n      sess.run(tf.global_variables_initializer())\n      with self.assertRaises(tf.errors.InvalidArgumentError):\n        sess.run(feature_maps,\n                 feed_dict={preprocessed_inputs: test_preprocessed_image})\n\n  def check_feature_extractor_variables_under_scope(self,\n                                                    depth_multiplier,\n                                                    scope_name):\n    g = tf.Graph()\n    with g.as_default():\n      feature_extractor = self._create_feature_extractor(depth_multiplier)\n      preprocessed_inputs = tf.placeholder(tf.float32, (4, None, None, 3))\n      feature_extractor.extract_features(preprocessed_inputs)\n      variables = g.get_collection(tf.GraphKeys.GLOBAL_VARIABLES)\n      for variable in variables:\n        self.assertTrue(variable.name.startswith(scope_name))\n"
  },
  {
    "path": "object_detector_app/object_detection/models/ssd_inception_v2_feature_extractor.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"SSDFeatureExtractor for InceptionV2 features.\"\"\"\nimport tensorflow as tf\n\nfrom object_detection.meta_architectures import ssd_meta_arch\nfrom object_detection.models import feature_map_generators\nfrom nets import inception_v2\n\nslim = tf.contrib.slim\n\n\nclass SSDInceptionV2FeatureExtractor(ssd_meta_arch.SSDFeatureExtractor):\n  \"\"\"SSD Feature Extractor using InceptionV2 features.\"\"\"\n\n  def __init__(self,\n               depth_multiplier,\n               min_depth,\n               conv_hyperparams,\n               reuse_weights=None):\n    \"\"\"InceptionV2 Feature Extractor for SSD Models.\n\n    Args:\n      depth_multiplier: float depth multiplier for feature extractor.\n      min_depth: minimum feature extractor depth.\n      conv_hyperparams: tf slim arg_scope for conv2d and separable_conv2d ops.\n      reuse_weights: Whether to reuse variables. Default is None.\n    \"\"\"\n    super(SSDInceptionV2FeatureExtractor, self).__init__(\n        depth_multiplier, min_depth, conv_hyperparams, reuse_weights)\n\n  def preprocess(self, resized_inputs):\n    \"\"\"SSD preprocessing.\n\n    Maps pixel values to the range [-1, 1].\n\n    Args:\n      resized_inputs: a [batch, height, width, channels] float tensor\n        representing a batch of images.\n\n    Returns:\n      preprocessed_inputs: a [batch, height, width, channels] float tensor\n        representing a batch of images.\n    \"\"\"\n    return (2.0 / 255.0) * resized_inputs - 1.0\n\n  def extract_features(self, preprocessed_inputs):\n    \"\"\"Extract features from preprocessed inputs.\n\n    Args:\n      preprocessed_inputs: a [batch, height, width, channels] float tensor\n        representing a batch of images.\n\n    Returns:\n      feature_maps: a list of tensors where the ith tensor has shape\n        [batch, height_i, width_i, depth_i]\n    \"\"\"\n    preprocessed_inputs.get_shape().assert_has_rank(4)\n    shape_assert = tf.Assert(\n        tf.logical_and(tf.greater_equal(tf.shape(preprocessed_inputs)[1], 33),\n                       tf.greater_equal(tf.shape(preprocessed_inputs)[2], 33)),\n        ['image size must at least be 33 in both height and width.'])\n\n    feature_map_layout = {\n        'from_layer': ['Mixed_4c', 'Mixed_5c', '', '', '', ''],\n        'layer_depth': [-1, -1, 512, 256, 256, 128],\n    }\n\n    with tf.control_dependencies([shape_assert]):\n      with slim.arg_scope(self._conv_hyperparams):\n        with tf.variable_scope('InceptionV2',\n                               reuse=self._reuse_weights) as scope:\n          _, image_features = inception_v2.inception_v2_base(\n              preprocessed_inputs,\n              final_endpoint='Mixed_5c',\n              min_depth=self._min_depth,\n              depth_multiplier=self._depth_multiplier,\n              scope=scope)\n          feature_maps = feature_map_generators.multi_resolution_feature_maps(\n              feature_map_layout=feature_map_layout,\n              depth_multiplier=self._depth_multiplier,\n              min_depth=self._min_depth,\n              insert_1x1_conv=True,\n              image_features=image_features)\n\n    return feature_maps.values()\n"
  },
  {
    "path": "object_detector_app/object_detection/models/ssd_inception_v2_feature_extractor_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.models.ssd_inception_v2_feature_extractor.\"\"\"\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.models import ssd_feature_extractor_test\nfrom object_detection.models import ssd_inception_v2_feature_extractor\n\n\nclass SsdInceptionV2FeatureExtractorTest(\n    ssd_feature_extractor_test.SsdFeatureExtractorTestBase,\n    tf.test.TestCase):\n\n  def _create_feature_extractor(self, depth_multiplier):\n    \"\"\"Constructs a SsdInceptionV2FeatureExtractor.\n\n    Args:\n      depth_multiplier: float depth multiplier for feature extractor\n    Returns:\n      an ssd_inception_v2_feature_extractor.SsdInceptionV2FeatureExtractor.\n    \"\"\"\n    min_depth = 32\n    conv_hyperparams = {}\n    return ssd_inception_v2_feature_extractor.SSDInceptionV2FeatureExtractor(\n        depth_multiplier, min_depth, conv_hyperparams)\n\n  def test_extract_features_returns_correct_shapes_128(self):\n    image_height = 128\n    image_width = 128\n    depth_multiplier = 1.0\n    expected_feature_map_shape = [(4, 8, 8, 576), (4, 4, 4, 1024),\n                                  (4, 2, 2, 512), (4, 1, 1, 256),\n                                  (4, 1, 1, 256), (4, 1, 1, 128)]\n    self.check_extract_features_returns_correct_shape(\n        image_height, image_width, depth_multiplier, expected_feature_map_shape)\n\n  def test_extract_features_returns_correct_shapes_299(self):\n    image_height = 299\n    image_width = 299\n    depth_multiplier = 1.0\n    expected_feature_map_shape = [(4, 19, 19, 576), (4, 10, 10, 1024),\n                                  (4, 5, 5, 512), (4, 3, 3, 256),\n                                  (4, 2, 2, 256), (4, 1, 1, 128)]\n    self.check_extract_features_returns_correct_shape(\n        image_height, image_width, depth_multiplier, expected_feature_map_shape)\n\n  def test_extract_features_returns_correct_shapes_enforcing_min_depth(self):\n    image_height = 299\n    image_width = 299\n    depth_multiplier = 0.5**12\n    expected_feature_map_shape = [(4, 19, 19, 128), (4, 10, 10, 128),\n                                  (4, 5, 5, 32), (4, 3, 3, 32),\n                                  (4, 2, 2, 32), (4, 1, 1, 32)]\n    self.check_extract_features_returns_correct_shape(\n        image_height, image_width, depth_multiplier, expected_feature_map_shape)\n\n  def test_extract_features_raises_error_with_invalid_image_size(self):\n    image_height = 32\n    image_width = 32\n    depth_multiplier = 1.0\n    self.check_extract_features_raises_error_with_invalid_image_size(\n        image_height, image_width, depth_multiplier)\n\n  def test_preprocess_returns_correct_value_range(self):\n    image_height = 128\n    image_width = 128\n    depth_multiplier = 1\n    test_image = np.random.rand(4, image_height, image_width, 3)\n    feature_extractor = self._create_feature_extractor(depth_multiplier)\n    preprocessed_image = feature_extractor.preprocess(test_image)\n    self.assertTrue(np.all(np.less_equal(np.abs(preprocessed_image), 1.0)))\n\n  def test_variables_only_created_in_scope(self):\n    depth_multiplier = 1\n    scope_name = 'InceptionV2'\n    self.check_feature_extractor_variables_under_scope(depth_multiplier,\n                                                       scope_name)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/models/ssd_mobilenet_v1_feature_extractor.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"SSDFeatureExtractor for MobilenetV1 features.\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.meta_architectures import ssd_meta_arch\nfrom object_detection.models import feature_map_generators\nfrom nets import mobilenet_v1\n\nslim = tf.contrib.slim\n\n\nclass SSDMobileNetV1FeatureExtractor(ssd_meta_arch.SSDFeatureExtractor):\n  \"\"\"SSD Feature Extractor using MobilenetV1 features.\"\"\"\n\n  def __init__(self,\n               depth_multiplier,\n               min_depth,\n               conv_hyperparams,\n               reuse_weights=None):\n    \"\"\"MobileNetV1 Feature Extractor for SSD Models.\n\n    Args:\n      depth_multiplier: float depth multiplier for feature extractor.\n      min_depth: minimum feature extractor depth.\n      conv_hyperparams: tf slim arg_scope for conv2d and separable_conv2d ops.\n      reuse_weights: Whether to reuse variables. Default is None.\n    \"\"\"\n    super(SSDMobileNetV1FeatureExtractor, self).__init__(\n        depth_multiplier, min_depth, conv_hyperparams, reuse_weights)\n\n  def preprocess(self, resized_inputs):\n    \"\"\"SSD preprocessing.\n\n    Maps pixel values to the range [-1, 1].\n\n    Args:\n      resized_inputs: a [batch, height, width, channels] float tensor\n        representing a batch of images.\n\n    Returns:\n      preprocessed_inputs: a [batch, height, width, channels] float tensor\n        representing a batch of images.\n    \"\"\"\n    return (2.0 / 255.0) * resized_inputs - 1.0\n\n  def extract_features(self, preprocessed_inputs):\n    \"\"\"Extract features from preprocessed inputs.\n\n    Args:\n      preprocessed_inputs: a [batch, height, width, channels] float tensor\n        representing a batch of images.\n\n    Returns:\n      feature_maps: a list of tensors where the ith tensor has shape\n        [batch, height_i, width_i, depth_i]\n    \"\"\"\n    preprocessed_inputs.get_shape().assert_has_rank(4)\n    shape_assert = tf.Assert(\n        tf.logical_and(tf.greater_equal(tf.shape(preprocessed_inputs)[1], 33),\n                       tf.greater_equal(tf.shape(preprocessed_inputs)[2], 33)),\n        ['image size must at least be 33 in both height and width.'])\n\n    feature_map_layout = {\n        'from_layer': ['Conv2d_11_pointwise', 'Conv2d_13_pointwise', '', '',\n                       '', ''],\n        'layer_depth': [-1, -1, 512, 256, 256, 128],\n    }\n\n    with tf.control_dependencies([shape_assert]):\n      with slim.arg_scope(self._conv_hyperparams):\n        with tf.variable_scope('MobilenetV1',\n                               reuse=self._reuse_weights) as scope:\n          _, image_features = mobilenet_v1.mobilenet_v1_base(\n              preprocessed_inputs,\n              final_endpoint='Conv2d_13_pointwise',\n              min_depth=self._min_depth,\n              depth_multiplier=self._depth_multiplier,\n              scope=scope)\n          feature_maps = feature_map_generators.multi_resolution_feature_maps(\n              feature_map_layout=feature_map_layout,\n              depth_multiplier=self._depth_multiplier,\n              min_depth=self._min_depth,\n              insert_1x1_conv=True,\n              image_features=image_features)\n\n    return feature_maps.values()\n"
  },
  {
    "path": "object_detector_app/object_detection/models/ssd_mobilenet_v1_feature_extractor_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for ssd_mobilenet_v1_feature_extractor.\"\"\"\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.models import ssd_feature_extractor_test\nfrom object_detection.models import ssd_mobilenet_v1_feature_extractor\n\n\nclass SsdMobilenetV1FeatureExtractorTest(\n    ssd_feature_extractor_test.SsdFeatureExtractorTestBase, tf.test.TestCase):\n\n  def _create_feature_extractor(self, depth_multiplier):\n    \"\"\"Constructs a new feature extractor.\n\n    Args:\n      depth_multiplier: float depth multiplier for feature extractor\n    Returns:\n      an ssd_meta_arch.SSDFeatureExtractor object.\n    \"\"\"\n    min_depth = 32\n    conv_hyperparams = {}\n    return ssd_mobilenet_v1_feature_extractor.SSDMobileNetV1FeatureExtractor(\n        depth_multiplier, min_depth, conv_hyperparams)\n\n  def test_extract_features_returns_correct_shapes_128(self):\n    image_height = 128\n    image_width = 128\n    depth_multiplier = 1.0\n    expected_feature_map_shape = [(4, 8, 8, 512), (4, 4, 4, 1024),\n                                  (4, 2, 2, 512), (4, 1, 1, 256),\n                                  (4, 1, 1, 256), (4, 1, 1, 128)]\n    self.check_extract_features_returns_correct_shape(\n        image_height, image_width, depth_multiplier, expected_feature_map_shape)\n\n  def test_extract_features_returns_correct_shapes_299(self):\n    image_height = 299\n    image_width = 299\n    depth_multiplier = 1.0\n    expected_feature_map_shape = [(4, 19, 19, 512), (4, 10, 10, 1024),\n                                  (4, 5, 5, 512), (4, 3, 3, 256),\n                                  (4, 2, 2, 256), (4, 1, 1, 128)]\n    self.check_extract_features_returns_correct_shape(\n        image_height, image_width, depth_multiplier, expected_feature_map_shape)\n\n  def test_extract_features_returns_correct_shapes_enforcing_min_depth(self):\n    image_height = 299\n    image_width = 299\n    depth_multiplier = 0.5**12\n    expected_feature_map_shape = [(4, 19, 19, 32), (4, 10, 10, 32),\n                                  (4, 5, 5, 32), (4, 3, 3, 32),\n                                  (4, 2, 2, 32), (4, 1, 1, 32)]\n    self.check_extract_features_returns_correct_shape(\n        image_height, image_width, depth_multiplier, expected_feature_map_shape)\n\n  def test_extract_features_raises_error_with_invalid_image_size(self):\n    image_height = 32\n    image_width = 32\n    depth_multiplier = 1.0\n    self.check_extract_features_raises_error_with_invalid_image_size(\n        image_height, image_width, depth_multiplier)\n\n  def test_preprocess_returns_correct_value_range(self):\n    image_height = 128\n    image_width = 128\n    depth_multiplier = 1\n    test_image = np.random.rand(4, image_height, image_width, 3)\n    feature_extractor = self._create_feature_extractor(depth_multiplier)\n    preprocessed_image = feature_extractor.preprocess(test_image)\n    self.assertTrue(np.all(np.less_equal(np.abs(preprocessed_image), 1.0)))\n\n  def test_variables_only_created_in_scope(self):\n    depth_multiplier = 1\n    scope_name = 'MobilenetV1'\n    self.check_feature_extractor_variables_under_scope(depth_multiplier,\n                                                       scope_name)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/object_detection_tutorial.ipynb",
    "content": "{\n \"cells\": [\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"# Object Detection Demo\\n\",\n    \"Welcome to the object detection inference walkthrough!  This notebook will walk you step by step through the process of using a pre-trained model to detect objects in an image.\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"# Imports\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": 15,\n   \"metadata\": {\n    \"collapsed\": true,\n    \"scrolled\": true\n   },\n   \"outputs\": [],\n   \"source\": [\n    \"import numpy as np\\n\",\n    \"import os\\n\",\n    \"import six.moves.urllib as urllib\\n\",\n    \"import sys\\n\",\n    \"import tarfile\\n\",\n    \"import tensorflow as tf\\n\",\n    \"import zipfile\\n\",\n    \"\\n\",\n    \"from collections import defaultdict\\n\",\n    \"from io import StringIO\\n\",\n    \"from matplotlib import pyplot as plt\\n\",\n    \"from PIL import Image\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"## Env setup\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": 16,\n   \"metadata\": {\n    \"collapsed\": true\n   },\n   \"outputs\": [],\n   \"source\": [\n    \"# This is needed to display the images.\\n\",\n    \"%matplotlib inline\\n\",\n    \"\\n\",\n    \"# This is needed since the notebook is stored in the object_detection folder.\\n\",\n    \"sys.path.append(\\\"..\\\")\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": 17,\n   \"metadata\": {\n    \"collapsed\": false\n   },\n   \"outputs\": [\n    {\n     \"data\": {\n      \"text/plain\": [\n       \"['',\\n\",\n       \" '/Users/datitran/anaconda/envs/kaggle/lib/python35.zip',\\n\",\n       \" '/Users/datitran/anaconda/envs/kaggle/lib/python3.5',\\n\",\n       \" '/Users/datitran/anaconda/envs/kaggle/lib/python3.5/plat-darwin',\\n\",\n       \" '/Users/datitran/anaconda/envs/kaggle/lib/python3.5/lib-dynload',\\n\",\n       \" '/Users/datitran/anaconda/envs/kaggle/lib/python3.5/site-packages',\\n\",\n       \" '/Users/datitran/anaconda/envs/kaggle/lib/python3.5/site-packages/xgboost-0.6-py3.5.egg',\\n\",\n       \" '/Users/datitran/anaconda/envs/kaggle/lib/python3.5/site-packages/IPython/extensions',\\n\",\n       \" '/Users/datitran/.ipython',\\n\",\n       \" '..',\\n\",\n       \" '..',\\n\",\n       \" '..',\\n\",\n       \" '..']\"\n      ]\n     },\n     \"execution_count\": 17,\n     \"metadata\": {},\n     \"output_type\": \"execute_result\"\n    }\n   ],\n   \"source\": [\n    \"sys.path\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"## Object detection imports\\n\",\n    \"Here are the imports from the object detection module.\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": 18,\n   \"metadata\": {\n    \"collapsed\": false\n   },\n   \"outputs\": [\n    {\n     \"ename\": \"ImportError\",\n     \"evalue\": \"No module named 'object_detection.protos'; 'object_detection' is not a package\",\n     \"output_type\": \"error\",\n     \"traceback\": [\n      \"\\u001b[0;31m---------------------------------------------------------------------------\\u001b[0m\",\n      \"\\u001b[0;31mImportError\\u001b[0m                               Traceback (most recent call last)\",\n      \"\\u001b[0;32m<ipython-input-18-956de605e8fe>\\u001b[0m in \\u001b[0;36m<module>\\u001b[0;34m()\\u001b[0m\\n\\u001b[0;32m----> 1\\u001b[0;31m \\u001b[0;32mfrom\\u001b[0m \\u001b[0mutils\\u001b[0m \\u001b[0;32mimport\\u001b[0m \\u001b[0mlabel_map_util\\u001b[0m\\u001b[0;34m\\u001b[0m\\u001b[0m\\n\\u001b[0m\\u001b[1;32m      2\\u001b[0m \\u001b[0;34m\\u001b[0m\\u001b[0m\\n\\u001b[1;32m      3\\u001b[0m \\u001b[0;32mfrom\\u001b[0m \\u001b[0mutils\\u001b[0m \\u001b[0;32mimport\\u001b[0m \\u001b[0mvisualization_utils\\u001b[0m \\u001b[0;32mas\\u001b[0m \\u001b[0mvis_util\\u001b[0m\\u001b[0;34m\\u001b[0m\\u001b[0m\\n\",\n      \"\\u001b[0;32m/Users/datitran/Desktop/tensorflow-api/models/object_detection/utils/label_map_util.py\\u001b[0m in \\u001b[0;36m<module>\\u001b[0;34m()\\u001b[0m\\n\\u001b[1;32m     20\\u001b[0m \\u001b[0;32mimport\\u001b[0m \\u001b[0mtensorflow\\u001b[0m \\u001b[0;32mas\\u001b[0m \\u001b[0mtf\\u001b[0m\\u001b[0;34m\\u001b[0m\\u001b[0m\\n\\u001b[1;32m     21\\u001b[0m \\u001b[0;32mfrom\\u001b[0m \\u001b[0mgoogle\\u001b[0m\\u001b[0;34m.\\u001b[0m\\u001b[0mprotobuf\\u001b[0m \\u001b[0;32mimport\\u001b[0m \\u001b[0mtext_format\\u001b[0m\\u001b[0;34m\\u001b[0m\\u001b[0m\\n\\u001b[0;32m---> 22\\u001b[0;31m \\u001b[0;32mfrom\\u001b[0m \\u001b[0mobject_detection\\u001b[0m\\u001b[0;34m.\\u001b[0m\\u001b[0mprotos\\u001b[0m \\u001b[0;32mimport\\u001b[0m \\u001b[0mstring_int_label_map_pb2\\u001b[0m\\u001b[0;34m\\u001b[0m\\u001b[0m\\n\\u001b[0m\\u001b[1;32m     23\\u001b[0m \\u001b[0;34m\\u001b[0m\\u001b[0m\\n\\u001b[1;32m     24\\u001b[0m \\u001b[0;34m\\u001b[0m\\u001b[0m\\n\",\n      \"\\u001b[0;31mImportError\\u001b[0m: No module named 'object_detection.protos'; 'object_detection' is not a package\"\n     ]\n    }\n   ],\n   \"source\": [\n    \"from utils import label_map_util\\n\",\n    \"\\n\",\n    \"from utils import visualization_utils as vis_util\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"# Model preparation \"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"## Variables\\n\",\n    \"\\n\",\n    \"Any model exported using the `export_inference_graph.py` tool can be loaded here simply by changing `PATH_TO_CKPT` to point to a new .pb file.  \\n\",\n    \"\\n\",\n    \"By default we use an \\\"SSD with Mobilenet\\\" model here. See the [detection model zoo](g3doc/detection_model_zoo.md) for a list of other models that can be run out-of-the-box with varying speeds and accuracies.\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": null,\n   \"metadata\": {\n    \"collapsed\": true\n   },\n   \"outputs\": [],\n   \"source\": [\n    \"# What model to download.\\n\",\n    \"MODEL_NAME = 'ssd_mobilenet_v1_coco_11_06_2017'\\n\",\n    \"MODEL_FILE = MODEL_NAME + '.tar.gz'\\n\",\n    \"DOWNLOAD_BASE = 'http://download.tensorflow.org/models/object_detection/'\\n\",\n    \"\\n\",\n    \"# Path to frozen detection graph. This is the actual model that is used for the object detection.\\n\",\n    \"PATH_TO_CKPT = MODEL_NAME + '/frozen_inference_graph.pb'\\n\",\n    \"\\n\",\n    \"# List of the strings that is used to add correct label for each box.\\n\",\n    \"PATH_TO_LABELS = os.path.join('data', 'mscoco_label_map.pbtxt')\\n\",\n    \"\\n\",\n    \"NUM_CLASSES = 90\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"## Download Model\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": null,\n   \"metadata\": {\n    \"collapsed\": true\n   },\n   \"outputs\": [],\n   \"source\": [\n    \"opener = urllib.request.URLopener()\\n\",\n    \"opener.retrieve(DOWNLOAD_BASE + MODEL_FILE, MODEL_FILE)\\n\",\n    \"tar_file = tarfile.open(MODEL_FILE)\\n\",\n    \"for file in tar_file.getmembers():\\n\",\n    \"    file_name = os.path.basename(file.name)\\n\",\n    \"    if 'frozen_inference_graph.pb' in file_name:\\n\",\n    \"        tar_file.extract(file, os.getcwd())\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"## Load a (frozen) Tensorflow model into memory.\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": null,\n   \"metadata\": {\n    \"collapsed\": true\n   },\n   \"outputs\": [],\n   \"source\": [\n    \"detection_graph = tf.Graph()\\n\",\n    \"with detection_graph.as_default():\\n\",\n    \"    od_graph_def = tf.GraphDef()\\n\",\n    \"    with tf.gfile.GFile(PATH_TO_CKPT, 'rb') as fid:\\n\",\n    \"        serialized_graph = fid.read()\\n\",\n    \"        od_graph_def.ParseFromString(serialized_graph)\\n\",\n    \"        tf.import_graph_def(od_graph_def, name='')\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"## Loading label map\\n\",\n    \"Label maps map indices to category names, so that when our convolution network predicts `5`, we know that this corresponds to `airplane`.  Here we use internal utility functions, but anything that returns a dictionary mapping integers to appropriate string labels would be fine\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": null,\n   \"metadata\": {\n    \"collapsed\": true\n   },\n   \"outputs\": [],\n   \"source\": [\n    \"label_map = label_map_util.load_labelmap(PATH_TO_LABELS)\\n\",\n    \"categories = label_map_util.convert_label_map_to_categories(label_map, max_num_classes=NUM_CLASSES, use_display_name=True)\\n\",\n    \"category_index = label_map_util.create_category_index(categories)\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"## Helper code\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": null,\n   \"metadata\": {\n    \"collapsed\": true\n   },\n   \"outputs\": [],\n   \"source\": [\n    \"def load_image_into_numpy_array(image):\\n\",\n    \"  (im_width, im_height) = image.size\\n\",\n    \"  return np.array(image.getdata()).reshape(\\n\",\n    \"      (im_height, im_width, 3)).astype(np.uint8)\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"# Detection\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": null,\n   \"metadata\": {\n    \"collapsed\": true\n   },\n   \"outputs\": [],\n   \"source\": [\n    \"# For the sake of simplicity we will use only 2 images:\\n\",\n    \"# image1.jpg\\n\",\n    \"# image2.jpg\\n\",\n    \"# If you want to test the code with your images, just add path to the images to the TEST_IMAGE_PATHS.\\n\",\n    \"PATH_TO_TEST_IMAGES_DIR = 'test_images'\\n\",\n    \"TEST_IMAGE_PATHS = [ os.path.join(PATH_TO_TEST_IMAGES_DIR, 'image{}.jpg'.format(i)) for i in range(1, 3) ]\\n\",\n    \"\\n\",\n    \"# Size, in inches, of the output images.\\n\",\n    \"IMAGE_SIZE = (12, 8)\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": null,\n   \"metadata\": {\n    \"collapsed\": false,\n    \"scrolled\": true\n   },\n   \"outputs\": [],\n   \"source\": [\n    \"with detection_graph.as_default():\\n\",\n    \"  with tf.Session(graph=detection_graph) as sess:\\n\",\n    \"    for image_path in TEST_IMAGE_PATHS:\\n\",\n    \"      image = Image.open(image_path)\\n\",\n    \"      # the array based representation of the image will be used later in order to prepare the\\n\",\n    \"      # result image with boxes and labels on it.\\n\",\n    \"      image_np = load_image_into_numpy_array(image)\\n\",\n    \"      # Expand dimensions since the model expects images to have shape: [1, None, None, 3]\\n\",\n    \"      image_np_expanded = np.expand_dims(image_np, axis=0)\\n\",\n    \"      image_tensor = detection_graph.get_tensor_by_name('image_tensor:0')\\n\",\n    \"      # Each box represents a part of the image where a particular object was detected.\\n\",\n    \"      boxes = detection_graph.get_tensor_by_name('detection_boxes:0')\\n\",\n    \"      # Each score represent how level of confidence for each of the objects.\\n\",\n    \"      # Score is shown on the result image, together with the class label.\\n\",\n    \"      scores = detection_graph.get_tensor_by_name('detection_scores:0')\\n\",\n    \"      classes = detection_graph.get_tensor_by_name('detection_classes:0')\\n\",\n    \"      num_detections = detection_graph.get_tensor_by_name('num_detections:0')\\n\",\n    \"      # Actual detection.\\n\",\n    \"      (boxes, scores, classes, num_detections) = sess.run(\\n\",\n    \"          [boxes, scores, classes, num_detections],\\n\",\n    \"          feed_dict={image_tensor: image_np_expanded})\\n\",\n    \"      # Visualization of the results of a detection.\\n\",\n    \"      vis_util.visualize_boxes_and_labels_on_image_array(\\n\",\n    \"          image_np,\\n\",\n    \"          np.squeeze(boxes),\\n\",\n    \"          np.squeeze(classes).astype(np.int32),\\n\",\n    \"          np.squeeze(scores),\\n\",\n    \"          category_index,\\n\",\n    \"          use_normalized_coordinates=True,\\n\",\n    \"          line_thickness=8)\\n\",\n    \"      plt.figure(figsize=IMAGE_SIZE)\\n\",\n    \"      plt.imshow(image_np)\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": null,\n   \"metadata\": {\n    \"collapsed\": true\n   },\n   \"outputs\": [],\n   \"source\": []\n  }\n ],\n \"metadata\": {\n  \"kernelspec\": {\n   \"display_name\": \"Python 3\",\n   \"language\": \"python\",\n   \"name\": \"python3\"\n  },\n  \"language_info\": {\n   \"codemirror_mode\": {\n    \"name\": \"ipython\",\n    \"version\": 3\n   },\n   \"file_extension\": \".py\",\n   \"mimetype\": \"text/x-python\",\n   \"name\": \"python\",\n   \"nbconvert_exporter\": \"python\",\n   \"pygments_lexer\": \"ipython3\",\n   \"version\": \"3.5.2\"\n  },\n  \"widgets\": {\n   \"state\": {},\n   \"version\": \"1.1.2\"\n  }\n },\n \"nbformat\": 4,\n \"nbformat_minor\": 2\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/BUILD",
    "content": "# Tensorflow Object Detection API: Configuration protos.\n\npackage(\n    default_visibility = [\"//visibility:public\"],\n)\n\nlicenses([\"notice\"])\n\nproto_library(\n    name = \"argmax_matcher_proto\",\n    srcs = [\"argmax_matcher.proto\"],\n)\n\npy_proto_library(\n    name = \"argmax_matcher_py_pb2\",\n    api_version = 2,\n    deps = [\":argmax_matcher_proto\"],\n)\n\nproto_library(\n    name = \"bipartite_matcher_proto\",\n    srcs = [\"bipartite_matcher.proto\"],\n)\n\npy_proto_library(\n    name = \"bipartite_matcher_py_pb2\",\n    api_version = 2,\n    deps = [\":bipartite_matcher_proto\"],\n)\n\nproto_library(\n    name = \"matcher_proto\",\n    srcs = [\"matcher.proto\"],\n    deps = [\n        \":argmax_matcher_proto\",\n        \":bipartite_matcher_proto\",\n    ],\n)\n\npy_proto_library(\n    name = \"matcher_py_pb2\",\n    api_version = 2,\n    deps = [\":matcher_proto\"],\n)\n\nproto_library(\n    name = \"faster_rcnn_box_coder_proto\",\n    srcs = [\"faster_rcnn_box_coder.proto\"],\n)\n\npy_proto_library(\n    name = \"faster_rcnn_box_coder_py_pb2\",\n    api_version = 2,\n    deps = [\":faster_rcnn_box_coder_proto\"],\n)\n\nproto_library(\n    name = \"mean_stddev_box_coder_proto\",\n    srcs = [\"mean_stddev_box_coder.proto\"],\n)\n\npy_proto_library(\n    name = \"mean_stddev_box_coder_py_pb2\",\n    api_version = 2,\n    deps = [\":mean_stddev_box_coder_proto\"],\n)\n\nproto_library(\n    name = \"square_box_coder_proto\",\n    srcs = [\"square_box_coder.proto\"],\n)\n\npy_proto_library(\n    name = \"square_box_coder_py_pb2\",\n    api_version = 2,\n    deps = [\":square_box_coder_proto\"],\n)\n\nproto_library(\n    name = \"box_coder_proto\",\n    srcs = [\"box_coder.proto\"],\n    deps = [\n        \":faster_rcnn_box_coder_proto\",\n        \":mean_stddev_box_coder_proto\",\n        \":square_box_coder_proto\",\n    ],\n)\n\npy_proto_library(\n    name = \"box_coder_py_pb2\",\n    api_version = 2,\n    deps = [\":box_coder_proto\"],\n)\n\nproto_library(\n    name = \"grid_anchor_generator_proto\",\n    srcs = [\"grid_anchor_generator.proto\"],\n)\n\npy_proto_library(\n    name = \"grid_anchor_generator_py_pb2\",\n    api_version = 2,\n    deps = [\":grid_anchor_generator_proto\"],\n)\n\nproto_library(\n    name = \"ssd_anchor_generator_proto\",\n    srcs = [\"ssd_anchor_generator.proto\"],\n)\n\npy_proto_library(\n    name = \"ssd_anchor_generator_py_pb2\",\n    api_version = 2,\n    deps = [\":ssd_anchor_generator_proto\"],\n)\n\nproto_library(\n    name = \"anchor_generator_proto\",\n    srcs = [\"anchor_generator.proto\"],\n    deps = [\n        \":grid_anchor_generator_proto\",\n        \":ssd_anchor_generator_proto\",\n    ],\n)\n\npy_proto_library(\n    name = \"anchor_generator_py_pb2\",\n    api_version = 2,\n    deps = [\":anchor_generator_proto\"],\n)\n\nproto_library(\n    name = \"input_reader_proto\",\n    srcs = [\"input_reader.proto\"],\n)\n\npy_proto_library(\n    name = \"input_reader_py_pb2\",\n    api_version = 2,\n    deps = [\":input_reader_proto\"],\n)\n\nproto_library(\n    name = \"losses_proto\",\n    srcs = [\"losses.proto\"],\n)\n\npy_proto_library(\n    name = \"losses_py_pb2\",\n    api_version = 2,\n    deps = [\":losses_proto\"],\n)\n\nproto_library(\n    name = \"optimizer_proto\",\n    srcs = [\"optimizer.proto\"],\n)\n\npy_proto_library(\n    name = \"optimizer_py_pb2\",\n    api_version = 2,\n    deps = [\":optimizer_proto\"],\n)\n\nproto_library(\n    name = \"post_processing_proto\",\n    srcs = [\"post_processing.proto\"],\n)\n\npy_proto_library(\n    name = \"post_processing_py_pb2\",\n    api_version = 2,\n    deps = [\":post_processing_proto\"],\n)\n\nproto_library(\n    name = \"hyperparams_proto\",\n    srcs = [\"hyperparams.proto\"],\n)\n\npy_proto_library(\n    name = \"hyperparams_py_pb2\",\n    api_version = 2,\n    deps = [\":hyperparams_proto\"],\n)\n\nproto_library(\n    name = \"box_predictor_proto\",\n    srcs = [\"box_predictor.proto\"],\n    deps = [\":hyperparams_proto\"],\n)\n\npy_proto_library(\n    name = \"box_predictor_py_pb2\",\n    api_version = 2,\n    deps = [\":box_predictor_proto\"],\n)\n\nproto_library(\n    name = \"region_similarity_calculator_proto\",\n    srcs = [\"region_similarity_calculator.proto\"],\n    deps = [],\n)\n\npy_proto_library(\n    name = \"region_similarity_calculator_py_pb2\",\n    api_version = 2,\n    deps = [\":region_similarity_calculator_proto\"],\n)\n\nproto_library(\n    name = \"preprocessor_proto\",\n    srcs = [\"preprocessor.proto\"],\n)\n\npy_proto_library(\n    name = \"preprocessor_py_pb2\",\n    api_version = 2,\n    deps = [\":preprocessor_proto\"],\n)\n\nproto_library(\n    name = \"train_proto\",\n    srcs = [\"train.proto\"],\n    deps = [\n        \":optimizer_proto\",\n        \":preprocessor_proto\",\n    ],\n)\n\npy_proto_library(\n    name = \"train_py_pb2\",\n    api_version = 2,\n    deps = [\":train_proto\"],\n)\n\nproto_library(\n    name = \"eval_proto\",\n    srcs = [\"eval.proto\"],\n)\n\npy_proto_library(\n    name = \"eval_py_pb2\",\n    api_version = 2,\n    deps = [\":eval_proto\"],\n)\n\nproto_library(\n    name = \"image_resizer_proto\",\n    srcs = [\"image_resizer.proto\"],\n)\n\npy_proto_library(\n    name = \"image_resizer_py_pb2\",\n    api_version = 2,\n    deps = [\":image_resizer_proto\"],\n)\n\nproto_library(\n    name = \"faster_rcnn_proto\",\n    srcs = [\"faster_rcnn.proto\"],\n    deps = [\n        \":box_predictor_proto\",\n        \"//object_detection/protos:anchor_generator_proto\",\n        \"//object_detection/protos:hyperparams_proto\",\n        \"//object_detection/protos:image_resizer_proto\",\n        \"//object_detection/protos:losses_proto\",\n        \"//object_detection/protos:post_processing_proto\",\n    ],\n)\n\nproto_library(\n    name = \"ssd_proto\",\n    srcs = [\"ssd.proto\"],\n    deps = [\n        \":anchor_generator_proto\",\n        \":box_coder_proto\",\n        \":box_predictor_proto\",\n        \":hyperparams_proto\",\n        \":image_resizer_proto\",\n        \":losses_proto\",\n        \":matcher_proto\",\n        \":post_processing_proto\",\n        \":region_similarity_calculator_proto\",\n    ],\n)\n\nproto_library(\n    name = \"model_proto\",\n    srcs = [\"model.proto\"],\n    deps = [\n        \":faster_rcnn_proto\",\n        \":ssd_proto\",\n    ],\n)\n\npy_proto_library(\n    name = \"model_py_pb2\",\n    api_version = 2,\n    deps = [\":model_proto\"],\n)\n\nproto_library(\n    name = \"pipeline_proto\",\n    srcs = [\"pipeline.proto\"],\n    deps = [\n        \":eval_proto\",\n        \":input_reader_proto\",\n        \":model_proto\",\n        \":train_proto\",\n    ],\n)\n\npy_proto_library(\n    name = \"pipeline_py_pb2\",\n    api_version = 2,\n    deps = [\":pipeline_proto\"],\n)\n\nproto_library(\n    name = \"string_int_label_map_proto\",\n    srcs = [\"string_int_label_map.proto\"],\n)\n\npy_proto_library(\n    name = \"string_int_label_map_py_pb2\",\n    api_version = 2,\n    deps = [\":string_int_label_map_proto\"],\n)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/__init__.py",
    "content": ""
  },
  {
    "path": "object_detector_app/object_detection/protos/anchor_generator.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\nimport \"object_detection/protos/grid_anchor_generator.proto\";\nimport \"object_detection/protos/ssd_anchor_generator.proto\";\n\n// Configuration proto for the anchor generator to use in the object detection\n// pipeline. See core/anchor_generator.py for details.\nmessage AnchorGenerator {\n  oneof anchor_generator_oneof {\n    GridAnchorGenerator grid_anchor_generator = 1;\n    SsdAnchorGenerator ssd_anchor_generator = 2;\n  }\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/anchor_generator_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/anchor_generator.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\nimport object_detection.protos.grid_anchor_generator_pb2\nimport object_detection.protos.ssd_anchor_generator_pb2\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/anchor_generator.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n.object_detection/protos/anchor_generator.proto\\x12\\x17object_detection.protos\\x1a\\x33object_detection/protos/grid_anchor_generator.proto\\x1a\\x32object_detection/protos/ssd_anchor_generator.proto\\\"\\xc7\\x01\\n\\x0f\\x41nchorGenerator\\x12M\\n\\x15grid_anchor_generator\\x18\\x01 \\x01(\\x0b\\x32,.object_detection.protos.GridAnchorGeneratorH\\x00\\x12K\\n\\x14ssd_anchor_generator\\x18\\x02 \\x01(\\x0b\\x32+.object_detection.protos.SsdAnchorGeneratorH\\x00\\x42\\x18\\n\\x16\\x61nchor_generator_oneof')\n  ,\n  dependencies=[object_detection.protos.grid_anchor_generator_pb2.DESCRIPTOR,object_detection.protos.ssd_anchor_generator_pb2.DESCRIPTOR,])\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_ANCHORGENERATOR = _descriptor.Descriptor(\n  name='AnchorGenerator',\n  full_name='object_detection.protos.AnchorGenerator',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='grid_anchor_generator', full_name='object_detection.protos.AnchorGenerator.grid_anchor_generator', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='ssd_anchor_generator', full_name='object_detection.protos.AnchorGenerator.ssd_anchor_generator', index=1,\n      number=2, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n    _descriptor.OneofDescriptor(\n      name='anchor_generator_oneof', full_name='object_detection.protos.AnchorGenerator.anchor_generator_oneof',\n      index=0, containing_type=None, fields=[]),\n  ],\n  serialized_start=181,\n  serialized_end=380,\n)\n\n_ANCHORGENERATOR.fields_by_name['grid_anchor_generator'].message_type = object_detection.protos.grid_anchor_generator_pb2._GRIDANCHORGENERATOR\n_ANCHORGENERATOR.fields_by_name['ssd_anchor_generator'].message_type = object_detection.protos.ssd_anchor_generator_pb2._SSDANCHORGENERATOR\n_ANCHORGENERATOR.oneofs_by_name['anchor_generator_oneof'].fields.append(\n  _ANCHORGENERATOR.fields_by_name['grid_anchor_generator'])\n_ANCHORGENERATOR.fields_by_name['grid_anchor_generator'].containing_oneof = _ANCHORGENERATOR.oneofs_by_name['anchor_generator_oneof']\n_ANCHORGENERATOR.oneofs_by_name['anchor_generator_oneof'].fields.append(\n  _ANCHORGENERATOR.fields_by_name['ssd_anchor_generator'])\n_ANCHORGENERATOR.fields_by_name['ssd_anchor_generator'].containing_oneof = _ANCHORGENERATOR.oneofs_by_name['anchor_generator_oneof']\nDESCRIPTOR.message_types_by_name['AnchorGenerator'] = _ANCHORGENERATOR\n\nAnchorGenerator = _reflection.GeneratedProtocolMessageType('AnchorGenerator', (_message.Message,), dict(\n  DESCRIPTOR = _ANCHORGENERATOR,\n  __module__ = 'object_detection.protos.anchor_generator_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.AnchorGenerator)\n  ))\n_sym_db.RegisterMessage(AnchorGenerator)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/argmax_matcher.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\n// Configuration proto for ArgMaxMatcher. See\n// matchers/argmax_matcher.py for details.\nmessage ArgMaxMatcher {\n  // Threshold for positive matches.\n  optional float matched_threshold = 1 [default = 0.5];\n\n  // Threshold for negative matches.\n  optional float unmatched_threshold = 2 [default = 0.5];\n\n  // Whether to construct ArgMaxMatcher without thresholds.\n  optional bool ignore_thresholds = 3 [default = false];\n\n  // If True then negative matches are the ones below the unmatched_threshold,\n  // whereas ignored matches are in between the matched and umatched\n  // threshold. If False, then negative matches are in between the matched\n  // and unmatched threshold, and everything lower than unmatched is ignored.\n  optional bool negatives_lower_than_unmatched = 4 [default = true];\n\n  // Whether to ensure each row is matched to at least one column.\n  optional bool force_match_for_each_row = 5 [default = false];\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/argmax_matcher_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/argmax_matcher.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/argmax_matcher.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n,object_detection/protos/argmax_matcher.proto\\x12\\x17object_detection.protos\\\"\\xca\\x01\\n\\rArgMaxMatcher\\x12\\x1e\\n\\x11matched_threshold\\x18\\x01 \\x01(\\x02:\\x03\\x30.5\\x12 \\n\\x13unmatched_threshold\\x18\\x02 \\x01(\\x02:\\x03\\x30.5\\x12 \\n\\x11ignore_thresholds\\x18\\x03 \\x01(\\x08:\\x05\\x66\\x61lse\\x12,\\n\\x1enegatives_lower_than_unmatched\\x18\\x04 \\x01(\\x08:\\x04true\\x12\\'\\n\\x18\\x66orce_match_for_each_row\\x18\\x05 \\x01(\\x08:\\x05\\x66\\x61lse')\n)\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_ARGMAXMATCHER = _descriptor.Descriptor(\n  name='ArgMaxMatcher',\n  full_name='object_detection.protos.ArgMaxMatcher',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='matched_threshold', full_name='object_detection.protos.ArgMaxMatcher.matched_threshold', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.5,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='unmatched_threshold', full_name='object_detection.protos.ArgMaxMatcher.unmatched_threshold', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.5,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='ignore_thresholds', full_name='object_detection.protos.ArgMaxMatcher.ignore_thresholds', index=2,\n      number=3, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='negatives_lower_than_unmatched', full_name='object_detection.protos.ArgMaxMatcher.negatives_lower_than_unmatched', index=3,\n      number=4, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=True,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='force_match_for_each_row', full_name='object_detection.protos.ArgMaxMatcher.force_match_for_each_row', index=4,\n      number=5, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=74,\n  serialized_end=276,\n)\n\nDESCRIPTOR.message_types_by_name['ArgMaxMatcher'] = _ARGMAXMATCHER\n\nArgMaxMatcher = _reflection.GeneratedProtocolMessageType('ArgMaxMatcher', (_message.Message,), dict(\n  DESCRIPTOR = _ARGMAXMATCHER,\n  __module__ = 'object_detection.protos.argmax_matcher_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.ArgMaxMatcher)\n  ))\n_sym_db.RegisterMessage(ArgMaxMatcher)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/bipartite_matcher.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\n// Configuration proto for bipartite matcher. See\n// matchers/bipartite_matcher.py for details.\nmessage BipartiteMatcher {\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/bipartite_matcher_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/bipartite_matcher.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/bipartite_matcher.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n/object_detection/protos/bipartite_matcher.proto\\x12\\x17object_detection.protos\\\"\\x12\\n\\x10\\x42ipartiteMatcher')\n)\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_BIPARTITEMATCHER = _descriptor.Descriptor(\n  name='BipartiteMatcher',\n  full_name='object_detection.protos.BipartiteMatcher',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=76,\n  serialized_end=94,\n)\n\nDESCRIPTOR.message_types_by_name['BipartiteMatcher'] = _BIPARTITEMATCHER\n\nBipartiteMatcher = _reflection.GeneratedProtocolMessageType('BipartiteMatcher', (_message.Message,), dict(\n  DESCRIPTOR = _BIPARTITEMATCHER,\n  __module__ = 'object_detection.protos.bipartite_matcher_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.BipartiteMatcher)\n  ))\n_sym_db.RegisterMessage(BipartiteMatcher)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/box_coder.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\nimport \"object_detection/protos/faster_rcnn_box_coder.proto\";\nimport \"object_detection/protos/mean_stddev_box_coder.proto\";\nimport \"object_detection/protos/square_box_coder.proto\";\n\n// Configuration proto for the box coder to be used in the object detection\n// pipeline. See core/box_coder.py for details.\nmessage BoxCoder {\n  oneof box_coder_oneof {\n    FasterRcnnBoxCoder faster_rcnn_box_coder = 1;\n    MeanStddevBoxCoder mean_stddev_box_coder = 2;\n    SquareBoxCoder square_box_coder = 3;\n  }\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/box_coder_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/box_coder.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\nimport object_detection.protos.faster_rcnn_box_coder_pb2\nimport object_detection.protos.mean_stddev_box_coder_pb2\nimport object_detection.protos.square_box_coder_pb2\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/box_coder.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n\\'object_detection/protos/box_coder.proto\\x12\\x17object_detection.protos\\x1a\\x33object_detection/protos/faster_rcnn_box_coder.proto\\x1a\\x33object_detection/protos/mean_stddev_box_coder.proto\\x1a.object_detection/protos/square_box_coder.proto\\\"\\xfe\\x01\\n\\x08\\x42oxCoder\\x12L\\n\\x15\\x66\\x61ster_rcnn_box_coder\\x18\\x01 \\x01(\\x0b\\x32+.object_detection.protos.FasterRcnnBoxCoderH\\x00\\x12L\\n\\x15mean_stddev_box_coder\\x18\\x02 \\x01(\\x0b\\x32+.object_detection.protos.MeanStddevBoxCoderH\\x00\\x12\\x43\\n\\x10square_box_coder\\x18\\x03 \\x01(\\x0b\\x32\\'.object_detection.protos.SquareBoxCoderH\\x00\\x42\\x11\\n\\x0f\\x62ox_coder_oneof')\n  ,\n  dependencies=[object_detection.protos.faster_rcnn_box_coder_pb2.DESCRIPTOR,object_detection.protos.mean_stddev_box_coder_pb2.DESCRIPTOR,object_detection.protos.square_box_coder_pb2.DESCRIPTOR,])\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_BOXCODER = _descriptor.Descriptor(\n  name='BoxCoder',\n  full_name='object_detection.protos.BoxCoder',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='faster_rcnn_box_coder', full_name='object_detection.protos.BoxCoder.faster_rcnn_box_coder', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='mean_stddev_box_coder', full_name='object_detection.protos.BoxCoder.mean_stddev_box_coder', index=1,\n      number=2, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='square_box_coder', full_name='object_detection.protos.BoxCoder.square_box_coder', index=2,\n      number=3, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n    _descriptor.OneofDescriptor(\n      name='box_coder_oneof', full_name='object_detection.protos.BoxCoder.box_coder_oneof',\n      index=0, containing_type=None, fields=[]),\n  ],\n  serialized_start=223,\n  serialized_end=477,\n)\n\n_BOXCODER.fields_by_name['faster_rcnn_box_coder'].message_type = object_detection.protos.faster_rcnn_box_coder_pb2._FASTERRCNNBOXCODER\n_BOXCODER.fields_by_name['mean_stddev_box_coder'].message_type = object_detection.protos.mean_stddev_box_coder_pb2._MEANSTDDEVBOXCODER\n_BOXCODER.fields_by_name['square_box_coder'].message_type = object_detection.protos.square_box_coder_pb2._SQUAREBOXCODER\n_BOXCODER.oneofs_by_name['box_coder_oneof'].fields.append(\n  _BOXCODER.fields_by_name['faster_rcnn_box_coder'])\n_BOXCODER.fields_by_name['faster_rcnn_box_coder'].containing_oneof = _BOXCODER.oneofs_by_name['box_coder_oneof']\n_BOXCODER.oneofs_by_name['box_coder_oneof'].fields.append(\n  _BOXCODER.fields_by_name['mean_stddev_box_coder'])\n_BOXCODER.fields_by_name['mean_stddev_box_coder'].containing_oneof = _BOXCODER.oneofs_by_name['box_coder_oneof']\n_BOXCODER.oneofs_by_name['box_coder_oneof'].fields.append(\n  _BOXCODER.fields_by_name['square_box_coder'])\n_BOXCODER.fields_by_name['square_box_coder'].containing_oneof = _BOXCODER.oneofs_by_name['box_coder_oneof']\nDESCRIPTOR.message_types_by_name['BoxCoder'] = _BOXCODER\n\nBoxCoder = _reflection.GeneratedProtocolMessageType('BoxCoder', (_message.Message,), dict(\n  DESCRIPTOR = _BOXCODER,\n  __module__ = 'object_detection.protos.box_coder_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.BoxCoder)\n  ))\n_sym_db.RegisterMessage(BoxCoder)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/box_predictor.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\nimport \"object_detection/protos/hyperparams.proto\";\n\n\n// Configuration proto for box predictor. See core/box_predictor.py for details.\nmessage BoxPredictor {\n  oneof box_predictor_oneof {\n    ConvolutionalBoxPredictor convolutional_box_predictor = 1;\n    MaskRCNNBoxPredictor mask_rcnn_box_predictor = 2;\n    RfcnBoxPredictor rfcn_box_predictor = 3;\n  }\n}\n\n// Configuration proto for Convolutional box predictor.\nmessage ConvolutionalBoxPredictor {\n  // Hyperparameters for convolution ops used in the box predictor.\n  optional Hyperparams conv_hyperparams = 1;\n\n  // Minumum feature depth prior to predicting box encodings and class\n  // predictions.\n  optional int32 min_depth = 2 [default = 0];\n\n  // Maximum feature depth prior to predicting box encodings and class\n  // predictions. If max_depth is set to 0, no additional feature map will be\n  // inserted before location and class predictions.\n  optional int32 max_depth = 3 [default = 0];\n\n  // Number of the additional conv layers before the predictor.\n  optional int32 num_layers_before_predictor = 4 [default = 0];\n\n  // Whether to use dropout for class prediction.\n  optional bool use_dropout = 5 [default = true];\n\n  // Keep probability for dropout\n  optional float dropout_keep_probability = 6 [default = 0.8];\n\n  // Size of final convolution kernel. If the spatial resolution of the feature\n  // map is smaller than the kernel size, then the kernel size is set to\n  // min(feature_width, feature_height).\n  optional int32 kernel_size = 7 [default = 1];\n\n  // Size of the encoding for boxes.\n  optional int32 box_code_size = 8 [default = 4];\n\n  // Whether to apply sigmoid to the output of class predictions.\n  // TODO: Do we need this since we have a post processing module.?\n  optional bool apply_sigmoid_to_scores = 9 [default = false];\n}\n\nmessage MaskRCNNBoxPredictor {\n  // Hyperparameters for fully connected ops used in the box predictor.\n  optional Hyperparams fc_hyperparams = 1;\n\n  // Whether to use dropout op prior to the both box and class predictions.\n  optional bool use_dropout = 2 [default= false];\n\n  // Keep probability for dropout. This is only used if use_dropout is true.\n  optional float dropout_keep_probability = 3 [default = 0.5];\n\n  // Size of the encoding for the boxes.\n  optional int32 box_code_size = 4 [default = 4];\n\n  // Hyperparameters for convolution ops used in the box predictor.\n  optional Hyperparams conv_hyperparams = 5;\n\n  // Whether to predict instance masks inside detection boxes.\n  optional bool predict_instance_masks = 6 [default = false];\n\n  // The depth for the first conv2d_transpose op  applied to the\n  // image_features in the mask prediciton branch\n  optional int32 mask_prediction_conv_depth = 7 [default = 256];\n\n  // Whether to predict keypoints inside detection boxes.\n  optional bool predict_keypoints = 8 [default = false];\n}\n\nmessage RfcnBoxPredictor {\n  // Hyperparameters for convolution ops used in the box predictor.\n  optional Hyperparams conv_hyperparams = 1;\n\n  // Bin sizes for RFCN crops.\n  optional int32 num_spatial_bins_height = 2 [default = 3];\n\n  optional int32 num_spatial_bins_width = 3 [default = 3];\n\n  // Target depth to reduce the input image features to.\n  optional int32 depth = 4 [default=1024];\n\n  // Size of the encoding for the boxes.\n  optional int32 box_code_size = 5 [default = 4];\n\n  // Size to resize the rfcn crops to.\n  optional int32 crop_height = 6 [default= 12];\n\n  optional int32 crop_width = 7 [default=12];\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/box_predictor_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/box_predictor.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\nimport object_detection.protos.hyperparams_pb2\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/box_predictor.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n+object_detection/protos/box_predictor.proto\\x12\\x17object_detection.protos\\x1a)object_detection/protos/hyperparams.proto\\\"\\x9b\\x02\\n\\x0c\\x42oxPredictor\\x12Y\\n\\x1b\\x63onvolutional_box_predictor\\x18\\x01 \\x01(\\x0b\\x32\\x32.object_detection.protos.ConvolutionalBoxPredictorH\\x00\\x12P\\n\\x17mask_rcnn_box_predictor\\x18\\x02 \\x01(\\x0b\\x32-.object_detection.protos.MaskRCNNBoxPredictorH\\x00\\x12G\\n\\x12rfcn_box_predictor\\x18\\x03 \\x01(\\x0b\\x32).object_detection.protos.RfcnBoxPredictorH\\x00\\x42\\x15\\n\\x13\\x62ox_predictor_oneof\\\"\\xcb\\x02\\n\\x19\\x43onvolutionalBoxPredictor\\x12>\\n\\x10\\x63onv_hyperparams\\x18\\x01 \\x01(\\x0b\\x32$.object_detection.protos.Hyperparams\\x12\\x14\\n\\tmin_depth\\x18\\x02 \\x01(\\x05:\\x01\\x30\\x12\\x14\\n\\tmax_depth\\x18\\x03 \\x01(\\x05:\\x01\\x30\\x12&\\n\\x1bnum_layers_before_predictor\\x18\\x04 \\x01(\\x05:\\x01\\x30\\x12\\x19\\n\\x0buse_dropout\\x18\\x05 \\x01(\\x08:\\x04true\\x12%\\n\\x18\\x64ropout_keep_probability\\x18\\x06 \\x01(\\x02:\\x03\\x30.8\\x12\\x16\\n\\x0bkernel_size\\x18\\x07 \\x01(\\x05:\\x01\\x31\\x12\\x18\\n\\rbox_code_size\\x18\\x08 \\x01(\\x05:\\x01\\x34\\x12&\\n\\x17\\x61pply_sigmoid_to_scores\\x18\\t \\x01(\\x08:\\x05\\x66\\x61lse\\\"\\xe3\\x02\\n\\x14MaskRCNNBoxPredictor\\x12<\\n\\x0e\\x66\\x63_hyperparams\\x18\\x01 \\x01(\\x0b\\x32$.object_detection.protos.Hyperparams\\x12\\x1a\\n\\x0buse_dropout\\x18\\x02 \\x01(\\x08:\\x05\\x66\\x61lse\\x12%\\n\\x18\\x64ropout_keep_probability\\x18\\x03 \\x01(\\x02:\\x03\\x30.5\\x12\\x18\\n\\rbox_code_size\\x18\\x04 \\x01(\\x05:\\x01\\x34\\x12>\\n\\x10\\x63onv_hyperparams\\x18\\x05 \\x01(\\x0b\\x32$.object_detection.protos.Hyperparams\\x12%\\n\\x16predict_instance_masks\\x18\\x06 \\x01(\\x08:\\x05\\x66\\x61lse\\x12\\'\\n\\x1amask_prediction_conv_depth\\x18\\x07 \\x01(\\x05:\\x03\\x32\\x35\\x36\\x12 \\n\\x11predict_keypoints\\x18\\x08 \\x01(\\x08:\\x05\\x66\\x61lse\\\"\\xf9\\x01\\n\\x10RfcnBoxPredictor\\x12>\\n\\x10\\x63onv_hyperparams\\x18\\x01 \\x01(\\x0b\\x32$.object_detection.protos.Hyperparams\\x12\\\"\\n\\x17num_spatial_bins_height\\x18\\x02 \\x01(\\x05:\\x01\\x33\\x12!\\n\\x16num_spatial_bins_width\\x18\\x03 \\x01(\\x05:\\x01\\x33\\x12\\x13\\n\\x05\\x64\\x65pth\\x18\\x04 \\x01(\\x05:\\x04\\x31\\x30\\x32\\x34\\x12\\x18\\n\\rbox_code_size\\x18\\x05 \\x01(\\x05:\\x01\\x34\\x12\\x17\\n\\x0b\\x63rop_height\\x18\\x06 \\x01(\\x05:\\x02\\x31\\x32\\x12\\x16\\n\\ncrop_width\\x18\\x07 \\x01(\\x05:\\x02\\x31\\x32')\n  ,\n  dependencies=[object_detection.protos.hyperparams_pb2.DESCRIPTOR,])\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_BOXPREDICTOR = _descriptor.Descriptor(\n  name='BoxPredictor',\n  full_name='object_detection.protos.BoxPredictor',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='convolutional_box_predictor', full_name='object_detection.protos.BoxPredictor.convolutional_box_predictor', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='mask_rcnn_box_predictor', full_name='object_detection.protos.BoxPredictor.mask_rcnn_box_predictor', index=1,\n      number=2, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='rfcn_box_predictor', full_name='object_detection.protos.BoxPredictor.rfcn_box_predictor', index=2,\n      number=3, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n    _descriptor.OneofDescriptor(\n      name='box_predictor_oneof', full_name='object_detection.protos.BoxPredictor.box_predictor_oneof',\n      index=0, containing_type=None, fields=[]),\n  ],\n  serialized_start=116,\n  serialized_end=399,\n)\n\n\n_CONVOLUTIONALBOXPREDICTOR = _descriptor.Descriptor(\n  name='ConvolutionalBoxPredictor',\n  full_name='object_detection.protos.ConvolutionalBoxPredictor',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='conv_hyperparams', full_name='object_detection.protos.ConvolutionalBoxPredictor.conv_hyperparams', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='min_depth', full_name='object_detection.protos.ConvolutionalBoxPredictor.min_depth', index=1,\n      number=2, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_depth', full_name='object_detection.protos.ConvolutionalBoxPredictor.max_depth', index=2,\n      number=3, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='num_layers_before_predictor', full_name='object_detection.protos.ConvolutionalBoxPredictor.num_layers_before_predictor', index=3,\n      number=4, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='use_dropout', full_name='object_detection.protos.ConvolutionalBoxPredictor.use_dropout', index=4,\n      number=5, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=True,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='dropout_keep_probability', full_name='object_detection.protos.ConvolutionalBoxPredictor.dropout_keep_probability', index=5,\n      number=6, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.8,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='kernel_size', full_name='object_detection.protos.ConvolutionalBoxPredictor.kernel_size', index=6,\n      number=7, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='box_code_size', full_name='object_detection.protos.ConvolutionalBoxPredictor.box_code_size', index=7,\n      number=8, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=4,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='apply_sigmoid_to_scores', full_name='object_detection.protos.ConvolutionalBoxPredictor.apply_sigmoid_to_scores', index=8,\n      number=9, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=402,\n  serialized_end=733,\n)\n\n\n_MASKRCNNBOXPREDICTOR = _descriptor.Descriptor(\n  name='MaskRCNNBoxPredictor',\n  full_name='object_detection.protos.MaskRCNNBoxPredictor',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='fc_hyperparams', full_name='object_detection.protos.MaskRCNNBoxPredictor.fc_hyperparams', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='use_dropout', full_name='object_detection.protos.MaskRCNNBoxPredictor.use_dropout', index=1,\n      number=2, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='dropout_keep_probability', full_name='object_detection.protos.MaskRCNNBoxPredictor.dropout_keep_probability', index=2,\n      number=3, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.5,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='box_code_size', full_name='object_detection.protos.MaskRCNNBoxPredictor.box_code_size', index=3,\n      number=4, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=4,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='conv_hyperparams', full_name='object_detection.protos.MaskRCNNBoxPredictor.conv_hyperparams', index=4,\n      number=5, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='predict_instance_masks', full_name='object_detection.protos.MaskRCNNBoxPredictor.predict_instance_masks', index=5,\n      number=6, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='mask_prediction_conv_depth', full_name='object_detection.protos.MaskRCNNBoxPredictor.mask_prediction_conv_depth', index=6,\n      number=7, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=256,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='predict_keypoints', full_name='object_detection.protos.MaskRCNNBoxPredictor.predict_keypoints', index=7,\n      number=8, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=736,\n  serialized_end=1091,\n)\n\n\n_RFCNBOXPREDICTOR = _descriptor.Descriptor(\n  name='RfcnBoxPredictor',\n  full_name='object_detection.protos.RfcnBoxPredictor',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='conv_hyperparams', full_name='object_detection.protos.RfcnBoxPredictor.conv_hyperparams', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='num_spatial_bins_height', full_name='object_detection.protos.RfcnBoxPredictor.num_spatial_bins_height', index=1,\n      number=2, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=3,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='num_spatial_bins_width', full_name='object_detection.protos.RfcnBoxPredictor.num_spatial_bins_width', index=2,\n      number=3, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=3,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='depth', full_name='object_detection.protos.RfcnBoxPredictor.depth', index=3,\n      number=4, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=1024,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='box_code_size', full_name='object_detection.protos.RfcnBoxPredictor.box_code_size', index=4,\n      number=5, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=4,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='crop_height', full_name='object_detection.protos.RfcnBoxPredictor.crop_height', index=5,\n      number=6, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=12,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='crop_width', full_name='object_detection.protos.RfcnBoxPredictor.crop_width', index=6,\n      number=7, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=12,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=1094,\n  serialized_end=1343,\n)\n\n_BOXPREDICTOR.fields_by_name['convolutional_box_predictor'].message_type = _CONVOLUTIONALBOXPREDICTOR\n_BOXPREDICTOR.fields_by_name['mask_rcnn_box_predictor'].message_type = _MASKRCNNBOXPREDICTOR\n_BOXPREDICTOR.fields_by_name['rfcn_box_predictor'].message_type = _RFCNBOXPREDICTOR\n_BOXPREDICTOR.oneofs_by_name['box_predictor_oneof'].fields.append(\n  _BOXPREDICTOR.fields_by_name['convolutional_box_predictor'])\n_BOXPREDICTOR.fields_by_name['convolutional_box_predictor'].containing_oneof = _BOXPREDICTOR.oneofs_by_name['box_predictor_oneof']\n_BOXPREDICTOR.oneofs_by_name['box_predictor_oneof'].fields.append(\n  _BOXPREDICTOR.fields_by_name['mask_rcnn_box_predictor'])\n_BOXPREDICTOR.fields_by_name['mask_rcnn_box_predictor'].containing_oneof = _BOXPREDICTOR.oneofs_by_name['box_predictor_oneof']\n_BOXPREDICTOR.oneofs_by_name['box_predictor_oneof'].fields.append(\n  _BOXPREDICTOR.fields_by_name['rfcn_box_predictor'])\n_BOXPREDICTOR.fields_by_name['rfcn_box_predictor'].containing_oneof = _BOXPREDICTOR.oneofs_by_name['box_predictor_oneof']\n_CONVOLUTIONALBOXPREDICTOR.fields_by_name['conv_hyperparams'].message_type = object_detection.protos.hyperparams_pb2._HYPERPARAMS\n_MASKRCNNBOXPREDICTOR.fields_by_name['fc_hyperparams'].message_type = object_detection.protos.hyperparams_pb2._HYPERPARAMS\n_MASKRCNNBOXPREDICTOR.fields_by_name['conv_hyperparams'].message_type = object_detection.protos.hyperparams_pb2._HYPERPARAMS\n_RFCNBOXPREDICTOR.fields_by_name['conv_hyperparams'].message_type = object_detection.protos.hyperparams_pb2._HYPERPARAMS\nDESCRIPTOR.message_types_by_name['BoxPredictor'] = _BOXPREDICTOR\nDESCRIPTOR.message_types_by_name['ConvolutionalBoxPredictor'] = _CONVOLUTIONALBOXPREDICTOR\nDESCRIPTOR.message_types_by_name['MaskRCNNBoxPredictor'] = _MASKRCNNBOXPREDICTOR\nDESCRIPTOR.message_types_by_name['RfcnBoxPredictor'] = _RFCNBOXPREDICTOR\n\nBoxPredictor = _reflection.GeneratedProtocolMessageType('BoxPredictor', (_message.Message,), dict(\n  DESCRIPTOR = _BOXPREDICTOR,\n  __module__ = 'object_detection.protos.box_predictor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.BoxPredictor)\n  ))\n_sym_db.RegisterMessage(BoxPredictor)\n\nConvolutionalBoxPredictor = _reflection.GeneratedProtocolMessageType('ConvolutionalBoxPredictor', (_message.Message,), dict(\n  DESCRIPTOR = _CONVOLUTIONALBOXPREDICTOR,\n  __module__ = 'object_detection.protos.box_predictor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.ConvolutionalBoxPredictor)\n  ))\n_sym_db.RegisterMessage(ConvolutionalBoxPredictor)\n\nMaskRCNNBoxPredictor = _reflection.GeneratedProtocolMessageType('MaskRCNNBoxPredictor', (_message.Message,), dict(\n  DESCRIPTOR = _MASKRCNNBOXPREDICTOR,\n  __module__ = 'object_detection.protos.box_predictor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.MaskRCNNBoxPredictor)\n  ))\n_sym_db.RegisterMessage(MaskRCNNBoxPredictor)\n\nRfcnBoxPredictor = _reflection.GeneratedProtocolMessageType('RfcnBoxPredictor', (_message.Message,), dict(\n  DESCRIPTOR = _RFCNBOXPREDICTOR,\n  __module__ = 'object_detection.protos.box_predictor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RfcnBoxPredictor)\n  ))\n_sym_db.RegisterMessage(RfcnBoxPredictor)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/eval.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\n// Message for configuring DetectionModel evaluation jobs (eval.py).\nmessage EvalConfig {\n  // Number of visualization images to generate.\n  optional uint32 num_visualizations = 1 [default=10];\n\n  // Number of examples to process of evaluation.\n  optional uint32 num_examples = 2 [default=5000];\n\n  // How often to run evaluation.\n  optional uint32 eval_interval_secs = 3 [default=300];\n\n  // Maximum number of times to run evaluation. If set to 0, will run forever.\n  optional uint32 max_evals = 4 [default=0];\n\n  // Whether the TensorFlow graph used for evaluation should be saved to disk.\n  optional bool save_graph = 5 [default=false];\n\n  // Path to directory to store visualizations in. If empty, visualization\n  // images are not exported (only shown on Tensorboard).\n  optional string visualization_export_dir = 6 [default=\"\"];\n\n  // BNS name of the TensorFlow master.\n  optional string eval_master = 7 [default=\"\"];\n\n  // Type of metrics to use for evaluation. Currently supports only Pascal VOC\n  // detection metrics.\n  optional string metrics_set = 8 [default=\"pascal_voc_metrics\"];\n\n  // Path to export detections to COCO compatible JSON format.\n  optional string export_path = 9 [default=''];\n\n  // Option to not read groundtruth labels and only export detections to\n  // COCO-compatible JSON file.\n  optional bool ignore_groundtruth = 10 [default=false];\n\n  // Use exponential moving averages of variables for evaluation.\n  // TODO: When this is false make sure the model is constructed\n  // without moving averages in restore_fn.\n  optional bool use_moving_averages = 11 [default=false];\n\n  // Whether to evaluate instance masks.\n  optional bool eval_instance_masks = 12 [default=false];\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/eval_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/eval.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/eval.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n\\\"object_detection/protos/eval.proto\\x12\\x17object_detection.protos\\\"\\x80\\x03\\n\\nEvalConfig\\x12\\x1e\\n\\x12num_visualizations\\x18\\x01 \\x01(\\r:\\x02\\x31\\x30\\x12\\x1a\\n\\x0cnum_examples\\x18\\x02 \\x01(\\r:\\x04\\x35\\x30\\x30\\x30\\x12\\x1f\\n\\x12\\x65val_interval_secs\\x18\\x03 \\x01(\\r:\\x03\\x33\\x30\\x30\\x12\\x14\\n\\tmax_evals\\x18\\x04 \\x01(\\r:\\x01\\x30\\x12\\x19\\n\\nsave_graph\\x18\\x05 \\x01(\\x08:\\x05\\x66\\x61lse\\x12\\\"\\n\\x18visualization_export_dir\\x18\\x06 \\x01(\\t:\\x00\\x12\\x15\\n\\x0b\\x65val_master\\x18\\x07 \\x01(\\t:\\x00\\x12\\'\\n\\x0bmetrics_set\\x18\\x08 \\x01(\\t:\\x12pascal_voc_metrics\\x12\\x15\\n\\x0b\\x65xport_path\\x18\\t \\x01(\\t:\\x00\\x12!\\n\\x12ignore_groundtruth\\x18\\n \\x01(\\x08:\\x05\\x66\\x61lse\\x12\\\"\\n\\x13use_moving_averages\\x18\\x0b \\x01(\\x08:\\x05\\x66\\x61lse\\x12\\\"\\n\\x13\\x65val_instance_masks\\x18\\x0c \\x01(\\x08:\\x05\\x66\\x61lse')\n)\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_EVALCONFIG = _descriptor.Descriptor(\n  name='EvalConfig',\n  full_name='object_detection.protos.EvalConfig',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='num_visualizations', full_name='object_detection.protos.EvalConfig.num_visualizations', index=0,\n      number=1, type=13, cpp_type=3, label=1,\n      has_default_value=True, default_value=10,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='num_examples', full_name='object_detection.protos.EvalConfig.num_examples', index=1,\n      number=2, type=13, cpp_type=3, label=1,\n      has_default_value=True, default_value=5000,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='eval_interval_secs', full_name='object_detection.protos.EvalConfig.eval_interval_secs', index=2,\n      number=3, type=13, cpp_type=3, label=1,\n      has_default_value=True, default_value=300,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_evals', full_name='object_detection.protos.EvalConfig.max_evals', index=3,\n      number=4, type=13, cpp_type=3, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='save_graph', full_name='object_detection.protos.EvalConfig.save_graph', index=4,\n      number=5, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='visualization_export_dir', full_name='object_detection.protos.EvalConfig.visualization_export_dir', index=5,\n      number=6, type=9, cpp_type=9, label=1,\n      has_default_value=True, default_value=_b(\"\").decode('utf-8'),\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='eval_master', full_name='object_detection.protos.EvalConfig.eval_master', index=6,\n      number=7, type=9, cpp_type=9, label=1,\n      has_default_value=True, default_value=_b(\"\").decode('utf-8'),\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='metrics_set', full_name='object_detection.protos.EvalConfig.metrics_set', index=7,\n      number=8, type=9, cpp_type=9, label=1,\n      has_default_value=True, default_value=_b(\"pascal_voc_metrics\").decode('utf-8'),\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='export_path', full_name='object_detection.protos.EvalConfig.export_path', index=8,\n      number=9, type=9, cpp_type=9, label=1,\n      has_default_value=True, default_value=_b(\"\").decode('utf-8'),\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='ignore_groundtruth', full_name='object_detection.protos.EvalConfig.ignore_groundtruth', index=9,\n      number=10, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='use_moving_averages', full_name='object_detection.protos.EvalConfig.use_moving_averages', index=10,\n      number=11, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='eval_instance_masks', full_name='object_detection.protos.EvalConfig.eval_instance_masks', index=11,\n      number=12, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=64,\n  serialized_end=448,\n)\n\nDESCRIPTOR.message_types_by_name['EvalConfig'] = _EVALCONFIG\n\nEvalConfig = _reflection.GeneratedProtocolMessageType('EvalConfig', (_message.Message,), dict(\n  DESCRIPTOR = _EVALCONFIG,\n  __module__ = 'object_detection.protos.eval_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.EvalConfig)\n  ))\n_sym_db.RegisterMessage(EvalConfig)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/faster_rcnn.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\nimport \"object_detection/protos/anchor_generator.proto\";\nimport \"object_detection/protos/box_predictor.proto\";\nimport \"object_detection/protos/hyperparams.proto\";\nimport \"object_detection/protos/image_resizer.proto\";\nimport \"object_detection/protos/losses.proto\";\nimport \"object_detection/protos/post_processing.proto\";\n\n// Configuration for Faster R-CNN models.\n// See meta_architectures/faster_rcnn_meta_arch.py and models/model_builder.py\n//\n// Naming conventions:\n// Faster R-CNN models have two stages: a first stage region proposal network\n// (or RPN) and a second stage box classifier.  We thus use the prefixes\n// `first_stage_` and `second_stage_` to indicate the stage to which each\n// parameter pertains when relevant.\nmessage FasterRcnn {\n\n  // Whether to construct only the Region Proposal Network (RPN).\n  optional bool first_stage_only = 1 [default=false];\n\n  // Number of classes to predict.\n  optional int32 num_classes = 3;\n\n  // Image resizer for preprocessing the input image.\n  optional ImageResizer image_resizer = 4;\n\n  // Feature extractor config.\n  optional FasterRcnnFeatureExtractor feature_extractor = 5;\n\n\n  // (First stage) region proposal network (RPN) parameters.\n\n  // Anchor generator to compute RPN anchors.\n  optional AnchorGenerator first_stage_anchor_generator = 6;\n\n  // Atrous rate for the convolution op applied to the\n  // `first_stage_features_to_crop` tensor to obtain box predictions.\n  optional int32 first_stage_atrous_rate = 7 [default=1];\n\n  // Hyperparameters for the convolutional RPN box predictor.\n  optional Hyperparams first_stage_box_predictor_conv_hyperparams = 8;\n\n  // Kernel size to use for the convolution op just prior to RPN box\n  // predictions.\n  optional int32 first_stage_box_predictor_kernel_size = 9 [default=3];\n\n  // Output depth for the convolution op just prior to RPN box predictions.\n  optional int32 first_stage_box_predictor_depth = 10 [default=512];\n\n  // The batch size to use for computing the first stage objectness and\n  // location losses.\n  optional int32 first_stage_minibatch_size = 11 [default=256];\n\n  // Fraction of positive examples per image for the RPN.\n  optional float first_stage_positive_balance_fraction = 12 [default=0.5];\n\n  // Non max suppression score threshold applied to first stage RPN proposals.\n  optional float first_stage_nms_score_threshold = 13 [default=0.0];\n\n  // Non max suppression IOU threshold applied to first stage RPN proposals.\n  optional float first_stage_nms_iou_threshold = 14 [default=0.7];\n\n  // Maximum number of RPN proposals retained after first stage postprocessing.\n  optional int32 first_stage_max_proposals = 15 [default=300];\n\n  // First stage RPN localization loss weight.\n  optional float first_stage_localization_loss_weight = 16 [default=1.0];\n\n  // First stage RPN objectness loss weight.\n  optional float first_stage_objectness_loss_weight = 17 [default=1.0];\n\n\n  // Per-region cropping parameters.\n  // Note that if a R-FCN model is constructed the per region cropping\n  // parameters below are ignored.\n\n  // Output size (width and height are set to be the same) of the initial\n  // bilinear interpolation based cropping during ROI pooling.\n  optional int32 initial_crop_size = 18;\n\n  // Kernel size of the max pool op on the cropped feature map during\n  // ROI pooling.\n  optional int32 maxpool_kernel_size = 19;\n\n  // Stride of the max pool op on the cropped feature map during ROI pooling.\n  optional int32 maxpool_stride = 20;\n\n\n  // (Second stage) box classifier parameters\n\n  // Hyperparameters for the second stage box predictor. If box predictor type\n  // is set to rfcn_box_predictor, a R-FCN model is constructed, otherwise a\n  // Faster R-CNN model is constructed.\n  optional BoxPredictor second_stage_box_predictor  = 21;\n\n  // The batch size per image used for computing the classification and refined\n  // location loss of the box classifier.\n  // Note that this field is ignored if `hard_example_miner` is configured.\n  optional int32 second_stage_batch_size = 22 [default=64];\n\n  // Fraction of positive examples to use per image for the box classifier.\n  optional float second_stage_balance_fraction = 23 [default=0.25];\n\n  // Post processing to apply on the second stage box classifier predictions.\n  // Note: the `score_converter` provided to the FasterRCNNMetaArch constructor\n  // is taken from this `second_stage_post_processing` proto.\n  optional PostProcessing second_stage_post_processing = 24;\n\n  // Second stage refined localization loss weight.\n  optional float second_stage_localization_loss_weight = 25 [default=1.0];\n\n  // Second stage classification loss weight\n  optional float second_stage_classification_loss_weight = 26 [default=1.0];\n\n  // If not left to default, applies hard example mining.\n  optional HardExampleMiner hard_example_miner = 27;\n}\n\n\nmessage FasterRcnnFeatureExtractor {\n  // Type of Faster R-CNN model (e.g., 'faster_rcnn_resnet101';\n  // See models/model_builder.py for expected types).\n  optional string type = 1;\n\n  // Output stride of extracted RPN feature map.\n  optional int32 first_stage_features_stride = 2 [default=16];\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/faster_rcnn_box_coder.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\n// Configuration proto for FasterRCNNBoxCoder. See\n// box_coders/faster_rcnn_box_coder.py for details.\nmessage FasterRcnnBoxCoder {\n  // Scale factor for anchor encoded box center.\n  optional float y_scale = 1 [default = 10.0];\n  optional float x_scale = 2 [default = 10.0];\n\n  // Scale factor for anchor encoded box height.\n  optional float height_scale = 3 [default = 5.0];\n\n  // Scale factor for anchor encoded box width.\n  optional float width_scale = 4 [default = 5.0];\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/faster_rcnn_box_coder_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/faster_rcnn_box_coder.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/faster_rcnn_box_coder.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n3object_detection/protos/faster_rcnn_box_coder.proto\\x12\\x17object_detection.protos\\\"o\\n\\x12\\x46\\x61sterRcnnBoxCoder\\x12\\x13\\n\\x07y_scale\\x18\\x01 \\x01(\\x02:\\x02\\x31\\x30\\x12\\x13\\n\\x07x_scale\\x18\\x02 \\x01(\\x02:\\x02\\x31\\x30\\x12\\x17\\n\\x0cheight_scale\\x18\\x03 \\x01(\\x02:\\x01\\x35\\x12\\x16\\n\\x0bwidth_scale\\x18\\x04 \\x01(\\x02:\\x01\\x35')\n)\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_FASTERRCNNBOXCODER = _descriptor.Descriptor(\n  name='FasterRcnnBoxCoder',\n  full_name='object_detection.protos.FasterRcnnBoxCoder',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='y_scale', full_name='object_detection.protos.FasterRcnnBoxCoder.y_scale', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=10,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='x_scale', full_name='object_detection.protos.FasterRcnnBoxCoder.x_scale', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=10,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='height_scale', full_name='object_detection.protos.FasterRcnnBoxCoder.height_scale', index=2,\n      number=3, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=5,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='width_scale', full_name='object_detection.protos.FasterRcnnBoxCoder.width_scale', index=3,\n      number=4, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=5,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=80,\n  serialized_end=191,\n)\n\nDESCRIPTOR.message_types_by_name['FasterRcnnBoxCoder'] = _FASTERRCNNBOXCODER\n\nFasterRcnnBoxCoder = _reflection.GeneratedProtocolMessageType('FasterRcnnBoxCoder', (_message.Message,), dict(\n  DESCRIPTOR = _FASTERRCNNBOXCODER,\n  __module__ = 'object_detection.protos.faster_rcnn_box_coder_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.FasterRcnnBoxCoder)\n  ))\n_sym_db.RegisterMessage(FasterRcnnBoxCoder)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/faster_rcnn_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/faster_rcnn.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\nimport object_detection.protos.anchor_generator_pb2\nimport object_detection.protos.box_predictor_pb2\nimport object_detection.protos.hyperparams_pb2\nimport object_detection.protos.image_resizer_pb2\nimport object_detection.protos.losses_pb2\nimport object_detection.protos.post_processing_pb2\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/faster_rcnn.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n)object_detection/protos/faster_rcnn.proto\\x12\\x17object_detection.protos\\x1a.object_detection/protos/anchor_generator.proto\\x1a+object_detection/protos/box_predictor.proto\\x1a)object_detection/protos/hyperparams.proto\\x1a+object_detection/protos/image_resizer.proto\\x1a$object_detection/protos/losses.proto\\x1a-object_detection/protos/post_processing.proto\\\"\\xa4\\n\\n\\nFasterRcnn\\x12\\x1f\\n\\x10\\x66irst_stage_only\\x18\\x01 \\x01(\\x08:\\x05\\x66\\x61lse\\x12\\x13\\n\\x0bnum_classes\\x18\\x03 \\x01(\\x05\\x12<\\n\\rimage_resizer\\x18\\x04 \\x01(\\x0b\\x32%.object_detection.protos.ImageResizer\\x12N\\n\\x11\\x66\\x65\\x61ture_extractor\\x18\\x05 \\x01(\\x0b\\x32\\x33.object_detection.protos.FasterRcnnFeatureExtractor\\x12N\\n\\x1c\\x66irst_stage_anchor_generator\\x18\\x06 \\x01(\\x0b\\x32(.object_detection.protos.AnchorGenerator\\x12\\\"\\n\\x17\\x66irst_stage_atrous_rate\\x18\\x07 \\x01(\\x05:\\x01\\x31\\x12X\\n*first_stage_box_predictor_conv_hyperparams\\x18\\x08 \\x01(\\x0b\\x32$.object_detection.protos.Hyperparams\\x12\\x30\\n%first_stage_box_predictor_kernel_size\\x18\\t \\x01(\\x05:\\x01\\x33\\x12,\\n\\x1f\\x66irst_stage_box_predictor_depth\\x18\\n \\x01(\\x05:\\x03\\x35\\x31\\x32\\x12\\'\\n\\x1a\\x66irst_stage_minibatch_size\\x18\\x0b \\x01(\\x05:\\x03\\x32\\x35\\x36\\x12\\x32\\n%first_stage_positive_balance_fraction\\x18\\x0c \\x01(\\x02:\\x03\\x30.5\\x12*\\n\\x1f\\x66irst_stage_nms_score_threshold\\x18\\r \\x01(\\x02:\\x01\\x30\\x12*\\n\\x1d\\x66irst_stage_nms_iou_threshold\\x18\\x0e \\x01(\\x02:\\x03\\x30.7\\x12&\\n\\x19\\x66irst_stage_max_proposals\\x18\\x0f \\x01(\\x05:\\x03\\x33\\x30\\x30\\x12/\\n$first_stage_localization_loss_weight\\x18\\x10 \\x01(\\x02:\\x01\\x31\\x12-\\n\\\"first_stage_objectness_loss_weight\\x18\\x11 \\x01(\\x02:\\x01\\x31\\x12\\x19\\n\\x11initial_crop_size\\x18\\x12 \\x01(\\x05\\x12\\x1b\\n\\x13maxpool_kernel_size\\x18\\x13 \\x01(\\x05\\x12\\x16\\n\\x0emaxpool_stride\\x18\\x14 \\x01(\\x05\\x12I\\n\\x1asecond_stage_box_predictor\\x18\\x15 \\x01(\\x0b\\x32%.object_detection.protos.BoxPredictor\\x12#\\n\\x17second_stage_batch_size\\x18\\x16 \\x01(\\x05:\\x02\\x36\\x34\\x12+\\n\\x1dsecond_stage_balance_fraction\\x18\\x17 \\x01(\\x02:\\x04\\x30.25\\x12M\\n\\x1csecond_stage_post_processing\\x18\\x18 \\x01(\\x0b\\x32\\'.object_detection.protos.PostProcessing\\x12\\x30\\n%second_stage_localization_loss_weight\\x18\\x19 \\x01(\\x02:\\x01\\x31\\x12\\x32\\n\\'second_stage_classification_loss_weight\\x18\\x1a \\x01(\\x02:\\x01\\x31\\x12\\x45\\n\\x12hard_example_miner\\x18\\x1b \\x01(\\x0b\\x32).object_detection.protos.HardExampleMiner\\\"S\\n\\x1a\\x46\\x61sterRcnnFeatureExtractor\\x12\\x0c\\n\\x04type\\x18\\x01 \\x01(\\t\\x12\\'\\n\\x1b\\x66irst_stage_features_stride\\x18\\x02 \\x01(\\x05:\\x02\\x31\\x36')\n  ,\n  dependencies=[object_detection.protos.anchor_generator_pb2.DESCRIPTOR,object_detection.protos.box_predictor_pb2.DESCRIPTOR,object_detection.protos.hyperparams_pb2.DESCRIPTOR,object_detection.protos.image_resizer_pb2.DESCRIPTOR,object_detection.protos.losses_pb2.DESCRIPTOR,object_detection.protos.post_processing_pb2.DESCRIPTOR,])\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_FASTERRCNN = _descriptor.Descriptor(\n  name='FasterRcnn',\n  full_name='object_detection.protos.FasterRcnn',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='first_stage_only', full_name='object_detection.protos.FasterRcnn.first_stage_only', index=0,\n      number=1, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='num_classes', full_name='object_detection.protos.FasterRcnn.num_classes', index=1,\n      number=3, type=5, cpp_type=1, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='image_resizer', full_name='object_detection.protos.FasterRcnn.image_resizer', index=2,\n      number=4, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='feature_extractor', full_name='object_detection.protos.FasterRcnn.feature_extractor', index=3,\n      number=5, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='first_stage_anchor_generator', full_name='object_detection.protos.FasterRcnn.first_stage_anchor_generator', index=4,\n      number=6, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='first_stage_atrous_rate', full_name='object_detection.protos.FasterRcnn.first_stage_atrous_rate', index=5,\n      number=7, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='first_stage_box_predictor_conv_hyperparams', full_name='object_detection.protos.FasterRcnn.first_stage_box_predictor_conv_hyperparams', index=6,\n      number=8, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='first_stage_box_predictor_kernel_size', full_name='object_detection.protos.FasterRcnn.first_stage_box_predictor_kernel_size', index=7,\n      number=9, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=3,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='first_stage_box_predictor_depth', full_name='object_detection.protos.FasterRcnn.first_stage_box_predictor_depth', index=8,\n      number=10, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=512,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='first_stage_minibatch_size', full_name='object_detection.protos.FasterRcnn.first_stage_minibatch_size', index=9,\n      number=11, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=256,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='first_stage_positive_balance_fraction', full_name='object_detection.protos.FasterRcnn.first_stage_positive_balance_fraction', index=10,\n      number=12, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.5,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='first_stage_nms_score_threshold', full_name='object_detection.protos.FasterRcnn.first_stage_nms_score_threshold', index=11,\n      number=13, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='first_stage_nms_iou_threshold', full_name='object_detection.protos.FasterRcnn.first_stage_nms_iou_threshold', index=12,\n      number=14, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.7,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='first_stage_max_proposals', full_name='object_detection.protos.FasterRcnn.first_stage_max_proposals', index=13,\n      number=15, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=300,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='first_stage_localization_loss_weight', full_name='object_detection.protos.FasterRcnn.first_stage_localization_loss_weight', index=14,\n      number=16, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='first_stage_objectness_loss_weight', full_name='object_detection.protos.FasterRcnn.first_stage_objectness_loss_weight', index=15,\n      number=17, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='initial_crop_size', full_name='object_detection.protos.FasterRcnn.initial_crop_size', index=16,\n      number=18, type=5, cpp_type=1, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='maxpool_kernel_size', full_name='object_detection.protos.FasterRcnn.maxpool_kernel_size', index=17,\n      number=19, type=5, cpp_type=1, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='maxpool_stride', full_name='object_detection.protos.FasterRcnn.maxpool_stride', index=18,\n      number=20, type=5, cpp_type=1, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='second_stage_box_predictor', full_name='object_detection.protos.FasterRcnn.second_stage_box_predictor', index=19,\n      number=21, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='second_stage_batch_size', full_name='object_detection.protos.FasterRcnn.second_stage_batch_size', index=20,\n      number=22, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=64,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='second_stage_balance_fraction', full_name='object_detection.protos.FasterRcnn.second_stage_balance_fraction', index=21,\n      number=23, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.25,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='second_stage_post_processing', full_name='object_detection.protos.FasterRcnn.second_stage_post_processing', index=22,\n      number=24, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='second_stage_localization_loss_weight', full_name='object_detection.protos.FasterRcnn.second_stage_localization_loss_weight', index=23,\n      number=25, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='second_stage_classification_loss_weight', full_name='object_detection.protos.FasterRcnn.second_stage_classification_loss_weight', index=24,\n      number=26, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='hard_example_miner', full_name='object_detection.protos.FasterRcnn.hard_example_miner', index=25,\n      number=27, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=337,\n  serialized_end=1653,\n)\n\n\n_FASTERRCNNFEATUREEXTRACTOR = _descriptor.Descriptor(\n  name='FasterRcnnFeatureExtractor',\n  full_name='object_detection.protos.FasterRcnnFeatureExtractor',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='type', full_name='object_detection.protos.FasterRcnnFeatureExtractor.type', index=0,\n      number=1, type=9, cpp_type=9, label=1,\n      has_default_value=False, default_value=_b(\"\").decode('utf-8'),\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='first_stage_features_stride', full_name='object_detection.protos.FasterRcnnFeatureExtractor.first_stage_features_stride', index=1,\n      number=2, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=16,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=1655,\n  serialized_end=1738,\n)\n\n_FASTERRCNN.fields_by_name['image_resizer'].message_type = object_detection.protos.image_resizer_pb2._IMAGERESIZER\n_FASTERRCNN.fields_by_name['feature_extractor'].message_type = _FASTERRCNNFEATUREEXTRACTOR\n_FASTERRCNN.fields_by_name['first_stage_anchor_generator'].message_type = object_detection.protos.anchor_generator_pb2._ANCHORGENERATOR\n_FASTERRCNN.fields_by_name['first_stage_box_predictor_conv_hyperparams'].message_type = object_detection.protos.hyperparams_pb2._HYPERPARAMS\n_FASTERRCNN.fields_by_name['second_stage_box_predictor'].message_type = object_detection.protos.box_predictor_pb2._BOXPREDICTOR\n_FASTERRCNN.fields_by_name['second_stage_post_processing'].message_type = object_detection.protos.post_processing_pb2._POSTPROCESSING\n_FASTERRCNN.fields_by_name['hard_example_miner'].message_type = object_detection.protos.losses_pb2._HARDEXAMPLEMINER\nDESCRIPTOR.message_types_by_name['FasterRcnn'] = _FASTERRCNN\nDESCRIPTOR.message_types_by_name['FasterRcnnFeatureExtractor'] = _FASTERRCNNFEATUREEXTRACTOR\n\nFasterRcnn = _reflection.GeneratedProtocolMessageType('FasterRcnn', (_message.Message,), dict(\n  DESCRIPTOR = _FASTERRCNN,\n  __module__ = 'object_detection.protos.faster_rcnn_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.FasterRcnn)\n  ))\n_sym_db.RegisterMessage(FasterRcnn)\n\nFasterRcnnFeatureExtractor = _reflection.GeneratedProtocolMessageType('FasterRcnnFeatureExtractor', (_message.Message,), dict(\n  DESCRIPTOR = _FASTERRCNNFEATUREEXTRACTOR,\n  __module__ = 'object_detection.protos.faster_rcnn_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.FasterRcnnFeatureExtractor)\n  ))\n_sym_db.RegisterMessage(FasterRcnnFeatureExtractor)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/grid_anchor_generator.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\n// Configuration proto for GridAnchorGenerator. See\n// anchor_generators/grid_anchor_generator.py for details.\nmessage GridAnchorGenerator {\n   // Anchor height in pixels.\n  optional int32 height = 1 [default = 256];\n\n  // Anchor width in pixels.\n  optional int32 width = 2 [default = 256];\n\n  // Anchor stride in height dimension in pixels.\n  optional int32 height_stride = 3 [default = 16];\n\n  // Anchor stride in width dimension in pixels.\n  optional int32 width_stride = 4 [default = 16];\n\n  // Anchor height offset in pixels.\n  optional int32 height_offset = 5 [default = 0];\n\n  // Anchor width offset in pixels.\n  optional int32 width_offset = 6 [default = 0];\n\n  // At any given location, len(scales) * len(aspect_ratios) anchors are\n  // generated with all possible combinations of scales and aspect ratios.\n\n  // List of scales for the anchors.\n  repeated float scales = 7;\n\n  // List of aspect ratios for the anchors.\n  repeated float aspect_ratios = 8;\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/grid_anchor_generator_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/grid_anchor_generator.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/grid_anchor_generator.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n3object_detection/protos/grid_anchor_generator.proto\\x12\\x17object_detection.protos\\\"\\xcd\\x01\\n\\x13GridAnchorGenerator\\x12\\x13\\n\\x06height\\x18\\x01 \\x01(\\x05:\\x03\\x32\\x35\\x36\\x12\\x12\\n\\x05width\\x18\\x02 \\x01(\\x05:\\x03\\x32\\x35\\x36\\x12\\x19\\n\\rheight_stride\\x18\\x03 \\x01(\\x05:\\x02\\x31\\x36\\x12\\x18\\n\\x0cwidth_stride\\x18\\x04 \\x01(\\x05:\\x02\\x31\\x36\\x12\\x18\\n\\rheight_offset\\x18\\x05 \\x01(\\x05:\\x01\\x30\\x12\\x17\\n\\x0cwidth_offset\\x18\\x06 \\x01(\\x05:\\x01\\x30\\x12\\x0e\\n\\x06scales\\x18\\x07 \\x03(\\x02\\x12\\x15\\n\\raspect_ratios\\x18\\x08 \\x03(\\x02')\n)\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_GRIDANCHORGENERATOR = _descriptor.Descriptor(\n  name='GridAnchorGenerator',\n  full_name='object_detection.protos.GridAnchorGenerator',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='height', full_name='object_detection.protos.GridAnchorGenerator.height', index=0,\n      number=1, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=256,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='width', full_name='object_detection.protos.GridAnchorGenerator.width', index=1,\n      number=2, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=256,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='height_stride', full_name='object_detection.protos.GridAnchorGenerator.height_stride', index=2,\n      number=3, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=16,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='width_stride', full_name='object_detection.protos.GridAnchorGenerator.width_stride', index=3,\n      number=4, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=16,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='height_offset', full_name='object_detection.protos.GridAnchorGenerator.height_offset', index=4,\n      number=5, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='width_offset', full_name='object_detection.protos.GridAnchorGenerator.width_offset', index=5,\n      number=6, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='scales', full_name='object_detection.protos.GridAnchorGenerator.scales', index=6,\n      number=7, type=2, cpp_type=6, label=3,\n      has_default_value=False, default_value=[],\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='aspect_ratios', full_name='object_detection.protos.GridAnchorGenerator.aspect_ratios', index=7,\n      number=8, type=2, cpp_type=6, label=3,\n      has_default_value=False, default_value=[],\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=81,\n  serialized_end=286,\n)\n\nDESCRIPTOR.message_types_by_name['GridAnchorGenerator'] = _GRIDANCHORGENERATOR\n\nGridAnchorGenerator = _reflection.GeneratedProtocolMessageType('GridAnchorGenerator', (_message.Message,), dict(\n  DESCRIPTOR = _GRIDANCHORGENERATOR,\n  __module__ = 'object_detection.protos.grid_anchor_generator_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.GridAnchorGenerator)\n  ))\n_sym_db.RegisterMessage(GridAnchorGenerator)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/hyperparams.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\n// Configuration proto for the convolution op hyperparameters to use in the\n// object detection pipeline.\nmessage Hyperparams {\n\n  // Operations affected by hyperparameters.\n  enum Op {\n    // Convolution, Separable Convolution, Convolution transpose.\n    CONV = 1;\n\n    // Fully connected\n    FC = 2;\n  }\n  optional Op op = 1 [default = CONV];\n\n  // Regularizer for the weights of the convolution op.\n  optional Regularizer regularizer = 2;\n\n  // Initializer for the weights of the convolution op.\n  optional Initializer initializer = 3;\n\n  // Type of activation to apply after convolution.\n  enum Activation {\n    // Use None (no activation)\n    NONE = 0;\n\n    // Use tf.nn.relu\n    RELU = 1;\n\n    // Use tf.nn.relu6\n    RELU_6 = 2;\n  }\n  optional Activation activation = 4 [default = RELU];\n\n  // BatchNorm hyperparameters. If this parameter is NOT set then BatchNorm is\n  // not applied!\n  optional BatchNorm batch_norm = 5;\n}\n\n// Proto with one-of field for regularizers.\nmessage Regularizer {\n  oneof regularizer_oneof {\n    L1Regularizer l1_regularizer = 1;\n    L2Regularizer l2_regularizer = 2;\n  }\n}\n\n// Configuration proto for L1 Regularizer.\n// See https://www.tensorflow.org/api_docs/python/tf/contrib/layers/l1_regularizer\nmessage L1Regularizer {\n  optional float weight = 1 [default = 1.0];\n}\n\n// Configuration proto for L2 Regularizer.\n// See https://www.tensorflow.org/api_docs/python/tf/contrib/layers/l2_regularizer\nmessage L2Regularizer {\n  optional float weight = 1 [default = 1.0];\n}\n\n// Proto with one-of field for initializers.\nmessage Initializer {\n  oneof initializer_oneof {\n    TruncatedNormalInitializer truncated_normal_initializer = 1;\n    VarianceScalingInitializer variance_scaling_initializer = 2;\n  }\n}\n\n// Configuration proto for truncated normal initializer. See\n// https://www.tensorflow.org/api_docs/python/tf/truncated_normal_initializer\nmessage TruncatedNormalInitializer {\n  optional float mean = 1 [default = 0.0];\n  optional float stddev = 2 [default = 1.0];\n}\n\n// Configuration proto for variance scaling initializer. See\n// https://www.tensorflow.org/api_docs/python/tf/contrib/layers/\n// variance_scaling_initializer\nmessage VarianceScalingInitializer {\n  optional float factor = 1 [default = 2.0];\n  optional bool uniform = 2 [default = false];\n  enum Mode {\n    FAN_IN = 0;\n    FAN_OUT = 1;\n    FAN_AVG = 2;\n  }\n  optional Mode mode = 3 [default = FAN_IN];\n}\n\n// Configuration proto for batch norm to apply after convolution op. See\n// https://www.tensorflow.org/api_docs/python/tf/contrib/layers/batch_norm\nmessage BatchNorm {\n  optional float decay = 1 [default = 0.999];\n  optional bool center = 2 [default = true];\n  optional bool scale = 3 [default = false];\n  optional float epsilon = 4 [default = 0.001];\n  // Whether to train the batch norm variables. If this is set to false during\n  // training, the current value of the batch_norm variables are used for\n  // forward pass but they are never updated.\n  optional bool train = 5 [default = true];\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/hyperparams_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/hyperparams.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/hyperparams.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n)object_detection/protos/hyperparams.proto\\x12\\x17object_detection.protos\\\"\\x87\\x03\\n\\x0bHyperparams\\x12\\x39\\n\\x02op\\x18\\x01 \\x01(\\x0e\\x32\\'.object_detection.protos.Hyperparams.Op:\\x04\\x43ONV\\x12\\x39\\n\\x0bregularizer\\x18\\x02 \\x01(\\x0b\\x32$.object_detection.protos.Regularizer\\x12\\x39\\n\\x0binitializer\\x18\\x03 \\x01(\\x0b\\x32$.object_detection.protos.Initializer\\x12I\\n\\nactivation\\x18\\x04 \\x01(\\x0e\\x32/.object_detection.protos.Hyperparams.Activation:\\x04RELU\\x12\\x36\\n\\nbatch_norm\\x18\\x05 \\x01(\\x0b\\x32\\\".object_detection.protos.BatchNorm\\\"\\x16\\n\\x02Op\\x12\\x08\\n\\x04\\x43ONV\\x10\\x01\\x12\\x06\\n\\x02\\x46\\x43\\x10\\x02\\\",\\n\\nActivation\\x12\\x08\\n\\x04NONE\\x10\\x00\\x12\\x08\\n\\x04RELU\\x10\\x01\\x12\\n\\n\\x06RELU_6\\x10\\x02\\\"\\xa6\\x01\\n\\x0bRegularizer\\x12@\\n\\x0el1_regularizer\\x18\\x01 \\x01(\\x0b\\x32&.object_detection.protos.L1RegularizerH\\x00\\x12@\\n\\x0el2_regularizer\\x18\\x02 \\x01(\\x0b\\x32&.object_detection.protos.L2RegularizerH\\x00\\x42\\x13\\n\\x11regularizer_oneof\\\"\\\"\\n\\rL1Regularizer\\x12\\x11\\n\\x06weight\\x18\\x01 \\x01(\\x02:\\x01\\x31\\\"\\\"\\n\\rL2Regularizer\\x12\\x11\\n\\x06weight\\x18\\x01 \\x01(\\x02:\\x01\\x31\\\"\\xdc\\x01\\n\\x0bInitializer\\x12[\\n\\x1ctruncated_normal_initializer\\x18\\x01 \\x01(\\x0b\\x32\\x33.object_detection.protos.TruncatedNormalInitializerH\\x00\\x12[\\n\\x1cvariance_scaling_initializer\\x18\\x02 \\x01(\\x0b\\x32\\x33.object_detection.protos.VarianceScalingInitializerH\\x00\\x42\\x13\\n\\x11initializer_oneof\\\"@\\n\\x1aTruncatedNormalInitializer\\x12\\x0f\\n\\x04mean\\x18\\x01 \\x01(\\x02:\\x01\\x30\\x12\\x11\\n\\x06stddev\\x18\\x02 \\x01(\\x02:\\x01\\x31\\\"\\xc5\\x01\\n\\x1aVarianceScalingInitializer\\x12\\x11\\n\\x06\\x66\\x61\\x63tor\\x18\\x01 \\x01(\\x02:\\x01\\x32\\x12\\x16\\n\\x07uniform\\x18\\x02 \\x01(\\x08:\\x05\\x66\\x61lse\\x12N\\n\\x04mode\\x18\\x03 \\x01(\\x0e\\x32\\x38.object_detection.protos.VarianceScalingInitializer.Mode:\\x06\\x46\\x41N_IN\\\",\\n\\x04Mode\\x12\\n\\n\\x06\\x46\\x41N_IN\\x10\\x00\\x12\\x0b\\n\\x07\\x46\\x41N_OUT\\x10\\x01\\x12\\x0b\\n\\x07\\x46\\x41N_AVG\\x10\\x02\\\"z\\n\\tBatchNorm\\x12\\x14\\n\\x05\\x64\\x65\\x63\\x61y\\x18\\x01 \\x01(\\x02:\\x05\\x30.999\\x12\\x14\\n\\x06\\x63\\x65nter\\x18\\x02 \\x01(\\x08:\\x04true\\x12\\x14\\n\\x05scale\\x18\\x03 \\x01(\\x08:\\x05\\x66\\x61lse\\x12\\x16\\n\\x07\\x65psilon\\x18\\x04 \\x01(\\x02:\\x05\\x30.001\\x12\\x13\\n\\x05train\\x18\\x05 \\x01(\\x08:\\x04true')\n)\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n_HYPERPARAMS_OP = _descriptor.EnumDescriptor(\n  name='Op',\n  full_name='object_detection.protos.Hyperparams.Op',\n  filename=None,\n  file=DESCRIPTOR,\n  values=[\n    _descriptor.EnumValueDescriptor(\n      name='CONV', index=0, number=1,\n      options=None,\n      type=None),\n    _descriptor.EnumValueDescriptor(\n      name='FC', index=1, number=2,\n      options=None,\n      type=None),\n  ],\n  containing_type=None,\n  options=None,\n  serialized_start=394,\n  serialized_end=416,\n)\n_sym_db.RegisterEnumDescriptor(_HYPERPARAMS_OP)\n\n_HYPERPARAMS_ACTIVATION = _descriptor.EnumDescriptor(\n  name='Activation',\n  full_name='object_detection.protos.Hyperparams.Activation',\n  filename=None,\n  file=DESCRIPTOR,\n  values=[\n    _descriptor.EnumValueDescriptor(\n      name='NONE', index=0, number=0,\n      options=None,\n      type=None),\n    _descriptor.EnumValueDescriptor(\n      name='RELU', index=1, number=1,\n      options=None,\n      type=None),\n    _descriptor.EnumValueDescriptor(\n      name='RELU_6', index=2, number=2,\n      options=None,\n      type=None),\n  ],\n  containing_type=None,\n  options=None,\n  serialized_start=418,\n  serialized_end=462,\n)\n_sym_db.RegisterEnumDescriptor(_HYPERPARAMS_ACTIVATION)\n\n_VARIANCESCALINGINITIALIZER_MODE = _descriptor.EnumDescriptor(\n  name='Mode',\n  full_name='object_detection.protos.VarianceScalingInitializer.Mode',\n  filename=None,\n  file=DESCRIPTOR,\n  values=[\n    _descriptor.EnumValueDescriptor(\n      name='FAN_IN', index=0, number=0,\n      options=None,\n      type=None),\n    _descriptor.EnumValueDescriptor(\n      name='FAN_OUT', index=1, number=1,\n      options=None,\n      type=None),\n    _descriptor.EnumValueDescriptor(\n      name='FAN_AVG', index=2, number=2,\n      options=None,\n      type=None),\n  ],\n  containing_type=None,\n  options=None,\n  serialized_start=1148,\n  serialized_end=1192,\n)\n_sym_db.RegisterEnumDescriptor(_VARIANCESCALINGINITIALIZER_MODE)\n\n\n_HYPERPARAMS = _descriptor.Descriptor(\n  name='Hyperparams',\n  full_name='object_detection.protos.Hyperparams',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='op', full_name='object_detection.protos.Hyperparams.op', index=0,\n      number=1, type=14, cpp_type=8, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='regularizer', full_name='object_detection.protos.Hyperparams.regularizer', index=1,\n      number=2, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='initializer', full_name='object_detection.protos.Hyperparams.initializer', index=2,\n      number=3, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='activation', full_name='object_detection.protos.Hyperparams.activation', index=3,\n      number=4, type=14, cpp_type=8, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='batch_norm', full_name='object_detection.protos.Hyperparams.batch_norm', index=4,\n      number=5, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n    _HYPERPARAMS_OP,\n    _HYPERPARAMS_ACTIVATION,\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=71,\n  serialized_end=462,\n)\n\n\n_REGULARIZER = _descriptor.Descriptor(\n  name='Regularizer',\n  full_name='object_detection.protos.Regularizer',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='l1_regularizer', full_name='object_detection.protos.Regularizer.l1_regularizer', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='l2_regularizer', full_name='object_detection.protos.Regularizer.l2_regularizer', index=1,\n      number=2, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n    _descriptor.OneofDescriptor(\n      name='regularizer_oneof', full_name='object_detection.protos.Regularizer.regularizer_oneof',\n      index=0, containing_type=None, fields=[]),\n  ],\n  serialized_start=465,\n  serialized_end=631,\n)\n\n\n_L1REGULARIZER = _descriptor.Descriptor(\n  name='L1Regularizer',\n  full_name='object_detection.protos.L1Regularizer',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='weight', full_name='object_detection.protos.L1Regularizer.weight', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=633,\n  serialized_end=667,\n)\n\n\n_L2REGULARIZER = _descriptor.Descriptor(\n  name='L2Regularizer',\n  full_name='object_detection.protos.L2Regularizer',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='weight', full_name='object_detection.protos.L2Regularizer.weight', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=669,\n  serialized_end=703,\n)\n\n\n_INITIALIZER = _descriptor.Descriptor(\n  name='Initializer',\n  full_name='object_detection.protos.Initializer',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='truncated_normal_initializer', full_name='object_detection.protos.Initializer.truncated_normal_initializer', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='variance_scaling_initializer', full_name='object_detection.protos.Initializer.variance_scaling_initializer', index=1,\n      number=2, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n    _descriptor.OneofDescriptor(\n      name='initializer_oneof', full_name='object_detection.protos.Initializer.initializer_oneof',\n      index=0, containing_type=None, fields=[]),\n  ],\n  serialized_start=706,\n  serialized_end=926,\n)\n\n\n_TRUNCATEDNORMALINITIALIZER = _descriptor.Descriptor(\n  name='TruncatedNormalInitializer',\n  full_name='object_detection.protos.TruncatedNormalInitializer',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='mean', full_name='object_detection.protos.TruncatedNormalInitializer.mean', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='stddev', full_name='object_detection.protos.TruncatedNormalInitializer.stddev', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=928,\n  serialized_end=992,\n)\n\n\n_VARIANCESCALINGINITIALIZER = _descriptor.Descriptor(\n  name='VarianceScalingInitializer',\n  full_name='object_detection.protos.VarianceScalingInitializer',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='factor', full_name='object_detection.protos.VarianceScalingInitializer.factor', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=2,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='uniform', full_name='object_detection.protos.VarianceScalingInitializer.uniform', index=1,\n      number=2, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='mode', full_name='object_detection.protos.VarianceScalingInitializer.mode', index=2,\n      number=3, type=14, cpp_type=8, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n    _VARIANCESCALINGINITIALIZER_MODE,\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=995,\n  serialized_end=1192,\n)\n\n\n_BATCHNORM = _descriptor.Descriptor(\n  name='BatchNorm',\n  full_name='object_detection.protos.BatchNorm',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='decay', full_name='object_detection.protos.BatchNorm.decay', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.999,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='center', full_name='object_detection.protos.BatchNorm.center', index=1,\n      number=2, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=True,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='scale', full_name='object_detection.protos.BatchNorm.scale', index=2,\n      number=3, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='epsilon', full_name='object_detection.protos.BatchNorm.epsilon', index=3,\n      number=4, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.001,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='train', full_name='object_detection.protos.BatchNorm.train', index=4,\n      number=5, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=True,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=1194,\n  serialized_end=1316,\n)\n\n_HYPERPARAMS.fields_by_name['op'].enum_type = _HYPERPARAMS_OP\n_HYPERPARAMS.fields_by_name['regularizer'].message_type = _REGULARIZER\n_HYPERPARAMS.fields_by_name['initializer'].message_type = _INITIALIZER\n_HYPERPARAMS.fields_by_name['activation'].enum_type = _HYPERPARAMS_ACTIVATION\n_HYPERPARAMS.fields_by_name['batch_norm'].message_type = _BATCHNORM\n_HYPERPARAMS_OP.containing_type = _HYPERPARAMS\n_HYPERPARAMS_ACTIVATION.containing_type = _HYPERPARAMS\n_REGULARIZER.fields_by_name['l1_regularizer'].message_type = _L1REGULARIZER\n_REGULARIZER.fields_by_name['l2_regularizer'].message_type = _L2REGULARIZER\n_REGULARIZER.oneofs_by_name['regularizer_oneof'].fields.append(\n  _REGULARIZER.fields_by_name['l1_regularizer'])\n_REGULARIZER.fields_by_name['l1_regularizer'].containing_oneof = _REGULARIZER.oneofs_by_name['regularizer_oneof']\n_REGULARIZER.oneofs_by_name['regularizer_oneof'].fields.append(\n  _REGULARIZER.fields_by_name['l2_regularizer'])\n_REGULARIZER.fields_by_name['l2_regularizer'].containing_oneof = _REGULARIZER.oneofs_by_name['regularizer_oneof']\n_INITIALIZER.fields_by_name['truncated_normal_initializer'].message_type = _TRUNCATEDNORMALINITIALIZER\n_INITIALIZER.fields_by_name['variance_scaling_initializer'].message_type = _VARIANCESCALINGINITIALIZER\n_INITIALIZER.oneofs_by_name['initializer_oneof'].fields.append(\n  _INITIALIZER.fields_by_name['truncated_normal_initializer'])\n_INITIALIZER.fields_by_name['truncated_normal_initializer'].containing_oneof = _INITIALIZER.oneofs_by_name['initializer_oneof']\n_INITIALIZER.oneofs_by_name['initializer_oneof'].fields.append(\n  _INITIALIZER.fields_by_name['variance_scaling_initializer'])\n_INITIALIZER.fields_by_name['variance_scaling_initializer'].containing_oneof = _INITIALIZER.oneofs_by_name['initializer_oneof']\n_VARIANCESCALINGINITIALIZER.fields_by_name['mode'].enum_type = _VARIANCESCALINGINITIALIZER_MODE\n_VARIANCESCALINGINITIALIZER_MODE.containing_type = _VARIANCESCALINGINITIALIZER\nDESCRIPTOR.message_types_by_name['Hyperparams'] = _HYPERPARAMS\nDESCRIPTOR.message_types_by_name['Regularizer'] = _REGULARIZER\nDESCRIPTOR.message_types_by_name['L1Regularizer'] = _L1REGULARIZER\nDESCRIPTOR.message_types_by_name['L2Regularizer'] = _L2REGULARIZER\nDESCRIPTOR.message_types_by_name['Initializer'] = _INITIALIZER\nDESCRIPTOR.message_types_by_name['TruncatedNormalInitializer'] = _TRUNCATEDNORMALINITIALIZER\nDESCRIPTOR.message_types_by_name['VarianceScalingInitializer'] = _VARIANCESCALINGINITIALIZER\nDESCRIPTOR.message_types_by_name['BatchNorm'] = _BATCHNORM\n\nHyperparams = _reflection.GeneratedProtocolMessageType('Hyperparams', (_message.Message,), dict(\n  DESCRIPTOR = _HYPERPARAMS,\n  __module__ = 'object_detection.protos.hyperparams_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.Hyperparams)\n  ))\n_sym_db.RegisterMessage(Hyperparams)\n\nRegularizer = _reflection.GeneratedProtocolMessageType('Regularizer', (_message.Message,), dict(\n  DESCRIPTOR = _REGULARIZER,\n  __module__ = 'object_detection.protos.hyperparams_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.Regularizer)\n  ))\n_sym_db.RegisterMessage(Regularizer)\n\nL1Regularizer = _reflection.GeneratedProtocolMessageType('L1Regularizer', (_message.Message,), dict(\n  DESCRIPTOR = _L1REGULARIZER,\n  __module__ = 'object_detection.protos.hyperparams_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.L1Regularizer)\n  ))\n_sym_db.RegisterMessage(L1Regularizer)\n\nL2Regularizer = _reflection.GeneratedProtocolMessageType('L2Regularizer', (_message.Message,), dict(\n  DESCRIPTOR = _L2REGULARIZER,\n  __module__ = 'object_detection.protos.hyperparams_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.L2Regularizer)\n  ))\n_sym_db.RegisterMessage(L2Regularizer)\n\nInitializer = _reflection.GeneratedProtocolMessageType('Initializer', (_message.Message,), dict(\n  DESCRIPTOR = _INITIALIZER,\n  __module__ = 'object_detection.protos.hyperparams_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.Initializer)\n  ))\n_sym_db.RegisterMessage(Initializer)\n\nTruncatedNormalInitializer = _reflection.GeneratedProtocolMessageType('TruncatedNormalInitializer', (_message.Message,), dict(\n  DESCRIPTOR = _TRUNCATEDNORMALINITIALIZER,\n  __module__ = 'object_detection.protos.hyperparams_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.TruncatedNormalInitializer)\n  ))\n_sym_db.RegisterMessage(TruncatedNormalInitializer)\n\nVarianceScalingInitializer = _reflection.GeneratedProtocolMessageType('VarianceScalingInitializer', (_message.Message,), dict(\n  DESCRIPTOR = _VARIANCESCALINGINITIALIZER,\n  __module__ = 'object_detection.protos.hyperparams_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.VarianceScalingInitializer)\n  ))\n_sym_db.RegisterMessage(VarianceScalingInitializer)\n\nBatchNorm = _reflection.GeneratedProtocolMessageType('BatchNorm', (_message.Message,), dict(\n  DESCRIPTOR = _BATCHNORM,\n  __module__ = 'object_detection.protos.hyperparams_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.BatchNorm)\n  ))\n_sym_db.RegisterMessage(BatchNorm)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/image_resizer.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\n// Configuration proto for image resizing operations.\n// See builders/image_resizer_builder.py for details.\nmessage ImageResizer {\n  oneof image_resizer_oneof {\n    KeepAspectRatioResizer keep_aspect_ratio_resizer = 1;\n    FixedShapeResizer fixed_shape_resizer = 2;\n  }\n}\n\n\n// Configuration proto for image resizer that keeps aspect ratio.\nmessage KeepAspectRatioResizer {\n  // Desired size of the smaller image dimension in pixels.\n  optional int32 min_dimension = 1 [default = 600];\n\n  // Desired size of the larger image dimension in pixels.\n  optional int32 max_dimension = 2 [default = 1024];\n}\n\n\n// Configuration proto for image resizer that resizes to a fixed shape.\nmessage FixedShapeResizer {\n  // Desired height of image in pixels.\n  optional int32 height = 1 [default = 300];\n\n  // Desired width of image in pixels.\n  optional int32 width = 2 [default = 300];\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/image_resizer_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/image_resizer.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/image_resizer.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n+object_detection/protos/image_resizer.proto\\x12\\x17object_detection.protos\\\"\\xc6\\x01\\n\\x0cImageResizer\\x12T\\n\\x19keep_aspect_ratio_resizer\\x18\\x01 \\x01(\\x0b\\x32/.object_detection.protos.KeepAspectRatioResizerH\\x00\\x12I\\n\\x13\\x66ixed_shape_resizer\\x18\\x02 \\x01(\\x0b\\x32*.object_detection.protos.FixedShapeResizerH\\x00\\x42\\x15\\n\\x13image_resizer_oneof\\\"Q\\n\\x16KeepAspectRatioResizer\\x12\\x1a\\n\\rmin_dimension\\x18\\x01 \\x01(\\x05:\\x03\\x36\\x30\\x30\\x12\\x1b\\n\\rmax_dimension\\x18\\x02 \\x01(\\x05:\\x04\\x31\\x30\\x32\\x34\\\"<\\n\\x11\\x46ixedShapeResizer\\x12\\x13\\n\\x06height\\x18\\x01 \\x01(\\x05:\\x03\\x33\\x30\\x30\\x12\\x12\\n\\x05width\\x18\\x02 \\x01(\\x05:\\x03\\x33\\x30\\x30')\n)\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_IMAGERESIZER = _descriptor.Descriptor(\n  name='ImageResizer',\n  full_name='object_detection.protos.ImageResizer',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='keep_aspect_ratio_resizer', full_name='object_detection.protos.ImageResizer.keep_aspect_ratio_resizer', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='fixed_shape_resizer', full_name='object_detection.protos.ImageResizer.fixed_shape_resizer', index=1,\n      number=2, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n    _descriptor.OneofDescriptor(\n      name='image_resizer_oneof', full_name='object_detection.protos.ImageResizer.image_resizer_oneof',\n      index=0, containing_type=None, fields=[]),\n  ],\n  serialized_start=73,\n  serialized_end=271,\n)\n\n\n_KEEPASPECTRATIORESIZER = _descriptor.Descriptor(\n  name='KeepAspectRatioResizer',\n  full_name='object_detection.protos.KeepAspectRatioResizer',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='min_dimension', full_name='object_detection.protos.KeepAspectRatioResizer.min_dimension', index=0,\n      number=1, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=600,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_dimension', full_name='object_detection.protos.KeepAspectRatioResizer.max_dimension', index=1,\n      number=2, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=1024,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=273,\n  serialized_end=354,\n)\n\n\n_FIXEDSHAPERESIZER = _descriptor.Descriptor(\n  name='FixedShapeResizer',\n  full_name='object_detection.protos.FixedShapeResizer',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='height', full_name='object_detection.protos.FixedShapeResizer.height', index=0,\n      number=1, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=300,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='width', full_name='object_detection.protos.FixedShapeResizer.width', index=1,\n      number=2, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=300,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=356,\n  serialized_end=416,\n)\n\n_IMAGERESIZER.fields_by_name['keep_aspect_ratio_resizer'].message_type = _KEEPASPECTRATIORESIZER\n_IMAGERESIZER.fields_by_name['fixed_shape_resizer'].message_type = _FIXEDSHAPERESIZER\n_IMAGERESIZER.oneofs_by_name['image_resizer_oneof'].fields.append(\n  _IMAGERESIZER.fields_by_name['keep_aspect_ratio_resizer'])\n_IMAGERESIZER.fields_by_name['keep_aspect_ratio_resizer'].containing_oneof = _IMAGERESIZER.oneofs_by_name['image_resizer_oneof']\n_IMAGERESIZER.oneofs_by_name['image_resizer_oneof'].fields.append(\n  _IMAGERESIZER.fields_by_name['fixed_shape_resizer'])\n_IMAGERESIZER.fields_by_name['fixed_shape_resizer'].containing_oneof = _IMAGERESIZER.oneofs_by_name['image_resizer_oneof']\nDESCRIPTOR.message_types_by_name['ImageResizer'] = _IMAGERESIZER\nDESCRIPTOR.message_types_by_name['KeepAspectRatioResizer'] = _KEEPASPECTRATIORESIZER\nDESCRIPTOR.message_types_by_name['FixedShapeResizer'] = _FIXEDSHAPERESIZER\n\nImageResizer = _reflection.GeneratedProtocolMessageType('ImageResizer', (_message.Message,), dict(\n  DESCRIPTOR = _IMAGERESIZER,\n  __module__ = 'object_detection.protos.image_resizer_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.ImageResizer)\n  ))\n_sym_db.RegisterMessage(ImageResizer)\n\nKeepAspectRatioResizer = _reflection.GeneratedProtocolMessageType('KeepAspectRatioResizer', (_message.Message,), dict(\n  DESCRIPTOR = _KEEPASPECTRATIORESIZER,\n  __module__ = 'object_detection.protos.image_resizer_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.KeepAspectRatioResizer)\n  ))\n_sym_db.RegisterMessage(KeepAspectRatioResizer)\n\nFixedShapeResizer = _reflection.GeneratedProtocolMessageType('FixedShapeResizer', (_message.Message,), dict(\n  DESCRIPTOR = _FIXEDSHAPERESIZER,\n  __module__ = 'object_detection.protos.image_resizer_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.FixedShapeResizer)\n  ))\n_sym_db.RegisterMessage(FixedShapeResizer)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/input_reader.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\n// Configuration proto for defining input readers that generate Object Detection\n// Examples from input sources. Input readers are expected to generate a\n// dictionary of tensors, with the following fields populated:\n//\n// 'image': an [image_height, image_width, channels] image tensor that detection\n//    will be run on.\n// 'groundtruth_classes': a [num_boxes] int32 tensor storing the class\n//    labels of detected boxes in the image.\n// 'groundtruth_boxes': a [num_boxes, 4] float tensor storing the coordinates of\n//    detected boxes in the image.\n// 'groundtruth_instance_masks': (Optional), a [num_boxes, image_height,\n//    image_width] float tensor storing binary mask of the objects in boxes.\n\nmessage InputReader {\n  // Path to StringIntLabelMap pbtxt file specifying the mapping from string\n  // labels to integer ids.\n  optional string label_map_path = 1 [default=\"\"];\n\n  // Whether data should be processed in the order they are read in, or\n  // shuffled randomly.\n  optional bool shuffle = 2 [default=true];\n\n  // Maximum number of records to keep in reader queue.\n  optional uint32 queue_capacity = 3 [default=2000];\n\n  // Minimum number of records to keep in reader queue. A large value is needed\n  // to generate a good random shuffle.\n  optional uint32 min_after_dequeue = 4 [default=1000];\n\n  // The number of times a data source is read. If set to zero, the data source\n  // will be reused indefinitely.\n  optional uint32 num_epochs = 5 [default=0];\n\n  // Number of reader instances to create.\n  optional uint32 num_readers = 6 [default=8];\n\n  // Whether to load groundtruth instance masks.\n  optional bool load_instance_masks = 7 [default = false];\n\n  oneof input_reader {\n    TFRecordInputReader tf_record_input_reader = 8;\n    ExternalInputReader external_input_reader = 9;\n  }\n}\n\n// An input reader that reads TF Example protos from local TFRecord files.\nmessage TFRecordInputReader {\n  // Path to TFRecordFile.\n  optional string input_path = 1 [default=\"\"];\n}\n\n// An externally defined input reader. Users may define an extension to this\n// proto to interface their own input readers.\nmessage ExternalInputReader {\n  extensions 1 to 999;\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/input_reader_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/input_reader.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/input_reader.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n*object_detection/protos/input_reader.proto\\x12\\x17object_detection.protos\\\"\\xff\\x02\\n\\x0bInputReader\\x12\\x18\\n\\x0elabel_map_path\\x18\\x01 \\x01(\\t:\\x00\\x12\\x15\\n\\x07shuffle\\x18\\x02 \\x01(\\x08:\\x04true\\x12\\x1c\\n\\x0equeue_capacity\\x18\\x03 \\x01(\\r:\\x04\\x32\\x30\\x30\\x30\\x12\\x1f\\n\\x11min_after_dequeue\\x18\\x04 \\x01(\\r:\\x04\\x31\\x30\\x30\\x30\\x12\\x15\\n\\nnum_epochs\\x18\\x05 \\x01(\\r:\\x01\\x30\\x12\\x16\\n\\x0bnum_readers\\x18\\x06 \\x01(\\r:\\x01\\x38\\x12\\\"\\n\\x13load_instance_masks\\x18\\x07 \\x01(\\x08:\\x05\\x66\\x61lse\\x12N\\n\\x16tf_record_input_reader\\x18\\x08 \\x01(\\x0b\\x32,.object_detection.protos.TFRecordInputReaderH\\x00\\x12M\\n\\x15\\x65xternal_input_reader\\x18\\t \\x01(\\x0b\\x32,.object_detection.protos.ExternalInputReaderH\\x00\\x42\\x0e\\n\\x0cinput_reader\\\"+\\n\\x13TFRecordInputReader\\x12\\x14\\n\\ninput_path\\x18\\x01 \\x01(\\t:\\x00\\\"\\x1c\\n\\x13\\x45xternalInputReader*\\x05\\x08\\x01\\x10\\xe8\\x07')\n)\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_INPUTREADER = _descriptor.Descriptor(\n  name='InputReader',\n  full_name='object_detection.protos.InputReader',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='label_map_path', full_name='object_detection.protos.InputReader.label_map_path', index=0,\n      number=1, type=9, cpp_type=9, label=1,\n      has_default_value=True, default_value=_b(\"\").decode('utf-8'),\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='shuffle', full_name='object_detection.protos.InputReader.shuffle', index=1,\n      number=2, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=True,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='queue_capacity', full_name='object_detection.protos.InputReader.queue_capacity', index=2,\n      number=3, type=13, cpp_type=3, label=1,\n      has_default_value=True, default_value=2000,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='min_after_dequeue', full_name='object_detection.protos.InputReader.min_after_dequeue', index=3,\n      number=4, type=13, cpp_type=3, label=1,\n      has_default_value=True, default_value=1000,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='num_epochs', full_name='object_detection.protos.InputReader.num_epochs', index=4,\n      number=5, type=13, cpp_type=3, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='num_readers', full_name='object_detection.protos.InputReader.num_readers', index=5,\n      number=6, type=13, cpp_type=3, label=1,\n      has_default_value=True, default_value=8,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='load_instance_masks', full_name='object_detection.protos.InputReader.load_instance_masks', index=6,\n      number=7, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='tf_record_input_reader', full_name='object_detection.protos.InputReader.tf_record_input_reader', index=7,\n      number=8, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='external_input_reader', full_name='object_detection.protos.InputReader.external_input_reader', index=8,\n      number=9, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n    _descriptor.OneofDescriptor(\n      name='input_reader', full_name='object_detection.protos.InputReader.input_reader',\n      index=0, containing_type=None, fields=[]),\n  ],\n  serialized_start=72,\n  serialized_end=455,\n)\n\n\n_TFRECORDINPUTREADER = _descriptor.Descriptor(\n  name='TFRecordInputReader',\n  full_name='object_detection.protos.TFRecordInputReader',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='input_path', full_name='object_detection.protos.TFRecordInputReader.input_path', index=0,\n      number=1, type=9, cpp_type=9, label=1,\n      has_default_value=True, default_value=_b(\"\").decode('utf-8'),\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=457,\n  serialized_end=500,\n)\n\n\n_EXTERNALINPUTREADER = _descriptor.Descriptor(\n  name='ExternalInputReader',\n  full_name='object_detection.protos.ExternalInputReader',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=True,\n  extension_ranges=[(1, 1000), ],\n  oneofs=[\n  ],\n  serialized_start=502,\n  serialized_end=530,\n)\n\n_INPUTREADER.fields_by_name['tf_record_input_reader'].message_type = _TFRECORDINPUTREADER\n_INPUTREADER.fields_by_name['external_input_reader'].message_type = _EXTERNALINPUTREADER\n_INPUTREADER.oneofs_by_name['input_reader'].fields.append(\n  _INPUTREADER.fields_by_name['tf_record_input_reader'])\n_INPUTREADER.fields_by_name['tf_record_input_reader'].containing_oneof = _INPUTREADER.oneofs_by_name['input_reader']\n_INPUTREADER.oneofs_by_name['input_reader'].fields.append(\n  _INPUTREADER.fields_by_name['external_input_reader'])\n_INPUTREADER.fields_by_name['external_input_reader'].containing_oneof = _INPUTREADER.oneofs_by_name['input_reader']\nDESCRIPTOR.message_types_by_name['InputReader'] = _INPUTREADER\nDESCRIPTOR.message_types_by_name['TFRecordInputReader'] = _TFRECORDINPUTREADER\nDESCRIPTOR.message_types_by_name['ExternalInputReader'] = _EXTERNALINPUTREADER\n\nInputReader = _reflection.GeneratedProtocolMessageType('InputReader', (_message.Message,), dict(\n  DESCRIPTOR = _INPUTREADER,\n  __module__ = 'object_detection.protos.input_reader_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.InputReader)\n  ))\n_sym_db.RegisterMessage(InputReader)\n\nTFRecordInputReader = _reflection.GeneratedProtocolMessageType('TFRecordInputReader', (_message.Message,), dict(\n  DESCRIPTOR = _TFRECORDINPUTREADER,\n  __module__ = 'object_detection.protos.input_reader_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.TFRecordInputReader)\n  ))\n_sym_db.RegisterMessage(TFRecordInputReader)\n\nExternalInputReader = _reflection.GeneratedProtocolMessageType('ExternalInputReader', (_message.Message,), dict(\n  DESCRIPTOR = _EXTERNALINPUTREADER,\n  __module__ = 'object_detection.protos.input_reader_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.ExternalInputReader)\n  ))\n_sym_db.RegisterMessage(ExternalInputReader)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/losses.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\n// Message for configuring the localization loss, classification loss and hard\n// example miner used for training object detection models. See core/losses.py\n// for details\nmessage Loss {\n  // Localization loss to use.\n  optional LocalizationLoss localization_loss = 1;\n\n  // Classification loss to use.\n  optional ClassificationLoss classification_loss = 2;\n\n  // If not left to default, applies hard example mining.\n  optional HardExampleMiner hard_example_miner = 3;\n\n  // Classification loss weight.\n  optional float classification_weight = 4 [default=1.0];\n\n  // Localization loss weight.\n  optional float localization_weight = 5 [default=1.0];\n}\n\n// Configuration for bounding box localization loss function.\nmessage LocalizationLoss {\n  oneof localization_loss {\n    WeightedL2LocalizationLoss weighted_l2 = 1;\n    WeightedSmoothL1LocalizationLoss weighted_smooth_l1 = 2;\n    WeightedIOULocalizationLoss weighted_iou = 3;\n  }\n}\n\n// L2 location loss: 0.5 * ||weight * (a - b)|| ^ 2\nmessage WeightedL2LocalizationLoss {\n  // Output loss per anchor.\n  optional bool anchorwise_output = 1 [default=false];\n}\n\n// SmoothL1 (Huber) location loss: .5 * x ^ 2 if |x| < 1 else |x| - .5\nmessage WeightedSmoothL1LocalizationLoss {\n  // Output loss per anchor.\n  optional bool anchorwise_output = 1 [default=false];\n}\n\n// Intersection over union location loss: 1 - IOU\nmessage WeightedIOULocalizationLoss {\n}\n\n// Configuration for class prediction loss function.\nmessage ClassificationLoss {\n  oneof classification_loss {\n    WeightedSigmoidClassificationLoss weighted_sigmoid = 1;\n    WeightedSoftmaxClassificationLoss weighted_softmax = 2;\n    BootstrappedSigmoidClassificationLoss bootstrapped_sigmoid = 3;\n  }\n}\n\n// Classification loss using a sigmoid function over class predictions.\nmessage WeightedSigmoidClassificationLoss {\n  // Output loss per anchor.\n  optional bool anchorwise_output = 1 [default=false];\n}\n\n// Classification loss using a softmax function over class predictions.\nmessage WeightedSoftmaxClassificationLoss {\n  // Output loss per anchor.\n  optional bool anchorwise_output = 1 [default=false];\n}\n\n// Classification loss using a sigmoid function over the class prediction with\n// the highest prediction score.\nmessage BootstrappedSigmoidClassificationLoss {\n  // Interpolation weight between 0 and 1.\n  optional float alpha = 1;\n\n  // Whether hard boot strapping should be used or not. If true, will only use\n  // one class favored by model. Othewise, will use all predicted class\n  // probabilities.\n  optional bool hard_bootstrap = 2 [default=false];\n\n  // Output loss per anchor.\n  optional bool anchorwise_output = 3 [default=false];\n}\n\n// Configuation for hard example miner.\nmessage HardExampleMiner {\n  // Maximum number of hard examples to be selected per image (prior to\n  // enforcing max negative to positive ratio constraint).  If set to 0,\n  // all examples obtained after NMS are considered.\n  optional int32 num_hard_examples = 1 [default=64];\n\n  // Minimum intersection over union for an example to be discarded during NMS.\n  optional float iou_threshold = 2 [default=0.7];\n\n  // Whether to use classification losses ('cls', default), localization losses\n  // ('loc') or both losses ('both'). In the case of 'both', cls_loss_weight and\n  // loc_loss_weight are used to compute weighted sum of the two losses.\n  enum LossType {\n    BOTH = 0;\n    CLASSIFICATION = 1;\n    LOCALIZATION = 2;\n  }\n  optional LossType loss_type = 3 [default=BOTH];\n\n  // Maximum number of negatives to retain for each positive anchor. If\n  // num_negatives_per_positive is 0 no prespecified negative:positive ratio is\n  // enforced.\n  optional int32 max_negatives_per_positive = 4 [default=0];\n\n  // Minimum number of negative anchors to sample for a given image. Setting\n  // this to a positive number samples negatives in an image without any\n  // positive anchors and thus not bias the model towards having at least one\n  // detection per image.\n  optional int32 min_negatives_per_image = 5 [default=0];\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/losses_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/losses.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/losses.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n$object_detection/protos/losses.proto\\x12\\x17object_detection.protos\\\"\\x9f\\x02\\n\\x04Loss\\x12\\x44\\n\\x11localization_loss\\x18\\x01 \\x01(\\x0b\\x32).object_detection.protos.LocalizationLoss\\x12H\\n\\x13\\x63lassification_loss\\x18\\x02 \\x01(\\x0b\\x32+.object_detection.protos.ClassificationLoss\\x12\\x45\\n\\x12hard_example_miner\\x18\\x03 \\x01(\\x0b\\x32).object_detection.protos.HardExampleMiner\\x12 \\n\\x15\\x63lassification_weight\\x18\\x04 \\x01(\\x02:\\x01\\x31\\x12\\x1e\\n\\x13localization_weight\\x18\\x05 \\x01(\\x02:\\x01\\x31\\\"\\x9a\\x02\\n\\x10LocalizationLoss\\x12J\\n\\x0bweighted_l2\\x18\\x01 \\x01(\\x0b\\x32\\x33.object_detection.protos.WeightedL2LocalizationLossH\\x00\\x12W\\n\\x12weighted_smooth_l1\\x18\\x02 \\x01(\\x0b\\x32\\x39.object_detection.protos.WeightedSmoothL1LocalizationLossH\\x00\\x12L\\n\\x0cweighted_iou\\x18\\x03 \\x01(\\x0b\\x32\\x34.object_detection.protos.WeightedIOULocalizationLossH\\x00\\x42\\x13\\n\\x11localization_loss\\\">\\n\\x1aWeightedL2LocalizationLoss\\x12 \\n\\x11\\x61nchorwise_output\\x18\\x01 \\x01(\\x08:\\x05\\x66\\x61lse\\\"D\\n WeightedSmoothL1LocalizationLoss\\x12 \\n\\x11\\x61nchorwise_output\\x18\\x01 \\x01(\\x08:\\x05\\x66\\x61lse\\\"\\x1d\\n\\x1bWeightedIOULocalizationLoss\\\"\\xbb\\x02\\n\\x12\\x43lassificationLoss\\x12V\\n\\x10weighted_sigmoid\\x18\\x01 \\x01(\\x0b\\x32:.object_detection.protos.WeightedSigmoidClassificationLossH\\x00\\x12V\\n\\x10weighted_softmax\\x18\\x02 \\x01(\\x0b\\x32:.object_detection.protos.WeightedSoftmaxClassificationLossH\\x00\\x12^\\n\\x14\\x62ootstrapped_sigmoid\\x18\\x03 \\x01(\\x0b\\x32>.object_detection.protos.BootstrappedSigmoidClassificationLossH\\x00\\x42\\x15\\n\\x13\\x63lassification_loss\\\"E\\n!WeightedSigmoidClassificationLoss\\x12 \\n\\x11\\x61nchorwise_output\\x18\\x01 \\x01(\\x08:\\x05\\x66\\x61lse\\\"E\\n!WeightedSoftmaxClassificationLoss\\x12 \\n\\x11\\x61nchorwise_output\\x18\\x01 \\x01(\\x08:\\x05\\x66\\x61lse\\\"w\\n%BootstrappedSigmoidClassificationLoss\\x12\\r\\n\\x05\\x61lpha\\x18\\x01 \\x01(\\x02\\x12\\x1d\\n\\x0ehard_bootstrap\\x18\\x02 \\x01(\\x08:\\x05\\x66\\x61lse\\x12 \\n\\x11\\x61nchorwise_output\\x18\\x03 \\x01(\\x08:\\x05\\x66\\x61lse\\\"\\xa1\\x02\\n\\x10HardExampleMiner\\x12\\x1d\\n\\x11num_hard_examples\\x18\\x01 \\x01(\\x05:\\x02\\x36\\x34\\x12\\x1a\\n\\riou_threshold\\x18\\x02 \\x01(\\x02:\\x03\\x30.7\\x12K\\n\\tloss_type\\x18\\x03 \\x01(\\x0e\\x32\\x32.object_detection.protos.HardExampleMiner.LossType:\\x04\\x42OTH\\x12%\\n\\x1amax_negatives_per_positive\\x18\\x04 \\x01(\\x05:\\x01\\x30\\x12\\\"\\n\\x17min_negatives_per_image\\x18\\x05 \\x01(\\x05:\\x01\\x30\\\":\\n\\x08LossType\\x12\\x08\\n\\x04\\x42OTH\\x10\\x00\\x12\\x12\\n\\x0e\\x43LASSIFICATION\\x10\\x01\\x12\\x10\\n\\x0cLOCALIZATION\\x10\\x02')\n)\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n_HARDEXAMPLEMINER_LOSSTYPE = _descriptor.EnumDescriptor(\n  name='LossType',\n  full_name='object_detection.protos.HardExampleMiner.LossType',\n  filename=None,\n  file=DESCRIPTOR,\n  values=[\n    _descriptor.EnumValueDescriptor(\n      name='BOTH', index=0, number=0,\n      options=None,\n      type=None),\n    _descriptor.EnumValueDescriptor(\n      name='CLASSIFICATION', index=1, number=1,\n      options=None,\n      type=None),\n    _descriptor.EnumValueDescriptor(\n      name='LOCALIZATION', index=2, number=2,\n      options=None,\n      type=None),\n  ],\n  containing_type=None,\n  options=None,\n  serialized_start=1618,\n  serialized_end=1676,\n)\n_sym_db.RegisterEnumDescriptor(_HARDEXAMPLEMINER_LOSSTYPE)\n\n\n_LOSS = _descriptor.Descriptor(\n  name='Loss',\n  full_name='object_detection.protos.Loss',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='localization_loss', full_name='object_detection.protos.Loss.localization_loss', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='classification_loss', full_name='object_detection.protos.Loss.classification_loss', index=1,\n      number=2, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='hard_example_miner', full_name='object_detection.protos.Loss.hard_example_miner', index=2,\n      number=3, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='classification_weight', full_name='object_detection.protos.Loss.classification_weight', index=3,\n      number=4, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='localization_weight', full_name='object_detection.protos.Loss.localization_weight', index=4,\n      number=5, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=66,\n  serialized_end=353,\n)\n\n\n_LOCALIZATIONLOSS = _descriptor.Descriptor(\n  name='LocalizationLoss',\n  full_name='object_detection.protos.LocalizationLoss',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='weighted_l2', full_name='object_detection.protos.LocalizationLoss.weighted_l2', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='weighted_smooth_l1', full_name='object_detection.protos.LocalizationLoss.weighted_smooth_l1', index=1,\n      number=2, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='weighted_iou', full_name='object_detection.protos.LocalizationLoss.weighted_iou', index=2,\n      number=3, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n    _descriptor.OneofDescriptor(\n      name='localization_loss', full_name='object_detection.protos.LocalizationLoss.localization_loss',\n      index=0, containing_type=None, fields=[]),\n  ],\n  serialized_start=356,\n  serialized_end=638,\n)\n\n\n_WEIGHTEDL2LOCALIZATIONLOSS = _descriptor.Descriptor(\n  name='WeightedL2LocalizationLoss',\n  full_name='object_detection.protos.WeightedL2LocalizationLoss',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='anchorwise_output', full_name='object_detection.protos.WeightedL2LocalizationLoss.anchorwise_output', index=0,\n      number=1, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=640,\n  serialized_end=702,\n)\n\n\n_WEIGHTEDSMOOTHL1LOCALIZATIONLOSS = _descriptor.Descriptor(\n  name='WeightedSmoothL1LocalizationLoss',\n  full_name='object_detection.protos.WeightedSmoothL1LocalizationLoss',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='anchorwise_output', full_name='object_detection.protos.WeightedSmoothL1LocalizationLoss.anchorwise_output', index=0,\n      number=1, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=704,\n  serialized_end=772,\n)\n\n\n_WEIGHTEDIOULOCALIZATIONLOSS = _descriptor.Descriptor(\n  name='WeightedIOULocalizationLoss',\n  full_name='object_detection.protos.WeightedIOULocalizationLoss',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=774,\n  serialized_end=803,\n)\n\n\n_CLASSIFICATIONLOSS = _descriptor.Descriptor(\n  name='ClassificationLoss',\n  full_name='object_detection.protos.ClassificationLoss',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='weighted_sigmoid', full_name='object_detection.protos.ClassificationLoss.weighted_sigmoid', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='weighted_softmax', full_name='object_detection.protos.ClassificationLoss.weighted_softmax', index=1,\n      number=2, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='bootstrapped_sigmoid', full_name='object_detection.protos.ClassificationLoss.bootstrapped_sigmoid', index=2,\n      number=3, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n    _descriptor.OneofDescriptor(\n      name='classification_loss', full_name='object_detection.protos.ClassificationLoss.classification_loss',\n      index=0, containing_type=None, fields=[]),\n  ],\n  serialized_start=806,\n  serialized_end=1121,\n)\n\n\n_WEIGHTEDSIGMOIDCLASSIFICATIONLOSS = _descriptor.Descriptor(\n  name='WeightedSigmoidClassificationLoss',\n  full_name='object_detection.protos.WeightedSigmoidClassificationLoss',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='anchorwise_output', full_name='object_detection.protos.WeightedSigmoidClassificationLoss.anchorwise_output', index=0,\n      number=1, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=1123,\n  serialized_end=1192,\n)\n\n\n_WEIGHTEDSOFTMAXCLASSIFICATIONLOSS = _descriptor.Descriptor(\n  name='WeightedSoftmaxClassificationLoss',\n  full_name='object_detection.protos.WeightedSoftmaxClassificationLoss',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='anchorwise_output', full_name='object_detection.protos.WeightedSoftmaxClassificationLoss.anchorwise_output', index=0,\n      number=1, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=1194,\n  serialized_end=1263,\n)\n\n\n_BOOTSTRAPPEDSIGMOIDCLASSIFICATIONLOSS = _descriptor.Descriptor(\n  name='BootstrappedSigmoidClassificationLoss',\n  full_name='object_detection.protos.BootstrappedSigmoidClassificationLoss',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='alpha', full_name='object_detection.protos.BootstrappedSigmoidClassificationLoss.alpha', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='hard_bootstrap', full_name='object_detection.protos.BootstrappedSigmoidClassificationLoss.hard_bootstrap', index=1,\n      number=2, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='anchorwise_output', full_name='object_detection.protos.BootstrappedSigmoidClassificationLoss.anchorwise_output', index=2,\n      number=3, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=1265,\n  serialized_end=1384,\n)\n\n\n_HARDEXAMPLEMINER = _descriptor.Descriptor(\n  name='HardExampleMiner',\n  full_name='object_detection.protos.HardExampleMiner',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='num_hard_examples', full_name='object_detection.protos.HardExampleMiner.num_hard_examples', index=0,\n      number=1, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=64,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='iou_threshold', full_name='object_detection.protos.HardExampleMiner.iou_threshold', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.7,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='loss_type', full_name='object_detection.protos.HardExampleMiner.loss_type', index=2,\n      number=3, type=14, cpp_type=8, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_negatives_per_positive', full_name='object_detection.protos.HardExampleMiner.max_negatives_per_positive', index=3,\n      number=4, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='min_negatives_per_image', full_name='object_detection.protos.HardExampleMiner.min_negatives_per_image', index=4,\n      number=5, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n    _HARDEXAMPLEMINER_LOSSTYPE,\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=1387,\n  serialized_end=1676,\n)\n\n_LOSS.fields_by_name['localization_loss'].message_type = _LOCALIZATIONLOSS\n_LOSS.fields_by_name['classification_loss'].message_type = _CLASSIFICATIONLOSS\n_LOSS.fields_by_name['hard_example_miner'].message_type = _HARDEXAMPLEMINER\n_LOCALIZATIONLOSS.fields_by_name['weighted_l2'].message_type = _WEIGHTEDL2LOCALIZATIONLOSS\n_LOCALIZATIONLOSS.fields_by_name['weighted_smooth_l1'].message_type = _WEIGHTEDSMOOTHL1LOCALIZATIONLOSS\n_LOCALIZATIONLOSS.fields_by_name['weighted_iou'].message_type = _WEIGHTEDIOULOCALIZATIONLOSS\n_LOCALIZATIONLOSS.oneofs_by_name['localization_loss'].fields.append(\n  _LOCALIZATIONLOSS.fields_by_name['weighted_l2'])\n_LOCALIZATIONLOSS.fields_by_name['weighted_l2'].containing_oneof = _LOCALIZATIONLOSS.oneofs_by_name['localization_loss']\n_LOCALIZATIONLOSS.oneofs_by_name['localization_loss'].fields.append(\n  _LOCALIZATIONLOSS.fields_by_name['weighted_smooth_l1'])\n_LOCALIZATIONLOSS.fields_by_name['weighted_smooth_l1'].containing_oneof = _LOCALIZATIONLOSS.oneofs_by_name['localization_loss']\n_LOCALIZATIONLOSS.oneofs_by_name['localization_loss'].fields.append(\n  _LOCALIZATIONLOSS.fields_by_name['weighted_iou'])\n_LOCALIZATIONLOSS.fields_by_name['weighted_iou'].containing_oneof = _LOCALIZATIONLOSS.oneofs_by_name['localization_loss']\n_CLASSIFICATIONLOSS.fields_by_name['weighted_sigmoid'].message_type = _WEIGHTEDSIGMOIDCLASSIFICATIONLOSS\n_CLASSIFICATIONLOSS.fields_by_name['weighted_softmax'].message_type = _WEIGHTEDSOFTMAXCLASSIFICATIONLOSS\n_CLASSIFICATIONLOSS.fields_by_name['bootstrapped_sigmoid'].message_type = _BOOTSTRAPPEDSIGMOIDCLASSIFICATIONLOSS\n_CLASSIFICATIONLOSS.oneofs_by_name['classification_loss'].fields.append(\n  _CLASSIFICATIONLOSS.fields_by_name['weighted_sigmoid'])\n_CLASSIFICATIONLOSS.fields_by_name['weighted_sigmoid'].containing_oneof = _CLASSIFICATIONLOSS.oneofs_by_name['classification_loss']\n_CLASSIFICATIONLOSS.oneofs_by_name['classification_loss'].fields.append(\n  _CLASSIFICATIONLOSS.fields_by_name['weighted_softmax'])\n_CLASSIFICATIONLOSS.fields_by_name['weighted_softmax'].containing_oneof = _CLASSIFICATIONLOSS.oneofs_by_name['classification_loss']\n_CLASSIFICATIONLOSS.oneofs_by_name['classification_loss'].fields.append(\n  _CLASSIFICATIONLOSS.fields_by_name['bootstrapped_sigmoid'])\n_CLASSIFICATIONLOSS.fields_by_name['bootstrapped_sigmoid'].containing_oneof = _CLASSIFICATIONLOSS.oneofs_by_name['classification_loss']\n_HARDEXAMPLEMINER.fields_by_name['loss_type'].enum_type = _HARDEXAMPLEMINER_LOSSTYPE\n_HARDEXAMPLEMINER_LOSSTYPE.containing_type = _HARDEXAMPLEMINER\nDESCRIPTOR.message_types_by_name['Loss'] = _LOSS\nDESCRIPTOR.message_types_by_name['LocalizationLoss'] = _LOCALIZATIONLOSS\nDESCRIPTOR.message_types_by_name['WeightedL2LocalizationLoss'] = _WEIGHTEDL2LOCALIZATIONLOSS\nDESCRIPTOR.message_types_by_name['WeightedSmoothL1LocalizationLoss'] = _WEIGHTEDSMOOTHL1LOCALIZATIONLOSS\nDESCRIPTOR.message_types_by_name['WeightedIOULocalizationLoss'] = _WEIGHTEDIOULOCALIZATIONLOSS\nDESCRIPTOR.message_types_by_name['ClassificationLoss'] = _CLASSIFICATIONLOSS\nDESCRIPTOR.message_types_by_name['WeightedSigmoidClassificationLoss'] = _WEIGHTEDSIGMOIDCLASSIFICATIONLOSS\nDESCRIPTOR.message_types_by_name['WeightedSoftmaxClassificationLoss'] = _WEIGHTEDSOFTMAXCLASSIFICATIONLOSS\nDESCRIPTOR.message_types_by_name['BootstrappedSigmoidClassificationLoss'] = _BOOTSTRAPPEDSIGMOIDCLASSIFICATIONLOSS\nDESCRIPTOR.message_types_by_name['HardExampleMiner'] = _HARDEXAMPLEMINER\n\nLoss = _reflection.GeneratedProtocolMessageType('Loss', (_message.Message,), dict(\n  DESCRIPTOR = _LOSS,\n  __module__ = 'object_detection.protos.losses_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.Loss)\n  ))\n_sym_db.RegisterMessage(Loss)\n\nLocalizationLoss = _reflection.GeneratedProtocolMessageType('LocalizationLoss', (_message.Message,), dict(\n  DESCRIPTOR = _LOCALIZATIONLOSS,\n  __module__ = 'object_detection.protos.losses_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.LocalizationLoss)\n  ))\n_sym_db.RegisterMessage(LocalizationLoss)\n\nWeightedL2LocalizationLoss = _reflection.GeneratedProtocolMessageType('WeightedL2LocalizationLoss', (_message.Message,), dict(\n  DESCRIPTOR = _WEIGHTEDL2LOCALIZATIONLOSS,\n  __module__ = 'object_detection.protos.losses_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.WeightedL2LocalizationLoss)\n  ))\n_sym_db.RegisterMessage(WeightedL2LocalizationLoss)\n\nWeightedSmoothL1LocalizationLoss = _reflection.GeneratedProtocolMessageType('WeightedSmoothL1LocalizationLoss', (_message.Message,), dict(\n  DESCRIPTOR = _WEIGHTEDSMOOTHL1LOCALIZATIONLOSS,\n  __module__ = 'object_detection.protos.losses_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.WeightedSmoothL1LocalizationLoss)\n  ))\n_sym_db.RegisterMessage(WeightedSmoothL1LocalizationLoss)\n\nWeightedIOULocalizationLoss = _reflection.GeneratedProtocolMessageType('WeightedIOULocalizationLoss', (_message.Message,), dict(\n  DESCRIPTOR = _WEIGHTEDIOULOCALIZATIONLOSS,\n  __module__ = 'object_detection.protos.losses_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.WeightedIOULocalizationLoss)\n  ))\n_sym_db.RegisterMessage(WeightedIOULocalizationLoss)\n\nClassificationLoss = _reflection.GeneratedProtocolMessageType('ClassificationLoss', (_message.Message,), dict(\n  DESCRIPTOR = _CLASSIFICATIONLOSS,\n  __module__ = 'object_detection.protos.losses_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.ClassificationLoss)\n  ))\n_sym_db.RegisterMessage(ClassificationLoss)\n\nWeightedSigmoidClassificationLoss = _reflection.GeneratedProtocolMessageType('WeightedSigmoidClassificationLoss', (_message.Message,), dict(\n  DESCRIPTOR = _WEIGHTEDSIGMOIDCLASSIFICATIONLOSS,\n  __module__ = 'object_detection.protos.losses_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.WeightedSigmoidClassificationLoss)\n  ))\n_sym_db.RegisterMessage(WeightedSigmoidClassificationLoss)\n\nWeightedSoftmaxClassificationLoss = _reflection.GeneratedProtocolMessageType('WeightedSoftmaxClassificationLoss', (_message.Message,), dict(\n  DESCRIPTOR = _WEIGHTEDSOFTMAXCLASSIFICATIONLOSS,\n  __module__ = 'object_detection.protos.losses_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.WeightedSoftmaxClassificationLoss)\n  ))\n_sym_db.RegisterMessage(WeightedSoftmaxClassificationLoss)\n\nBootstrappedSigmoidClassificationLoss = _reflection.GeneratedProtocolMessageType('BootstrappedSigmoidClassificationLoss', (_message.Message,), dict(\n  DESCRIPTOR = _BOOTSTRAPPEDSIGMOIDCLASSIFICATIONLOSS,\n  __module__ = 'object_detection.protos.losses_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.BootstrappedSigmoidClassificationLoss)\n  ))\n_sym_db.RegisterMessage(BootstrappedSigmoidClassificationLoss)\n\nHardExampleMiner = _reflection.GeneratedProtocolMessageType('HardExampleMiner', (_message.Message,), dict(\n  DESCRIPTOR = _HARDEXAMPLEMINER,\n  __module__ = 'object_detection.protos.losses_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.HardExampleMiner)\n  ))\n_sym_db.RegisterMessage(HardExampleMiner)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/matcher.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\nimport \"object_detection/protos/argmax_matcher.proto\";\nimport \"object_detection/protos/bipartite_matcher.proto\";\n\n// Configuration proto for the matcher to be used in the object detection\n// pipeline. See core/matcher.py for details.\nmessage Matcher {\n  oneof matcher_oneof {\n    ArgMaxMatcher argmax_matcher = 1;\n    BipartiteMatcher bipartite_matcher = 2;\n  }\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/matcher_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/matcher.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\nimport object_detection.protos.argmax_matcher_pb2\nimport object_detection.protos.bipartite_matcher_pb2\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/matcher.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n%object_detection/protos/matcher.proto\\x12\\x17object_detection.protos\\x1a,object_detection/protos/argmax_matcher.proto\\x1a/object_detection/protos/bipartite_matcher.proto\\\"\\xa4\\x01\\n\\x07Matcher\\x12@\\n\\x0e\\x61rgmax_matcher\\x18\\x01 \\x01(\\x0b\\x32&.object_detection.protos.ArgMaxMatcherH\\x00\\x12\\x46\\n\\x11\\x62ipartite_matcher\\x18\\x02 \\x01(\\x0b\\x32).object_detection.protos.BipartiteMatcherH\\x00\\x42\\x0f\\n\\rmatcher_oneof')\n  ,\n  dependencies=[object_detection.protos.argmax_matcher_pb2.DESCRIPTOR,object_detection.protos.bipartite_matcher_pb2.DESCRIPTOR,])\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_MATCHER = _descriptor.Descriptor(\n  name='Matcher',\n  full_name='object_detection.protos.Matcher',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='argmax_matcher', full_name='object_detection.protos.Matcher.argmax_matcher', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='bipartite_matcher', full_name='object_detection.protos.Matcher.bipartite_matcher', index=1,\n      number=2, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n    _descriptor.OneofDescriptor(\n      name='matcher_oneof', full_name='object_detection.protos.Matcher.matcher_oneof',\n      index=0, containing_type=None, fields=[]),\n  ],\n  serialized_start=162,\n  serialized_end=326,\n)\n\n_MATCHER.fields_by_name['argmax_matcher'].message_type = object_detection.protos.argmax_matcher_pb2._ARGMAXMATCHER\n_MATCHER.fields_by_name['bipartite_matcher'].message_type = object_detection.protos.bipartite_matcher_pb2._BIPARTITEMATCHER\n_MATCHER.oneofs_by_name['matcher_oneof'].fields.append(\n  _MATCHER.fields_by_name['argmax_matcher'])\n_MATCHER.fields_by_name['argmax_matcher'].containing_oneof = _MATCHER.oneofs_by_name['matcher_oneof']\n_MATCHER.oneofs_by_name['matcher_oneof'].fields.append(\n  _MATCHER.fields_by_name['bipartite_matcher'])\n_MATCHER.fields_by_name['bipartite_matcher'].containing_oneof = _MATCHER.oneofs_by_name['matcher_oneof']\nDESCRIPTOR.message_types_by_name['Matcher'] = _MATCHER\n\nMatcher = _reflection.GeneratedProtocolMessageType('Matcher', (_message.Message,), dict(\n  DESCRIPTOR = _MATCHER,\n  __module__ = 'object_detection.protos.matcher_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.Matcher)\n  ))\n_sym_db.RegisterMessage(Matcher)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/mean_stddev_box_coder.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\n// Configuration proto for MeanStddevBoxCoder. See\n// box_coders/mean_stddev_box_coder.py for details.\nmessage MeanStddevBoxCoder {\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/mean_stddev_box_coder_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/mean_stddev_box_coder.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/mean_stddev_box_coder.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n3object_detection/protos/mean_stddev_box_coder.proto\\x12\\x17object_detection.protos\\\"\\x14\\n\\x12MeanStddevBoxCoder')\n)\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_MEANSTDDEVBOXCODER = _descriptor.Descriptor(\n  name='MeanStddevBoxCoder',\n  full_name='object_detection.protos.MeanStddevBoxCoder',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=80,\n  serialized_end=100,\n)\n\nDESCRIPTOR.message_types_by_name['MeanStddevBoxCoder'] = _MEANSTDDEVBOXCODER\n\nMeanStddevBoxCoder = _reflection.GeneratedProtocolMessageType('MeanStddevBoxCoder', (_message.Message,), dict(\n  DESCRIPTOR = _MEANSTDDEVBOXCODER,\n  __module__ = 'object_detection.protos.mean_stddev_box_coder_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.MeanStddevBoxCoder)\n  ))\n_sym_db.RegisterMessage(MeanStddevBoxCoder)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/model.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\nimport \"object_detection/protos/faster_rcnn.proto\";\nimport \"object_detection/protos/ssd.proto\";\n\n// Top level configuration for DetectionModels.\nmessage DetectionModel {\n  oneof model {\n    FasterRcnn faster_rcnn = 1;\n    Ssd ssd = 2;\n  }\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/model_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/model.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\nimport object_detection.protos.faster_rcnn_pb2\nimport object_detection.protos.ssd_pb2\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/model.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n#object_detection/protos/model.proto\\x12\\x17object_detection.protos\\x1a)object_detection/protos/faster_rcnn.proto\\x1a!object_detection/protos/ssd.proto\\\"\\x82\\x01\\n\\x0e\\x44\\x65tectionModel\\x12:\\n\\x0b\\x66\\x61ster_rcnn\\x18\\x01 \\x01(\\x0b\\x32#.object_detection.protos.FasterRcnnH\\x00\\x12+\\n\\x03ssd\\x18\\x02 \\x01(\\x0b\\x32\\x1c.object_detection.protos.SsdH\\x00\\x42\\x07\\n\\x05model')\n  ,\n  dependencies=[object_detection.protos.faster_rcnn_pb2.DESCRIPTOR,object_detection.protos.ssd_pb2.DESCRIPTOR,])\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_DETECTIONMODEL = _descriptor.Descriptor(\n  name='DetectionModel',\n  full_name='object_detection.protos.DetectionModel',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='faster_rcnn', full_name='object_detection.protos.DetectionModel.faster_rcnn', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='ssd', full_name='object_detection.protos.DetectionModel.ssd', index=1,\n      number=2, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n    _descriptor.OneofDescriptor(\n      name='model', full_name='object_detection.protos.DetectionModel.model',\n      index=0, containing_type=None, fields=[]),\n  ],\n  serialized_start=143,\n  serialized_end=273,\n)\n\n_DETECTIONMODEL.fields_by_name['faster_rcnn'].message_type = object_detection.protos.faster_rcnn_pb2._FASTERRCNN\n_DETECTIONMODEL.fields_by_name['ssd'].message_type = object_detection.protos.ssd_pb2._SSD\n_DETECTIONMODEL.oneofs_by_name['model'].fields.append(\n  _DETECTIONMODEL.fields_by_name['faster_rcnn'])\n_DETECTIONMODEL.fields_by_name['faster_rcnn'].containing_oneof = _DETECTIONMODEL.oneofs_by_name['model']\n_DETECTIONMODEL.oneofs_by_name['model'].fields.append(\n  _DETECTIONMODEL.fields_by_name['ssd'])\n_DETECTIONMODEL.fields_by_name['ssd'].containing_oneof = _DETECTIONMODEL.oneofs_by_name['model']\nDESCRIPTOR.message_types_by_name['DetectionModel'] = _DETECTIONMODEL\n\nDetectionModel = _reflection.GeneratedProtocolMessageType('DetectionModel', (_message.Message,), dict(\n  DESCRIPTOR = _DETECTIONMODEL,\n  __module__ = 'object_detection.protos.model_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.DetectionModel)\n  ))\n_sym_db.RegisterMessage(DetectionModel)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/optimizer.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\n// Messages for configuring the optimizing strategy for training object\n// detection models.\n\n// Top level optimizer message.\nmessage Optimizer {\n  oneof optimizer {\n    RMSPropOptimizer rms_prop_optimizer = 1;\n    MomentumOptimizer momentum_optimizer = 2;\n    AdamOptimizer adam_optimizer = 3;\n  }\n  optional bool use_moving_average = 4 [default=true];\n  optional float moving_average_decay = 5 [default=0.9999];\n}\n\n// Configuration message for the RMSPropOptimizer\n// See: https://www.tensorflow.org/api_docs/python/tf/train/RMSPropOptimizer\nmessage RMSPropOptimizer {\n  optional LearningRate learning_rate = 1;\n  optional float momentum_optimizer_value = 2 [default=0.9];\n  optional float decay = 3 [default=0.9];\n  optional float epsilon = 4 [default=1.0];\n}\n\n// Configuration message for the MomentumOptimizer\n// See: https://www.tensorflow.org/api_docs/python/tf/train/MomentumOptimizer\nmessage MomentumOptimizer {\n  optional LearningRate learning_rate = 1;\n  optional float momentum_optimizer_value = 2 [default=0.9];\n}\n\n// Configuration message for the AdamOptimizer\n// See: https://www.tensorflow.org/api_docs/python/tf/train/AdamOptimizer\nmessage AdamOptimizer {\n  optional LearningRate learning_rate = 1;\n}\n\n// Configuration message for optimizer learning rate.\nmessage LearningRate {\n  oneof learning_rate {\n    ConstantLearningRate constant_learning_rate = 1;\n    ExponentialDecayLearningRate exponential_decay_learning_rate = 2;\n    ManualStepLearningRate manual_step_learning_rate = 3;\n  }\n}\n\n// Configuration message for a constant learning rate.\nmessage ConstantLearningRate {\n  optional float learning_rate = 1 [default=0.002];\n}\n\n// Configuration message for an exponentially decaying learning rate.\n// See https://www.tensorflow.org/versions/master/api_docs/python/train/ \\\n//     decaying_the_learning_rate#exponential_decay\nmessage ExponentialDecayLearningRate {\n  optional float initial_learning_rate = 1 [default=0.002];\n  optional uint32 decay_steps = 2 [default=4000000];\n  optional float decay_factor = 3 [default=0.95];\n  optional bool staircase = 4 [default=true];\n}\n\n// Configuration message for a manually defined learning rate schedule.\nmessage ManualStepLearningRate {\n  optional float initial_learning_rate = 1 [default=0.002];\n  message LearningRateSchedule {\n    optional uint32 step = 1;\n    optional float learning_rate = 2 [default=0.002];\n  }\n  repeated LearningRateSchedule schedule = 2;\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/optimizer_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/optimizer.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/optimizer.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n\\'object_detection/protos/optimizer.proto\\x12\\x17object_detection.protos\\\"\\xb5\\x02\\n\\tOptimizer\\x12G\\n\\x12rms_prop_optimizer\\x18\\x01 \\x01(\\x0b\\x32).object_detection.protos.RMSPropOptimizerH\\x00\\x12H\\n\\x12momentum_optimizer\\x18\\x02 \\x01(\\x0b\\x32*.object_detection.protos.MomentumOptimizerH\\x00\\x12@\\n\\x0e\\x61\\x64\\x61m_optimizer\\x18\\x03 \\x01(\\x0b\\x32&.object_detection.protos.AdamOptimizerH\\x00\\x12 \\n\\x12use_moving_average\\x18\\x04 \\x01(\\x08:\\x04true\\x12$\\n\\x14moving_average_decay\\x18\\x05 \\x01(\\x02:\\x06\\x30.9999B\\x0b\\n\\toptimizer\\\"\\x9f\\x01\\n\\x10RMSPropOptimizer\\x12<\\n\\rlearning_rate\\x18\\x01 \\x01(\\x0b\\x32%.object_detection.protos.LearningRate\\x12%\\n\\x18momentum_optimizer_value\\x18\\x02 \\x01(\\x02:\\x03\\x30.9\\x12\\x12\\n\\x05\\x64\\x65\\x63\\x61y\\x18\\x03 \\x01(\\x02:\\x03\\x30.9\\x12\\x12\\n\\x07\\x65psilon\\x18\\x04 \\x01(\\x02:\\x01\\x31\\\"x\\n\\x11MomentumOptimizer\\x12<\\n\\rlearning_rate\\x18\\x01 \\x01(\\x0b\\x32%.object_detection.protos.LearningRate\\x12%\\n\\x18momentum_optimizer_value\\x18\\x02 \\x01(\\x02:\\x03\\x30.9\\\"M\\n\\rAdamOptimizer\\x12<\\n\\rlearning_rate\\x18\\x01 \\x01(\\x0b\\x32%.object_detection.protos.LearningRate\\\"\\xa8\\x02\\n\\x0cLearningRate\\x12O\\n\\x16\\x63onstant_learning_rate\\x18\\x01 \\x01(\\x0b\\x32-.object_detection.protos.ConstantLearningRateH\\x00\\x12`\\n\\x1f\\x65xponential_decay_learning_rate\\x18\\x02 \\x01(\\x0b\\x32\\x35.object_detection.protos.ExponentialDecayLearningRateH\\x00\\x12T\\n\\x19manual_step_learning_rate\\x18\\x03 \\x01(\\x0b\\x32/.object_detection.protos.ManualStepLearningRateH\\x00\\x42\\x0f\\n\\rlearning_rate\\\"4\\n\\x14\\x43onstantLearningRate\\x12\\x1c\\n\\rlearning_rate\\x18\\x01 \\x01(\\x02:\\x05\\x30.002\\\"\\x97\\x01\\n\\x1c\\x45xponentialDecayLearningRate\\x12$\\n\\x15initial_learning_rate\\x18\\x01 \\x01(\\x02:\\x05\\x30.002\\x12\\x1c\\n\\x0b\\x64\\x65\\x63\\x61y_steps\\x18\\x02 \\x01(\\r:\\x07\\x34\\x30\\x30\\x30\\x30\\x30\\x30\\x12\\x1a\\n\\x0c\\x64\\x65\\x63\\x61y_factor\\x18\\x03 \\x01(\\x02:\\x04\\x30.95\\x12\\x17\\n\\tstaircase\\x18\\x04 \\x01(\\x08:\\x04true\\\"\\xda\\x01\\n\\x16ManualStepLearningRate\\x12$\\n\\x15initial_learning_rate\\x18\\x01 \\x01(\\x02:\\x05\\x30.002\\x12V\\n\\x08schedule\\x18\\x02 \\x03(\\x0b\\x32\\x44.object_detection.protos.ManualStepLearningRate.LearningRateSchedule\\x1a\\x42\\n\\x14LearningRateSchedule\\x12\\x0c\\n\\x04step\\x18\\x01 \\x01(\\r\\x12\\x1c\\n\\rlearning_rate\\x18\\x02 \\x01(\\x02:\\x05\\x30.002')\n)\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_OPTIMIZER = _descriptor.Descriptor(\n  name='Optimizer',\n  full_name='object_detection.protos.Optimizer',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='rms_prop_optimizer', full_name='object_detection.protos.Optimizer.rms_prop_optimizer', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='momentum_optimizer', full_name='object_detection.protos.Optimizer.momentum_optimizer', index=1,\n      number=2, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='adam_optimizer', full_name='object_detection.protos.Optimizer.adam_optimizer', index=2,\n      number=3, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='use_moving_average', full_name='object_detection.protos.Optimizer.use_moving_average', index=3,\n      number=4, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=True,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='moving_average_decay', full_name='object_detection.protos.Optimizer.moving_average_decay', index=4,\n      number=5, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.9999,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n    _descriptor.OneofDescriptor(\n      name='optimizer', full_name='object_detection.protos.Optimizer.optimizer',\n      index=0, containing_type=None, fields=[]),\n  ],\n  serialized_start=69,\n  serialized_end=378,\n)\n\n\n_RMSPROPOPTIMIZER = _descriptor.Descriptor(\n  name='RMSPropOptimizer',\n  full_name='object_detection.protos.RMSPropOptimizer',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='learning_rate', full_name='object_detection.protos.RMSPropOptimizer.learning_rate', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='momentum_optimizer_value', full_name='object_detection.protos.RMSPropOptimizer.momentum_optimizer_value', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.9,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='decay', full_name='object_detection.protos.RMSPropOptimizer.decay', index=2,\n      number=3, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.9,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='epsilon', full_name='object_detection.protos.RMSPropOptimizer.epsilon', index=3,\n      number=4, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=381,\n  serialized_end=540,\n)\n\n\n_MOMENTUMOPTIMIZER = _descriptor.Descriptor(\n  name='MomentumOptimizer',\n  full_name='object_detection.protos.MomentumOptimizer',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='learning_rate', full_name='object_detection.protos.MomentumOptimizer.learning_rate', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='momentum_optimizer_value', full_name='object_detection.protos.MomentumOptimizer.momentum_optimizer_value', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.9,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=542,\n  serialized_end=662,\n)\n\n\n_ADAMOPTIMIZER = _descriptor.Descriptor(\n  name='AdamOptimizer',\n  full_name='object_detection.protos.AdamOptimizer',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='learning_rate', full_name='object_detection.protos.AdamOptimizer.learning_rate', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=664,\n  serialized_end=741,\n)\n\n\n_LEARNINGRATE = _descriptor.Descriptor(\n  name='LearningRate',\n  full_name='object_detection.protos.LearningRate',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='constant_learning_rate', full_name='object_detection.protos.LearningRate.constant_learning_rate', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='exponential_decay_learning_rate', full_name='object_detection.protos.LearningRate.exponential_decay_learning_rate', index=1,\n      number=2, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='manual_step_learning_rate', full_name='object_detection.protos.LearningRate.manual_step_learning_rate', index=2,\n      number=3, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n    _descriptor.OneofDescriptor(\n      name='learning_rate', full_name='object_detection.protos.LearningRate.learning_rate',\n      index=0, containing_type=None, fields=[]),\n  ],\n  serialized_start=744,\n  serialized_end=1040,\n)\n\n\n_CONSTANTLEARNINGRATE = _descriptor.Descriptor(\n  name='ConstantLearningRate',\n  full_name='object_detection.protos.ConstantLearningRate',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='learning_rate', full_name='object_detection.protos.ConstantLearningRate.learning_rate', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.002,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=1042,\n  serialized_end=1094,\n)\n\n\n_EXPONENTIALDECAYLEARNINGRATE = _descriptor.Descriptor(\n  name='ExponentialDecayLearningRate',\n  full_name='object_detection.protos.ExponentialDecayLearningRate',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='initial_learning_rate', full_name='object_detection.protos.ExponentialDecayLearningRate.initial_learning_rate', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.002,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='decay_steps', full_name='object_detection.protos.ExponentialDecayLearningRate.decay_steps', index=1,\n      number=2, type=13, cpp_type=3, label=1,\n      has_default_value=True, default_value=4000000,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='decay_factor', full_name='object_detection.protos.ExponentialDecayLearningRate.decay_factor', index=2,\n      number=3, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.95,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='staircase', full_name='object_detection.protos.ExponentialDecayLearningRate.staircase', index=3,\n      number=4, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=True,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=1097,\n  serialized_end=1248,\n)\n\n\n_MANUALSTEPLEARNINGRATE_LEARNINGRATESCHEDULE = _descriptor.Descriptor(\n  name='LearningRateSchedule',\n  full_name='object_detection.protos.ManualStepLearningRate.LearningRateSchedule',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='step', full_name='object_detection.protos.ManualStepLearningRate.LearningRateSchedule.step', index=0,\n      number=1, type=13, cpp_type=3, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='learning_rate', full_name='object_detection.protos.ManualStepLearningRate.LearningRateSchedule.learning_rate', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.002,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=1403,\n  serialized_end=1469,\n)\n\n_MANUALSTEPLEARNINGRATE = _descriptor.Descriptor(\n  name='ManualStepLearningRate',\n  full_name='object_detection.protos.ManualStepLearningRate',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='initial_learning_rate', full_name='object_detection.protos.ManualStepLearningRate.initial_learning_rate', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.002,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='schedule', full_name='object_detection.protos.ManualStepLearningRate.schedule', index=1,\n      number=2, type=11, cpp_type=10, label=3,\n      has_default_value=False, default_value=[],\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[_MANUALSTEPLEARNINGRATE_LEARNINGRATESCHEDULE, ],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=1251,\n  serialized_end=1469,\n)\n\n_OPTIMIZER.fields_by_name['rms_prop_optimizer'].message_type = _RMSPROPOPTIMIZER\n_OPTIMIZER.fields_by_name['momentum_optimizer'].message_type = _MOMENTUMOPTIMIZER\n_OPTIMIZER.fields_by_name['adam_optimizer'].message_type = _ADAMOPTIMIZER\n_OPTIMIZER.oneofs_by_name['optimizer'].fields.append(\n  _OPTIMIZER.fields_by_name['rms_prop_optimizer'])\n_OPTIMIZER.fields_by_name['rms_prop_optimizer'].containing_oneof = _OPTIMIZER.oneofs_by_name['optimizer']\n_OPTIMIZER.oneofs_by_name['optimizer'].fields.append(\n  _OPTIMIZER.fields_by_name['momentum_optimizer'])\n_OPTIMIZER.fields_by_name['momentum_optimizer'].containing_oneof = _OPTIMIZER.oneofs_by_name['optimizer']\n_OPTIMIZER.oneofs_by_name['optimizer'].fields.append(\n  _OPTIMIZER.fields_by_name['adam_optimizer'])\n_OPTIMIZER.fields_by_name['adam_optimizer'].containing_oneof = _OPTIMIZER.oneofs_by_name['optimizer']\n_RMSPROPOPTIMIZER.fields_by_name['learning_rate'].message_type = _LEARNINGRATE\n_MOMENTUMOPTIMIZER.fields_by_name['learning_rate'].message_type = _LEARNINGRATE\n_ADAMOPTIMIZER.fields_by_name['learning_rate'].message_type = _LEARNINGRATE\n_LEARNINGRATE.fields_by_name['constant_learning_rate'].message_type = _CONSTANTLEARNINGRATE\n_LEARNINGRATE.fields_by_name['exponential_decay_learning_rate'].message_type = _EXPONENTIALDECAYLEARNINGRATE\n_LEARNINGRATE.fields_by_name['manual_step_learning_rate'].message_type = _MANUALSTEPLEARNINGRATE\n_LEARNINGRATE.oneofs_by_name['learning_rate'].fields.append(\n  _LEARNINGRATE.fields_by_name['constant_learning_rate'])\n_LEARNINGRATE.fields_by_name['constant_learning_rate'].containing_oneof = _LEARNINGRATE.oneofs_by_name['learning_rate']\n_LEARNINGRATE.oneofs_by_name['learning_rate'].fields.append(\n  _LEARNINGRATE.fields_by_name['exponential_decay_learning_rate'])\n_LEARNINGRATE.fields_by_name['exponential_decay_learning_rate'].containing_oneof = _LEARNINGRATE.oneofs_by_name['learning_rate']\n_LEARNINGRATE.oneofs_by_name['learning_rate'].fields.append(\n  _LEARNINGRATE.fields_by_name['manual_step_learning_rate'])\n_LEARNINGRATE.fields_by_name['manual_step_learning_rate'].containing_oneof = _LEARNINGRATE.oneofs_by_name['learning_rate']\n_MANUALSTEPLEARNINGRATE_LEARNINGRATESCHEDULE.containing_type = _MANUALSTEPLEARNINGRATE\n_MANUALSTEPLEARNINGRATE.fields_by_name['schedule'].message_type = _MANUALSTEPLEARNINGRATE_LEARNINGRATESCHEDULE\nDESCRIPTOR.message_types_by_name['Optimizer'] = _OPTIMIZER\nDESCRIPTOR.message_types_by_name['RMSPropOptimizer'] = _RMSPROPOPTIMIZER\nDESCRIPTOR.message_types_by_name['MomentumOptimizer'] = _MOMENTUMOPTIMIZER\nDESCRIPTOR.message_types_by_name['AdamOptimizer'] = _ADAMOPTIMIZER\nDESCRIPTOR.message_types_by_name['LearningRate'] = _LEARNINGRATE\nDESCRIPTOR.message_types_by_name['ConstantLearningRate'] = _CONSTANTLEARNINGRATE\nDESCRIPTOR.message_types_by_name['ExponentialDecayLearningRate'] = _EXPONENTIALDECAYLEARNINGRATE\nDESCRIPTOR.message_types_by_name['ManualStepLearningRate'] = _MANUALSTEPLEARNINGRATE\n\nOptimizer = _reflection.GeneratedProtocolMessageType('Optimizer', (_message.Message,), dict(\n  DESCRIPTOR = _OPTIMIZER,\n  __module__ = 'object_detection.protos.optimizer_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.Optimizer)\n  ))\n_sym_db.RegisterMessage(Optimizer)\n\nRMSPropOptimizer = _reflection.GeneratedProtocolMessageType('RMSPropOptimizer', (_message.Message,), dict(\n  DESCRIPTOR = _RMSPROPOPTIMIZER,\n  __module__ = 'object_detection.protos.optimizer_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RMSPropOptimizer)\n  ))\n_sym_db.RegisterMessage(RMSPropOptimizer)\n\nMomentumOptimizer = _reflection.GeneratedProtocolMessageType('MomentumOptimizer', (_message.Message,), dict(\n  DESCRIPTOR = _MOMENTUMOPTIMIZER,\n  __module__ = 'object_detection.protos.optimizer_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.MomentumOptimizer)\n  ))\n_sym_db.RegisterMessage(MomentumOptimizer)\n\nAdamOptimizer = _reflection.GeneratedProtocolMessageType('AdamOptimizer', (_message.Message,), dict(\n  DESCRIPTOR = _ADAMOPTIMIZER,\n  __module__ = 'object_detection.protos.optimizer_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.AdamOptimizer)\n  ))\n_sym_db.RegisterMessage(AdamOptimizer)\n\nLearningRate = _reflection.GeneratedProtocolMessageType('LearningRate', (_message.Message,), dict(\n  DESCRIPTOR = _LEARNINGRATE,\n  __module__ = 'object_detection.protos.optimizer_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.LearningRate)\n  ))\n_sym_db.RegisterMessage(LearningRate)\n\nConstantLearningRate = _reflection.GeneratedProtocolMessageType('ConstantLearningRate', (_message.Message,), dict(\n  DESCRIPTOR = _CONSTANTLEARNINGRATE,\n  __module__ = 'object_detection.protos.optimizer_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.ConstantLearningRate)\n  ))\n_sym_db.RegisterMessage(ConstantLearningRate)\n\nExponentialDecayLearningRate = _reflection.GeneratedProtocolMessageType('ExponentialDecayLearningRate', (_message.Message,), dict(\n  DESCRIPTOR = _EXPONENTIALDECAYLEARNINGRATE,\n  __module__ = 'object_detection.protos.optimizer_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.ExponentialDecayLearningRate)\n  ))\n_sym_db.RegisterMessage(ExponentialDecayLearningRate)\n\nManualStepLearningRate = _reflection.GeneratedProtocolMessageType('ManualStepLearningRate', (_message.Message,), dict(\n\n  LearningRateSchedule = _reflection.GeneratedProtocolMessageType('LearningRateSchedule', (_message.Message,), dict(\n    DESCRIPTOR = _MANUALSTEPLEARNINGRATE_LEARNINGRATESCHEDULE,\n    __module__ = 'object_detection.protos.optimizer_pb2'\n    # @@protoc_insertion_point(class_scope:object_detection.protos.ManualStepLearningRate.LearningRateSchedule)\n    ))\n  ,\n  DESCRIPTOR = _MANUALSTEPLEARNINGRATE,\n  __module__ = 'object_detection.protos.optimizer_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.ManualStepLearningRate)\n  ))\n_sym_db.RegisterMessage(ManualStepLearningRate)\n_sym_db.RegisterMessage(ManualStepLearningRate.LearningRateSchedule)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/pipeline.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\nimport \"object_detection/protos/eval.proto\";\nimport \"object_detection/protos/input_reader.proto\";\nimport \"object_detection/protos/model.proto\";\nimport \"object_detection/protos/train.proto\";\n\n// Convenience message for configuring a training and eval pipeline. Allows all\n// of the pipeline parameters to be configured from one file.\nmessage TrainEvalPipelineConfig {\n  optional DetectionModel model = 1;\n  optional TrainConfig train_config = 2;\n  optional InputReader train_input_reader = 3;\n  optional EvalConfig eval_config = 4;\n  optional InputReader eval_input_reader = 5;\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/pipeline_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/pipeline.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\nimport object_detection.protos.eval_pb2\nimport object_detection.protos.input_reader_pb2\nimport object_detection.protos.model_pb2\nimport object_detection.protos.train_pb2\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/pipeline.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n&object_detection/protos/pipeline.proto\\x12\\x17object_detection.protos\\x1a\\\"object_detection/protos/eval.proto\\x1a*object_detection/protos/input_reader.proto\\x1a#object_detection/protos/model.proto\\x1a#object_detection/protos/train.proto\\\"\\xca\\x02\\n\\x17TrainEvalPipelineConfig\\x12\\x36\\n\\x05model\\x18\\x01 \\x01(\\x0b\\x32\\'.object_detection.protos.DetectionModel\\x12:\\n\\x0ctrain_config\\x18\\x02 \\x01(\\x0b\\x32$.object_detection.protos.TrainConfig\\x12@\\n\\x12train_input_reader\\x18\\x03 \\x01(\\x0b\\x32$.object_detection.protos.InputReader\\x12\\x38\\n\\x0b\\x65val_config\\x18\\x04 \\x01(\\x0b\\x32#.object_detection.protos.EvalConfig\\x12?\\n\\x11\\x65val_input_reader\\x18\\x05 \\x01(\\x0b\\x32$.object_detection.protos.InputReader')\n  ,\n  dependencies=[object_detection.protos.eval_pb2.DESCRIPTOR,object_detection.protos.input_reader_pb2.DESCRIPTOR,object_detection.protos.model_pb2.DESCRIPTOR,object_detection.protos.train_pb2.DESCRIPTOR,])\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_TRAINEVALPIPELINECONFIG = _descriptor.Descriptor(\n  name='TrainEvalPipelineConfig',\n  full_name='object_detection.protos.TrainEvalPipelineConfig',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='model', full_name='object_detection.protos.TrainEvalPipelineConfig.model', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='train_config', full_name='object_detection.protos.TrainEvalPipelineConfig.train_config', index=1,\n      number=2, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='train_input_reader', full_name='object_detection.protos.TrainEvalPipelineConfig.train_input_reader', index=2,\n      number=3, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='eval_config', full_name='object_detection.protos.TrainEvalPipelineConfig.eval_config', index=3,\n      number=4, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='eval_input_reader', full_name='object_detection.protos.TrainEvalPipelineConfig.eval_input_reader', index=4,\n      number=5, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=222,\n  serialized_end=552,\n)\n\n_TRAINEVALPIPELINECONFIG.fields_by_name['model'].message_type = object_detection.protos.model_pb2._DETECTIONMODEL\n_TRAINEVALPIPELINECONFIG.fields_by_name['train_config'].message_type = object_detection.protos.train_pb2._TRAINCONFIG\n_TRAINEVALPIPELINECONFIG.fields_by_name['train_input_reader'].message_type = object_detection.protos.input_reader_pb2._INPUTREADER\n_TRAINEVALPIPELINECONFIG.fields_by_name['eval_config'].message_type = object_detection.protos.eval_pb2._EVALCONFIG\n_TRAINEVALPIPELINECONFIG.fields_by_name['eval_input_reader'].message_type = object_detection.protos.input_reader_pb2._INPUTREADER\nDESCRIPTOR.message_types_by_name['TrainEvalPipelineConfig'] = _TRAINEVALPIPELINECONFIG\n\nTrainEvalPipelineConfig = _reflection.GeneratedProtocolMessageType('TrainEvalPipelineConfig', (_message.Message,), dict(\n  DESCRIPTOR = _TRAINEVALPIPELINECONFIG,\n  __module__ = 'object_detection.protos.pipeline_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.TrainEvalPipelineConfig)\n  ))\n_sym_db.RegisterMessage(TrainEvalPipelineConfig)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/post_processing.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\n// Configuration proto for non-max-suppression operation on a batch of\n// detections.\nmessage BatchNonMaxSuppression {\n  // Scalar threshold for score (low scoring boxes are removed).\n  optional float score_threshold = 1 [default = 0.0];\n\n  // Scalar threshold for IOU (boxes that have high IOU overlap\n  // with previously selected boxes are removed).\n  optional float iou_threshold = 2 [default = 0.6];\n\n  // Maximum number of detections to retain per class.\n  optional int32 max_detections_per_class = 3 [default = 100];\n\n  // Maximum number of detections to retain across all classes.\n  optional int32 max_total_detections = 5 [default = 100];\n}\n\n// Configuration proto for post-processing predicted boxes and\n// scores.\nmessage PostProcessing {\n  // Non max suppression parameters.\n  optional BatchNonMaxSuppression batch_non_max_suppression = 1;\n\n  // Enum to specify how to convert the detection scores.\n  enum ScoreConverter {\n    // Input scores equals output scores.\n    IDENTITY = 0;\n\n    // Applies a sigmoid on input scores.\n    SIGMOID = 1;\n\n    // Applies a softmax on input scores\n    SOFTMAX = 2;\n  }\n\n  // Score converter to use.\n  optional ScoreConverter score_converter = 2 [default = IDENTITY];\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/post_processing_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/post_processing.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/post_processing.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n-object_detection/protos/post_processing.proto\\x12\\x17object_detection.protos\\\"\\x9a\\x01\\n\\x16\\x42\\x61tchNonMaxSuppression\\x12\\x1a\\n\\x0fscore_threshold\\x18\\x01 \\x01(\\x02:\\x01\\x30\\x12\\x1a\\n\\riou_threshold\\x18\\x02 \\x01(\\x02:\\x03\\x30.6\\x12%\\n\\x18max_detections_per_class\\x18\\x03 \\x01(\\x05:\\x03\\x31\\x30\\x30\\x12!\\n\\x14max_total_detections\\x18\\x05 \\x01(\\x05:\\x03\\x31\\x30\\x30\\\"\\xf9\\x01\\n\\x0ePostProcessing\\x12R\\n\\x19\\x62\\x61tch_non_max_suppression\\x18\\x01 \\x01(\\x0b\\x32/.object_detection.protos.BatchNonMaxSuppression\\x12Y\\n\\x0fscore_converter\\x18\\x02 \\x01(\\x0e\\x32\\x36.object_detection.protos.PostProcessing.ScoreConverter:\\x08IDENTITY\\\"8\\n\\x0eScoreConverter\\x12\\x0c\\n\\x08IDENTITY\\x10\\x00\\x12\\x0b\\n\\x07SIGMOID\\x10\\x01\\x12\\x0b\\n\\x07SOFTMAX\\x10\\x02')\n)\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n_POSTPROCESSING_SCORECONVERTER = _descriptor.EnumDescriptor(\n  name='ScoreConverter',\n  full_name='object_detection.protos.PostProcessing.ScoreConverter',\n  filename=None,\n  file=DESCRIPTOR,\n  values=[\n    _descriptor.EnumValueDescriptor(\n      name='IDENTITY', index=0, number=0,\n      options=None,\n      type=None),\n    _descriptor.EnumValueDescriptor(\n      name='SIGMOID', index=1, number=1,\n      options=None,\n      type=None),\n    _descriptor.EnumValueDescriptor(\n      name='SOFTMAX', index=2, number=2,\n      options=None,\n      type=None),\n  ],\n  containing_type=None,\n  options=None,\n  serialized_start=425,\n  serialized_end=481,\n)\n_sym_db.RegisterEnumDescriptor(_POSTPROCESSING_SCORECONVERTER)\n\n\n_BATCHNONMAXSUPPRESSION = _descriptor.Descriptor(\n  name='BatchNonMaxSuppression',\n  full_name='object_detection.protos.BatchNonMaxSuppression',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='score_threshold', full_name='object_detection.protos.BatchNonMaxSuppression.score_threshold', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='iou_threshold', full_name='object_detection.protos.BatchNonMaxSuppression.iou_threshold', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.6,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_detections_per_class', full_name='object_detection.protos.BatchNonMaxSuppression.max_detections_per_class', index=2,\n      number=3, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=100,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_total_detections', full_name='object_detection.protos.BatchNonMaxSuppression.max_total_detections', index=3,\n      number=5, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=100,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=75,\n  serialized_end=229,\n)\n\n\n_POSTPROCESSING = _descriptor.Descriptor(\n  name='PostProcessing',\n  full_name='object_detection.protos.PostProcessing',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='batch_non_max_suppression', full_name='object_detection.protos.PostProcessing.batch_non_max_suppression', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='score_converter', full_name='object_detection.protos.PostProcessing.score_converter', index=1,\n      number=2, type=14, cpp_type=8, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n    _POSTPROCESSING_SCORECONVERTER,\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=232,\n  serialized_end=481,\n)\n\n_POSTPROCESSING.fields_by_name['batch_non_max_suppression'].message_type = _BATCHNONMAXSUPPRESSION\n_POSTPROCESSING.fields_by_name['score_converter'].enum_type = _POSTPROCESSING_SCORECONVERTER\n_POSTPROCESSING_SCORECONVERTER.containing_type = _POSTPROCESSING\nDESCRIPTOR.message_types_by_name['BatchNonMaxSuppression'] = _BATCHNONMAXSUPPRESSION\nDESCRIPTOR.message_types_by_name['PostProcessing'] = _POSTPROCESSING\n\nBatchNonMaxSuppression = _reflection.GeneratedProtocolMessageType('BatchNonMaxSuppression', (_message.Message,), dict(\n  DESCRIPTOR = _BATCHNONMAXSUPPRESSION,\n  __module__ = 'object_detection.protos.post_processing_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.BatchNonMaxSuppression)\n  ))\n_sym_db.RegisterMessage(BatchNonMaxSuppression)\n\nPostProcessing = _reflection.GeneratedProtocolMessageType('PostProcessing', (_message.Message,), dict(\n  DESCRIPTOR = _POSTPROCESSING,\n  __module__ = 'object_detection.protos.post_processing_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.PostProcessing)\n  ))\n_sym_db.RegisterMessage(PostProcessing)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/preprocessor.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\n// Message for defining a preprocessing operation on input data.\n// See: //object_detection/core/preprocessor.py\nmessage PreprocessingStep {\n  oneof preprocessing_step {\n    NormalizeImage normalize_image = 1;\n    RandomHorizontalFlip random_horizontal_flip = 2;\n    RandomPixelValueScale random_pixel_value_scale = 3;\n    RandomImageScale random_image_scale = 4;\n    RandomRGBtoGray random_rgb_to_gray = 5;\n    RandomAdjustBrightness random_adjust_brightness = 6;\n    RandomAdjustContrast random_adjust_contrast = 7;\n    RandomAdjustHue random_adjust_hue = 8;\n    RandomAdjustSaturation random_adjust_saturation = 9;\n    RandomDistortColor random_distort_color = 10;\n    RandomJitterBoxes random_jitter_boxes = 11;\n    RandomCropImage random_crop_image = 12;\n    RandomPadImage random_pad_image = 13;\n    RandomCropPadImage random_crop_pad_image = 14;\n    RandomCropToAspectRatio random_crop_to_aspect_ratio = 15;\n    RandomBlackPatches random_black_patches = 16;\n    RandomResizeMethod random_resize_method = 17;\n    ScaleBoxesToPixelCoordinates scale_boxes_to_pixel_coordinates = 18;\n    ResizeImage resize_image = 19;\n    SubtractChannelMean subtract_channel_mean = 20;\n    SSDRandomCrop ssd_random_crop = 21;\n    SSDRandomCropPad ssd_random_crop_pad = 22;\n    SSDRandomCropFixedAspectRatio ssd_random_crop_fixed_aspect_ratio = 23;\n  }\n}\n\n// Normalizes pixel values in an image.\n// For every channel in the image, moves the pixel values from the range\n// [original_minval, original_maxval] to [target_minval, target_maxval].\nmessage NormalizeImage {\n  optional float original_minval = 1;\n  optional float original_maxval = 2;\n  optional float target_minval = 3 [default=0];\n  optional float target_maxval = 4 [default=1];\n}\n\n// Randomly horizontally mirrors the image and detections 50% of the time.\nmessage RandomHorizontalFlip {\n}\n\n// Randomly scales the values of all pixels in the image by some constant value\n// between [minval, maxval], then clip the value to a range between [0, 1.0].\nmessage RandomPixelValueScale {\n  optional float minval = 1 [default=0.9];\n  optional float maxval = 2 [default=1.1];\n}\n\n// Randomly enlarges or shrinks image (keeping aspect ratio).\nmessage RandomImageScale {\n  optional float min_scale_ratio = 1 [default=0.5];\n  optional float max_scale_ratio = 2 [default=2.0];\n}\n\n// Randomly convert entire image to grey scale.\nmessage RandomRGBtoGray {\n  optional float probability = 1 [default=0.1];\n}\n\n// Randomly changes image brightness by up to max_delta. Image outputs will be\n// saturated between 0 and 1.\nmessage RandomAdjustBrightness {\n  optional float max_delta=1 [default=0.2];\n}\n\n// Randomly scales contract by a value between [min_delta, max_delta].\nmessage RandomAdjustContrast {\n  optional float min_delta = 1 [default=0.8];\n  optional float max_delta = 2 [default=1.25];\n}\n\n// Randomly alters hue by a value of up to max_delta.\nmessage RandomAdjustHue {\n  optional float max_delta = 1 [default=0.02];\n}\n\n// Randomly changes saturation by a value between [min_delta, max_delta].\nmessage RandomAdjustSaturation {\n  optional float min_delta = 1 [default=0.8];\n  optional float max_delta = 2 [default=1.25];\n}\n\n// Performs a random color distortion. color_orderings should either be 0 or 1.\nmessage RandomDistortColor {\n  optional int32 color_ordering = 1;\n}\n\n// Randomly jitters corners of boxes in the image determined by ratio.\n// ie. If a box is [100, 200] and ratio is 0.02, the corners can move by [1, 4].\nmessage RandomJitterBoxes {\n  optional float ratio = 1 [default=0.05];\n}\n\n// Randomly crops the image and bounding boxes.\nmessage RandomCropImage {\n  // Cropped image must cover at least one box by this fraction.\n  optional float min_object_covered = 1 [default=1.0];\n\n  // Aspect ratio bounds of cropped image.\n  optional float min_aspect_ratio = 2 [default=0.75];\n  optional float max_aspect_ratio = 3 [default=1.33];\n\n  // Allowed area ratio of cropped image to original image.\n  optional float min_area = 4 [default=0.1];\n  optional float max_area = 5 [default=1.0];\n\n  // Minimum overlap threshold of cropped boxes to keep in new image. If the\n  // ratio between a cropped bounding box and the original is less than this\n  // value, it is removed from the new image.\n  optional float overlap_thresh = 6 [default=0.3];\n\n  // Probability of keeping the original image.\n  optional float random_coef = 7 [default=0.0];\n}\n\n// Randomly adds padding to the image.\nmessage RandomPadImage {\n  // Minimum dimensions for padded image. If unset, will use original image\n  // dimension as a lower bound.\n  optional float min_image_height = 1;\n  optional float min_image_width = 2;\n\n  // Maximum dimensions for padded image. If unset, will use double the original\n  // image dimension as a lower bound.\n  optional float max_image_height = 3;\n  optional float max_image_width = 4;\n\n  // Color of the padding. If unset, will pad using average color of the input\n  // image.\n  repeated float pad_color = 5;\n}\n\n// Randomly crops an image followed by a random pad.\nmessage RandomCropPadImage {\n  // Cropping operation must cover at least one box by this fraction.\n  optional float min_object_covered = 1 [default=1.0];\n\n  // Aspect ratio bounds of image after cropping operation.\n  optional float min_aspect_ratio = 2 [default=0.75];\n  optional float max_aspect_ratio = 3 [default=1.33];\n\n  // Allowed area ratio of image after cropping operation.\n  optional float min_area = 4 [default=0.1];\n  optional float max_area = 5 [default=1.0];\n\n  // Minimum overlap threshold of cropped boxes to keep in new image. If the\n  // ratio between a cropped bounding box and the original is less than this\n  // value, it is removed from the new image.\n  optional float overlap_thresh = 6 [default=0.3];\n\n  // Probability of keeping the original image during the crop operation.\n  optional float random_coef = 7 [default=0.0];\n\n  // Maximum dimensions for padded image. If unset, will use double the original\n  // image dimension as a lower bound. Both of the following fields should be\n  // length 2.\n  repeated float min_padded_size_ratio = 8;\n  repeated float max_padded_size_ratio = 9;\n\n  // Color of the padding. If unset, will pad using average color of the input\n  // image.\n  repeated float pad_color = 10;\n}\n\n// Randomly crops an iamge to a given aspect ratio.\nmessage RandomCropToAspectRatio {\n  // Aspect ratio.\n  optional float aspect_ratio = 1 [default=1.0];\n\n  // Minimum overlap threshold of cropped boxes to keep in new image. If the\n  // ratio between a cropped bounding box and the original is less than this\n  // value, it is removed from the new image.\n  optional float overlap_thresh = 2 [default=0.3];\n}\n\n// Randomly adds black square patches to an image.\nmessage RandomBlackPatches {\n  // The maximum number of black patches to add.\n  optional int32 max_black_patches = 1 [default=10];\n\n  // The probability of a black patch being added to an image.\n  optional float probability = 2 [default=0.5];\n\n  // Ratio between the dimension of the black patch to the minimum dimension of\n  // the image (patch_width = patch_height = min(image_height, image_width)).\n  optional float size_to_image_ratio = 3 [default=0.1];\n}\n\n// Randomly resizes the image up to [target_height, target_width].\nmessage RandomResizeMethod {\n  optional float target_height = 1;\n  optional float target_width = 2;\n}\n\n// Scales boxes from normalized coordinates to pixel coordinates.\nmessage ScaleBoxesToPixelCoordinates {\n}\n\n// Resizes images to [new_height, new_width].\nmessage ResizeImage {\n  optional int32 new_height = 1;\n  optional int32 new_width = 2;\n  enum Method {\n    AREA=1;\n    BICUBIC=2;\n    BILINEAR=3;\n    NEAREST_NEIGHBOR=4;\n  }\n  optional Method method = 3 [default=BILINEAR];\n}\n\n// Normalizes an image by subtracting a mean from each channel.\nmessage SubtractChannelMean {\n  // The mean to subtract from each channel. Should be of same dimension of\n  // channels in the input image.\n  repeated float means = 1;\n}\n\nmessage SSDRandomCropOperation {\n  // Cropped image must cover at least this fraction of one original bounding\n  // box.\n  optional float min_object_covered = 1;\n\n  // The aspect ratio of the cropped image must be within the range of\n  // [min_aspect_ratio, max_aspect_ratio].\n  optional float min_aspect_ratio = 2;\n  optional float max_aspect_ratio = 3;\n\n  // The area of the cropped image must be within the range of\n  // [min_area, max_area].\n  optional float min_area = 4;\n  optional float max_area = 5;\n\n  // Cropped box area ratio must be above this threhold to be kept.\n  optional float overlap_thresh = 6;\n\n  // Probability a crop operation is skipped.\n  optional float random_coef = 7;\n}\n\n// Randomly crops a image according to:\n//     Liu et al., SSD: Single shot multibox detector.\n// This preprocessing step defines multiple SSDRandomCropOperations. Only one\n// operation (chosen at random) is actually performed on an image.\nmessage SSDRandomCrop {\n  repeated SSDRandomCropOperation operations = 1;\n}\n\nmessage SSDRandomCropPadOperation {\n  // Cropped image must cover at least this fraction of one original bounding\n  // box.\n  optional float min_object_covered = 1;\n\n  // The aspect ratio of the cropped image must be within the range of\n  // [min_aspect_ratio, max_aspect_ratio].\n  optional float min_aspect_ratio = 2;\n  optional float max_aspect_ratio = 3;\n\n  // The area of the cropped image must be within the range of\n  // [min_area, max_area].\n  optional float min_area = 4;\n  optional float max_area = 5;\n\n  // Cropped box area ratio must be above this threhold to be kept.\n  optional float overlap_thresh = 6;\n\n  // Probability a crop operation is skipped.\n  optional float random_coef = 7;\n\n  // Min ratio of padded image height and width to the input image's height and\n  // width. Two entries per operation.\n  repeated float min_padded_size_ratio = 8;\n\n  // Max ratio of padded image height and width to the input image's height and\n  // width. Two entries per operation.\n  repeated float max_padded_size_ratio = 9;\n\n  // Padding color.\n  optional float pad_color_r = 10;\n  optional float pad_color_g = 11;\n  optional float pad_color_b = 12;\n}\n\n// Randomly crops and pads an image according to:\n//     Liu et al., SSD: Single shot multibox detector.\n// This preprocessing step defines multiple SSDRandomCropPadOperations. Only one\n// operation (chosen at random) is actually performed on an image.\nmessage SSDRandomCropPad {\n  repeated SSDRandomCropPadOperation operations = 1;\n}\n\nmessage SSDRandomCropFixedAspectRatioOperation {\n  // Cropped image must cover at least this fraction of one original bounding\n  // box.\n  optional float min_object_covered = 1;\n\n  // The area of the cropped image must be within the range of\n  // [min_area, max_area].\n  optional float min_area = 4;\n  optional float max_area = 5;\n\n  // Cropped box area ratio must be above this threhold to be kept.\n  optional float overlap_thresh = 6;\n\n  // Probability a crop operation is skipped.\n  optional float random_coef = 7;\n}\n\n// Randomly crops a image to a fixed aspect ratio according to:\n//     Liu et al., SSD: Single shot multibox detector.\n// Multiple SSDRandomCropFixedAspectRatioOperations are defined by this\n// preprocessing step. Only one operation (chosen at random) is actually\n// performed on an image.\nmessage SSDRandomCropFixedAspectRatio {\n  repeated SSDRandomCropFixedAspectRatioOperation operations = 1;\n\n  // Aspect ratio to crop to. This value is used for all crop operations.\n  optional float aspect_ratio = 2 [default=1.0];\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/preprocessor_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/preprocessor.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/preprocessor.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n*object_detection/protos/preprocessor.proto\\x12\\x17object_detection.protos\\\"\\xad\\x0e\\n\\x11PreprocessingStep\\x12\\x42\\n\\x0fnormalize_image\\x18\\x01 \\x01(\\x0b\\x32\\'.object_detection.protos.NormalizeImageH\\x00\\x12O\\n\\x16random_horizontal_flip\\x18\\x02 \\x01(\\x0b\\x32-.object_detection.protos.RandomHorizontalFlipH\\x00\\x12R\\n\\x18random_pixel_value_scale\\x18\\x03 \\x01(\\x0b\\x32..object_detection.protos.RandomPixelValueScaleH\\x00\\x12G\\n\\x12random_image_scale\\x18\\x04 \\x01(\\x0b\\x32).object_detection.protos.RandomImageScaleH\\x00\\x12\\x46\\n\\x12random_rgb_to_gray\\x18\\x05 \\x01(\\x0b\\x32(.object_detection.protos.RandomRGBtoGrayH\\x00\\x12S\\n\\x18random_adjust_brightness\\x18\\x06 \\x01(\\x0b\\x32/.object_detection.protos.RandomAdjustBrightnessH\\x00\\x12O\\n\\x16random_adjust_contrast\\x18\\x07 \\x01(\\x0b\\x32-.object_detection.protos.RandomAdjustContrastH\\x00\\x12\\x45\\n\\x11random_adjust_hue\\x18\\x08 \\x01(\\x0b\\x32(.object_detection.protos.RandomAdjustHueH\\x00\\x12S\\n\\x18random_adjust_saturation\\x18\\t \\x01(\\x0b\\x32/.object_detection.protos.RandomAdjustSaturationH\\x00\\x12K\\n\\x14random_distort_color\\x18\\n \\x01(\\x0b\\x32+.object_detection.protos.RandomDistortColorH\\x00\\x12I\\n\\x13random_jitter_boxes\\x18\\x0b \\x01(\\x0b\\x32*.object_detection.protos.RandomJitterBoxesH\\x00\\x12\\x45\\n\\x11random_crop_image\\x18\\x0c \\x01(\\x0b\\x32(.object_detection.protos.RandomCropImageH\\x00\\x12\\x43\\n\\x10random_pad_image\\x18\\r \\x01(\\x0b\\x32\\'.object_detection.protos.RandomPadImageH\\x00\\x12L\\n\\x15random_crop_pad_image\\x18\\x0e \\x01(\\x0b\\x32+.object_detection.protos.RandomCropPadImageH\\x00\\x12W\\n\\x1brandom_crop_to_aspect_ratio\\x18\\x0f \\x01(\\x0b\\x32\\x30.object_detection.protos.RandomCropToAspectRatioH\\x00\\x12K\\n\\x14random_black_patches\\x18\\x10 \\x01(\\x0b\\x32+.object_detection.protos.RandomBlackPatchesH\\x00\\x12K\\n\\x14random_resize_method\\x18\\x11 \\x01(\\x0b\\x32+.object_detection.protos.RandomResizeMethodH\\x00\\x12\\x61\\n scale_boxes_to_pixel_coordinates\\x18\\x12 \\x01(\\x0b\\x32\\x35.object_detection.protos.ScaleBoxesToPixelCoordinatesH\\x00\\x12<\\n\\x0cresize_image\\x18\\x13 \\x01(\\x0b\\x32$.object_detection.protos.ResizeImageH\\x00\\x12M\\n\\x15subtract_channel_mean\\x18\\x14 \\x01(\\x0b\\x32,.object_detection.protos.SubtractChannelMeanH\\x00\\x12\\x41\\n\\x0fssd_random_crop\\x18\\x15 \\x01(\\x0b\\x32&.object_detection.protos.SSDRandomCropH\\x00\\x12H\\n\\x13ssd_random_crop_pad\\x18\\x16 \\x01(\\x0b\\x32).object_detection.protos.SSDRandomCropPadH\\x00\\x12\\x64\\n\\\"ssd_random_crop_fixed_aspect_ratio\\x18\\x17 \\x01(\\x0b\\x32\\x36.object_detection.protos.SSDRandomCropFixedAspectRatioH\\x00\\x42\\x14\\n\\x12preprocessing_step\\\"v\\n\\x0eNormalizeImage\\x12\\x17\\n\\x0foriginal_minval\\x18\\x01 \\x01(\\x02\\x12\\x17\\n\\x0foriginal_maxval\\x18\\x02 \\x01(\\x02\\x12\\x18\\n\\rtarget_minval\\x18\\x03 \\x01(\\x02:\\x01\\x30\\x12\\x18\\n\\rtarget_maxval\\x18\\x04 \\x01(\\x02:\\x01\\x31\\\"\\x16\\n\\x14RandomHorizontalFlip\\\"A\\n\\x15RandomPixelValueScale\\x12\\x13\\n\\x06minval\\x18\\x01 \\x01(\\x02:\\x03\\x30.9\\x12\\x13\\n\\x06maxval\\x18\\x02 \\x01(\\x02:\\x03\\x31.1\\\"L\\n\\x10RandomImageScale\\x12\\x1c\\n\\x0fmin_scale_ratio\\x18\\x01 \\x01(\\x02:\\x03\\x30.5\\x12\\x1a\\n\\x0fmax_scale_ratio\\x18\\x02 \\x01(\\x02:\\x01\\x32\\\"+\\n\\x0fRandomRGBtoGray\\x12\\x18\\n\\x0bprobability\\x18\\x01 \\x01(\\x02:\\x03\\x30.1\\\"0\\n\\x16RandomAdjustBrightness\\x12\\x16\\n\\tmax_delta\\x18\\x01 \\x01(\\x02:\\x03\\x30.2\\\"G\\n\\x14RandomAdjustContrast\\x12\\x16\\n\\tmin_delta\\x18\\x01 \\x01(\\x02:\\x03\\x30.8\\x12\\x17\\n\\tmax_delta\\x18\\x02 \\x01(\\x02:\\x04\\x31.25\\\"*\\n\\x0fRandomAdjustHue\\x12\\x17\\n\\tmax_delta\\x18\\x01 \\x01(\\x02:\\x04\\x30.02\\\"I\\n\\x16RandomAdjustSaturation\\x12\\x16\\n\\tmin_delta\\x18\\x01 \\x01(\\x02:\\x03\\x30.8\\x12\\x17\\n\\tmax_delta\\x18\\x02 \\x01(\\x02:\\x04\\x31.25\\\",\\n\\x12RandomDistortColor\\x12\\x16\\n\\x0e\\x63olor_ordering\\x18\\x01 \\x01(\\x05\\\"(\\n\\x11RandomJitterBoxes\\x12\\x13\\n\\x05ratio\\x18\\x01 \\x01(\\x02:\\x04\\x30.05\\\"\\xd1\\x01\\n\\x0fRandomCropImage\\x12\\x1d\\n\\x12min_object_covered\\x18\\x01 \\x01(\\x02:\\x01\\x31\\x12\\x1e\\n\\x10min_aspect_ratio\\x18\\x02 \\x01(\\x02:\\x04\\x30.75\\x12\\x1e\\n\\x10max_aspect_ratio\\x18\\x03 \\x01(\\x02:\\x04\\x31.33\\x12\\x15\\n\\x08min_area\\x18\\x04 \\x01(\\x02:\\x03\\x30.1\\x12\\x13\\n\\x08max_area\\x18\\x05 \\x01(\\x02:\\x01\\x31\\x12\\x1b\\n\\x0eoverlap_thresh\\x18\\x06 \\x01(\\x02:\\x03\\x30.3\\x12\\x16\\n\\x0brandom_coef\\x18\\x07 \\x01(\\x02:\\x01\\x30\\\"\\x89\\x01\\n\\x0eRandomPadImage\\x12\\x18\\n\\x10min_image_height\\x18\\x01 \\x01(\\x02\\x12\\x17\\n\\x0fmin_image_width\\x18\\x02 \\x01(\\x02\\x12\\x18\\n\\x10max_image_height\\x18\\x03 \\x01(\\x02\\x12\\x17\\n\\x0fmax_image_width\\x18\\x04 \\x01(\\x02\\x12\\x11\\n\\tpad_color\\x18\\x05 \\x03(\\x02\\\"\\xa5\\x02\\n\\x12RandomCropPadImage\\x12\\x1d\\n\\x12min_object_covered\\x18\\x01 \\x01(\\x02:\\x01\\x31\\x12\\x1e\\n\\x10min_aspect_ratio\\x18\\x02 \\x01(\\x02:\\x04\\x30.75\\x12\\x1e\\n\\x10max_aspect_ratio\\x18\\x03 \\x01(\\x02:\\x04\\x31.33\\x12\\x15\\n\\x08min_area\\x18\\x04 \\x01(\\x02:\\x03\\x30.1\\x12\\x13\\n\\x08max_area\\x18\\x05 \\x01(\\x02:\\x01\\x31\\x12\\x1b\\n\\x0eoverlap_thresh\\x18\\x06 \\x01(\\x02:\\x03\\x30.3\\x12\\x16\\n\\x0brandom_coef\\x18\\x07 \\x01(\\x02:\\x01\\x30\\x12\\x1d\\n\\x15min_padded_size_ratio\\x18\\x08 \\x03(\\x02\\x12\\x1d\\n\\x15max_padded_size_ratio\\x18\\t \\x03(\\x02\\x12\\x11\\n\\tpad_color\\x18\\n \\x03(\\x02\\\"O\\n\\x17RandomCropToAspectRatio\\x12\\x17\\n\\x0c\\x61spect_ratio\\x18\\x01 \\x01(\\x02:\\x01\\x31\\x12\\x1b\\n\\x0eoverlap_thresh\\x18\\x02 \\x01(\\x02:\\x03\\x30.3\\\"o\\n\\x12RandomBlackPatches\\x12\\x1d\\n\\x11max_black_patches\\x18\\x01 \\x01(\\x05:\\x02\\x31\\x30\\x12\\x18\\n\\x0bprobability\\x18\\x02 \\x01(\\x02:\\x03\\x30.5\\x12 \\n\\x13size_to_image_ratio\\x18\\x03 \\x01(\\x02:\\x03\\x30.1\\\"A\\n\\x12RandomResizeMethod\\x12\\x15\\n\\rtarget_height\\x18\\x01 \\x01(\\x02\\x12\\x14\\n\\x0ctarget_width\\x18\\x02 \\x01(\\x02\\\"\\x1e\\n\\x1cScaleBoxesToPixelCoordinates\\\"\\xc0\\x01\\n\\x0bResizeImage\\x12\\x12\\n\\nnew_height\\x18\\x01 \\x01(\\x05\\x12\\x11\\n\\tnew_width\\x18\\x02 \\x01(\\x05\\x12\\x45\\n\\x06method\\x18\\x03 \\x01(\\x0e\\x32+.object_detection.protos.ResizeImage.Method:\\x08\\x42ILINEAR\\\"C\\n\\x06Method\\x12\\x08\\n\\x04\\x41REA\\x10\\x01\\x12\\x0b\\n\\x07\\x42ICUBIC\\x10\\x02\\x12\\x0c\\n\\x08\\x42ILINEAR\\x10\\x03\\x12\\x14\\n\\x10NEAREST_NEIGHBOR\\x10\\x04\\\"$\\n\\x13SubtractChannelMean\\x12\\r\\n\\x05means\\x18\\x01 \\x03(\\x02\\\"\\xb9\\x01\\n\\x16SSDRandomCropOperation\\x12\\x1a\\n\\x12min_object_covered\\x18\\x01 \\x01(\\x02\\x12\\x18\\n\\x10min_aspect_ratio\\x18\\x02 \\x01(\\x02\\x12\\x18\\n\\x10max_aspect_ratio\\x18\\x03 \\x01(\\x02\\x12\\x10\\n\\x08min_area\\x18\\x04 \\x01(\\x02\\x12\\x10\\n\\x08max_area\\x18\\x05 \\x01(\\x02\\x12\\x16\\n\\x0eoverlap_thresh\\x18\\x06 \\x01(\\x02\\x12\\x13\\n\\x0brandom_coef\\x18\\x07 \\x01(\\x02\\\"T\\n\\rSSDRandomCrop\\x12\\x43\\n\\noperations\\x18\\x01 \\x03(\\x0b\\x32/.object_detection.protos.SSDRandomCropOperation\\\"\\xb9\\x02\\n\\x19SSDRandomCropPadOperation\\x12\\x1a\\n\\x12min_object_covered\\x18\\x01 \\x01(\\x02\\x12\\x18\\n\\x10min_aspect_ratio\\x18\\x02 \\x01(\\x02\\x12\\x18\\n\\x10max_aspect_ratio\\x18\\x03 \\x01(\\x02\\x12\\x10\\n\\x08min_area\\x18\\x04 \\x01(\\x02\\x12\\x10\\n\\x08max_area\\x18\\x05 \\x01(\\x02\\x12\\x16\\n\\x0eoverlap_thresh\\x18\\x06 \\x01(\\x02\\x12\\x13\\n\\x0brandom_coef\\x18\\x07 \\x01(\\x02\\x12\\x1d\\n\\x15min_padded_size_ratio\\x18\\x08 \\x03(\\x02\\x12\\x1d\\n\\x15max_padded_size_ratio\\x18\\t \\x03(\\x02\\x12\\x13\\n\\x0bpad_color_r\\x18\\n \\x01(\\x02\\x12\\x13\\n\\x0bpad_color_g\\x18\\x0b \\x01(\\x02\\x12\\x13\\n\\x0bpad_color_b\\x18\\x0c \\x01(\\x02\\\"Z\\n\\x10SSDRandomCropPad\\x12\\x46\\n\\noperations\\x18\\x01 \\x03(\\x0b\\x32\\x32.object_detection.protos.SSDRandomCropPadOperation\\\"\\x95\\x01\\n&SSDRandomCropFixedAspectRatioOperation\\x12\\x1a\\n\\x12min_object_covered\\x18\\x01 \\x01(\\x02\\x12\\x10\\n\\x08min_area\\x18\\x04 \\x01(\\x02\\x12\\x10\\n\\x08max_area\\x18\\x05 \\x01(\\x02\\x12\\x16\\n\\x0eoverlap_thresh\\x18\\x06 \\x01(\\x02\\x12\\x13\\n\\x0brandom_coef\\x18\\x07 \\x01(\\x02\\\"\\x8d\\x01\\n\\x1dSSDRandomCropFixedAspectRatio\\x12S\\n\\noperations\\x18\\x01 \\x03(\\x0b\\x32?.object_detection.protos.SSDRandomCropFixedAspectRatioOperation\\x12\\x17\\n\\x0c\\x61spect_ratio\\x18\\x02 \\x01(\\x02:\\x01\\x31')\n)\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n_RESIZEIMAGE_METHOD = _descriptor.EnumDescriptor(\n  name='Method',\n  full_name='object_detection.protos.ResizeImage.Method',\n  filename=None,\n  file=DESCRIPTOR,\n  values=[\n    _descriptor.EnumValueDescriptor(\n      name='AREA', index=0, number=1,\n      options=None,\n      type=None),\n    _descriptor.EnumValueDescriptor(\n      name='BICUBIC', index=1, number=2,\n      options=None,\n      type=None),\n    _descriptor.EnumValueDescriptor(\n      name='BILINEAR', index=2, number=3,\n      options=None,\n      type=None),\n    _descriptor.EnumValueDescriptor(\n      name='NEAREST_NEIGHBOR', index=3, number=4,\n      options=None,\n      type=None),\n  ],\n  containing_type=None,\n  options=None,\n  serialized_start=3642,\n  serialized_end=3709,\n)\n_sym_db.RegisterEnumDescriptor(_RESIZEIMAGE_METHOD)\n\n\n_PREPROCESSINGSTEP = _descriptor.Descriptor(\n  name='PreprocessingStep',\n  full_name='object_detection.protos.PreprocessingStep',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='normalize_image', full_name='object_detection.protos.PreprocessingStep.normalize_image', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_horizontal_flip', full_name='object_detection.protos.PreprocessingStep.random_horizontal_flip', index=1,\n      number=2, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_pixel_value_scale', full_name='object_detection.protos.PreprocessingStep.random_pixel_value_scale', index=2,\n      number=3, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_image_scale', full_name='object_detection.protos.PreprocessingStep.random_image_scale', index=3,\n      number=4, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_rgb_to_gray', full_name='object_detection.protos.PreprocessingStep.random_rgb_to_gray', index=4,\n      number=5, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_adjust_brightness', full_name='object_detection.protos.PreprocessingStep.random_adjust_brightness', index=5,\n      number=6, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_adjust_contrast', full_name='object_detection.protos.PreprocessingStep.random_adjust_contrast', index=6,\n      number=7, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_adjust_hue', full_name='object_detection.protos.PreprocessingStep.random_adjust_hue', index=7,\n      number=8, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_adjust_saturation', full_name='object_detection.protos.PreprocessingStep.random_adjust_saturation', index=8,\n      number=9, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_distort_color', full_name='object_detection.protos.PreprocessingStep.random_distort_color', index=9,\n      number=10, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_jitter_boxes', full_name='object_detection.protos.PreprocessingStep.random_jitter_boxes', index=10,\n      number=11, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_crop_image', full_name='object_detection.protos.PreprocessingStep.random_crop_image', index=11,\n      number=12, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_pad_image', full_name='object_detection.protos.PreprocessingStep.random_pad_image', index=12,\n      number=13, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_crop_pad_image', full_name='object_detection.protos.PreprocessingStep.random_crop_pad_image', index=13,\n      number=14, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_crop_to_aspect_ratio', full_name='object_detection.protos.PreprocessingStep.random_crop_to_aspect_ratio', index=14,\n      number=15, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_black_patches', full_name='object_detection.protos.PreprocessingStep.random_black_patches', index=15,\n      number=16, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_resize_method', full_name='object_detection.protos.PreprocessingStep.random_resize_method', index=16,\n      number=17, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='scale_boxes_to_pixel_coordinates', full_name='object_detection.protos.PreprocessingStep.scale_boxes_to_pixel_coordinates', index=17,\n      number=18, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='resize_image', full_name='object_detection.protos.PreprocessingStep.resize_image', index=18,\n      number=19, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='subtract_channel_mean', full_name='object_detection.protos.PreprocessingStep.subtract_channel_mean', index=19,\n      number=20, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='ssd_random_crop', full_name='object_detection.protos.PreprocessingStep.ssd_random_crop', index=20,\n      number=21, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='ssd_random_crop_pad', full_name='object_detection.protos.PreprocessingStep.ssd_random_crop_pad', index=21,\n      number=22, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='ssd_random_crop_fixed_aspect_ratio', full_name='object_detection.protos.PreprocessingStep.ssd_random_crop_fixed_aspect_ratio', index=22,\n      number=23, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n    _descriptor.OneofDescriptor(\n      name='preprocessing_step', full_name='object_detection.protos.PreprocessingStep.preprocessing_step',\n      index=0, containing_type=None, fields=[]),\n  ],\n  serialized_start=72,\n  serialized_end=1909,\n)\n\n\n_NORMALIZEIMAGE = _descriptor.Descriptor(\n  name='NormalizeImage',\n  full_name='object_detection.protos.NormalizeImage',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='original_minval', full_name='object_detection.protos.NormalizeImage.original_minval', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='original_maxval', full_name='object_detection.protos.NormalizeImage.original_maxval', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='target_minval', full_name='object_detection.protos.NormalizeImage.target_minval', index=2,\n      number=3, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='target_maxval', full_name='object_detection.protos.NormalizeImage.target_maxval', index=3,\n      number=4, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=1911,\n  serialized_end=2029,\n)\n\n\n_RANDOMHORIZONTALFLIP = _descriptor.Descriptor(\n  name='RandomHorizontalFlip',\n  full_name='object_detection.protos.RandomHorizontalFlip',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=2031,\n  serialized_end=2053,\n)\n\n\n_RANDOMPIXELVALUESCALE = _descriptor.Descriptor(\n  name='RandomPixelValueScale',\n  full_name='object_detection.protos.RandomPixelValueScale',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='minval', full_name='object_detection.protos.RandomPixelValueScale.minval', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.9,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='maxval', full_name='object_detection.protos.RandomPixelValueScale.maxval', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1.1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=2055,\n  serialized_end=2120,\n)\n\n\n_RANDOMIMAGESCALE = _descriptor.Descriptor(\n  name='RandomImageScale',\n  full_name='object_detection.protos.RandomImageScale',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='min_scale_ratio', full_name='object_detection.protos.RandomImageScale.min_scale_ratio', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.5,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_scale_ratio', full_name='object_detection.protos.RandomImageScale.max_scale_ratio', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=2,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=2122,\n  serialized_end=2198,\n)\n\n\n_RANDOMRGBTOGRAY = _descriptor.Descriptor(\n  name='RandomRGBtoGray',\n  full_name='object_detection.protos.RandomRGBtoGray',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='probability', full_name='object_detection.protos.RandomRGBtoGray.probability', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=2200,\n  serialized_end=2243,\n)\n\n\n_RANDOMADJUSTBRIGHTNESS = _descriptor.Descriptor(\n  name='RandomAdjustBrightness',\n  full_name='object_detection.protos.RandomAdjustBrightness',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='max_delta', full_name='object_detection.protos.RandomAdjustBrightness.max_delta', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.2,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=2245,\n  serialized_end=2293,\n)\n\n\n_RANDOMADJUSTCONTRAST = _descriptor.Descriptor(\n  name='RandomAdjustContrast',\n  full_name='object_detection.protos.RandomAdjustContrast',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='min_delta', full_name='object_detection.protos.RandomAdjustContrast.min_delta', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.8,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_delta', full_name='object_detection.protos.RandomAdjustContrast.max_delta', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1.25,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=2295,\n  serialized_end=2366,\n)\n\n\n_RANDOMADJUSTHUE = _descriptor.Descriptor(\n  name='RandomAdjustHue',\n  full_name='object_detection.protos.RandomAdjustHue',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='max_delta', full_name='object_detection.protos.RandomAdjustHue.max_delta', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.02,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=2368,\n  serialized_end=2410,\n)\n\n\n_RANDOMADJUSTSATURATION = _descriptor.Descriptor(\n  name='RandomAdjustSaturation',\n  full_name='object_detection.protos.RandomAdjustSaturation',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='min_delta', full_name='object_detection.protos.RandomAdjustSaturation.min_delta', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.8,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_delta', full_name='object_detection.protos.RandomAdjustSaturation.max_delta', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1.25,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=2412,\n  serialized_end=2485,\n)\n\n\n_RANDOMDISTORTCOLOR = _descriptor.Descriptor(\n  name='RandomDistortColor',\n  full_name='object_detection.protos.RandomDistortColor',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='color_ordering', full_name='object_detection.protos.RandomDistortColor.color_ordering', index=0,\n      number=1, type=5, cpp_type=1, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=2487,\n  serialized_end=2531,\n)\n\n\n_RANDOMJITTERBOXES = _descriptor.Descriptor(\n  name='RandomJitterBoxes',\n  full_name='object_detection.protos.RandomJitterBoxes',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='ratio', full_name='object_detection.protos.RandomJitterBoxes.ratio', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.05,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=2533,\n  serialized_end=2573,\n)\n\n\n_RANDOMCROPIMAGE = _descriptor.Descriptor(\n  name='RandomCropImage',\n  full_name='object_detection.protos.RandomCropImage',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='min_object_covered', full_name='object_detection.protos.RandomCropImage.min_object_covered', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='min_aspect_ratio', full_name='object_detection.protos.RandomCropImage.min_aspect_ratio', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.75,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_aspect_ratio', full_name='object_detection.protos.RandomCropImage.max_aspect_ratio', index=2,\n      number=3, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1.33,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='min_area', full_name='object_detection.protos.RandomCropImage.min_area', index=3,\n      number=4, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_area', full_name='object_detection.protos.RandomCropImage.max_area', index=4,\n      number=5, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='overlap_thresh', full_name='object_detection.protos.RandomCropImage.overlap_thresh', index=5,\n      number=6, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.3,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_coef', full_name='object_detection.protos.RandomCropImage.random_coef', index=6,\n      number=7, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=2576,\n  serialized_end=2785,\n)\n\n\n_RANDOMPADIMAGE = _descriptor.Descriptor(\n  name='RandomPadImage',\n  full_name='object_detection.protos.RandomPadImage',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='min_image_height', full_name='object_detection.protos.RandomPadImage.min_image_height', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='min_image_width', full_name='object_detection.protos.RandomPadImage.min_image_width', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_image_height', full_name='object_detection.protos.RandomPadImage.max_image_height', index=2,\n      number=3, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_image_width', full_name='object_detection.protos.RandomPadImage.max_image_width', index=3,\n      number=4, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='pad_color', full_name='object_detection.protos.RandomPadImage.pad_color', index=4,\n      number=5, type=2, cpp_type=6, label=3,\n      has_default_value=False, default_value=[],\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=2788,\n  serialized_end=2925,\n)\n\n\n_RANDOMCROPPADIMAGE = _descriptor.Descriptor(\n  name='RandomCropPadImage',\n  full_name='object_detection.protos.RandomCropPadImage',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='min_object_covered', full_name='object_detection.protos.RandomCropPadImage.min_object_covered', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='min_aspect_ratio', full_name='object_detection.protos.RandomCropPadImage.min_aspect_ratio', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.75,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_aspect_ratio', full_name='object_detection.protos.RandomCropPadImage.max_aspect_ratio', index=2,\n      number=3, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1.33,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='min_area', full_name='object_detection.protos.RandomCropPadImage.min_area', index=3,\n      number=4, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_area', full_name='object_detection.protos.RandomCropPadImage.max_area', index=4,\n      number=5, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='overlap_thresh', full_name='object_detection.protos.RandomCropPadImage.overlap_thresh', index=5,\n      number=6, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.3,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_coef', full_name='object_detection.protos.RandomCropPadImage.random_coef', index=6,\n      number=7, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='min_padded_size_ratio', full_name='object_detection.protos.RandomCropPadImage.min_padded_size_ratio', index=7,\n      number=8, type=2, cpp_type=6, label=3,\n      has_default_value=False, default_value=[],\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_padded_size_ratio', full_name='object_detection.protos.RandomCropPadImage.max_padded_size_ratio', index=8,\n      number=9, type=2, cpp_type=6, label=3,\n      has_default_value=False, default_value=[],\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='pad_color', full_name='object_detection.protos.RandomCropPadImage.pad_color', index=9,\n      number=10, type=2, cpp_type=6, label=3,\n      has_default_value=False, default_value=[],\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=2928,\n  serialized_end=3221,\n)\n\n\n_RANDOMCROPTOASPECTRATIO = _descriptor.Descriptor(\n  name='RandomCropToAspectRatio',\n  full_name='object_detection.protos.RandomCropToAspectRatio',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='aspect_ratio', full_name='object_detection.protos.RandomCropToAspectRatio.aspect_ratio', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='overlap_thresh', full_name='object_detection.protos.RandomCropToAspectRatio.overlap_thresh', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.3,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=3223,\n  serialized_end=3302,\n)\n\n\n_RANDOMBLACKPATCHES = _descriptor.Descriptor(\n  name='RandomBlackPatches',\n  full_name='object_detection.protos.RandomBlackPatches',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='max_black_patches', full_name='object_detection.protos.RandomBlackPatches.max_black_patches', index=0,\n      number=1, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=10,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='probability', full_name='object_detection.protos.RandomBlackPatches.probability', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.5,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='size_to_image_ratio', full_name='object_detection.protos.RandomBlackPatches.size_to_image_ratio', index=2,\n      number=3, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=3304,\n  serialized_end=3415,\n)\n\n\n_RANDOMRESIZEMETHOD = _descriptor.Descriptor(\n  name='RandomResizeMethod',\n  full_name='object_detection.protos.RandomResizeMethod',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='target_height', full_name='object_detection.protos.RandomResizeMethod.target_height', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='target_width', full_name='object_detection.protos.RandomResizeMethod.target_width', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=3417,\n  serialized_end=3482,\n)\n\n\n_SCALEBOXESTOPIXELCOORDINATES = _descriptor.Descriptor(\n  name='ScaleBoxesToPixelCoordinates',\n  full_name='object_detection.protos.ScaleBoxesToPixelCoordinates',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=3484,\n  serialized_end=3514,\n)\n\n\n_RESIZEIMAGE = _descriptor.Descriptor(\n  name='ResizeImage',\n  full_name='object_detection.protos.ResizeImage',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='new_height', full_name='object_detection.protos.ResizeImage.new_height', index=0,\n      number=1, type=5, cpp_type=1, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='new_width', full_name='object_detection.protos.ResizeImage.new_width', index=1,\n      number=2, type=5, cpp_type=1, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='method', full_name='object_detection.protos.ResizeImage.method', index=2,\n      number=3, type=14, cpp_type=8, label=1,\n      has_default_value=True, default_value=3,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n    _RESIZEIMAGE_METHOD,\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=3517,\n  serialized_end=3709,\n)\n\n\n_SUBTRACTCHANNELMEAN = _descriptor.Descriptor(\n  name='SubtractChannelMean',\n  full_name='object_detection.protos.SubtractChannelMean',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='means', full_name='object_detection.protos.SubtractChannelMean.means', index=0,\n      number=1, type=2, cpp_type=6, label=3,\n      has_default_value=False, default_value=[],\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=3711,\n  serialized_end=3747,\n)\n\n\n_SSDRANDOMCROPOPERATION = _descriptor.Descriptor(\n  name='SSDRandomCropOperation',\n  full_name='object_detection.protos.SSDRandomCropOperation',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='min_object_covered', full_name='object_detection.protos.SSDRandomCropOperation.min_object_covered', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='min_aspect_ratio', full_name='object_detection.protos.SSDRandomCropOperation.min_aspect_ratio', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_aspect_ratio', full_name='object_detection.protos.SSDRandomCropOperation.max_aspect_ratio', index=2,\n      number=3, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='min_area', full_name='object_detection.protos.SSDRandomCropOperation.min_area', index=3,\n      number=4, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_area', full_name='object_detection.protos.SSDRandomCropOperation.max_area', index=4,\n      number=5, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='overlap_thresh', full_name='object_detection.protos.SSDRandomCropOperation.overlap_thresh', index=5,\n      number=6, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_coef', full_name='object_detection.protos.SSDRandomCropOperation.random_coef', index=6,\n      number=7, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=3750,\n  serialized_end=3935,\n)\n\n\n_SSDRANDOMCROP = _descriptor.Descriptor(\n  name='SSDRandomCrop',\n  full_name='object_detection.protos.SSDRandomCrop',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='operations', full_name='object_detection.protos.SSDRandomCrop.operations', index=0,\n      number=1, type=11, cpp_type=10, label=3,\n      has_default_value=False, default_value=[],\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=3937,\n  serialized_end=4021,\n)\n\n\n_SSDRANDOMCROPPADOPERATION = _descriptor.Descriptor(\n  name='SSDRandomCropPadOperation',\n  full_name='object_detection.protos.SSDRandomCropPadOperation',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='min_object_covered', full_name='object_detection.protos.SSDRandomCropPadOperation.min_object_covered', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='min_aspect_ratio', full_name='object_detection.protos.SSDRandomCropPadOperation.min_aspect_ratio', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_aspect_ratio', full_name='object_detection.protos.SSDRandomCropPadOperation.max_aspect_ratio', index=2,\n      number=3, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='min_area', full_name='object_detection.protos.SSDRandomCropPadOperation.min_area', index=3,\n      number=4, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_area', full_name='object_detection.protos.SSDRandomCropPadOperation.max_area', index=4,\n      number=5, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='overlap_thresh', full_name='object_detection.protos.SSDRandomCropPadOperation.overlap_thresh', index=5,\n      number=6, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_coef', full_name='object_detection.protos.SSDRandomCropPadOperation.random_coef', index=6,\n      number=7, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='min_padded_size_ratio', full_name='object_detection.protos.SSDRandomCropPadOperation.min_padded_size_ratio', index=7,\n      number=8, type=2, cpp_type=6, label=3,\n      has_default_value=False, default_value=[],\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_padded_size_ratio', full_name='object_detection.protos.SSDRandomCropPadOperation.max_padded_size_ratio', index=8,\n      number=9, type=2, cpp_type=6, label=3,\n      has_default_value=False, default_value=[],\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='pad_color_r', full_name='object_detection.protos.SSDRandomCropPadOperation.pad_color_r', index=9,\n      number=10, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='pad_color_g', full_name='object_detection.protos.SSDRandomCropPadOperation.pad_color_g', index=10,\n      number=11, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='pad_color_b', full_name='object_detection.protos.SSDRandomCropPadOperation.pad_color_b', index=11,\n      number=12, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=4024,\n  serialized_end=4337,\n)\n\n\n_SSDRANDOMCROPPAD = _descriptor.Descriptor(\n  name='SSDRandomCropPad',\n  full_name='object_detection.protos.SSDRandomCropPad',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='operations', full_name='object_detection.protos.SSDRandomCropPad.operations', index=0,\n      number=1, type=11, cpp_type=10, label=3,\n      has_default_value=False, default_value=[],\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=4339,\n  serialized_end=4429,\n)\n\n\n_SSDRANDOMCROPFIXEDASPECTRATIOOPERATION = _descriptor.Descriptor(\n  name='SSDRandomCropFixedAspectRatioOperation',\n  full_name='object_detection.protos.SSDRandomCropFixedAspectRatioOperation',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='min_object_covered', full_name='object_detection.protos.SSDRandomCropFixedAspectRatioOperation.min_object_covered', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='min_area', full_name='object_detection.protos.SSDRandomCropFixedAspectRatioOperation.min_area', index=1,\n      number=4, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_area', full_name='object_detection.protos.SSDRandomCropFixedAspectRatioOperation.max_area', index=2,\n      number=5, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='overlap_thresh', full_name='object_detection.protos.SSDRandomCropFixedAspectRatioOperation.overlap_thresh', index=3,\n      number=6, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='random_coef', full_name='object_detection.protos.SSDRandomCropFixedAspectRatioOperation.random_coef', index=4,\n      number=7, type=2, cpp_type=6, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=4432,\n  serialized_end=4581,\n)\n\n\n_SSDRANDOMCROPFIXEDASPECTRATIO = _descriptor.Descriptor(\n  name='SSDRandomCropFixedAspectRatio',\n  full_name='object_detection.protos.SSDRandomCropFixedAspectRatio',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='operations', full_name='object_detection.protos.SSDRandomCropFixedAspectRatio.operations', index=0,\n      number=1, type=11, cpp_type=10, label=3,\n      has_default_value=False, default_value=[],\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='aspect_ratio', full_name='object_detection.protos.SSDRandomCropFixedAspectRatio.aspect_ratio', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=4584,\n  serialized_end=4725,\n)\n\n_PREPROCESSINGSTEP.fields_by_name['normalize_image'].message_type = _NORMALIZEIMAGE\n_PREPROCESSINGSTEP.fields_by_name['random_horizontal_flip'].message_type = _RANDOMHORIZONTALFLIP\n_PREPROCESSINGSTEP.fields_by_name['random_pixel_value_scale'].message_type = _RANDOMPIXELVALUESCALE\n_PREPROCESSINGSTEP.fields_by_name['random_image_scale'].message_type = _RANDOMIMAGESCALE\n_PREPROCESSINGSTEP.fields_by_name['random_rgb_to_gray'].message_type = _RANDOMRGBTOGRAY\n_PREPROCESSINGSTEP.fields_by_name['random_adjust_brightness'].message_type = _RANDOMADJUSTBRIGHTNESS\n_PREPROCESSINGSTEP.fields_by_name['random_adjust_contrast'].message_type = _RANDOMADJUSTCONTRAST\n_PREPROCESSINGSTEP.fields_by_name['random_adjust_hue'].message_type = _RANDOMADJUSTHUE\n_PREPROCESSINGSTEP.fields_by_name['random_adjust_saturation'].message_type = _RANDOMADJUSTSATURATION\n_PREPROCESSINGSTEP.fields_by_name['random_distort_color'].message_type = _RANDOMDISTORTCOLOR\n_PREPROCESSINGSTEP.fields_by_name['random_jitter_boxes'].message_type = _RANDOMJITTERBOXES\n_PREPROCESSINGSTEP.fields_by_name['random_crop_image'].message_type = _RANDOMCROPIMAGE\n_PREPROCESSINGSTEP.fields_by_name['random_pad_image'].message_type = _RANDOMPADIMAGE\n_PREPROCESSINGSTEP.fields_by_name['random_crop_pad_image'].message_type = _RANDOMCROPPADIMAGE\n_PREPROCESSINGSTEP.fields_by_name['random_crop_to_aspect_ratio'].message_type = _RANDOMCROPTOASPECTRATIO\n_PREPROCESSINGSTEP.fields_by_name['random_black_patches'].message_type = _RANDOMBLACKPATCHES\n_PREPROCESSINGSTEP.fields_by_name['random_resize_method'].message_type = _RANDOMRESIZEMETHOD\n_PREPROCESSINGSTEP.fields_by_name['scale_boxes_to_pixel_coordinates'].message_type = _SCALEBOXESTOPIXELCOORDINATES\n_PREPROCESSINGSTEP.fields_by_name['resize_image'].message_type = _RESIZEIMAGE\n_PREPROCESSINGSTEP.fields_by_name['subtract_channel_mean'].message_type = _SUBTRACTCHANNELMEAN\n_PREPROCESSINGSTEP.fields_by_name['ssd_random_crop'].message_type = _SSDRANDOMCROP\n_PREPROCESSINGSTEP.fields_by_name['ssd_random_crop_pad'].message_type = _SSDRANDOMCROPPAD\n_PREPROCESSINGSTEP.fields_by_name['ssd_random_crop_fixed_aspect_ratio'].message_type = _SSDRANDOMCROPFIXEDASPECTRATIO\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['normalize_image'])\n_PREPROCESSINGSTEP.fields_by_name['normalize_image'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['random_horizontal_flip'])\n_PREPROCESSINGSTEP.fields_by_name['random_horizontal_flip'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['random_pixel_value_scale'])\n_PREPROCESSINGSTEP.fields_by_name['random_pixel_value_scale'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['random_image_scale'])\n_PREPROCESSINGSTEP.fields_by_name['random_image_scale'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['random_rgb_to_gray'])\n_PREPROCESSINGSTEP.fields_by_name['random_rgb_to_gray'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['random_adjust_brightness'])\n_PREPROCESSINGSTEP.fields_by_name['random_adjust_brightness'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['random_adjust_contrast'])\n_PREPROCESSINGSTEP.fields_by_name['random_adjust_contrast'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['random_adjust_hue'])\n_PREPROCESSINGSTEP.fields_by_name['random_adjust_hue'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['random_adjust_saturation'])\n_PREPROCESSINGSTEP.fields_by_name['random_adjust_saturation'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['random_distort_color'])\n_PREPROCESSINGSTEP.fields_by_name['random_distort_color'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['random_jitter_boxes'])\n_PREPROCESSINGSTEP.fields_by_name['random_jitter_boxes'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['random_crop_image'])\n_PREPROCESSINGSTEP.fields_by_name['random_crop_image'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['random_pad_image'])\n_PREPROCESSINGSTEP.fields_by_name['random_pad_image'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['random_crop_pad_image'])\n_PREPROCESSINGSTEP.fields_by_name['random_crop_pad_image'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['random_crop_to_aspect_ratio'])\n_PREPROCESSINGSTEP.fields_by_name['random_crop_to_aspect_ratio'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['random_black_patches'])\n_PREPROCESSINGSTEP.fields_by_name['random_black_patches'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['random_resize_method'])\n_PREPROCESSINGSTEP.fields_by_name['random_resize_method'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['scale_boxes_to_pixel_coordinates'])\n_PREPROCESSINGSTEP.fields_by_name['scale_boxes_to_pixel_coordinates'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['resize_image'])\n_PREPROCESSINGSTEP.fields_by_name['resize_image'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['subtract_channel_mean'])\n_PREPROCESSINGSTEP.fields_by_name['subtract_channel_mean'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['ssd_random_crop'])\n_PREPROCESSINGSTEP.fields_by_name['ssd_random_crop'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['ssd_random_crop_pad'])\n_PREPROCESSINGSTEP.fields_by_name['ssd_random_crop_pad'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step'].fields.append(\n  _PREPROCESSINGSTEP.fields_by_name['ssd_random_crop_fixed_aspect_ratio'])\n_PREPROCESSINGSTEP.fields_by_name['ssd_random_crop_fixed_aspect_ratio'].containing_oneof = _PREPROCESSINGSTEP.oneofs_by_name['preprocessing_step']\n_RESIZEIMAGE.fields_by_name['method'].enum_type = _RESIZEIMAGE_METHOD\n_RESIZEIMAGE_METHOD.containing_type = _RESIZEIMAGE\n_SSDRANDOMCROP.fields_by_name['operations'].message_type = _SSDRANDOMCROPOPERATION\n_SSDRANDOMCROPPAD.fields_by_name['operations'].message_type = _SSDRANDOMCROPPADOPERATION\n_SSDRANDOMCROPFIXEDASPECTRATIO.fields_by_name['operations'].message_type = _SSDRANDOMCROPFIXEDASPECTRATIOOPERATION\nDESCRIPTOR.message_types_by_name['PreprocessingStep'] = _PREPROCESSINGSTEP\nDESCRIPTOR.message_types_by_name['NormalizeImage'] = _NORMALIZEIMAGE\nDESCRIPTOR.message_types_by_name['RandomHorizontalFlip'] = _RANDOMHORIZONTALFLIP\nDESCRIPTOR.message_types_by_name['RandomPixelValueScale'] = _RANDOMPIXELVALUESCALE\nDESCRIPTOR.message_types_by_name['RandomImageScale'] = _RANDOMIMAGESCALE\nDESCRIPTOR.message_types_by_name['RandomRGBtoGray'] = _RANDOMRGBTOGRAY\nDESCRIPTOR.message_types_by_name['RandomAdjustBrightness'] = _RANDOMADJUSTBRIGHTNESS\nDESCRIPTOR.message_types_by_name['RandomAdjustContrast'] = _RANDOMADJUSTCONTRAST\nDESCRIPTOR.message_types_by_name['RandomAdjustHue'] = _RANDOMADJUSTHUE\nDESCRIPTOR.message_types_by_name['RandomAdjustSaturation'] = _RANDOMADJUSTSATURATION\nDESCRIPTOR.message_types_by_name['RandomDistortColor'] = _RANDOMDISTORTCOLOR\nDESCRIPTOR.message_types_by_name['RandomJitterBoxes'] = _RANDOMJITTERBOXES\nDESCRIPTOR.message_types_by_name['RandomCropImage'] = _RANDOMCROPIMAGE\nDESCRIPTOR.message_types_by_name['RandomPadImage'] = _RANDOMPADIMAGE\nDESCRIPTOR.message_types_by_name['RandomCropPadImage'] = _RANDOMCROPPADIMAGE\nDESCRIPTOR.message_types_by_name['RandomCropToAspectRatio'] = _RANDOMCROPTOASPECTRATIO\nDESCRIPTOR.message_types_by_name['RandomBlackPatches'] = _RANDOMBLACKPATCHES\nDESCRIPTOR.message_types_by_name['RandomResizeMethod'] = _RANDOMRESIZEMETHOD\nDESCRIPTOR.message_types_by_name['ScaleBoxesToPixelCoordinates'] = _SCALEBOXESTOPIXELCOORDINATES\nDESCRIPTOR.message_types_by_name['ResizeImage'] = _RESIZEIMAGE\nDESCRIPTOR.message_types_by_name['SubtractChannelMean'] = _SUBTRACTCHANNELMEAN\nDESCRIPTOR.message_types_by_name['SSDRandomCropOperation'] = _SSDRANDOMCROPOPERATION\nDESCRIPTOR.message_types_by_name['SSDRandomCrop'] = _SSDRANDOMCROP\nDESCRIPTOR.message_types_by_name['SSDRandomCropPadOperation'] = _SSDRANDOMCROPPADOPERATION\nDESCRIPTOR.message_types_by_name['SSDRandomCropPad'] = _SSDRANDOMCROPPAD\nDESCRIPTOR.message_types_by_name['SSDRandomCropFixedAspectRatioOperation'] = _SSDRANDOMCROPFIXEDASPECTRATIOOPERATION\nDESCRIPTOR.message_types_by_name['SSDRandomCropFixedAspectRatio'] = _SSDRANDOMCROPFIXEDASPECTRATIO\n\nPreprocessingStep = _reflection.GeneratedProtocolMessageType('PreprocessingStep', (_message.Message,), dict(\n  DESCRIPTOR = _PREPROCESSINGSTEP,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.PreprocessingStep)\n  ))\n_sym_db.RegisterMessage(PreprocessingStep)\n\nNormalizeImage = _reflection.GeneratedProtocolMessageType('NormalizeImage', (_message.Message,), dict(\n  DESCRIPTOR = _NORMALIZEIMAGE,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.NormalizeImage)\n  ))\n_sym_db.RegisterMessage(NormalizeImage)\n\nRandomHorizontalFlip = _reflection.GeneratedProtocolMessageType('RandomHorizontalFlip', (_message.Message,), dict(\n  DESCRIPTOR = _RANDOMHORIZONTALFLIP,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RandomHorizontalFlip)\n  ))\n_sym_db.RegisterMessage(RandomHorizontalFlip)\n\nRandomPixelValueScale = _reflection.GeneratedProtocolMessageType('RandomPixelValueScale', (_message.Message,), dict(\n  DESCRIPTOR = _RANDOMPIXELVALUESCALE,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RandomPixelValueScale)\n  ))\n_sym_db.RegisterMessage(RandomPixelValueScale)\n\nRandomImageScale = _reflection.GeneratedProtocolMessageType('RandomImageScale', (_message.Message,), dict(\n  DESCRIPTOR = _RANDOMIMAGESCALE,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RandomImageScale)\n  ))\n_sym_db.RegisterMessage(RandomImageScale)\n\nRandomRGBtoGray = _reflection.GeneratedProtocolMessageType('RandomRGBtoGray', (_message.Message,), dict(\n  DESCRIPTOR = _RANDOMRGBTOGRAY,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RandomRGBtoGray)\n  ))\n_sym_db.RegisterMessage(RandomRGBtoGray)\n\nRandomAdjustBrightness = _reflection.GeneratedProtocolMessageType('RandomAdjustBrightness', (_message.Message,), dict(\n  DESCRIPTOR = _RANDOMADJUSTBRIGHTNESS,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RandomAdjustBrightness)\n  ))\n_sym_db.RegisterMessage(RandomAdjustBrightness)\n\nRandomAdjustContrast = _reflection.GeneratedProtocolMessageType('RandomAdjustContrast', (_message.Message,), dict(\n  DESCRIPTOR = _RANDOMADJUSTCONTRAST,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RandomAdjustContrast)\n  ))\n_sym_db.RegisterMessage(RandomAdjustContrast)\n\nRandomAdjustHue = _reflection.GeneratedProtocolMessageType('RandomAdjustHue', (_message.Message,), dict(\n  DESCRIPTOR = _RANDOMADJUSTHUE,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RandomAdjustHue)\n  ))\n_sym_db.RegisterMessage(RandomAdjustHue)\n\nRandomAdjustSaturation = _reflection.GeneratedProtocolMessageType('RandomAdjustSaturation', (_message.Message,), dict(\n  DESCRIPTOR = _RANDOMADJUSTSATURATION,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RandomAdjustSaturation)\n  ))\n_sym_db.RegisterMessage(RandomAdjustSaturation)\n\nRandomDistortColor = _reflection.GeneratedProtocolMessageType('RandomDistortColor', (_message.Message,), dict(\n  DESCRIPTOR = _RANDOMDISTORTCOLOR,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RandomDistortColor)\n  ))\n_sym_db.RegisterMessage(RandomDistortColor)\n\nRandomJitterBoxes = _reflection.GeneratedProtocolMessageType('RandomJitterBoxes', (_message.Message,), dict(\n  DESCRIPTOR = _RANDOMJITTERBOXES,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RandomJitterBoxes)\n  ))\n_sym_db.RegisterMessage(RandomJitterBoxes)\n\nRandomCropImage = _reflection.GeneratedProtocolMessageType('RandomCropImage', (_message.Message,), dict(\n  DESCRIPTOR = _RANDOMCROPIMAGE,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RandomCropImage)\n  ))\n_sym_db.RegisterMessage(RandomCropImage)\n\nRandomPadImage = _reflection.GeneratedProtocolMessageType('RandomPadImage', (_message.Message,), dict(\n  DESCRIPTOR = _RANDOMPADIMAGE,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RandomPadImage)\n  ))\n_sym_db.RegisterMessage(RandomPadImage)\n\nRandomCropPadImage = _reflection.GeneratedProtocolMessageType('RandomCropPadImage', (_message.Message,), dict(\n  DESCRIPTOR = _RANDOMCROPPADIMAGE,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RandomCropPadImage)\n  ))\n_sym_db.RegisterMessage(RandomCropPadImage)\n\nRandomCropToAspectRatio = _reflection.GeneratedProtocolMessageType('RandomCropToAspectRatio', (_message.Message,), dict(\n  DESCRIPTOR = _RANDOMCROPTOASPECTRATIO,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RandomCropToAspectRatio)\n  ))\n_sym_db.RegisterMessage(RandomCropToAspectRatio)\n\nRandomBlackPatches = _reflection.GeneratedProtocolMessageType('RandomBlackPatches', (_message.Message,), dict(\n  DESCRIPTOR = _RANDOMBLACKPATCHES,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RandomBlackPatches)\n  ))\n_sym_db.RegisterMessage(RandomBlackPatches)\n\nRandomResizeMethod = _reflection.GeneratedProtocolMessageType('RandomResizeMethod', (_message.Message,), dict(\n  DESCRIPTOR = _RANDOMRESIZEMETHOD,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RandomResizeMethod)\n  ))\n_sym_db.RegisterMessage(RandomResizeMethod)\n\nScaleBoxesToPixelCoordinates = _reflection.GeneratedProtocolMessageType('ScaleBoxesToPixelCoordinates', (_message.Message,), dict(\n  DESCRIPTOR = _SCALEBOXESTOPIXELCOORDINATES,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.ScaleBoxesToPixelCoordinates)\n  ))\n_sym_db.RegisterMessage(ScaleBoxesToPixelCoordinates)\n\nResizeImage = _reflection.GeneratedProtocolMessageType('ResizeImage', (_message.Message,), dict(\n  DESCRIPTOR = _RESIZEIMAGE,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.ResizeImage)\n  ))\n_sym_db.RegisterMessage(ResizeImage)\n\nSubtractChannelMean = _reflection.GeneratedProtocolMessageType('SubtractChannelMean', (_message.Message,), dict(\n  DESCRIPTOR = _SUBTRACTCHANNELMEAN,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.SubtractChannelMean)\n  ))\n_sym_db.RegisterMessage(SubtractChannelMean)\n\nSSDRandomCropOperation = _reflection.GeneratedProtocolMessageType('SSDRandomCropOperation', (_message.Message,), dict(\n  DESCRIPTOR = _SSDRANDOMCROPOPERATION,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.SSDRandomCropOperation)\n  ))\n_sym_db.RegisterMessage(SSDRandomCropOperation)\n\nSSDRandomCrop = _reflection.GeneratedProtocolMessageType('SSDRandomCrop', (_message.Message,), dict(\n  DESCRIPTOR = _SSDRANDOMCROP,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.SSDRandomCrop)\n  ))\n_sym_db.RegisterMessage(SSDRandomCrop)\n\nSSDRandomCropPadOperation = _reflection.GeneratedProtocolMessageType('SSDRandomCropPadOperation', (_message.Message,), dict(\n  DESCRIPTOR = _SSDRANDOMCROPPADOPERATION,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.SSDRandomCropPadOperation)\n  ))\n_sym_db.RegisterMessage(SSDRandomCropPadOperation)\n\nSSDRandomCropPad = _reflection.GeneratedProtocolMessageType('SSDRandomCropPad', (_message.Message,), dict(\n  DESCRIPTOR = _SSDRANDOMCROPPAD,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.SSDRandomCropPad)\n  ))\n_sym_db.RegisterMessage(SSDRandomCropPad)\n\nSSDRandomCropFixedAspectRatioOperation = _reflection.GeneratedProtocolMessageType('SSDRandomCropFixedAspectRatioOperation', (_message.Message,), dict(\n  DESCRIPTOR = _SSDRANDOMCROPFIXEDASPECTRATIOOPERATION,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.SSDRandomCropFixedAspectRatioOperation)\n  ))\n_sym_db.RegisterMessage(SSDRandomCropFixedAspectRatioOperation)\n\nSSDRandomCropFixedAspectRatio = _reflection.GeneratedProtocolMessageType('SSDRandomCropFixedAspectRatio', (_message.Message,), dict(\n  DESCRIPTOR = _SSDRANDOMCROPFIXEDASPECTRATIO,\n  __module__ = 'object_detection.protos.preprocessor_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.SSDRandomCropFixedAspectRatio)\n  ))\n_sym_db.RegisterMessage(SSDRandomCropFixedAspectRatio)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/region_similarity_calculator.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\n// Configuration proto for region similarity calculators. See\n// core/region_similarity_calculator.py for details.\nmessage RegionSimilarityCalculator {\n  oneof region_similarity {\n    NegSqDistSimilarity neg_sq_dist_similarity = 1;\n    IouSimilarity iou_similarity = 2;\n    IoaSimilarity ioa_similarity = 3;\n  }\n}\n\n// Configuration for negative squared distance similarity calculator.\nmessage NegSqDistSimilarity {\n}\n\n// Configuration for intersection-over-union (IOU) similarity calculator.\nmessage IouSimilarity {\n}\n\n// Configuration for intersection-over-area (IOA) similarity calculator.\nmessage IoaSimilarity {\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/region_similarity_calculator_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/region_similarity_calculator.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/region_similarity_calculator.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n:object_detection/protos/region_similarity_calculator.proto\\x12\\x17object_detection.protos\\\"\\x85\\x02\\n\\x1aRegionSimilarityCalculator\\x12N\\n\\x16neg_sq_dist_similarity\\x18\\x01 \\x01(\\x0b\\x32,.object_detection.protos.NegSqDistSimilarityH\\x00\\x12@\\n\\x0eiou_similarity\\x18\\x02 \\x01(\\x0b\\x32&.object_detection.protos.IouSimilarityH\\x00\\x12@\\n\\x0eioa_similarity\\x18\\x03 \\x01(\\x0b\\x32&.object_detection.protos.IoaSimilarityH\\x00\\x42\\x13\\n\\x11region_similarity\\\"\\x15\\n\\x13NegSqDistSimilarity\\\"\\x0f\\n\\rIouSimilarity\\\"\\x0f\\n\\rIoaSimilarity')\n)\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_REGIONSIMILARITYCALCULATOR = _descriptor.Descriptor(\n  name='RegionSimilarityCalculator',\n  full_name='object_detection.protos.RegionSimilarityCalculator',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='neg_sq_dist_similarity', full_name='object_detection.protos.RegionSimilarityCalculator.neg_sq_dist_similarity', index=0,\n      number=1, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='iou_similarity', full_name='object_detection.protos.RegionSimilarityCalculator.iou_similarity', index=1,\n      number=2, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='ioa_similarity', full_name='object_detection.protos.RegionSimilarityCalculator.ioa_similarity', index=2,\n      number=3, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n    _descriptor.OneofDescriptor(\n      name='region_similarity', full_name='object_detection.protos.RegionSimilarityCalculator.region_similarity',\n      index=0, containing_type=None, fields=[]),\n  ],\n  serialized_start=88,\n  serialized_end=349,\n)\n\n\n_NEGSQDISTSIMILARITY = _descriptor.Descriptor(\n  name='NegSqDistSimilarity',\n  full_name='object_detection.protos.NegSqDistSimilarity',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=351,\n  serialized_end=372,\n)\n\n\n_IOUSIMILARITY = _descriptor.Descriptor(\n  name='IouSimilarity',\n  full_name='object_detection.protos.IouSimilarity',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=374,\n  serialized_end=389,\n)\n\n\n_IOASIMILARITY = _descriptor.Descriptor(\n  name='IoaSimilarity',\n  full_name='object_detection.protos.IoaSimilarity',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=391,\n  serialized_end=406,\n)\n\n_REGIONSIMILARITYCALCULATOR.fields_by_name['neg_sq_dist_similarity'].message_type = _NEGSQDISTSIMILARITY\n_REGIONSIMILARITYCALCULATOR.fields_by_name['iou_similarity'].message_type = _IOUSIMILARITY\n_REGIONSIMILARITYCALCULATOR.fields_by_name['ioa_similarity'].message_type = _IOASIMILARITY\n_REGIONSIMILARITYCALCULATOR.oneofs_by_name['region_similarity'].fields.append(\n  _REGIONSIMILARITYCALCULATOR.fields_by_name['neg_sq_dist_similarity'])\n_REGIONSIMILARITYCALCULATOR.fields_by_name['neg_sq_dist_similarity'].containing_oneof = _REGIONSIMILARITYCALCULATOR.oneofs_by_name['region_similarity']\n_REGIONSIMILARITYCALCULATOR.oneofs_by_name['region_similarity'].fields.append(\n  _REGIONSIMILARITYCALCULATOR.fields_by_name['iou_similarity'])\n_REGIONSIMILARITYCALCULATOR.fields_by_name['iou_similarity'].containing_oneof = _REGIONSIMILARITYCALCULATOR.oneofs_by_name['region_similarity']\n_REGIONSIMILARITYCALCULATOR.oneofs_by_name['region_similarity'].fields.append(\n  _REGIONSIMILARITYCALCULATOR.fields_by_name['ioa_similarity'])\n_REGIONSIMILARITYCALCULATOR.fields_by_name['ioa_similarity'].containing_oneof = _REGIONSIMILARITYCALCULATOR.oneofs_by_name['region_similarity']\nDESCRIPTOR.message_types_by_name['RegionSimilarityCalculator'] = _REGIONSIMILARITYCALCULATOR\nDESCRIPTOR.message_types_by_name['NegSqDistSimilarity'] = _NEGSQDISTSIMILARITY\nDESCRIPTOR.message_types_by_name['IouSimilarity'] = _IOUSIMILARITY\nDESCRIPTOR.message_types_by_name['IoaSimilarity'] = _IOASIMILARITY\n\nRegionSimilarityCalculator = _reflection.GeneratedProtocolMessageType('RegionSimilarityCalculator', (_message.Message,), dict(\n  DESCRIPTOR = _REGIONSIMILARITYCALCULATOR,\n  __module__ = 'object_detection.protos.region_similarity_calculator_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.RegionSimilarityCalculator)\n  ))\n_sym_db.RegisterMessage(RegionSimilarityCalculator)\n\nNegSqDistSimilarity = _reflection.GeneratedProtocolMessageType('NegSqDistSimilarity', (_message.Message,), dict(\n  DESCRIPTOR = _NEGSQDISTSIMILARITY,\n  __module__ = 'object_detection.protos.region_similarity_calculator_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.NegSqDistSimilarity)\n  ))\n_sym_db.RegisterMessage(NegSqDistSimilarity)\n\nIouSimilarity = _reflection.GeneratedProtocolMessageType('IouSimilarity', (_message.Message,), dict(\n  DESCRIPTOR = _IOUSIMILARITY,\n  __module__ = 'object_detection.protos.region_similarity_calculator_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.IouSimilarity)\n  ))\n_sym_db.RegisterMessage(IouSimilarity)\n\nIoaSimilarity = _reflection.GeneratedProtocolMessageType('IoaSimilarity', (_message.Message,), dict(\n  DESCRIPTOR = _IOASIMILARITY,\n  __module__ = 'object_detection.protos.region_similarity_calculator_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.IoaSimilarity)\n  ))\n_sym_db.RegisterMessage(IoaSimilarity)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/square_box_coder.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\n// Configuration proto for SquareBoxCoder. See\n// box_coders/square_box_coder.py for details.\nmessage SquareBoxCoder {\n  // Scale factor for anchor encoded box center.\n  optional float y_scale = 1 [default = 10.0];\n  optional float x_scale = 2 [default = 10.0];\n\n  // Scale factor for anchor encoded box length.\n  optional float length_scale = 3 [default = 5.0];\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/square_box_coder_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/square_box_coder.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/square_box_coder.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n.object_detection/protos/square_box_coder.proto\\x12\\x17object_detection.protos\\\"S\\n\\x0eSquareBoxCoder\\x12\\x13\\n\\x07y_scale\\x18\\x01 \\x01(\\x02:\\x02\\x31\\x30\\x12\\x13\\n\\x07x_scale\\x18\\x02 \\x01(\\x02:\\x02\\x31\\x30\\x12\\x17\\n\\x0clength_scale\\x18\\x03 \\x01(\\x02:\\x01\\x35')\n)\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_SQUAREBOXCODER = _descriptor.Descriptor(\n  name='SquareBoxCoder',\n  full_name='object_detection.protos.SquareBoxCoder',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='y_scale', full_name='object_detection.protos.SquareBoxCoder.y_scale', index=0,\n      number=1, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=10,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='x_scale', full_name='object_detection.protos.SquareBoxCoder.x_scale', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=10,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='length_scale', full_name='object_detection.protos.SquareBoxCoder.length_scale', index=2,\n      number=3, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=5,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=75,\n  serialized_end=158,\n)\n\nDESCRIPTOR.message_types_by_name['SquareBoxCoder'] = _SQUAREBOXCODER\n\nSquareBoxCoder = _reflection.GeneratedProtocolMessageType('SquareBoxCoder', (_message.Message,), dict(\n  DESCRIPTOR = _SQUAREBOXCODER,\n  __module__ = 'object_detection.protos.square_box_coder_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.SquareBoxCoder)\n  ))\n_sym_db.RegisterMessage(SquareBoxCoder)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/ssd.proto",
    "content": "syntax = \"proto2\";\npackage object_detection.protos;\n\nimport \"object_detection/protos/anchor_generator.proto\";\nimport \"object_detection/protos/box_coder.proto\";\nimport \"object_detection/protos/box_predictor.proto\";\nimport \"object_detection/protos/hyperparams.proto\";\nimport \"object_detection/protos/image_resizer.proto\";\nimport \"object_detection/protos/matcher.proto\";\nimport \"object_detection/protos/losses.proto\";\nimport \"object_detection/protos/post_processing.proto\";\nimport \"object_detection/protos/region_similarity_calculator.proto\";\n\n// Configuration for Single Shot Detection (SSD) models.\nmessage Ssd {\n\n  // Number of classes to predict.\n  optional int32 num_classes = 1;\n\n  // Image resizer for preprocessing the input image.\n  optional ImageResizer image_resizer = 2;\n\n  // Feature extractor config.\n  optional SsdFeatureExtractor feature_extractor = 3;\n\n  // Box coder to encode the boxes.\n  optional BoxCoder box_coder = 4;\n\n  // Matcher to match groundtruth with anchors.\n  optional Matcher matcher = 5;\n\n  // Region similarity calculator to compute similarity of boxes.\n  optional RegionSimilarityCalculator similarity_calculator = 6;\n\n  // Box predictor to attach to the features.\n  optional BoxPredictor box_predictor = 7;\n\n  // Anchor generator to compute anchors.\n  optional AnchorGenerator anchor_generator = 8;\n\n  // Post processing to apply on the predictions.\n  optional PostProcessing post_processing = 9;\n\n  // Whether to normalize the loss by number of groundtruth boxes that match to\n  // the anchors.\n  optional bool normalize_loss_by_num_matches = 10 [default=true];\n\n  // Loss configuration for training.\n  optional Loss loss = 11;\n}\n\n\nmessage SsdFeatureExtractor {\n  // Type of ssd feature extractor.\n  optional string type = 1;\n\n  // The factor to alter the depth of the channels in the feature extractor.\n  optional float depth_multiplier = 2 [default=1.0];\n\n  // Minimum number of the channels in the feature extractor.\n  optional int32 min_depth = 3 [default=16];\n\n  // Hyperparameters for the feature extractor.\n  optional Hyperparams conv_hyperparams = 4;\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/ssd_anchor_generator.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\n// Configuration proto for SSD anchor generator described in\n// https://arxiv.org/abs/1512.02325. See\n// anchor_generators/multiple_grid_anchor_generator.py for details.\nmessage SsdAnchorGenerator {\n  // Number of grid layers to create anchors for.\n  optional int32 num_layers = 1 [default = 6];\n\n  // Scale of anchors corresponding to finest resolution.\n  optional float min_scale = 2 [default = 0.2];\n\n  // Scale of anchors corresponding to coarsest resolution\n  optional float max_scale = 3 [default = 0.95];\n\n  // Aspect ratios for anchors at each grid point.\n  repeated float aspect_ratios = 4;\n\n  // Whether to use the following aspect ratio and scale combination for the\n  // layer with the finest resolution : (scale=0.1, aspect_ratio=1.0),\n  // (scale=min_scale, aspect_ration=2.0), (scale=min_scale, aspect_ratio=0.5).\n  optional bool reduce_boxes_in_lowest_layer = 5 [default = true];\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/ssd_anchor_generator_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/ssd_anchor_generator.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/ssd_anchor_generator.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n2object_detection/protos/ssd_anchor_generator.proto\\x12\\x17object_detection.protos\\\"\\x9f\\x01\\n\\x12SsdAnchorGenerator\\x12\\x15\\n\\nnum_layers\\x18\\x01 \\x01(\\x05:\\x01\\x36\\x12\\x16\\n\\tmin_scale\\x18\\x02 \\x01(\\x02:\\x03\\x30.2\\x12\\x17\\n\\tmax_scale\\x18\\x03 \\x01(\\x02:\\x04\\x30.95\\x12\\x15\\n\\raspect_ratios\\x18\\x04 \\x03(\\x02\\x12*\\n\\x1creduce_boxes_in_lowest_layer\\x18\\x05 \\x01(\\x08:\\x04true')\n)\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_SSDANCHORGENERATOR = _descriptor.Descriptor(\n  name='SsdAnchorGenerator',\n  full_name='object_detection.protos.SsdAnchorGenerator',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='num_layers', full_name='object_detection.protos.SsdAnchorGenerator.num_layers', index=0,\n      number=1, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=6,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='min_scale', full_name='object_detection.protos.SsdAnchorGenerator.min_scale', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.2,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='max_scale', full_name='object_detection.protos.SsdAnchorGenerator.max_scale', index=2,\n      number=3, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0.95,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='aspect_ratios', full_name='object_detection.protos.SsdAnchorGenerator.aspect_ratios', index=3,\n      number=4, type=2, cpp_type=6, label=3,\n      has_default_value=False, default_value=[],\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='reduce_boxes_in_lowest_layer', full_name='object_detection.protos.SsdAnchorGenerator.reduce_boxes_in_lowest_layer', index=4,\n      number=5, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=True,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=80,\n  serialized_end=239,\n)\n\nDESCRIPTOR.message_types_by_name['SsdAnchorGenerator'] = _SSDANCHORGENERATOR\n\nSsdAnchorGenerator = _reflection.GeneratedProtocolMessageType('SsdAnchorGenerator', (_message.Message,), dict(\n  DESCRIPTOR = _SSDANCHORGENERATOR,\n  __module__ = 'object_detection.protos.ssd_anchor_generator_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.SsdAnchorGenerator)\n  ))\n_sym_db.RegisterMessage(SsdAnchorGenerator)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/ssd_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/ssd.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\nimport object_detection.protos.anchor_generator_pb2\nimport object_detection.protos.box_coder_pb2\nimport object_detection.protos.box_predictor_pb2\nimport object_detection.protos.hyperparams_pb2\nimport object_detection.protos.image_resizer_pb2\nimport object_detection.protos.matcher_pb2\nimport object_detection.protos.losses_pb2\nimport object_detection.protos.post_processing_pb2\nimport object_detection.protos.region_similarity_calculator_pb2\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/ssd.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n!object_detection/protos/ssd.proto\\x12\\x17object_detection.protos\\x1a.object_detection/protos/anchor_generator.proto\\x1a\\'object_detection/protos/box_coder.proto\\x1a+object_detection/protos/box_predictor.proto\\x1a)object_detection/protos/hyperparams.proto\\x1a+object_detection/protos/image_resizer.proto\\x1a%object_detection/protos/matcher.proto\\x1a$object_detection/protos/losses.proto\\x1a-object_detection/protos/post_processing.proto\\x1a:object_detection/protos/region_similarity_calculator.proto\\\"\\xfc\\x04\\n\\x03Ssd\\x12\\x13\\n\\x0bnum_classes\\x18\\x01 \\x01(\\x05\\x12<\\n\\rimage_resizer\\x18\\x02 \\x01(\\x0b\\x32%.object_detection.protos.ImageResizer\\x12G\\n\\x11\\x66\\x65\\x61ture_extractor\\x18\\x03 \\x01(\\x0b\\x32,.object_detection.protos.SsdFeatureExtractor\\x12\\x34\\n\\tbox_coder\\x18\\x04 \\x01(\\x0b\\x32!.object_detection.protos.BoxCoder\\x12\\x31\\n\\x07matcher\\x18\\x05 \\x01(\\x0b\\x32 .object_detection.protos.Matcher\\x12R\\n\\x15similarity_calculator\\x18\\x06 \\x01(\\x0b\\x32\\x33.object_detection.protos.RegionSimilarityCalculator\\x12<\\n\\rbox_predictor\\x18\\x07 \\x01(\\x0b\\x32%.object_detection.protos.BoxPredictor\\x12\\x42\\n\\x10\\x61nchor_generator\\x18\\x08 \\x01(\\x0b\\x32(.object_detection.protos.AnchorGenerator\\x12@\\n\\x0fpost_processing\\x18\\t \\x01(\\x0b\\x32\\'.object_detection.protos.PostProcessing\\x12+\\n\\x1dnormalize_loss_by_num_matches\\x18\\n \\x01(\\x08:\\x04true\\x12+\\n\\x04loss\\x18\\x0b \\x01(\\x0b\\x32\\x1d.object_detection.protos.Loss\\\"\\x97\\x01\\n\\x13SsdFeatureExtractor\\x12\\x0c\\n\\x04type\\x18\\x01 \\x01(\\t\\x12\\x1b\\n\\x10\\x64\\x65pth_multiplier\\x18\\x02 \\x01(\\x02:\\x01\\x31\\x12\\x15\\n\\tmin_depth\\x18\\x03 \\x01(\\x05:\\x02\\x31\\x36\\x12>\\n\\x10\\x63onv_hyperparams\\x18\\x04 \\x01(\\x0b\\x32$.object_detection.protos.Hyperparams')\n  ,\n  dependencies=[object_detection.protos.anchor_generator_pb2.DESCRIPTOR,object_detection.protos.box_coder_pb2.DESCRIPTOR,object_detection.protos.box_predictor_pb2.DESCRIPTOR,object_detection.protos.hyperparams_pb2.DESCRIPTOR,object_detection.protos.image_resizer_pb2.DESCRIPTOR,object_detection.protos.matcher_pb2.DESCRIPTOR,object_detection.protos.losses_pb2.DESCRIPTOR,object_detection.protos.post_processing_pb2.DESCRIPTOR,object_detection.protos.region_similarity_calculator_pb2.DESCRIPTOR,])\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_SSD = _descriptor.Descriptor(\n  name='Ssd',\n  full_name='object_detection.protos.Ssd',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='num_classes', full_name='object_detection.protos.Ssd.num_classes', index=0,\n      number=1, type=5, cpp_type=1, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='image_resizer', full_name='object_detection.protos.Ssd.image_resizer', index=1,\n      number=2, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='feature_extractor', full_name='object_detection.protos.Ssd.feature_extractor', index=2,\n      number=3, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='box_coder', full_name='object_detection.protos.Ssd.box_coder', index=3,\n      number=4, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='matcher', full_name='object_detection.protos.Ssd.matcher', index=4,\n      number=5, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='similarity_calculator', full_name='object_detection.protos.Ssd.similarity_calculator', index=5,\n      number=6, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='box_predictor', full_name='object_detection.protos.Ssd.box_predictor', index=6,\n      number=7, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='anchor_generator', full_name='object_detection.protos.Ssd.anchor_generator', index=7,\n      number=8, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='post_processing', full_name='object_detection.protos.Ssd.post_processing', index=8,\n      number=9, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='normalize_loss_by_num_matches', full_name='object_detection.protos.Ssd.normalize_loss_by_num_matches', index=9,\n      number=10, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=True,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='loss', full_name='object_detection.protos.Ssd.loss', index=10,\n      number=11, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=469,\n  serialized_end=1105,\n)\n\n\n_SSDFEATUREEXTRACTOR = _descriptor.Descriptor(\n  name='SsdFeatureExtractor',\n  full_name='object_detection.protos.SsdFeatureExtractor',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='type', full_name='object_detection.protos.SsdFeatureExtractor.type', index=0,\n      number=1, type=9, cpp_type=9, label=1,\n      has_default_value=False, default_value=_b(\"\").decode('utf-8'),\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='depth_multiplier', full_name='object_detection.protos.SsdFeatureExtractor.depth_multiplier', index=1,\n      number=2, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='min_depth', full_name='object_detection.protos.SsdFeatureExtractor.min_depth', index=2,\n      number=3, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=16,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='conv_hyperparams', full_name='object_detection.protos.SsdFeatureExtractor.conv_hyperparams', index=3,\n      number=4, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=1108,\n  serialized_end=1259,\n)\n\n_SSD.fields_by_name['image_resizer'].message_type = object_detection.protos.image_resizer_pb2._IMAGERESIZER\n_SSD.fields_by_name['feature_extractor'].message_type = _SSDFEATUREEXTRACTOR\n_SSD.fields_by_name['box_coder'].message_type = object_detection.protos.box_coder_pb2._BOXCODER\n_SSD.fields_by_name['matcher'].message_type = object_detection.protos.matcher_pb2._MATCHER\n_SSD.fields_by_name['similarity_calculator'].message_type = object_detection.protos.region_similarity_calculator_pb2._REGIONSIMILARITYCALCULATOR\n_SSD.fields_by_name['box_predictor'].message_type = object_detection.protos.box_predictor_pb2._BOXPREDICTOR\n_SSD.fields_by_name['anchor_generator'].message_type = object_detection.protos.anchor_generator_pb2._ANCHORGENERATOR\n_SSD.fields_by_name['post_processing'].message_type = object_detection.protos.post_processing_pb2._POSTPROCESSING\n_SSD.fields_by_name['loss'].message_type = object_detection.protos.losses_pb2._LOSS\n_SSDFEATUREEXTRACTOR.fields_by_name['conv_hyperparams'].message_type = object_detection.protos.hyperparams_pb2._HYPERPARAMS\nDESCRIPTOR.message_types_by_name['Ssd'] = _SSD\nDESCRIPTOR.message_types_by_name['SsdFeatureExtractor'] = _SSDFEATUREEXTRACTOR\n\nSsd = _reflection.GeneratedProtocolMessageType('Ssd', (_message.Message,), dict(\n  DESCRIPTOR = _SSD,\n  __module__ = 'object_detection.protos.ssd_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.Ssd)\n  ))\n_sym_db.RegisterMessage(Ssd)\n\nSsdFeatureExtractor = _reflection.GeneratedProtocolMessageType('SsdFeatureExtractor', (_message.Message,), dict(\n  DESCRIPTOR = _SSDFEATUREEXTRACTOR,\n  __module__ = 'object_detection.protos.ssd_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.SsdFeatureExtractor)\n  ))\n_sym_db.RegisterMessage(SsdFeatureExtractor)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/string_int_label_map.proto",
    "content": "// Message to store the mapping from class label strings to class id. Datasets\n// use string labels to represent classes while the object detection framework\n// works with class ids. This message maps them so they can be converted back\n// and forth as needed.\nsyntax = \"proto2\";\n\npackage object_detection.protos;\n\nmessage StringIntLabelMapItem {\n  // String name. The most common practice is to set this to a MID or synsets\n  // id.\n  optional string name = 1;\n\n  // Integer id that maps to the string name above. Label ids should start from\n  // 1.\n  optional int32 id = 2;\n\n  // Human readable string label.\n  optional string display_name = 3;\n};\n\nmessage StringIntLabelMap {\n  repeated StringIntLabelMapItem item = 1;\n};\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/string_int_label_map_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/string_int_label_map.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/string_int_label_map.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n2object_detection/protos/string_int_label_map.proto\\x12\\x17object_detection.protos\\\"G\\n\\x15StringIntLabelMapItem\\x12\\x0c\\n\\x04name\\x18\\x01 \\x01(\\t\\x12\\n\\n\\x02id\\x18\\x02 \\x01(\\x05\\x12\\x14\\n\\x0c\\x64isplay_name\\x18\\x03 \\x01(\\t\\\"Q\\n\\x11StringIntLabelMap\\x12<\\n\\x04item\\x18\\x01 \\x03(\\x0b\\x32..object_detection.protos.StringIntLabelMapItem')\n)\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_STRINGINTLABELMAPITEM = _descriptor.Descriptor(\n  name='StringIntLabelMapItem',\n  full_name='object_detection.protos.StringIntLabelMapItem',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='name', full_name='object_detection.protos.StringIntLabelMapItem.name', index=0,\n      number=1, type=9, cpp_type=9, label=1,\n      has_default_value=False, default_value=_b(\"\").decode('utf-8'),\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='id', full_name='object_detection.protos.StringIntLabelMapItem.id', index=1,\n      number=2, type=5, cpp_type=1, label=1,\n      has_default_value=False, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='display_name', full_name='object_detection.protos.StringIntLabelMapItem.display_name', index=2,\n      number=3, type=9, cpp_type=9, label=1,\n      has_default_value=False, default_value=_b(\"\").decode('utf-8'),\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=79,\n  serialized_end=150,\n)\n\n\n_STRINGINTLABELMAP = _descriptor.Descriptor(\n  name='StringIntLabelMap',\n  full_name='object_detection.protos.StringIntLabelMap',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='item', full_name='object_detection.protos.StringIntLabelMap.item', index=0,\n      number=1, type=11, cpp_type=10, label=3,\n      has_default_value=False, default_value=[],\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=152,\n  serialized_end=233,\n)\n\n_STRINGINTLABELMAP.fields_by_name['item'].message_type = _STRINGINTLABELMAPITEM\nDESCRIPTOR.message_types_by_name['StringIntLabelMapItem'] = _STRINGINTLABELMAPITEM\nDESCRIPTOR.message_types_by_name['StringIntLabelMap'] = _STRINGINTLABELMAP\n\nStringIntLabelMapItem = _reflection.GeneratedProtocolMessageType('StringIntLabelMapItem', (_message.Message,), dict(\n  DESCRIPTOR = _STRINGINTLABELMAPITEM,\n  __module__ = 'object_detection.protos.string_int_label_map_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.StringIntLabelMapItem)\n  ))\n_sym_db.RegisterMessage(StringIntLabelMapItem)\n\nStringIntLabelMap = _reflection.GeneratedProtocolMessageType('StringIntLabelMap', (_message.Message,), dict(\n  DESCRIPTOR = _STRINGINTLABELMAP,\n  __module__ = 'object_detection.protos.string_int_label_map_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.StringIntLabelMap)\n  ))\n_sym_db.RegisterMessage(StringIntLabelMap)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/train.proto",
    "content": "syntax = \"proto2\";\n\npackage object_detection.protos;\n\nimport \"object_detection/protos/optimizer.proto\";\nimport \"object_detection/protos/preprocessor.proto\";\n\n// Message for configuring DetectionModel training jobs (train.py).\nmessage TrainConfig {\n  // Input queue batch size.\n  optional uint32 batch_size = 1 [default=32];\n\n  // Data augmentation options.\n  repeated PreprocessingStep data_augmentation_options = 2;\n\n  // Whether to synchronize replicas during training.\n  optional bool sync_replicas = 3 [default=false];\n\n  // How frequently to keep checkpoints.\n  optional uint32 keep_checkpoint_every_n_hours = 4 [default=1000];\n\n  // Optimizer used to train the DetectionModel.\n  optional Optimizer optimizer = 5;\n\n  // If greater than 0, clips gradients by this value.\n  optional float gradient_clipping_by_norm = 6 [default=0.0];\n\n  // Checkpoint to restore variables from. Typically used to load feature\n  // extractor variables trained outside of object detection.\n  optional string fine_tune_checkpoint = 7 [default=\"\"];\n\n  // Specifies if the finetune checkpoint is from an object detection model.\n  // If from an object detection model, the model being trained should have\n  // the same parameters with the exception of the num_classes parameter.\n  // If false, it assumes the checkpoint was a object classification model.\n  optional bool from_detection_checkpoint = 8 [default=false];\n\n  // Number of steps to train the DetectionModel for. If 0, will train the model\n  // indefinitely.\n  optional uint32 num_steps = 9 [default=0];\n\n  // Number of training steps between replica startup.\n  // This flag must be set to 0 if sync_replicas is set to true.\n  optional float startup_delay_steps = 10 [default=15];\n\n  // If greater than 0, multiplies the gradient of bias variables by this\n  // amount.\n  optional float bias_grad_multiplier = 11 [default=0];\n\n  // Variables that should not be updated during training.\n  repeated string freeze_variables = 12;\n\n  // Number of replicas to aggregate before making parameter updates.\n  optional int32 replicas_to_aggregate = 13 [default=1];\n\n  // Maximum number of elements to store within a queue.\n  optional int32 batch_queue_capacity = 14 [default=600];\n\n  // Number of threads to use for batching.\n  optional int32 num_batch_queue_threads = 15 [default=8];\n\n  // Maximum capacity of the queue used to prefetch assembled batches.\n  optional int32 prefetch_queue_capacity = 16 [default=10];\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/protos/train_pb2.py",
    "content": "# Generated by the protocol buffer compiler.  DO NOT EDIT!\n# source: object_detection/protos/train.proto\n\nimport sys\n_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))\nfrom google.protobuf import descriptor as _descriptor\nfrom google.protobuf import message as _message\nfrom google.protobuf import reflection as _reflection\nfrom google.protobuf import symbol_database as _symbol_database\nfrom google.protobuf import descriptor_pb2\n# @@protoc_insertion_point(imports)\n\n_sym_db = _symbol_database.Default()\n\n\nimport object_detection.protos.optimizer_pb2\nimport object_detection.protos.preprocessor_pb2\n\n\nDESCRIPTOR = _descriptor.FileDescriptor(\n  name='object_detection/protos/train.proto',\n  package='object_detection.protos',\n  serialized_pb=_b('\\n#object_detection/protos/train.proto\\x12\\x17object_detection.protos\\x1a\\'object_detection/protos/optimizer.proto\\x1a*object_detection/protos/preprocessor.proto\\\"\\xe6\\x04\\n\\x0bTrainConfig\\x12\\x16\\n\\nbatch_size\\x18\\x01 \\x01(\\r:\\x02\\x33\\x32\\x12M\\n\\x19\\x64\\x61ta_augmentation_options\\x18\\x02 \\x03(\\x0b\\x32*.object_detection.protos.PreprocessingStep\\x12\\x1c\\n\\rsync_replicas\\x18\\x03 \\x01(\\x08:\\x05\\x66\\x61lse\\x12+\\n\\x1dkeep_checkpoint_every_n_hours\\x18\\x04 \\x01(\\r:\\x04\\x31\\x30\\x30\\x30\\x12\\x35\\n\\toptimizer\\x18\\x05 \\x01(\\x0b\\x32\\\".object_detection.protos.Optimizer\\x12$\\n\\x19gradient_clipping_by_norm\\x18\\x06 \\x01(\\x02:\\x01\\x30\\x12\\x1e\\n\\x14\\x66ine_tune_checkpoint\\x18\\x07 \\x01(\\t:\\x00\\x12(\\n\\x19\\x66rom_detection_checkpoint\\x18\\x08 \\x01(\\x08:\\x05\\x66\\x61lse\\x12\\x14\\n\\tnum_steps\\x18\\t \\x01(\\r:\\x01\\x30\\x12\\x1f\\n\\x13startup_delay_steps\\x18\\n \\x01(\\x02:\\x02\\x31\\x35\\x12\\x1f\\n\\x14\\x62ias_grad_multiplier\\x18\\x0b \\x01(\\x02:\\x01\\x30\\x12\\x18\\n\\x10\\x66reeze_variables\\x18\\x0c \\x03(\\t\\x12 \\n\\x15replicas_to_aggregate\\x18\\r \\x01(\\x05:\\x01\\x31\\x12!\\n\\x14\\x62\\x61tch_queue_capacity\\x18\\x0e \\x01(\\x05:\\x03\\x36\\x30\\x30\\x12\\\"\\n\\x17num_batch_queue_threads\\x18\\x0f \\x01(\\x05:\\x01\\x38\\x12#\\n\\x17prefetch_queue_capacity\\x18\\x10 \\x01(\\x05:\\x02\\x31\\x30')\n  ,\n  dependencies=[object_detection.protos.optimizer_pb2.DESCRIPTOR,object_detection.protos.preprocessor_pb2.DESCRIPTOR,])\n_sym_db.RegisterFileDescriptor(DESCRIPTOR)\n\n\n\n\n_TRAINCONFIG = _descriptor.Descriptor(\n  name='TrainConfig',\n  full_name='object_detection.protos.TrainConfig',\n  filename=None,\n  file=DESCRIPTOR,\n  containing_type=None,\n  fields=[\n    _descriptor.FieldDescriptor(\n      name='batch_size', full_name='object_detection.protos.TrainConfig.batch_size', index=0,\n      number=1, type=13, cpp_type=3, label=1,\n      has_default_value=True, default_value=32,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='data_augmentation_options', full_name='object_detection.protos.TrainConfig.data_augmentation_options', index=1,\n      number=2, type=11, cpp_type=10, label=3,\n      has_default_value=False, default_value=[],\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='sync_replicas', full_name='object_detection.protos.TrainConfig.sync_replicas', index=2,\n      number=3, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='keep_checkpoint_every_n_hours', full_name='object_detection.protos.TrainConfig.keep_checkpoint_every_n_hours', index=3,\n      number=4, type=13, cpp_type=3, label=1,\n      has_default_value=True, default_value=1000,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='optimizer', full_name='object_detection.protos.TrainConfig.optimizer', index=4,\n      number=5, type=11, cpp_type=10, label=1,\n      has_default_value=False, default_value=None,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='gradient_clipping_by_norm', full_name='object_detection.protos.TrainConfig.gradient_clipping_by_norm', index=5,\n      number=6, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='fine_tune_checkpoint', full_name='object_detection.protos.TrainConfig.fine_tune_checkpoint', index=6,\n      number=7, type=9, cpp_type=9, label=1,\n      has_default_value=True, default_value=_b(\"\").decode('utf-8'),\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='from_detection_checkpoint', full_name='object_detection.protos.TrainConfig.from_detection_checkpoint', index=7,\n      number=8, type=8, cpp_type=7, label=1,\n      has_default_value=True, default_value=False,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='num_steps', full_name='object_detection.protos.TrainConfig.num_steps', index=8,\n      number=9, type=13, cpp_type=3, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='startup_delay_steps', full_name='object_detection.protos.TrainConfig.startup_delay_steps', index=9,\n      number=10, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=15,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='bias_grad_multiplier', full_name='object_detection.protos.TrainConfig.bias_grad_multiplier', index=10,\n      number=11, type=2, cpp_type=6, label=1,\n      has_default_value=True, default_value=0,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='freeze_variables', full_name='object_detection.protos.TrainConfig.freeze_variables', index=11,\n      number=12, type=9, cpp_type=9, label=3,\n      has_default_value=False, default_value=[],\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='replicas_to_aggregate', full_name='object_detection.protos.TrainConfig.replicas_to_aggregate', index=12,\n      number=13, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=1,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='batch_queue_capacity', full_name='object_detection.protos.TrainConfig.batch_queue_capacity', index=13,\n      number=14, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=600,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='num_batch_queue_threads', full_name='object_detection.protos.TrainConfig.num_batch_queue_threads', index=14,\n      number=15, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=8,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n    _descriptor.FieldDescriptor(\n      name='prefetch_queue_capacity', full_name='object_detection.protos.TrainConfig.prefetch_queue_capacity', index=15,\n      number=16, type=5, cpp_type=1, label=1,\n      has_default_value=True, default_value=10,\n      message_type=None, enum_type=None, containing_type=None,\n      is_extension=False, extension_scope=None,\n      options=None),\n  ],\n  extensions=[\n  ],\n  nested_types=[],\n  enum_types=[\n  ],\n  options=None,\n  is_extendable=False,\n  extension_ranges=[],\n  oneofs=[\n  ],\n  serialized_start=150,\n  serialized_end=764,\n)\n\n_TRAINCONFIG.fields_by_name['data_augmentation_options'].message_type = object_detection.protos.preprocessor_pb2._PREPROCESSINGSTEP\n_TRAINCONFIG.fields_by_name['optimizer'].message_type = object_detection.protos.optimizer_pb2._OPTIMIZER\nDESCRIPTOR.message_types_by_name['TrainConfig'] = _TRAINCONFIG\n\nTrainConfig = _reflection.GeneratedProtocolMessageType('TrainConfig', (_message.Message,), dict(\n  DESCRIPTOR = _TRAINCONFIG,\n  __module__ = 'object_detection.protos.train_pb2'\n  # @@protoc_insertion_point(class_scope:object_detection.protos.TrainConfig)\n  ))\n_sym_db.RegisterMessage(TrainConfig)\n\n\n# @@protoc_insertion_point(module_scope)\n"
  },
  {
    "path": "object_detector_app/object_detection/samples/cloud/cloud.yml",
    "content": "trainingInput:\n  runtimeVersion: \"1.0\"\n  scaleTier: CUSTOM\n  masterType: standard_gpu\n  workerCount: 5\n  workerType: standard_gpu\n  parameterServerCount: 3\n  parameterServerType: standard\n\n\n\n"
  },
  {
    "path": "object_detector_app/object_detection/samples/configs/faster_rcnn_inception_resnet_v2_atrous_pets.config",
    "content": "# Faster R-CNN with Inception Resnet v2, Atrous version;\n# Configured for Oxford-IIT Pets Dataset.\n# Users should configure the fine_tune_checkpoint field in the train config as\n# well as the label_map_path and input_path fields in the train_input_reader and\n# eval_input_reader. Search for \"PATH_TO_BE_CONFIGURED\" to find the fields that\n# should be configured.\n\nmodel {\n  faster_rcnn {\n    num_classes: 37\n    image_resizer {\n      keep_aspect_ratio_resizer {\n        min_dimension: 600\n        max_dimension: 1024\n      }\n    }\n    feature_extractor {\n      type: 'faster_rcnn_inception_resnet_v2'\n      first_stage_features_stride: 8\n    }\n    first_stage_anchor_generator {\n      grid_anchor_generator {\n        scales: [0.25, 0.5, 1.0, 2.0]\n        aspect_ratios: [0.5, 1.0, 2.0]\n        height_stride: 8\n        width_stride: 8\n      }\n    }\n    first_stage_atrous_rate: 2\n    first_stage_box_predictor_conv_hyperparams {\n      op: CONV\n      regularizer {\n        l2_regularizer {\n          weight: 0.0\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n          stddev: 0.01\n        }\n      }\n    }\n    first_stage_nms_score_threshold: 0.0\n    first_stage_nms_iou_threshold: 0.7\n    first_stage_max_proposals: 300\n    first_stage_localization_loss_weight: 2.0\n    first_stage_objectness_loss_weight: 1.0\n    initial_crop_size: 17\n    maxpool_kernel_size: 1\n    maxpool_stride: 1\n    second_stage_box_predictor {\n      mask_rcnn_box_predictor {\n        use_dropout: false\n        dropout_keep_probability: 1.0\n        fc_hyperparams {\n          op: FC\n          regularizer {\n            l2_regularizer {\n              weight: 0.0\n            }\n          }\n          initializer {\n            variance_scaling_initializer {\n              factor: 1.0\n              uniform: true\n              mode: FAN_AVG\n            }\n          }\n        }\n      }\n    }\n    second_stage_post_processing {\n      batch_non_max_suppression {\n        score_threshold: 0.0\n        iou_threshold: 0.6\n        max_detections_per_class: 100\n        max_total_detections: 100\n      }\n      score_converter: SOFTMAX\n    }\n    second_stage_localization_loss_weight: 2.0\n    second_stage_classification_loss_weight: 1.0\n  }\n}\n\ntrain_config: {\n  batch_size: 1\n  optimizer {\n    momentum_optimizer: {\n      learning_rate: {\n        manual_step_learning_rate {\n          initial_learning_rate: 0.0003\n          schedule {\n            step: 0\n            learning_rate: .0003\n          }\n          schedule {\n            step: 900000\n            learning_rate: .00003\n          }\n          schedule {\n            step: 1200000\n            learning_rate: .000003\n          }\n        }\n      }\n      momentum_optimizer_value: 0.9\n    }\n    use_moving_average: false\n  }\n  gradient_clipping_by_norm: 10.0\n  fine_tune_checkpoint: \"PATH_TO_BE_CONFIGURED/model.ckpt\"\n  from_detection_checkpoint: true\n  data_augmentation_options {\n    random_horizontal_flip {\n    }\n  }\n}\n\ntrain_input_reader: {\n  tf_record_input_reader {\n    input_path: \"PATH_TO_BE_CONFIGURED/pet_train.record\"\n  }\n  label_map_path: \"PATH_TO_BE_CONFIGURED/pet_label_map.pbtxt\"\n}\n\neval_config: {\n  num_examples: 2000\n}\n\neval_input_reader: {\n  tf_record_input_reader {\n    input_path: \"PATH_TO_BE_CONFIGURED/pet_val.record\"\n  }\n  label_map_path: \"PATH_TO_BE_CONFIGURED/pet_label_map.pbtxt\"\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/samples/configs/faster_rcnn_resnet101_pets.config",
    "content": "# Faster R-CNN with Resnet-101 (v1) configured for the Oxford-IIT Pet Dataset.\n# Users should configure the fine_tune_checkpoint field in the train config as\n# well as the label_map_path and input_path fields in the train_input_reader and\n# eval_input_reader. Search for \"PATH_TO_BE_CONFIGURED\" to find the fields that\n# should be configured.\n\nmodel {\n  faster_rcnn {\n    num_classes: 37\n    image_resizer {\n      keep_aspect_ratio_resizer {\n        min_dimension: 600\n        max_dimension: 1024\n      }\n    }\n    feature_extractor {\n      type: 'faster_rcnn_resnet101'\n      first_stage_features_stride: 16\n    }\n    first_stage_anchor_generator {\n      grid_anchor_generator {\n        scales: [0.25, 0.5, 1.0, 2.0]\n        aspect_ratios: [0.5, 1.0, 2.0]\n        height_stride: 16\n        width_stride: 16\n      }\n    }\n    first_stage_box_predictor_conv_hyperparams {\n      op: CONV\n      regularizer {\n        l2_regularizer {\n          weight: 0.0\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n          stddev: 0.01\n        }\n      }\n    }\n    first_stage_nms_score_threshold: 0.0\n    first_stage_nms_iou_threshold: 0.7\n    first_stage_max_proposals: 300\n    first_stage_localization_loss_weight: 2.0\n    first_stage_objectness_loss_weight: 1.0\n    initial_crop_size: 14\n    maxpool_kernel_size: 2\n    maxpool_stride: 2\n    second_stage_box_predictor {\n      mask_rcnn_box_predictor {\n        use_dropout: false\n        dropout_keep_probability: 1.0\n        fc_hyperparams {\n          op: FC\n          regularizer {\n            l2_regularizer {\n              weight: 0.0\n            }\n          }\n          initializer {\n            variance_scaling_initializer {\n              factor: 1.0\n              uniform: true\n              mode: FAN_AVG\n            }\n          }\n        }\n      }\n    }\n    second_stage_post_processing {\n      batch_non_max_suppression {\n        score_threshold: 0.0\n        iou_threshold: 0.6\n        max_detections_per_class: 100\n        max_total_detections: 300\n      }\n      score_converter: SOFTMAX\n    }\n    second_stage_localization_loss_weight: 2.0\n    second_stage_classification_loss_weight: 1.0\n  }\n}\n\ntrain_config: {\n  batch_size: 1\n  optimizer {\n    momentum_optimizer: {\n      learning_rate: {\n        manual_step_learning_rate {\n          initial_learning_rate: 0.0003\n          schedule {\n            step: 0\n            learning_rate: .0003\n          }\n          schedule {\n            step: 900000\n            learning_rate: .00003\n          }\n          schedule {\n            step: 1200000\n            learning_rate: .000003\n          }\n        }\n      }\n      momentum_optimizer_value: 0.9\n    }\n    use_moving_average: false\n  }\n  gradient_clipping_by_norm: 10.0\n  fine_tune_checkpoint: \"PATH_TO_BE_CONFIGURED/model.ckpt\"\n  from_detection_checkpoint: true\n  data_augmentation_options {\n    random_horizontal_flip {\n    }\n  }\n}\n\ntrain_input_reader: {\n  tf_record_input_reader {\n    input_path: \"PATH_TO_BE_CONFIGURED/pet_train.record\"\n  }\n  label_map_path: \"PATH_TO_BE_CONFIGURED/pet_label_map.pbtxt\"\n}\n\neval_config: {\n  num_examples: 2000\n}\n\neval_input_reader: {\n  tf_record_input_reader {\n    input_path: \"PATH_TO_BE_CONFIGURED/pet_val.record\"\n  }\n  label_map_path: \"PATH_TO_BE_CONFIGURED/pet_label_map.pbtxt\"\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/samples/configs/faster_rcnn_resnet101_voc07.config",
    "content": "# Faster R-CNN with Resnet-101 (v1), configured for Pascal VOC Dataset.\n# Users should configure the fine_tune_checkpoint field in the train config as\n# well as the label_map_path and input_path fields in the train_input_reader and\n# eval_input_reader. Search for \"PATH_TO_BE_CONFIGURED\" to find the fields that\n# should be configured.\n\nmodel {\n  faster_rcnn {\n    num_classes: 20\n    image_resizer {\n      keep_aspect_ratio_resizer {\n        min_dimension: 600\n        max_dimension: 1024\n      }\n    }\n    feature_extractor {\n      type: 'faster_rcnn_resnet101'\n      first_stage_features_stride: 16\n    }\n    first_stage_anchor_generator {\n      grid_anchor_generator {\n        scales: [0.25, 0.5, 1.0, 2.0]\n        aspect_ratios: [0.5, 1.0, 2.0]\n        height_stride: 16\n        width_stride: 16\n      }\n    }\n    first_stage_box_predictor_conv_hyperparams {\n      op: CONV\n      regularizer {\n        l2_regularizer {\n          weight: 0.0\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n          stddev: 0.01\n        }\n      }\n    }\n    first_stage_nms_score_threshold: 0.0\n    first_stage_nms_iou_threshold: 0.7\n    first_stage_max_proposals: 300\n    first_stage_localization_loss_weight: 2.0\n    first_stage_objectness_loss_weight: 1.0\n    initial_crop_size: 14\n    maxpool_kernel_size: 2\n    maxpool_stride: 2\n    second_stage_box_predictor {\n      mask_rcnn_box_predictor {\n        use_dropout: false\n        dropout_keep_probability: 1.0\n        fc_hyperparams {\n          op: FC\n          regularizer {\n            l2_regularizer {\n              weight: 0.0\n            }\n          }\n          initializer {\n            variance_scaling_initializer {\n              factor: 1.0\n              uniform: true\n              mode: FAN_AVG\n            }\n          }\n        }\n      }\n    }\n    second_stage_post_processing {\n      batch_non_max_suppression {\n        score_threshold: 0.0\n        iou_threshold: 0.6\n        max_detections_per_class: 100\n        max_total_detections: 300\n      }\n      score_converter: SOFTMAX\n    }\n    second_stage_localization_loss_weight: 2.0\n    second_stage_classification_loss_weight: 1.0\n  }\n}\n\ntrain_config: {\n  batch_size: 1\n  optimizer {\n    momentum_optimizer: {\n      learning_rate: {\n        manual_step_learning_rate {\n          initial_learning_rate: 0.0001\n          schedule {\n            step: 0\n            learning_rate: .0001\n          }\n          schedule {\n            step: 500000\n            learning_rate: .00001\n          }\n          schedule {\n            step: 700000\n            learning_rate: .000001\n          }\n        }\n      }\n      momentum_optimizer_value: 0.9\n    }\n    use_moving_average: false\n  }\n  gradient_clipping_by_norm: 10.0\n  fine_tune_checkpoint: \"PATH_TO_BE_CONFIGURED/model.ckpt\"\n  from_detection_checkpoint: true\n  num_steps: 800000\n  data_augmentation_options {\n    random_horizontal_flip {\n    }\n  }\n}\n\ntrain_input_reader: {\n  tf_record_input_reader {\n    input_path: \"PATH_TO_BE_CONFIGURED/pascal_voc_train.record\"\n  }\n  label_map_path: \"PATH_TO_BE_CONFIGURED/pascal_voc_label_map.pbtxt\"\n}\n\neval_config: {\n  num_examples: 4952\n}\n\neval_input_reader: {\n  tf_record_input_reader {\n    input_path: \"PATH_TO_BE_CONFIGURED/pascal_voc_val.record\"\n  }\n  label_map_path: \"PATH_TO_BE_CONFIGURED/pascal_voc_label_map.pbtxt\"\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/samples/configs/faster_rcnn_resnet152_pets.config",
    "content": "# Faster R-CNN with Resnet-152 (v1), configured for Oxford-IIT Pets Dataset.\n# Users should configure the fine_tune_checkpoint field in the train config as\n# well as the label_map_path and input_path fields in the train_input_reader and\n# eval_input_reader. Search for \"PATH_TO_BE_CONFIGURED\" to find the fields that\n# should be configured.\n\nmodel {\n  faster_rcnn {\n    num_classes: 37\n    image_resizer {\n      keep_aspect_ratio_resizer {\n        min_dimension: 600\n        max_dimension: 1024\n      }\n    }\n    feature_extractor {\n      type: 'faster_rcnn_resnet152'\n      first_stage_features_stride: 16\n    }\n    first_stage_anchor_generator {\n      grid_anchor_generator {\n        scales: [0.25, 0.5, 1.0, 2.0]\n        aspect_ratios: [0.5, 1.0, 2.0]\n        height_stride: 16\n        width_stride: 16\n      }\n    }\n    first_stage_box_predictor_conv_hyperparams {\n      op: CONV\n      regularizer {\n        l2_regularizer {\n          weight: 0.0\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n          stddev: 0.01\n        }\n      }\n    }\n    first_stage_nms_score_threshold: 0.0\n    first_stage_nms_iou_threshold: 0.7\n    first_stage_max_proposals: 300\n    first_stage_localization_loss_weight: 2.0\n    first_stage_objectness_loss_weight: 1.0\n    initial_crop_size: 14\n    maxpool_kernel_size: 2\n    maxpool_stride: 2\n    second_stage_box_predictor {\n      mask_rcnn_box_predictor {\n        use_dropout: false\n        dropout_keep_probability: 1.0\n        fc_hyperparams {\n          op: FC\n          regularizer {\n            l2_regularizer {\n              weight: 0.0\n            }\n          }\n          initializer {\n            variance_scaling_initializer {\n              factor: 1.0\n              uniform: true\n              mode: FAN_AVG\n            }\n          }\n        }\n      }\n    }\n    second_stage_post_processing {\n      batch_non_max_suppression {\n        score_threshold: 0.0\n        iou_threshold: 0.6\n        max_detections_per_class: 100\n        max_total_detections: 300\n      }\n      score_converter: SOFTMAX\n    }\n    second_stage_localization_loss_weight: 2.0\n    second_stage_classification_loss_weight: 1.0\n  }\n}\n\ntrain_config: {\n  batch_size: 1\n  optimizer {\n    momentum_optimizer: {\n      learning_rate: {\n        manual_step_learning_rate {\n          initial_learning_rate: 0.0003\n          schedule {\n            step: 0\n            learning_rate: .0003\n          }\n          schedule {\n            step: 900000\n            learning_rate: .00003\n          }\n          schedule {\n            step: 1200000\n            learning_rate: .000003\n          }\n        }\n      }\n      momentum_optimizer_value: 0.9\n    }\n    use_moving_average: false\n  }\n  gradient_clipping_by_norm: 10.0\n  fine_tune_checkpoint: \"PATH_TO_BE_CONFIGURED/model.ckpt\"\n  from_detection_checkpoint: true\n  data_augmentation_options {\n    random_horizontal_flip {\n    }\n  }\n}\n\ntrain_input_reader: {\n  tf_record_input_reader {\n    input_path: \"PATH_TO_BE_CONFIGURED/pet_train.record\"\n  }\n  label_map_path: \"PATH_TO_BE_CONFIGURED/pet_label_map.pbtxt\"\n}\n\neval_config: {\n  num_examples: 2000\n}\n\neval_input_reader: {\n  tf_record_input_reader {\n    input_path: \"PATH_TO_BE_CONFIGURED/pet_val.record\"\n  }\n  label_map_path: \"PATH_TO_BE_CONFIGURED/pet_label_map.pbtxt\"\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/samples/configs/faster_rcnn_resnet50_pets.config",
    "content": "# Faster R-CNN with Resnet-50 (v1), configured for Oxford-IIT Pets Dataset.\n# Users should configure the fine_tune_checkpoint field in the train config as\n# well as the label_map_path and input_path fields in the train_input_reader and\n# eval_input_reader. Search for \"PATH_TO_BE_CONFIGURED\" to find the fields that\n# should be configured.\n\nmodel {\n  faster_rcnn {\n    num_classes: 37\n    image_resizer {\n      keep_aspect_ratio_resizer {\n        min_dimension: 600\n        max_dimension: 1024\n      }\n    }\n    feature_extractor {\n      type: 'faster_rcnn_resnet50'\n      first_stage_features_stride: 16\n    }\n    first_stage_anchor_generator {\n      grid_anchor_generator {\n        scales: [0.25, 0.5, 1.0, 2.0]\n        aspect_ratios: [0.5, 1.0, 2.0]\n        height_stride: 16\n        width_stride: 16\n      }\n    }\n    first_stage_box_predictor_conv_hyperparams {\n      op: CONV\n      regularizer {\n        l2_regularizer {\n          weight: 0.0\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n          stddev: 0.01\n        }\n      }\n    }\n    first_stage_nms_score_threshold: 0.0\n    first_stage_nms_iou_threshold: 0.7\n    first_stage_max_proposals: 300\n    first_stage_localization_loss_weight: 2.0\n    first_stage_objectness_loss_weight: 1.0\n    initial_crop_size: 14\n    maxpool_kernel_size: 2\n    maxpool_stride: 2\n    second_stage_box_predictor {\n      mask_rcnn_box_predictor {\n        use_dropout: false\n        dropout_keep_probability: 1.0\n        fc_hyperparams {\n          op: FC\n          regularizer {\n            l2_regularizer {\n              weight: 0.0\n            }\n          }\n          initializer {\n            variance_scaling_initializer {\n              factor: 1.0\n              uniform: true\n              mode: FAN_AVG\n            }\n          }\n        }\n      }\n    }\n    second_stage_post_processing {\n      batch_non_max_suppression {\n        score_threshold: 0.0\n        iou_threshold: 0.6\n        max_detections_per_class: 100\n        max_total_detections: 300\n      }\n      score_converter: SOFTMAX\n    }\n    second_stage_localization_loss_weight: 2.0\n    second_stage_classification_loss_weight: 1.0\n  }\n}\n\ntrain_config: {\n  batch_size: 1\n  optimizer {\n    momentum_optimizer: {\n      learning_rate: {\n        manual_step_learning_rate {\n          initial_learning_rate: 0.0003\n          schedule {\n            step: 0\n            learning_rate: .0003\n          }\n          schedule {\n            step: 900000\n            learning_rate: .00003\n          }\n          schedule {\n            step: 1200000\n            learning_rate: .000003\n          }\n        }\n      }\n      momentum_optimizer_value: 0.9\n    }\n    use_moving_average: false\n  }\n  gradient_clipping_by_norm: 10.0\n  fine_tune_checkpoint: \"PATH_TO_BE_CONFIGURED/model.ckpt\"\n  from_detection_checkpoint: true\n  data_augmentation_options {\n    random_horizontal_flip {\n    }\n  }\n}\n\ntrain_input_reader: {\n  tf_record_input_reader {\n    input_path: \"PATH_TO_BE_CONFIGURED/pet_train.record\"\n  }\n  label_map_path: \"PATH_TO_BE_CONFIGURED/pet_label_map.pbtxt\"\n}\n\neval_config: {\n  num_examples: 2000\n}\n\neval_input_reader: {\n  tf_record_input_reader {\n    input_path: \"PATH_TO_BE_CONFIGURED/pet_val.record\"\n  }\n  label_map_path: \"PATH_TO_BE_CONFIGURED/pet_label_map.pbtxt\"\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/samples/configs/rfcn_resnet101_pets.config",
    "content": "# R-FCN with Resnet-101 (v1),  configured for Oxford-IIT Pets Dataset.\n# Users should configure the fine_tune_checkpoint field in the train config as\n# well as the label_map_path and input_path fields in the train_input_reader and\n# eval_input_reader. Search for \"PATH_TO_BE_CONFIGURED\" to find the fields that\n# should be configured.\n\nmodel {\n  faster_rcnn {\n    num_classes: 37\n    image_resizer {\n      keep_aspect_ratio_resizer {\n        min_dimension: 600\n        max_dimension: 1024\n      }\n    }\n    feature_extractor {\n      type: 'faster_rcnn_resnet101'\n      first_stage_features_stride: 16\n    }\n    first_stage_anchor_generator {\n      grid_anchor_generator {\n        scales: [0.25, 0.5, 1.0, 2.0]\n        aspect_ratios: [0.5, 1.0, 2.0]\n        height_stride: 16\n        width_stride: 16\n      }\n    }\n    first_stage_box_predictor_conv_hyperparams {\n      op: CONV\n      regularizer {\n        l2_regularizer {\n          weight: 0.0\n        }\n      }\n      initializer {\n        truncated_normal_initializer {\n          stddev: 0.01\n        }\n      }\n    }\n    first_stage_nms_score_threshold: 0.0\n    first_stage_nms_iou_threshold: 0.7\n    first_stage_max_proposals: 300\n    first_stage_localization_loss_weight: 2.0\n    first_stage_objectness_loss_weight: 1.0\n    second_stage_box_predictor {\n      rfcn_box_predictor {\n        conv_hyperparams {\n          op: CONV\n          regularizer {\n            l2_regularizer {\n              weight: 0.0\n            }\n          }\n          initializer {\n            truncated_normal_initializer {\n              stddev: 0.01\n            }\n          }\n        }\n        crop_height: 18\n        crop_width: 18\n        num_spatial_bins_height: 3\n        num_spatial_bins_width: 3\n      }\n    }\n    second_stage_post_processing {\n      batch_non_max_suppression {\n        score_threshold: 0.0\n        iou_threshold: 0.6\n        max_detections_per_class: 100\n        max_total_detections: 300\n      }\n      score_converter: SOFTMAX\n    }\n    second_stage_localization_loss_weight: 2.0\n    second_stage_classification_loss_weight: 1.0\n  }\n}\n\ntrain_config: {\n  batch_size: 1\n  optimizer {\n    momentum_optimizer: {\n      learning_rate: {\n        manual_step_learning_rate {\n          initial_learning_rate: 0.0003\n          schedule {\n            step: 0\n            learning_rate: .0003\n          }\n          schedule {\n            step: 900000\n            learning_rate: .00003\n          }\n          schedule {\n            step: 1200000\n            learning_rate: .000003\n          }\n        }\n      }\n      momentum_optimizer_value: 0.9\n    }\n    use_moving_average: false\n  }\n  gradient_clipping_by_norm: 10.0\n  fine_tune_checkpoint: \"PATH_TO_BE_CONFIGURED/model.ckpt\"\n  from_detection_checkpoint: true\n  data_augmentation_options {\n    random_horizontal_flip {\n    }\n  }\n}\n\ntrain_input_reader: {\n  tf_record_input_reader {\n    input_path: \"PATH_TO_BE_CONFIGURED/pet_train.record\"\n  }\n  label_map_path: \"PATH_TO_BE_CONFIGURED/pet_label_map.pbtxt\"\n}\n\neval_config: {\n  num_examples: 2000\n}\n\neval_input_reader: {\n  tf_record_input_reader {\n    input_path: \"PATH_TO_BE_CONFIGURED/pet_val.record\"\n  }\n  label_map_path: \"PATH_TO_BE_CONFIGURED/pet_label_map.pbtxt\"\n}"
  },
  {
    "path": "object_detector_app/object_detection/samples/configs/ssd_inception_v2_pets.config",
    "content": "# SSD with Inception v2 configured for Oxford-IIT Pets Dataset.\n# Users should configure the fine_tune_checkpoint field in the train config as\n# well as the label_map_path and input_path fields in the train_input_reader and\n# eval_input_reader. Search for \"PATH_TO_BE_CONFIGURED\" to find the fields that\n# should be configured.\n\nmodel {\n  ssd {\n    num_classes: 37\n    box_coder {\n      faster_rcnn_box_coder {\n        y_scale: 10.0\n        x_scale: 10.0\n        height_scale: 5.0\n        width_scale: 5.0\n      }\n    }\n    matcher {\n      argmax_matcher {\n        matched_threshold: 0.5\n        unmatched_threshold: 0.5\n        ignore_thresholds: false\n        negatives_lower_than_unmatched: true\n        force_match_for_each_row: true\n      }\n    }\n    similarity_calculator {\n      iou_similarity {\n      }\n    }\n    anchor_generator {\n      ssd_anchor_generator {\n        num_layers: 6\n        min_scale: 0.2\n        max_scale: 0.95\n        aspect_ratios: 1.0\n        aspect_ratios: 2.0\n        aspect_ratios: 0.5\n        aspect_ratios: 3.0\n        aspect_ratios: 0.3333\n        reduce_boxes_in_lowest_layer: true\n      }\n    }\n    image_resizer {\n      fixed_shape_resizer {\n        height: 300\n        width: 300\n      }\n    }\n    box_predictor {\n      convolutional_box_predictor {\n        min_depth: 0\n        max_depth: 0\n        num_layers_before_predictor: 0\n        use_dropout: false\n        dropout_keep_probability: 0.8\n        kernel_size: 3\n        box_code_size: 4\n        apply_sigmoid_to_scores: false\n        conv_hyperparams {\n          activation: RELU_6,\n          regularizer {\n            l2_regularizer {\n              weight: 0.00004\n            }\n          }\n          initializer {\n            truncated_normal_initializer {\n              stddev: 0.03\n              mean: 0.0\n            }\n          }\n        }\n      }\n    }\n    feature_extractor {\n      type: 'ssd_inception_v2'\n      min_depth: 16\n      depth_multiplier: 1.0\n      conv_hyperparams {\n        activation: RELU_6,\n        regularizer {\n          l2_regularizer {\n            weight: 0.00004\n          }\n        }\n        initializer {\n          truncated_normal_initializer {\n            stddev: 0.03\n            mean: 0.0\n          }\n        }\n        batch_norm {\n          train: true,\n          scale: true,\n          center: true,\n          decay: 0.9997,\n          epsilon: 0.001,\n        }\n      }\n    }\n    loss {\n      classification_loss {\n        weighted_sigmoid {\n          anchorwise_output: true\n        }\n      }\n      localization_loss {\n        weighted_smooth_l1 {\n          anchorwise_output: true\n        }\n      }\n      hard_example_miner {\n        num_hard_examples: 3000\n        iou_threshold: 0.99\n        loss_type: CLASSIFICATION\n        max_negatives_per_positive: 3\n        min_negatives_per_image: 0\n      }\n      classification_weight: 1.0\n      localization_weight: 1.0\n    }\n    normalize_loss_by_num_matches: true\n    post_processing {\n      batch_non_max_suppression {\n        score_threshold: 1e-8\n        iou_threshold: 0.6\n        max_detections_per_class: 100\n        max_total_detections: 100\n      }\n      score_converter: SIGMOID\n    }\n  }\n}\n\ntrain_config: {\n  batch_size: 24\n  optimizer {\n    rms_prop_optimizer: {\n      learning_rate: {\n        exponential_decay_learning_rate {\n          initial_learning_rate: 0.004\n          decay_steps: 800720\n          decay_factor: 0.95\n        }\n      }\n      momentum_optimizer_value: 0.9\n      decay: 0.9\n      epsilon: 1.0\n    }\n  }\n  fine_tune_checkpoint: \"PATH_TO_BE_CONFIGURED/model.ckpt\"\n  from_detection_checkpoint: true\n  data_augmentation_options {\n    random_horizontal_flip {\n    }\n  }\n  data_augmentation_options {\n    ssd_random_crop {\n    }\n  }\n}\n\ntrain_input_reader: {\n  tf_record_input_reader {\n    input_path: \"PATH_TO_BE_CONFIGURED/pet_train.record\"\n  }\n  label_map_path: \"PATH_TO_BE_CONFIGURED/pet_label_map.pbtxt\"\n}\n\neval_config: {\n  num_examples: 2000\n}\n\neval_input_reader: {\n  tf_record_input_reader {\n    input_path: \"PATH_TO_BE_CONFIGURED/pet_val.record\"\n  }\n  label_map_path: \"PATH_TO_BE_CONFIGURED/pet_label_map.pbtxt\"\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/samples/configs/ssd_mobilenet_v1_pets.config",
    "content": "# SSD with Mobilenet v1, configured for Oxford-IIT Pets Dataset.\n# Users should configure the fine_tune_checkpoint field in the train config as\n# well as the label_map_path and input_path fields in the train_input_reader and\n# eval_input_reader. Search for \"PATH_TO_BE_CONFIGURED\" to find the fields that\n# should be configured.\n\nmodel {\n  ssd {\n    num_classes: 37\n    box_coder {\n      faster_rcnn_box_coder {\n        y_scale: 10.0\n        x_scale: 10.0\n        height_scale: 5.0\n        width_scale: 5.0\n      }\n    }\n    matcher {\n      argmax_matcher {\n        matched_threshold: 0.5\n        unmatched_threshold: 0.5\n        ignore_thresholds: false\n        negatives_lower_than_unmatched: true\n        force_match_for_each_row: true\n      }\n    }\n    similarity_calculator {\n      iou_similarity {\n      }\n    }\n    anchor_generator {\n      ssd_anchor_generator {\n        num_layers: 6\n        min_scale: 0.2\n        max_scale: 0.95\n        aspect_ratios: 1.0\n        aspect_ratios: 2.0\n        aspect_ratios: 0.5\n        aspect_ratios: 3.0\n        aspect_ratios: 0.3333\n      }\n    }\n    image_resizer {\n      fixed_shape_resizer {\n        height: 300\n        width: 300\n      }\n    }\n    box_predictor {\n      convolutional_box_predictor {\n        min_depth: 0\n        max_depth: 0\n        num_layers_before_predictor: 0\n        use_dropout: false\n        dropout_keep_probability: 0.8\n        kernel_size: 1\n        box_code_size: 4\n        apply_sigmoid_to_scores: false\n        conv_hyperparams {\n          activation: RELU_6,\n          regularizer {\n            l2_regularizer {\n              weight: 0.00004\n            }\n          }\n          initializer {\n            truncated_normal_initializer {\n              stddev: 0.03\n              mean: 0.0\n            }\n          }\n          batch_norm {\n            train: true,\n            scale: true,\n            center: true,\n            decay: 0.9997,\n            epsilon: 0.001,\n          }\n        }\n      }\n    }\n    feature_extractor {\n      type: 'ssd_mobilenet_v1'\n      min_depth: 16\n      depth_multiplier: 1.0\n      conv_hyperparams {\n        activation: RELU_6,\n        regularizer {\n          l2_regularizer {\n            weight: 0.00004\n          }\n        }\n        initializer {\n          truncated_normal_initializer {\n            stddev: 0.03\n            mean: 0.0\n          }\n        }\n        batch_norm {\n          train: true,\n          scale: true,\n          center: true,\n          decay: 0.9997,\n          epsilon: 0.001,\n        }\n      }\n    }\n    loss {\n      classification_loss {\n        weighted_sigmoid {\n          anchorwise_output: true\n        }\n      }\n      localization_loss {\n        weighted_smooth_l1 {\n          anchorwise_output: true\n        }\n      }\n      hard_example_miner {\n        num_hard_examples: 3000\n        iou_threshold: 0.99\n        loss_type: CLASSIFICATION\n        max_negatives_per_positive: 3\n        min_negatives_per_image: 0\n      }\n      classification_weight: 1.0\n      localization_weight: 1.0\n    }\n    normalize_loss_by_num_matches: true\n    post_processing {\n      batch_non_max_suppression {\n        score_threshold: 1e-8\n        iou_threshold: 0.6\n        max_detections_per_class: 100\n        max_total_detections: 100\n      }\n      score_converter: SIGMOID\n    }\n  }\n}\n\ntrain_config: {\n  batch_size: 24\n  optimizer {\n    rms_prop_optimizer: {\n      learning_rate: {\n        exponential_decay_learning_rate {\n          initial_learning_rate: 0.004\n          decay_steps: 800720\n          decay_factor: 0.95\n        }\n      }\n      momentum_optimizer_value: 0.9\n      decay: 0.9\n      epsilon: 1.0\n    }\n  }\n  fine_tune_checkpoint: \"PATH_TO_BE_CONFIGURED/model.ckpt\"\n  from_detection_checkpoint: true\n  data_augmentation_options {\n    random_horizontal_flip {\n    }\n  }\n  data_augmentation_options {\n    ssd_random_crop {\n    }\n  }\n}\n\ntrain_input_reader: {\n  tf_record_input_reader {\n    input_path: \"PATH_TO_BE_CONFIGURED/pet_train.record\"\n  }\n  label_map_path: \"PATH_TO_BE_CONFIGURED/pet_label_map.pbtxt\"\n}\n\neval_config: {\n  num_examples: 2000\n}\n\neval_input_reader: {\n  tf_record_input_reader {\n    input_path: \"PATH_TO_BE_CONFIGURED/pet_val.record\"\n  }\n  label_map_path: \"PATH_TO_BE_CONFIGURED/pet_label_map.pbtxt\"\n}\n"
  },
  {
    "path": "object_detector_app/object_detection/test_images/image_info.txt",
    "content": "\nImage provenance:\nimage1.jpg: https://commons.wikimedia.org/wiki/File:Baegle_dwa.jpg\nimage2.jpg: Michael Miley,\n  https://www.flickr.com/photos/mike_miley/4678754542/in/photolist-88rQHL-88oBVp-88oC2B-88rS6J-88rSqm-88oBLv-88oBC4\n\n"
  },
  {
    "path": "object_detector_app/object_detection/train.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\nr\"\"\"Training executable for detection models.\n\nThis executable is used to train DetectionModels. There are two ways of\nconfiguring the training job:\n\n1) A single pipeline_pb2.TrainEvalPipelineConfig configuration file\ncan be specified by --pipeline_config_path.\n\nExample usage:\n    ./train \\\n        --logtostderr \\\n        --train_dir=path/to/train_dir \\\n        --pipeline_config_path=pipeline_config.pbtxt\n\n2) Three configuration files can be provided: a model_pb2.DetectionModel\nconfiguration file to define what type of DetectionModel is being trained, an\ninput_reader_pb2.InputReader file to specify what training data will be used and\na train_pb2.TrainConfig file to configure training parameters.\n\nExample usage:\n    ./train \\\n        --logtostderr \\\n        --train_dir=path/to/train_dir \\\n        --model_config_path=model_config.pbtxt \\\n        --train_config_path=train_config.pbtxt \\\n        --input_config_path=train_input_config.pbtxt\n\"\"\"\n\nimport functools\nimport json\nimport os\nimport tensorflow as tf\n\nfrom google.protobuf import text_format\n\nfrom object_detection import trainer\nfrom object_detection.builders import input_reader_builder\nfrom object_detection.builders import model_builder\nfrom object_detection.protos import input_reader_pb2\nfrom object_detection.protos import model_pb2\nfrom object_detection.protos import pipeline_pb2\nfrom object_detection.protos import train_pb2\n\ntf.logging.set_verbosity(tf.logging.INFO)\n\nflags = tf.app.flags\nflags.DEFINE_string('master', '', 'BNS name of the TensorFlow master to use.')\nflags.DEFINE_integer('task', 0, 'task id')\nflags.DEFINE_integer('num_clones', 1, 'Number of clones to deploy per worker.')\nflags.DEFINE_boolean('clone_on_cpu', False,\n                     'Force clones to be deployed on CPU.  Note that even if '\n                     'set to False (allowing ops to run on gpu), some ops may '\n                     'still be run on the CPU if they have no GPU kernel.')\nflags.DEFINE_integer('worker_replicas', 1, 'Number of worker+trainer '\n                     'replicas.')\nflags.DEFINE_integer('ps_tasks', 0,\n                     'Number of parameter server tasks. If None, does not use '\n                     'a parameter server.')\nflags.DEFINE_string('train_dir', '',\n                    'Directory to save the checkpoints and training summaries.')\n\nflags.DEFINE_string('pipeline_config_path', '',\n                    'Path to a pipeline_pb2.TrainEvalPipelineConfig config '\n                    'file. If provided, other configs are ignored')\n\nflags.DEFINE_string('train_config_path', '',\n                    'Path to a train_pb2.TrainConfig config file.')\nflags.DEFINE_string('input_config_path', '',\n                    'Path to an input_reader_pb2.InputReader config file.')\nflags.DEFINE_string('model_config_path', '',\n                    'Path to a model_pb2.DetectionModel config file.')\n\nFLAGS = flags.FLAGS\n\n\ndef get_configs_from_pipeline_file():\n  \"\"\"Reads training configuration from a pipeline_pb2.TrainEvalPipelineConfig.\n\n  Reads training config from file specified by pipeline_config_path flag.\n\n  Returns:\n    model_config: model_pb2.DetectionModel\n    train_config: train_pb2.TrainConfig\n    input_config: input_reader_pb2.InputReader\n  \"\"\"\n  pipeline_config = pipeline_pb2.TrainEvalPipelineConfig()\n  with tf.gfile.GFile(FLAGS.pipeline_config_path, 'r') as f:\n    text_format.Merge(f.read(), pipeline_config)\n\n  model_config = pipeline_config.model\n  train_config = pipeline_config.train_config\n  input_config = pipeline_config.train_input_reader\n\n  return model_config, train_config, input_config\n\n\ndef get_configs_from_multiple_files():\n  \"\"\"Reads training configuration from multiple config files.\n\n  Reads the training config from the following files:\n    model_config: Read from --model_config_path\n    train_config: Read from --train_config_path\n    input_config: Read from --input_config_path\n\n  Returns:\n    model_config: model_pb2.DetectionModel\n    train_config: train_pb2.TrainConfig\n    input_config: input_reader_pb2.InputReader\n  \"\"\"\n  train_config = train_pb2.TrainConfig()\n  with tf.gfile.GFile(FLAGS.train_config_path, 'r') as f:\n    text_format.Merge(f.read(), train_config)\n\n  model_config = model_pb2.DetectionModel()\n  with tf.gfile.GFile(FLAGS.model_config_path, 'r') as f:\n    text_format.Merge(f.read(), model_config)\n\n  input_config = input_reader_pb2.InputReader()\n  with tf.gfile.GFile(FLAGS.input_config_path, 'r') as f:\n    text_format.Merge(f.read(), input_config)\n\n  return model_config, train_config, input_config\n\n\ndef main(_):\n  assert FLAGS.train_dir, '`train_dir` is missing.'\n  if FLAGS.pipeline_config_path:\n    model_config, train_config, input_config = get_configs_from_pipeline_file()\n  else:\n    model_config, train_config, input_config = get_configs_from_multiple_files()\n\n  model_fn = functools.partial(\n      model_builder.build,\n      model_config=model_config,\n      is_training=True)\n\n  create_input_dict_fn = functools.partial(\n      input_reader_builder.build, input_config)\n\n  env = json.loads(os.environ.get('TF_CONFIG', '{}'))\n  cluster_data = env.get('cluster', None)\n  cluster = tf.train.ClusterSpec(cluster_data) if cluster_data else None\n  task_data = env.get('task', None) or {'type': 'master', 'index': 0}\n  task_info = type('TaskSpec', (object,), task_data)\n\n  # Parameters for a single worker.\n  ps_tasks = 0\n  worker_replicas = 1\n  worker_job_name = 'lonely_worker'\n  task = 0\n  is_chief = True\n  master = ''\n\n  if cluster_data and 'worker' in cluster_data:\n    # Number of total worker replicas include \"worker\"s and the \"master\".\n    worker_replicas = len(cluster_data['worker']) + 1\n  if cluster_data and 'ps' in cluster_data:\n    ps_tasks = len(cluster_data['ps'])\n\n  if worker_replicas > 1 and ps_tasks < 1:\n    raise ValueError('At least 1 ps task is needed for distributed training.')\n\n  if worker_replicas >= 1 and ps_tasks > 0:\n    # Set up distributed training.\n    server = tf.train.Server(tf.train.ClusterSpec(cluster), protocol='grpc',\n                             job_name=task_info.type,\n                             task_index=task_info.index)\n    if task_info.type == 'ps':\n      server.join()\n      return\n\n    worker_job_name = '%s/task:%d' % (task_info.type, task_info.index)\n    task = task_info.index\n    is_chief = (task_info.type == 'master')\n    master = server.target\n\n  trainer.train(create_input_dict_fn, model_fn, train_config, master, task,\n                FLAGS.num_clones, worker_replicas, FLAGS.clone_on_cpu, ps_tasks,\n                worker_job_name, is_chief, FLAGS.train_dir)\n\n\nif __name__ == '__main__':\n  tf.app.run()\n"
  },
  {
    "path": "object_detector_app/object_detection/trainer.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Detection model trainer.\n\nThis file provides a generic training method that can be used to train a\nDetectionModel.\n\"\"\"\n\nimport functools\n\nimport tensorflow as tf\n\nfrom object_detection.builders import optimizer_builder\nfrom object_detection.builders import preprocessor_builder\nfrom object_detection.core import batcher\nfrom object_detection.core import preprocessor\nfrom object_detection.core import standard_fields as fields\nfrom object_detection.utils import ops as util_ops\nfrom object_detection.utils import variables_helper\nfrom deployment import model_deploy\n\nslim = tf.contrib.slim\n\n\ndef _create_input_queue(batch_size_per_clone, create_tensor_dict_fn,\n                        batch_queue_capacity, num_batch_queue_threads,\n                        prefetch_queue_capacity, data_augmentation_options):\n  \"\"\"Sets up reader, prefetcher and returns input queue.\n\n  Args:\n    batch_size_per_clone: batch size to use per clone.\n    create_tensor_dict_fn: function to create tensor dictionary.\n    batch_queue_capacity: maximum number of elements to store within a queue.\n    num_batch_queue_threads: number of threads to use for batching.\n    prefetch_queue_capacity: maximum capacity of the queue used to prefetch\n                             assembled batches.\n    data_augmentation_options: a list of tuples, where each tuple contains a\n      data augmentation function and a dictionary containing arguments and their\n      values (see preprocessor.py).\n\n  Returns:\n    input queue: a batcher.BatchQueue object holding enqueued tensor_dicts\n      (which hold images, boxes and targets).  To get a batch of tensor_dicts,\n      call input_queue.Dequeue().\n  \"\"\"\n  tensor_dict = create_tensor_dict_fn()\n\n  tensor_dict[fields.InputDataFields.image] = tf.expand_dims(\n      tensor_dict[fields.InputDataFields.image], 0)\n\n  images = tensor_dict[fields.InputDataFields.image]\n  float_images = tf.to_float(images)\n  tensor_dict[fields.InputDataFields.image] = float_images\n\n  if data_augmentation_options:\n    tensor_dict = preprocessor.preprocess(tensor_dict,\n                                          data_augmentation_options)\n\n  input_queue = batcher.BatchQueue(\n      tensor_dict,\n      batch_size=batch_size_per_clone,\n      batch_queue_capacity=batch_queue_capacity,\n      num_batch_queue_threads=num_batch_queue_threads,\n      prefetch_queue_capacity=prefetch_queue_capacity)\n  return input_queue\n\n\ndef _get_inputs(input_queue, num_classes):\n  \"\"\"Dequeue batch and construct inputs to object detection model.\n\n  Args:\n    input_queue: BatchQueue object holding enqueued tensor_dicts.\n    num_classes: Number of classes.\n\n  Returns:\n    images: a list of 3-D float tensor of images.\n    locations_list: a list of tensors of shape [num_boxes, 4]\n      containing the corners of the groundtruth boxes.\n    classes_list: a list of padded one-hot tensors containing target classes.\n    masks_list: a list of 3-D float tensors of shape [num_boxes, image_height,\n      image_width] containing instance masks for objects if present in the\n      input_queue. Else returns None.\n  \"\"\"\n  read_data_list = input_queue.dequeue()\n  label_id_offset = 1\n  def extract_images_and_targets(read_data):\n    image = read_data[fields.InputDataFields.image]\n    location_gt = read_data[fields.InputDataFields.groundtruth_boxes]\n    classes_gt = tf.cast(read_data[fields.InputDataFields.groundtruth_classes],\n                         tf.int32)\n    classes_gt -= label_id_offset\n    classes_gt = util_ops.padded_one_hot_encoding(indices=classes_gt,\n                                                  depth=num_classes, left_pad=0)\n    masks_gt = read_data.get(fields.InputDataFields.groundtruth_instance_masks)\n    return image, location_gt, classes_gt, masks_gt\n  return zip(*map(extract_images_and_targets, read_data_list))\n\n\ndef _create_losses(input_queue, create_model_fn):\n  \"\"\"Creates loss function for a DetectionModel.\n\n  Args:\n    input_queue: BatchQueue object holding enqueued tensor_dicts.\n    create_model_fn: A function to create the DetectionModel.\n  \"\"\"\n  detection_model = create_model_fn()\n  (images, groundtruth_boxes_list, groundtruth_classes_list,\n   groundtruth_masks_list\n  ) = _get_inputs(input_queue, detection_model.num_classes)\n  images = [detection_model.preprocess(image) for image in images]\n  images = tf.concat(images, 0)\n  if any(mask is None for mask in groundtruth_masks_list):\n    groundtruth_masks_list = None\n\n  detection_model.provide_groundtruth(groundtruth_boxes_list,\n                                      groundtruth_classes_list,\n                                      groundtruth_masks_list)\n  prediction_dict = detection_model.predict(images)\n\n  losses_dict = detection_model.loss(prediction_dict)\n  for loss_tensor in losses_dict.values():\n    tf.losses.add_loss(loss_tensor)\n\n\ndef train(create_tensor_dict_fn, create_model_fn, train_config, master, task,\n          num_clones, worker_replicas, clone_on_cpu, ps_tasks, worker_job_name,\n          is_chief, train_dir):\n  \"\"\"Training function for detection models.\n\n  Args:\n    create_tensor_dict_fn: a function to create a tensor input dictionary.\n    create_model_fn: a function that creates a DetectionModel and generates\n                     losses.\n    train_config: a train_pb2.TrainConfig protobuf.\n    master: BNS name of the TensorFlow master to use.\n    task: The task id of this training instance.\n    num_clones: The number of clones to run per machine.\n    worker_replicas: The number of work replicas to train with.\n    clone_on_cpu: True if clones should be forced to run on CPU.\n    ps_tasks: Number of parameter server tasks.\n    worker_job_name: Name of the worker job.\n    is_chief: Whether this replica is the chief replica.\n    train_dir: Directory to write checkpoints and training summaries to.\n  \"\"\"\n\n  detection_model = create_model_fn()\n  data_augmentation_options = [\n      preprocessor_builder.build(step)\n      for step in train_config.data_augmentation_options]\n\n  with tf.Graph().as_default():\n    # Build a configuration specifying multi-GPU and multi-replicas.\n    deploy_config = model_deploy.DeploymentConfig(\n        num_clones=num_clones,\n        clone_on_cpu=clone_on_cpu,\n        replica_id=task,\n        num_replicas=worker_replicas,\n        num_ps_tasks=ps_tasks,\n        worker_job_name=worker_job_name)\n\n    # Place the global step on the device storing the variables.\n    with tf.device(deploy_config.variables_device()):\n      global_step = slim.create_global_step()\n\n    with tf.device(deploy_config.inputs_device()):\n      input_queue = _create_input_queue(train_config.batch_size // num_clones,\n                                        create_tensor_dict_fn,\n                                        train_config.batch_queue_capacity,\n                                        train_config.num_batch_queue_threads,\n                                        train_config.prefetch_queue_capacity,\n                                        data_augmentation_options)\n\n    # Gather initial summaries.\n    summaries = set(tf.get_collection(tf.GraphKeys.SUMMARIES))\n    global_summaries = set([])\n\n    model_fn = functools.partial(_create_losses,\n                                 create_model_fn=create_model_fn)\n    clones = model_deploy.create_clones(deploy_config, model_fn, [input_queue])\n    first_clone_scope = clones[0].scope\n\n    # Gather update_ops from the first clone. These contain, for example,\n    # the updates for the batch_norm variables created by model_fn.\n    update_ops = tf.get_collection(tf.GraphKeys.UPDATE_OPS, first_clone_scope)\n\n    with tf.device(deploy_config.optimizer_device()):\n      training_optimizer = optimizer_builder.build(train_config.optimizer,\n                                                   global_summaries)\n\n    sync_optimizer = None\n    if train_config.sync_replicas:\n      training_optimizer = tf.SyncReplicasOptimizer(\n          training_optimizer,\n          replicas_to_aggregate=train_config.replicas_to_aggregate,\n          total_num_replicas=train_config.worker_replicas)\n      sync_optimizer = training_optimizer\n\n    # Create ops required to initialize the model from a given checkpoint.\n    init_fn = None\n    if train_config.fine_tune_checkpoint:\n      init_fn = detection_model.restore_fn(\n          train_config.fine_tune_checkpoint,\n          from_detection_checkpoint=train_config.from_detection_checkpoint)\n\n    with tf.device(deploy_config.optimizer_device()):\n      total_loss, grads_and_vars = model_deploy.optimize_clones(\n          clones, training_optimizer, regularization_losses=None)\n      total_loss = tf.check_numerics(total_loss, 'LossTensor is inf or nan.')\n\n      # Optionally multiply bias gradients by train_config.bias_grad_multiplier.\n      if train_config.bias_grad_multiplier:\n        biases_regex_list = ['.*/biases']\n        grads_and_vars = variables_helper.multiply_gradients_matching_regex(\n            grads_and_vars,\n            biases_regex_list,\n            multiplier=train_config.bias_grad_multiplier)\n\n      # Optionally freeze some layers by setting their gradients to be zero.\n      if train_config.freeze_variables:\n        grads_and_vars = variables_helper.freeze_gradients_matching_regex(\n            grads_and_vars, train_config.freeze_variables)\n\n      # Optionally clip gradients\n      if train_config.gradient_clipping_by_norm > 0:\n        with tf.name_scope('clip_grads'):\n          grads_and_vars = slim.learning.clip_gradient_norms(\n              grads_and_vars, train_config.gradient_clipping_by_norm)\n\n      # Create gradient updates.\n      grad_updates = training_optimizer.apply_gradients(grads_and_vars,\n                                                        global_step=global_step)\n      update_ops.append(grad_updates)\n\n      update_op = tf.group(*update_ops)\n      with tf.control_dependencies([update_op]):\n        train_tensor = tf.identity(total_loss, name='train_op')\n\n    # Add summaries.\n    for model_var in slim.get_model_variables():\n      global_summaries.add(tf.summary.histogram(model_var.op.name, model_var))\n    for loss_tensor in tf.losses.get_losses():\n      global_summaries.add(tf.summary.scalar(loss_tensor.op.name, loss_tensor))\n    global_summaries.add(\n        tf.summary.scalar('TotalLoss', tf.losses.get_total_loss()))\n\n    # Add the summaries from the first clone. These contain the summaries\n    # created by model_fn and either optimize_clones() or _gather_clone_loss().\n    summaries |= set(tf.get_collection(tf.GraphKeys.SUMMARIES,\n                                       first_clone_scope))\n    summaries |= global_summaries\n\n    # Merge all summaries together.\n    summary_op = tf.summary.merge(list(summaries), name='summary_op')\n\n    # Soft placement allows placing on CPU ops without GPU implementation.\n    session_config = tf.ConfigProto(allow_soft_placement=True,\n                                    log_device_placement=False)\n\n    # Save checkpoints regularly.\n    keep_checkpoint_every_n_hours = train_config.keep_checkpoint_every_n_hours\n    saver = tf.train.Saver(\n        keep_checkpoint_every_n_hours=keep_checkpoint_every_n_hours)\n\n    slim.learning.train(\n        train_tensor,\n        logdir=train_dir,\n        master=master,\n        is_chief=is_chief,\n        session_config=session_config,\n        startup_delay_steps=train_config.startup_delay_steps,\n        init_fn=init_fn,\n        summary_op=summary_op,\n        number_of_steps=(\n            train_config.num_steps if train_config.num_steps else None),\n        save_summaries_secs=120,\n        sync_optimizer=sync_optimizer,\n        saver=saver)\n"
  },
  {
    "path": "object_detector_app/object_detection/trainer_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.trainer.\"\"\"\n\nimport tensorflow as tf\n\nfrom google.protobuf import text_format\n\nfrom object_detection import trainer\nfrom object_detection.core import losses\nfrom object_detection.core import model\nfrom object_detection.core import standard_fields as fields\nfrom object_detection.protos import train_pb2\n\n\nNUMBER_OF_CLASSES = 2\n\n\ndef get_input_function():\n  \"\"\"A function to get test inputs. Returns an image with one box.\"\"\"\n  image = tf.random_uniform([32, 32, 3], dtype=tf.float32)\n  class_label = tf.random_uniform(\n      [1], minval=0, maxval=NUMBER_OF_CLASSES, dtype=tf.int32)\n  box_label = tf.random_uniform(\n      [1, 4], minval=0.4, maxval=0.6, dtype=tf.float32)\n\n  return {\n      fields.InputDataFields.image: image,\n      fields.InputDataFields.groundtruth_classes: class_label,\n      fields.InputDataFields.groundtruth_boxes: box_label\n  }\n\n\nclass FakeDetectionModel(model.DetectionModel):\n  \"\"\"A simple (and poor) DetectionModel for use in test.\"\"\"\n\n  def __init__(self):\n    super(FakeDetectionModel, self).__init__(num_classes=NUMBER_OF_CLASSES)\n    self._classification_loss = losses.WeightedSigmoidClassificationLoss(\n        anchorwise_output=True)\n    self._localization_loss = losses.WeightedSmoothL1LocalizationLoss(\n        anchorwise_output=True)\n\n  def preprocess(self, inputs):\n    \"\"\"Input preprocessing, resizes images to 28x28.\n\n    Args:\n      inputs: a [batch, height_in, width_in, channels] float32 tensor\n        representing a batch of images with values between 0 and 255.0.\n\n    Returns:\n      preprocessed_inputs: a [batch, 28, 28, channels] float32 tensor.\n    \"\"\"\n    return tf.image.resize_images(inputs, [28, 28])\n\n  def predict(self, preprocessed_inputs):\n    \"\"\"Prediction tensors from inputs tensor.\n\n    Args:\n      preprocessed_inputs: a [batch, 28, 28, channels] float32 tensor.\n\n    Returns:\n      prediction_dict: a dictionary holding prediction tensors to be\n        passed to the Loss or Postprocess functions.\n    \"\"\"\n    flattened_inputs = tf.contrib.layers.flatten(preprocessed_inputs)\n    class_prediction = tf.contrib.layers.fully_connected(\n        flattened_inputs, self._num_classes)\n    box_prediction = tf.contrib.layers.fully_connected(flattened_inputs, 4)\n\n    return {\n        'class_predictions_with_background': tf.reshape(\n            class_prediction, [-1, 1, self._num_classes]),\n        'box_encodings': tf.reshape(box_prediction, [-1, 1, 4])\n    }\n\n  def postprocess(self, prediction_dict, **params):\n    \"\"\"Convert predicted output tensors to final detections. Unused.\n\n    Args:\n      prediction_dict: a dictionary holding prediction tensors.\n      **params: Additional keyword arguments for specific implementations of\n        DetectionModel.\n\n    Returns:\n      detections: a dictionary with empty fields.\n    \"\"\"\n    return {\n        'detection_boxes': None,\n        'detection_scores': None,\n        'detection_classes': None,\n        'num_detections': None\n    }\n\n  def loss(self, prediction_dict):\n    \"\"\"Compute scalar loss tensors with respect to provided groundtruth.\n\n    Calling this function requires that groundtruth tensors have been\n    provided via the provide_groundtruth function.\n\n    Args:\n      prediction_dict: a dictionary holding predicted tensors\n\n    Returns:\n      a dictionary mapping strings (loss names) to scalar tensors representing\n        loss values.\n    \"\"\"\n    batch_reg_targets = tf.stack(\n        self.groundtruth_lists(fields.BoxListFields.boxes))\n    batch_cls_targets = tf.stack(\n        self.groundtruth_lists(fields.BoxListFields.classes))\n    weights = tf.constant(\n        1.0, dtype=tf.float32,\n        shape=[len(self.groundtruth_lists(fields.BoxListFields.boxes)), 1])\n\n    location_losses = self._localization_loss(\n        prediction_dict['box_encodings'], batch_reg_targets,\n        weights=weights)\n    cls_losses = self._classification_loss(\n        prediction_dict['class_predictions_with_background'], batch_cls_targets,\n        weights=weights)\n\n    loss_dict = {\n        'localization_loss': tf.reduce_sum(location_losses),\n        'classification_loss': tf.reduce_sum(cls_losses),\n    }\n    return loss_dict\n\n  def restore_fn(self, checkpoint_path, from_detection_checkpoint=True):\n    \"\"\"Return callable for loading a checkpoint into the tensorflow graph.\n\n    Args:\n      checkpoint_path: path to checkpoint to restore.\n      from_detection_checkpoint: whether to restore from a full detection\n        checkpoint (with compatible variable names) or to restore from a\n        classification checkpoint for initialization prior to training.\n\n    Returns:\n      a callable which takes a tf.Session and does nothing.\n    \"\"\"\n    def restore(unused_sess):\n      return\n    return restore\n\n\nclass TrainerTest(tf.test.TestCase):\n\n  def test_configure_trainer_and_train_two_steps(self):\n    train_config_text_proto = \"\"\"\n    optimizer {\n      adam_optimizer {\n        learning_rate {\n          constant_learning_rate {\n            learning_rate: 0.01\n          }\n        }\n      }\n    }\n    data_augmentation_options {\n      random_adjust_brightness {\n        max_delta: 0.2\n      }\n    }\n    data_augmentation_options {\n      random_adjust_contrast {\n        min_delta: 0.7\n        max_delta: 1.1\n      }\n    }\n    num_steps: 2\n    \"\"\"\n    train_config = train_pb2.TrainConfig()\n    text_format.Merge(train_config_text_proto, train_config)\n\n    train_dir = self.get_temp_dir()\n\n    trainer.train(create_tensor_dict_fn=get_input_function,\n                  create_model_fn=FakeDetectionModel,\n                  train_config=train_config,\n                  master='',\n                  task=0,\n                  num_clones=1,\n                  worker_replicas=1,\n                  clone_on_cpu=True,\n                  ps_tasks=0,\n                  worker_job_name='worker',\n                  is_chief=True,\n                  train_dir=train_dir)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/BUILD",
    "content": "# Tensorflow Object Detection API: Utility functions.\n\npackage(\n    default_visibility = [\"//visibility:public\"],\n)\n\nlicenses([\"notice\"])\n\n# Apache 2.0\n\npy_library(\n    name = \"category_util\",\n    srcs = [\"category_util.py\"],\n    deps = [\"//tensorflow\"],\n)\n\npy_library(\n    name = \"dataset_util\",\n    srcs = [\"dataset_util.py\"],\n    deps = [\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"label_map_util\",\n    srcs = [\"label_map_util.py\"],\n    deps = [\n        \"//third_party/py/google/protobuf\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/protos:string_int_label_map_py_pb2\",\n    ],\n)\n\npy_library(\n    name = \"learning_schedules\",\n    srcs = [\"learning_schedules.py\"],\n    deps = [\"//tensorflow\"],\n)\n\npy_library(\n    name = \"metrics\",\n    srcs = [\"metrics.py\"],\n    deps = [\"//third_party/py/numpy\"],\n)\n\npy_library(\n    name = \"np_box_list\",\n    srcs = [\"np_box_list.py\"],\n    deps = [\"//tensorflow\"],\n)\n\npy_library(\n    name = \"np_box_list_ops\",\n    srcs = [\"np_box_list_ops.py\"],\n    deps = [\n        \":np_box_list\",\n        \":np_box_ops\",\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"np_box_ops\",\n    srcs = [\"np_box_ops.py\"],\n    deps = [\"//tensorflow\"],\n)\n\npy_library(\n    name = \"object_detection_evaluation\",\n    srcs = [\"object_detection_evaluation.py\"],\n    deps = [\n        \":metrics\",\n        \":per_image_evaluation\",\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"ops\",\n    srcs = [\"ops.py\"],\n    deps = [\n        \":static_shape\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:box_list\",\n        \"//tensorflow_models/object_detection/core:box_list_ops\",\n        \"//tensorflow_models/object_detection/core:standard_fields\",\n    ],\n)\n\npy_library(\n    name = \"per_image_evaluation\",\n    srcs = [\"per_image_evaluation.py\"],\n    deps = [\n        \":np_box_list\",\n        \":np_box_list_ops\",\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"shape_utils\",\n    srcs = [\"shape_utils.py\"],\n    deps = [\"//tensorflow\"],\n)\n\npy_library(\n    name = \"static_shape\",\n    srcs = [\"static_shape.py\"],\n    deps = [],\n)\n\npy_library(\n    name = \"test_utils\",\n    srcs = [\"test_utils.py\"],\n    deps = [\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:anchor_generator\",\n        \"//tensorflow_models/object_detection/core:box_coder\",\n        \"//tensorflow_models/object_detection/core:box_list\",\n        \"//tensorflow_models/object_detection/core:box_predictor\",\n        \"//tensorflow_models/object_detection/core:matcher\",\n    ],\n)\n\npy_library(\n    name = \"variables_helper\",\n    srcs = [\"variables_helper.py\"],\n    deps = [\n        \"//tensorflow\",\n    ],\n)\n\npy_library(\n    name = \"visualization_utils\",\n    srcs = [\"visualization_utils.py\"],\n    deps = [\n        \"//third_party/py/PIL:pil\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"category_util_test\",\n    srcs = [\"category_util_test.py\"],\n    deps = [\n        \":category_util\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"dataset_util_test\",\n    srcs = [\"dataset_util_test.py\"],\n    deps = [\n        \":dataset_util\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"label_map_util_test\",\n    srcs = [\"label_map_util_test.py\"],\n    deps = [\n        \":label_map_util\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"learning_schedules_test\",\n    srcs = [\"learning_schedules_test.py\"],\n    deps = [\n        \":learning_schedules\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"metrics_test\",\n    srcs = [\"metrics_test.py\"],\n    deps = [\n        \":metrics\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"np_box_list_test\",\n    srcs = [\"np_box_list_test.py\"],\n    deps = [\n        \":np_box_list\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"np_box_list_ops_test\",\n    srcs = [\"np_box_list_ops_test.py\"],\n    deps = [\n        \":np_box_list\",\n        \":np_box_list_ops\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"np_box_ops_test\",\n    srcs = [\"np_box_ops_test.py\"],\n    deps = [\n        \":np_box_ops\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"object_detection_evaluation_test\",\n    srcs = [\"object_detection_evaluation_test.py\"],\n    deps = [\n        \":object_detection_evaluation\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"ops_test\",\n    srcs = [\"ops_test.py\"],\n    deps = [\n        \":ops\",\n        \"//tensorflow\",\n        \"//tensorflow_models/object_detection/core:standard_fields\",\n    ],\n)\n\npy_test(\n    name = \"per_image_evaluation_test\",\n    srcs = [\"per_image_evaluation_test.py\"],\n    deps = [\n        \":per_image_evaluation\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"shape_utils_test\",\n    srcs = [\"shape_utils_test.py\"],\n    deps = [\n        \":shape_utils\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"static_shape_test\",\n    srcs = [\"static_shape_test.py\"],\n    deps = [\n        \":static_shape\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"test_utils_test\",\n    srcs = [\"test_utils_test.py\"],\n    deps = [\n        \":test_utils\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"variables_helper_test\",\n    srcs = [\"variables_helper_test.py\"],\n    deps = [\n        \":variables_helper\",\n        \"//tensorflow\",\n    ],\n)\n\npy_test(\n    name = \"visualization_utils_test\",\n    srcs = [\"visualization_utils_test.py\"],\n    deps = [\n        \":visualization_utils\",\n        \"//third_party/py/PIL:pil\",\n    ],\n)\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/__init__.py",
    "content": ""
  },
  {
    "path": "object_detector_app/object_detection/utils/category_util.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Functions for importing/exporting Object Detection categories.\"\"\"\nimport csv\n\nimport tensorflow as tf\n\n\ndef load_categories_from_csv_file(csv_path):\n  \"\"\"Loads categories from a csv file.\n\n  The CSV file should have one comma delimited numeric category id and string\n  category name pair per line. For example:\n\n  0,\"cat\"\n  1,\"dog\"\n  2,\"bird\"\n  ...\n\n  Args:\n    csv_path: Path to the csv file to be parsed into categories.\n  Returns:\n    categories: A list of dictionaries representing all possible categories.\n                The categories will contain an integer 'id' field and a string\n                'name' field.\n  Raises:\n    ValueError: If the csv file is incorrectly formatted.\n  \"\"\"\n  categories = []\n\n  with tf.gfile.Open(csv_path, 'r') as csvfile:\n    reader = csv.reader(csvfile, delimiter=',', quotechar='\"')\n    for row in reader:\n      if not row:\n        continue\n\n      if len(row) != 2:\n        raise ValueError('Expected 2 fields per row in csv: %s' % ','.join(row))\n\n      category_id = int(row[0])\n      category_name = row[1]\n      categories.append({'id': category_id, 'name': category_name})\n\n  return categories\n\n\ndef save_categories_to_csv_file(categories, csv_path):\n  \"\"\"Saves categories to a csv file.\n\n  Args:\n    categories: A list of dictionaries representing categories to save to file.\n                Each category must contain an 'id' and 'name' field.\n    csv_path: Path to the csv file to be parsed into categories.\n  \"\"\"\n  categories.sort(key=lambda x: x['id'])\n  with tf.gfile.Open(csv_path, 'w') as csvfile:\n    writer = csv.writer(csvfile, delimiter=',', quotechar='\"')\n    for category in categories:\n      writer.writerow([category['id'], category['name']])\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/category_util_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.utils.category_util.\"\"\"\nimport os\n\nimport tensorflow as tf\n\nfrom object_detection.utils import category_util\n\n\nclass EvalUtilTest(tf.test.TestCase):\n\n  def test_load_categories_from_csv_file(self):\n    csv_data = \"\"\"\n        0,\"cat\"\n        1,\"dog\"\n        2,\"bird\"\n    \"\"\".strip(' ')\n    csv_path = os.path.join(self.get_temp_dir(), 'test.csv')\n    with tf.gfile.Open(csv_path, 'wb') as f:\n      f.write(csv_data)\n\n    categories = category_util.load_categories_from_csv_file(csv_path)\n    self.assertTrue({'id': 0, 'name': 'cat'} in categories)\n    self.assertTrue({'id': 1, 'name': 'dog'} in categories)\n    self.assertTrue({'id': 2, 'name': 'bird'} in categories)\n\n  def test_save_categories_to_csv_file(self):\n    categories = [\n        {'id': 0, 'name': 'cat'},\n        {'id': 1, 'name': 'dog'},\n        {'id': 2, 'name': 'bird'},\n    ]\n    csv_path = os.path.join(self.get_temp_dir(), 'test.csv')\n    category_util.save_categories_to_csv_file(categories, csv_path)\n    saved_categories = category_util.load_categories_from_csv_file(csv_path)\n    self.assertEqual(saved_categories, categories)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/dataset_util.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Utility functions for creating TFRecord data sets.\"\"\"\n\nimport tensorflow as tf\n\n\ndef int64_feature(value):\n  return tf.train.Feature(int64_list=tf.train.Int64List(value=[value]))\n\n\ndef int64_list_feature(value):\n  return tf.train.Feature(int64_list=tf.train.Int64List(value=value))\n\n\ndef bytes_feature(value):\n  return tf.train.Feature(bytes_list=tf.train.BytesList(value=[value]))\n\n\ndef bytes_list_feature(value):\n  return tf.train.Feature(bytes_list=tf.train.BytesList(value=value))\n\n\ndef float_list_feature(value):\n  return tf.train.Feature(float_list=tf.train.FloatList(value=value))\n\n\ndef read_examples_list(path):\n  \"\"\"Read list of training or validation examples.\n\n  The file is assumed to contain a single example per line where the first\n  token in the line is an identifier that allows us to find the image and\n  annotation xml for that example.\n\n  For example, the line:\n  xyz 3\n  would allow us to find files xyz.jpg and xyz.xml (the 3 would be ignored).\n\n  Args:\n    path: absolute path to examples list file.\n\n  Returns:\n    list of example identifiers (strings).\n  \"\"\"\n  with tf.gfile.GFile(path) as fid:\n    lines = fid.readlines()\n  return [line.strip().split(' ')[0] for line in lines]\n\n\ndef recursive_parse_xml_to_dict(xml):\n  \"\"\"Recursively parses XML contents to python dict.\n\n  We assume that `object` tags are the only ones that can appear\n  multiple times at the same level of a tree.\n\n  Args:\n    xml: xml tree obtained by parsing XML file contents using lxml.etree\n\n  Returns:\n    Python dictionary holding XML contents.\n  \"\"\"\n  if not xml:\n    return {xml.tag: xml.text}\n  result = {}\n  for child in xml:\n    child_result = recursive_parse_xml_to_dict(child)\n    if child.tag != 'object':\n      result[child.tag] = child_result[child.tag]\n    else:\n      if child.tag not in result:\n        result[child.tag] = []\n      result[child.tag].append(child_result[child.tag])\n  return {xml.tag: result}\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/dataset_util_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.utils.dataset_util.\"\"\"\n\nimport os\nimport tensorflow as tf\n\nfrom object_detection.utils import dataset_util\n\n\nclass DatasetUtilTest(tf.test.TestCase):\n\n  def test_read_examples_list(self):\n    example_list_data = \"\"\"example1 1\\nexample2 2\"\"\"\n    example_list_path = os.path.join(self.get_temp_dir(), 'examples.txt')\n    with tf.gfile.Open(example_list_path, 'wb') as f:\n      f.write(example_list_data)\n\n    examples = dataset_util.read_examples_list(example_list_path)\n    self.assertListEqual(['example1', 'example2'], examples)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/label_map_util.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Label map utility functions.\"\"\"\n\nimport logging\n\nimport tensorflow as tf\nfrom google.protobuf import text_format\nfrom object_detection.protos import string_int_label_map_pb2\n\n\ndef create_category_index(categories):\n  \"\"\"Creates dictionary of COCO compatible categories keyed by category id.\n\n  Args:\n    categories: a list of dicts, each of which has the following keys:\n      'id': (required) an integer id uniquely identifying this category.\n      'name': (required) string representing category name\n        e.g., 'cat', 'dog', 'pizza'.\n\n  Returns:\n    category_index: a dict containing the same entries as categories, but keyed\n      by the 'id' field of each category.\n  \"\"\"\n  category_index = {}\n  for cat in categories:\n    category_index[cat['id']] = cat\n  return category_index\n\n\ndef convert_label_map_to_categories(label_map,\n                                    max_num_classes,\n                                    use_display_name=True):\n  \"\"\"Loads label map proto and returns categories list compatible with eval.\n\n  This function loads a label map and returns a list of dicts, each of which\n  has the following keys:\n    'id': (required) an integer id uniquely identifying this category.\n    'name': (required) string representing category name\n      e.g., 'cat', 'dog', 'pizza'.\n  We only allow class into the list if its id-label_id_offset is\n  between 0 (inclusive) and max_num_classes (exclusive).\n  If there are several items mapping to the same id in the label map,\n  we will only keep the first one in the categories list.\n\n  Args:\n    label_map: a StringIntLabelMapProto or None.  If None, a default categories\n      list is created with max_num_classes categories.\n    max_num_classes: maximum number of (consecutive) label indices to include.\n    use_display_name: (boolean) choose whether to load 'display_name' field\n      as category name.  If False of if the display_name field does not exist,\n      uses 'name' field as category names instead.\n  Returns:\n    categories: a list of dictionaries representing all possible categories.\n  \"\"\"\n  categories = []\n  list_of_ids_already_added = []\n  if not label_map:\n    label_id_offset = 1\n    for class_id in range(max_num_classes):\n      categories.append({\n          'id': class_id + label_id_offset,\n          'name': 'category_{}'.format(class_id + label_id_offset)\n      })\n    return categories\n  for item in label_map.item:\n    if not 0 < item.id <= max_num_classes:\n      logging.info('Ignore item %d since it falls outside of requested '\n                   'label range.', item.id)\n      continue\n    if use_display_name and item.HasField('display_name'):\n      name = item.display_name\n    else:\n      name = item.name\n    if item.id not in list_of_ids_already_added:\n      list_of_ids_already_added.append(item.id)\n      categories.append({'id': item.id, 'name': name})\n  return categories\n\n\n# TODO: double check documentaion.\ndef load_labelmap(path):\n  \"\"\"Loads label map proto.\n\n  Args:\n    path: path to StringIntLabelMap proto text file.\n  Returns:\n    a StringIntLabelMapProto\n  \"\"\"\n  with tf.gfile.GFile(path, 'r') as fid:\n    label_map_string = fid.read()\n    label_map = string_int_label_map_pb2.StringIntLabelMap()\n    try:\n      text_format.Merge(label_map_string, label_map)\n    except text_format.ParseError:\n      label_map.ParseFromString(label_map_string)\n  return label_map\n\n\ndef get_label_map_dict(label_map_path):\n  \"\"\"Reads a label map and returns a dictionary of label names to id.\n\n  Args:\n    label_map_path: path to label_map.\n\n  Returns:\n    A dictionary mapping label names to id.\n  \"\"\"\n  label_map = load_labelmap(label_map_path)\n  label_map_dict = {}\n  for item in label_map.item:\n    label_map_dict[item.name] = item.id\n  return label_map_dict\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/label_map_util_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.utils.label_map_util.\"\"\"\n\nimport os\nimport tensorflow as tf\n\nfrom google.protobuf import text_format\nfrom object_detection.protos import string_int_label_map_pb2\nfrom object_detection.utils import label_map_util\n\n\nclass LabelMapUtilTest(tf.test.TestCase):\n\n  def _generate_label_map(self, num_classes):\n    label_map_proto = string_int_label_map_pb2.StringIntLabelMap()\n    for i in range(1, num_classes + 1):\n      item = label_map_proto.item.add()\n      item.id = i\n      item.name = 'label_' + str(i)\n      item.display_name = str(i)\n    return label_map_proto\n\n  def test_get_label_map_dict(self):\n    label_map_string = \"\"\"\n      item {\n        id:2\n        name:'cat'\n      }\n      item {\n        id:1\n        name:'dog'\n      }\n    \"\"\"\n    label_map_path = os.path.join(self.get_temp_dir(), 'label_map.pbtxt')\n    with tf.gfile.Open(label_map_path, 'wb') as f:\n      f.write(label_map_string)\n\n    label_map_dict = label_map_util.get_label_map_dict(label_map_path)\n    self.assertEqual(label_map_dict['dog'], 1)\n    self.assertEqual(label_map_dict['cat'], 2)\n\n  def test_keep_categories_with_unique_id(self):\n    label_map_proto = string_int_label_map_pb2.StringIntLabelMap()\n    label_map_string = \"\"\"\n      item {\n        id:2\n        name:'cat'\n      }\n      item {\n        id:1\n        name:'child'\n      }\n      item {\n        id:1\n        name:'person'\n      }\n      item {\n        id:1\n        name:'n00007846'\n      }\n    \"\"\"\n    text_format.Merge(label_map_string, label_map_proto)\n    categories = label_map_util.convert_label_map_to_categories(\n        label_map_proto, max_num_classes=3)\n    self.assertListEqual([{\n        'id': 2,\n        'name': u'cat'\n    }, {\n        'id': 1,\n        'name': u'child'\n    }], categories)\n\n  def test_convert_label_map_to_categories_no_label_map(self):\n    categories = label_map_util.convert_label_map_to_categories(\n        None, max_num_classes=3)\n    expected_categories_list = [{\n        'name': u'category_1',\n        'id': 1\n    }, {\n        'name': u'category_2',\n        'id': 2\n    }, {\n        'name': u'category_3',\n        'id': 3\n    }]\n    self.assertListEqual(expected_categories_list, categories)\n\n  def test_convert_label_map_to_coco_categories(self):\n    label_map_proto = self._generate_label_map(num_classes=4)\n    categories = label_map_util.convert_label_map_to_categories(\n        label_map_proto, max_num_classes=3)\n    expected_categories_list = [{\n        'name': u'1',\n        'id': 1\n    }, {\n        'name': u'2',\n        'id': 2\n    }, {\n        'name': u'3',\n        'id': 3\n    }]\n    self.assertListEqual(expected_categories_list, categories)\n\n  def test_convert_label_map_to_coco_categories_with_few_classes(self):\n    label_map_proto = self._generate_label_map(num_classes=4)\n    cat_no_offset = label_map_util.convert_label_map_to_categories(\n        label_map_proto, max_num_classes=2)\n    expected_categories_list = [{\n        'name': u'1',\n        'id': 1\n    }, {\n        'name': u'2',\n        'id': 2\n    }]\n    self.assertListEqual(expected_categories_list, cat_no_offset)\n\n  def test_create_category_index(self):\n    categories = [{'name': u'1', 'id': 1}, {'name': u'2', 'id': 2}]\n    category_index = label_map_util.create_category_index(categories)\n    self.assertDictEqual({\n        1: {\n            'name': u'1',\n            'id': 1\n        },\n        2: {\n            'name': u'2',\n            'id': 2\n        }\n    }, category_index)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/learning_schedules.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Library of common learning rate schedules.\"\"\"\n\nimport tensorflow as tf\n\n\ndef exponential_decay_with_burnin(global_step,\n                                  learning_rate_base,\n                                  learning_rate_decay_steps,\n                                  learning_rate_decay_factor,\n                                  burnin_learning_rate=0.0,\n                                  burnin_steps=0):\n  \"\"\"Exponential decay schedule with burn-in period.\n\n  In this schedule, learning rate is fixed at burnin_learning_rate\n  for a fixed period, before transitioning to a regular exponential\n  decay schedule.\n\n  Args:\n    global_step: int tensor representing global step.\n    learning_rate_base: base learning rate.\n    learning_rate_decay_steps: steps to take between decaying the learning rate.\n      Note that this includes the number of burn-in steps.\n    learning_rate_decay_factor: multiplicative factor by which to decay\n      learning rate.\n    burnin_learning_rate: initial learning rate during burn-in period.  If\n      0.0 (which is the default), then the burn-in learning rate is simply\n      set to learning_rate_base.\n    burnin_steps: number of steps to use burnin learning rate.\n\n  Returns:\n    a (scalar) float tensor representing learning rate\n  \"\"\"\n  if burnin_learning_rate == 0:\n    burnin_learning_rate = learning_rate_base\n  post_burnin_learning_rate = tf.train.exponential_decay(\n      learning_rate_base,\n      global_step,\n      learning_rate_decay_steps,\n      learning_rate_decay_factor,\n      staircase=True)\n  return tf.cond(\n      tf.less(global_step, burnin_steps),\n      lambda: tf.convert_to_tensor(burnin_learning_rate),\n      lambda: post_burnin_learning_rate)\n\n\ndef manual_stepping(global_step, boundaries, rates):\n  \"\"\"Manually stepped learning rate schedule.\n\n  This function provides fine grained control over learning rates.  One must\n  specify a sequence of learning rates as well as a set of integer steps\n  at which the current learning rate must transition to the next.  For example,\n  if boundaries = [5, 10] and rates = [.1, .01, .001], then the learning\n  rate returned by this function is .1 for global_step=0,...,4, .01 for\n  global_step=5...9, and .001 for global_step=10 and onward.\n\n  Args:\n    global_step: int64 (scalar) tensor representing global step.\n    boundaries: a list of global steps at which to switch learning\n      rates.  This list is assumed to consist of increasing positive integers.\n    rates: a list of (float) learning rates corresponding to intervals between\n      the boundaries.  The length of this list must be exactly\n      len(boundaries) + 1.\n\n  Returns:\n    a (scalar) float tensor representing learning rate\n  Raises:\n    ValueError: if one of the following checks fails:\n      1. boundaries is a strictly increasing list of positive integers\n      2. len(rates) == len(boundaries) + 1\n  \"\"\"\n  if any([b < 0 for b in boundaries]) or any(\n      [not isinstance(b, int) for b in boundaries]):\n    raise ValueError('boundaries must be a list of positive integers')\n  if any([bnext <= b for bnext, b in zip(boundaries[1:], boundaries[:-1])]):\n    raise ValueError('Entries in boundaries must be strictly increasing.')\n  if any([not isinstance(r, float) for r in rates]):\n    raise ValueError('Learning rates must be floats')\n  if len(rates) != len(boundaries) + 1:\n    raise ValueError('Number of provided learning rates must exceed '\n                     'number of boundary points by exactly 1.')\n  step_boundaries = tf.constant(boundaries, tf.int64)\n  learning_rates = tf.constant(rates, tf.float32)\n  unreached_boundaries = tf.reshape(tf.where(\n      tf.greater(step_boundaries, global_step)), [-1])\n  unreached_boundaries = tf.concat([unreached_boundaries, [len(boundaries)]], 0)\n  index = tf.reshape(tf.reduce_min(unreached_boundaries), [1])\n  return tf.reshape(tf.slice(learning_rates, index, [1]), [])\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/learning_schedules_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.utils.learning_schedules.\"\"\"\nimport tensorflow as tf\n\nfrom object_detection.utils import learning_schedules\n\n\nclass LearningSchedulesTest(tf.test.TestCase):\n\n  def testExponentialDecayWithBurnin(self):\n    global_step = tf.placeholder(tf.int32, [])\n    learning_rate_base = 1.0\n    learning_rate_decay_steps = 3\n    learning_rate_decay_factor = .1\n    burnin_learning_rate = .5\n    burnin_steps = 2\n    exp_rates = [.5, .5, 1, .1, .1, .1, .01, .01]\n    learning_rate = learning_schedules.exponential_decay_with_burnin(\n        global_step, learning_rate_base, learning_rate_decay_steps,\n        learning_rate_decay_factor, burnin_learning_rate, burnin_steps)\n    with self.test_session() as sess:\n      output_rates = []\n      for input_global_step in range(8):\n        output_rate = sess.run(learning_rate,\n                               feed_dict={global_step: input_global_step})\n        output_rates.append(output_rate)\n      self.assertAllClose(output_rates, exp_rates)\n\n  def testManualStepping(self):\n    global_step = tf.placeholder(tf.int64, [])\n    boundaries = [2, 3, 7]\n    rates = [1.0, 2.0, 3.0, 4.0]\n    exp_rates = [1.0, 1.0, 2.0, 3.0, 3.0, 3.0, 3.0, 4.0, 4.0, 4.0]\n    learning_rate = learning_schedules.manual_stepping(global_step, boundaries,\n                                                       rates)\n    with self.test_session() as sess:\n      output_rates = []\n      for input_global_step in range(10):\n        output_rate = sess.run(learning_rate,\n                               feed_dict={global_step: input_global_step})\n        output_rates.append(output_rate)\n      self.assertAllClose(output_rates, exp_rates)\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/metrics.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Functions for computing metrics like precision, recall, CorLoc and etc.\"\"\"\nfrom __future__ import division\n\nimport numpy as np\n\n\ndef compute_precision_recall(scores, labels, num_gt):\n  \"\"\"Compute precision and recall.\n\n  Args:\n    scores: A float numpy array representing detection score\n    labels: A boolean numpy array representing true/false positive labels\n    num_gt: Number of ground truth instances\n\n  Raises:\n    ValueError: if the input is not of the correct format\n\n  Returns:\n    precision: Fraction of positive instances over detected ones. This value is\n      None if no ground truth labels are present.\n    recall: Fraction of detected positive instance over all positive instances.\n      This value is None if no ground truth labels are present.\n\n  \"\"\"\n  if not isinstance(\n      labels, np.ndarray) or labels.dtype != np.bool or len(labels.shape) != 1:\n    raise ValueError(\"labels must be single dimension bool numpy array\")\n\n  if not isinstance(\n      scores, np.ndarray) or len(scores.shape) != 1:\n    raise ValueError(\"scores must be single dimension numpy array\")\n\n  if num_gt < np.sum(labels):\n    raise ValueError(\"Number of true positives must be smaller than num_gt.\")\n\n  if len(scores) != len(labels):\n    raise ValueError(\"scores and labels must be of the same size.\")\n\n  if num_gt == 0:\n    return None, None\n\n  sorted_indices = np.argsort(scores)\n  sorted_indices = sorted_indices[::-1]\n  labels = labels.astype(int)\n  true_positive_labels = labels[sorted_indices]\n  false_positive_labels = 1 - true_positive_labels\n  cum_true_positives = np.cumsum(true_positive_labels)\n  cum_false_positives = np.cumsum(false_positive_labels)\n  precision = cum_true_positives.astype(float) / (\n      cum_true_positives + cum_false_positives)\n  recall = cum_true_positives.astype(float) / num_gt\n  return precision, recall\n\n\ndef compute_average_precision(precision, recall):\n  \"\"\"Compute Average Precision according to the definition in VOCdevkit.\n\n  Precision is modified to ensure that it does not decrease as recall\n  decrease.\n\n  Args:\n    precision: A float [N, 1] numpy array of precisions\n    recall: A float [N, 1] numpy array of recalls\n\n  Raises:\n    ValueError: if the input is not of the correct format\n\n  Returns:\n    average_precison: The area under the precision recall curve. NaN if\n      precision and recall are None.\n\n  \"\"\"\n  if precision is None:\n    if recall is not None:\n      raise ValueError(\"If precision is None, recall must also be None\")\n    return np.NAN\n\n  if not isinstance(precision, np.ndarray) or not isinstance(recall,\n                                                             np.ndarray):\n    raise ValueError(\"precision and recall must be numpy array\")\n  if precision.dtype != np.float or recall.dtype != np.float:\n    raise ValueError(\"input must be float numpy array.\")\n  if len(precision) != len(recall):\n    raise ValueError(\"precision and recall must be of the same size.\")\n  if not precision.size:\n    return 0.0\n  if np.amin(precision) < 0 or np.amax(precision) > 1:\n    raise ValueError(\"Precision must be in the range of [0, 1].\")\n  if np.amin(recall) < 0 or np.amax(recall) > 1:\n    raise ValueError(\"recall must be in the range of [0, 1].\")\n  if not all(recall[i] <= recall[i + 1] for i in xrange(len(recall) - 1)):\n    raise ValueError(\"recall must be a non-decreasing array\")\n\n  recall = np.concatenate([[0], recall, [1]])\n  precision = np.concatenate([[0], precision, [0]])\n\n  # Preprocess precision to be a non-decreasing array\n  for i in range(len(precision) - 2, -1, -1):\n    precision[i] = np.maximum(precision[i], precision[i + 1])\n\n  indices = np.where(recall[1:] != recall[:-1])[0] + 1\n  average_precision = np.sum(\n      (recall[indices] - recall[indices - 1]) * precision[indices])\n  return average_precision\n\n\ndef compute_cor_loc(num_gt_imgs_per_class,\n                    num_images_correctly_detected_per_class):\n  \"\"\"Compute CorLoc according to the definition in the following paper.\n\n  https://www.robots.ox.ac.uk/~vgg/rg/papers/deselaers-eccv10.pdf\n\n  Returns nans if there are no ground truth images for a class.\n\n  Args:\n    num_gt_imgs_per_class: 1D array, representing number of images containing\n        at least one object instance of a particular class\n    num_images_correctly_detected_per_class: 1D array, representing number of\n        images that are correctly detected at least one object instance of a\n        particular class\n\n  Returns:\n    corloc_per_class: A float numpy array represents the corloc score of each\n      class\n  \"\"\"\n  return np.where(\n      num_gt_imgs_per_class == 0,\n      np.nan,\n      num_images_correctly_detected_per_class / num_gt_imgs_per_class)\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/metrics_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.metrics.\"\"\"\n\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.utils import metrics\n\n\nclass MetricsTest(tf.test.TestCase):\n\n  def test_compute_cor_loc(self):\n    num_gt_imgs_per_class = np.array([100, 1, 5, 1, 1], dtype=int)\n    num_images_correctly_detected_per_class = np.array([10, 0, 1, 0, 0],\n                                                       dtype=int)\n    corloc = metrics.compute_cor_loc(num_gt_imgs_per_class,\n                                     num_images_correctly_detected_per_class)\n    expected_corloc = np.array([0.1, 0, 0.2, 0, 0], dtype=float)\n    self.assertTrue(np.allclose(corloc, expected_corloc))\n\n  def test_compute_cor_loc_nans(self):\n    num_gt_imgs_per_class = np.array([100, 0, 0, 1, 1], dtype=int)\n    num_images_correctly_detected_per_class = np.array([10, 0, 1, 0, 0],\n                                                       dtype=int)\n    corloc = metrics.compute_cor_loc(num_gt_imgs_per_class,\n                                     num_images_correctly_detected_per_class)\n    expected_corloc = np.array([0.1, np.nan, np.nan, 0, 0], dtype=float)\n    self.assertAllClose(corloc, expected_corloc)\n\n  def test_compute_precision_recall(self):\n    num_gt = 10\n    scores = np.array([0.4, 0.3, 0.6, 0.2, 0.7, 0.1], dtype=float)\n    labels = np.array([0, 1, 1, 0, 0, 1], dtype=bool)\n    accumulated_tp_count = np.array([0, 1, 1, 2, 2, 3], dtype=float)\n    expected_precision = accumulated_tp_count / np.array([1, 2, 3, 4, 5, 6])\n    expected_recall = accumulated_tp_count / num_gt\n    precision, recall = metrics.compute_precision_recall(scores, labels, num_gt)\n    self.assertAllClose(precision, expected_precision)\n    self.assertAllClose(recall, expected_recall)\n\n  def test_compute_average_precision(self):\n    precision = np.array([0.8, 0.76, 0.9, 0.65, 0.7, 0.5, 0.55, 0], dtype=float)\n    recall = np.array([0.3, 0.3, 0.4, 0.4, 0.45, 0.45, 0.5, 0.5], dtype=float)\n    processed_precision = np.array([0.9, 0.9, 0.9, 0.7, 0.7, 0.55, 0.55, 0],\n                                   dtype=float)\n    recall_interval = np.array([0.3, 0, 0.1, 0, 0.05, 0, 0.05, 0], dtype=float)\n    expected_mean_ap = np.sum(recall_interval * processed_precision)\n    mean_ap = metrics.compute_average_precision(precision, recall)\n    self.assertAlmostEqual(expected_mean_ap, mean_ap)\n\n  def test_compute_precision_recall_and_ap_no_groundtruth(self):\n    num_gt = 0\n    scores = np.array([0.4, 0.3, 0.6, 0.2, 0.7, 0.1], dtype=float)\n    labels = np.array([0, 0, 0, 0, 0, 0], dtype=bool)\n    expected_precision = None\n    expected_recall = None\n    precision, recall = metrics.compute_precision_recall(scores, labels, num_gt)\n    self.assertEquals(precision, expected_precision)\n    self.assertEquals(recall, expected_recall)\n    ap = metrics.compute_average_precision(precision, recall)\n    self.assertTrue(np.isnan(ap))\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/np_box_list.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Numpy BoxList classes and functions.\"\"\"\n\nimport numpy as np\n\n\nclass BoxList(object):\n  \"\"\"Box collection.\n\n  BoxList represents a list of bounding boxes as numpy array, where each\n  bounding box is represented as a row of 4 numbers,\n  [y_min, x_min, y_max, x_max].  It is assumed that all bounding boxes within a\n  given list correspond to a single image.\n\n  Optionally, users can add additional related fields (such as\n  objectness/classification scores).\n  \"\"\"\n\n  def __init__(self, data):\n    \"\"\"Constructs box collection.\n\n    Args:\n      data: a numpy array of shape [N, 4] representing box coordinates\n\n    Raises:\n      ValueError: if bbox data is not a numpy array\n      ValueError: if invalid dimensions for bbox data\n    \"\"\"\n    if not isinstance(data, np.ndarray):\n      raise ValueError('data must be a numpy array.')\n    if len(data.shape) != 2 or data.shape[1] != 4:\n      raise ValueError('Invalid dimensions for box data.')\n    if data.dtype != np.float32 and data.dtype != np.float64:\n      raise ValueError('Invalid data type for box data: float is required.')\n    if not self._is_valid_boxes(data):\n      raise ValueError('Invalid box data. data must be a numpy array of '\n                       'N*[y_min, x_min, y_max, x_max]')\n    self.data = {'boxes': data}\n\n  def num_boxes(self):\n    \"\"\"Return number of boxes held in collections.\"\"\"\n    return self.data['boxes'].shape[0]\n\n  def get_extra_fields(self):\n    \"\"\"Return all non-box fields.\"\"\"\n    return [k for k in self.data.keys() if k != 'boxes']\n\n  def has_field(self, field):\n    return field in self.data\n\n  def add_field(self, field, field_data):\n    \"\"\"Add data to a specified field.\n\n    Args:\n      field: a string parameter used to speficy a related field to be accessed.\n      field_data: a numpy array of [N, ...] representing the data associated\n          with the field.\n    Raises:\n      ValueError: if the field is already exist or the dimension of the field\n          data does not matches the number of boxes.\n    \"\"\"\n    if self.has_field(field):\n      raise ValueError('Field ' + field + 'already exists')\n    if len(field_data.shape) < 1 or field_data.shape[0] != self.num_boxes():\n      raise ValueError('Invalid dimensions for field data')\n    self.data[field] = field_data\n\n  def get(self):\n    \"\"\"Convenience function for accesssing box coordinates.\n\n    Returns:\n      a numpy array of shape [N, 4] representing box corners\n    \"\"\"\n    return self.get_field('boxes')\n\n  def get_field(self, field):\n    \"\"\"Accesses data associated with the specified field in the box collection.\n\n    Args:\n      field: a string parameter used to speficy a related field to be accessed.\n\n    Returns:\n      a numpy 1-d array representing data of an associated field\n\n    Raises:\n      ValueError: if invalid field\n    \"\"\"\n    if not self.has_field(field):\n      raise ValueError('field {} does not exist'.format(field))\n    return self.data[field]\n\n  def get_coordinates(self):\n    \"\"\"Get corner coordinates of boxes.\n\n    Returns:\n     a list of 4 1-d numpy arrays [y_min, x_min, y_max, x_max]\n    \"\"\"\n    box_coordinates = self.get()\n    y_min = box_coordinates[:, 0]\n    x_min = box_coordinates[:, 1]\n    y_max = box_coordinates[:, 2]\n    x_max = box_coordinates[:, 3]\n    return [y_min, x_min, y_max, x_max]\n\n  def _is_valid_boxes(self, data):\n    \"\"\"Check whether data fullfills the format of N*[ymin, xmin, ymax, xmin].\n\n    Args:\n      data: a numpy array of shape [N, 4] representing box coordinates\n\n    Returns:\n      a boolean indicating whether all ymax of boxes are equal or greater than\n          ymin, and all xmax of boxes are equal or greater than xmin.\n    \"\"\"\n    if data.shape[0] > 0:\n      for i in xrange(data.shape[0]):\n        if data[i, 0] > data[i, 2] or data[i, 1] > data[i, 3]:\n          return False\n    return True\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/np_box_list_ops.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Bounding Box List operations for Numpy BoxLists.\n\nExample box operations that are supported:\n  * Areas: compute bounding box areas\n  * IOU: pairwise intersection-over-union scores\n\"\"\"\n\nimport numpy as np\n\nfrom object_detection.utils import np_box_list\nfrom object_detection.utils import np_box_ops\n\n\nclass SortOrder(object):\n  \"\"\"Enum class for sort order.\n\n  Attributes:\n    ascend: ascend order.\n    descend: descend order.\n  \"\"\"\n  ASCEND = 1\n  DESCEND = 2\n\n\ndef area(boxlist):\n  \"\"\"Computes area of boxes.\n\n  Args:\n    boxlist: BoxList holding N boxes\n\n  Returns:\n    a numpy array with shape [N*1] representing box areas\n  \"\"\"\n  y_min, x_min, y_max, x_max = boxlist.get_coordinates()\n  return (y_max - y_min) * (x_max - x_min)\n\n\ndef intersection(boxlist1, boxlist2):\n  \"\"\"Compute pairwise intersection areas between boxes.\n\n  Args:\n    boxlist1: BoxList holding N boxes\n    boxlist2: BoxList holding M boxes\n\n  Returns:\n    a numpy array with shape [N*M] representing pairwise intersection area\n  \"\"\"\n  return np_box_ops.intersection(boxlist1.get(), boxlist2.get())\n\n\ndef iou(boxlist1, boxlist2):\n  \"\"\"Computes pairwise intersection-over-union between box collections.\n\n  Args:\n    boxlist1: BoxList holding N boxes\n    boxlist2: BoxList holding M boxes\n\n  Returns:\n    a numpy array with shape [N, M] representing pairwise iou scores.\n  \"\"\"\n  return np_box_ops.iou(boxlist1.get(), boxlist2.get())\n\n\ndef ioa(boxlist1, boxlist2):\n  \"\"\"Computes pairwise intersection-over-area between box collections.\n\n  Intersection-over-area (ioa) between two boxes box1 and box2 is defined as\n  their intersection area over box2's area. Note that ioa is not symmetric,\n  that is, IOA(box1, box2) != IOA(box2, box1).\n\n  Args:\n    boxlist1: BoxList holding N boxes\n    boxlist2: BoxList holding M boxes\n\n  Returns:\n    a numpy array with shape [N, M] representing pairwise ioa scores.\n  \"\"\"\n  return np_box_ops.ioa(boxlist1.get(), boxlist2.get())\n\n\ndef gather(boxlist, indices, fields=None):\n  \"\"\"Gather boxes from BoxList according to indices and return new BoxList.\n\n  By default, Gather returns boxes corresponding to the input index list, as\n  well as all additional fields stored in the boxlist (indexing into the\n  first dimension).  However one can optionally only gather from a\n  subset of fields.\n\n  Args:\n    boxlist: BoxList holding N boxes\n    indices: a 1-d numpy array of type int_\n    fields: (optional) list of fields to also gather from.  If None (default),\n        all fields are gathered from.  Pass an empty fields list to only gather\n        the box coordinates.\n\n  Returns:\n    subboxlist: a BoxList corresponding to the subset of the input BoxList\n        specified by indices\n\n  Raises:\n    ValueError: if specified field is not contained in boxlist or if the\n        indices are not of type int_\n  \"\"\"\n  if indices.size:\n    if np.amax(indices) >= boxlist.num_boxes() or np.amin(indices) < 0:\n      raise ValueError('indices are out of valid range.')\n  subboxlist = np_box_list.BoxList(boxlist.get()[indices, :])\n  if fields is None:\n    fields = boxlist.get_extra_fields()\n  for field in fields:\n    extra_field_data = boxlist.get_field(field)\n    subboxlist.add_field(field, extra_field_data[indices, ...])\n  return subboxlist\n\n\ndef sort_by_field(boxlist, field, order=SortOrder.DESCEND):\n  \"\"\"Sort boxes and associated fields according to a scalar field.\n\n  A common use case is reordering the boxes according to descending scores.\n\n  Args:\n    boxlist: BoxList holding N boxes.\n    field: A BoxList field for sorting and reordering the BoxList.\n    order: (Optional) 'descend' or 'ascend'. Default is descend.\n\n  Returns:\n    sorted_boxlist: A sorted BoxList with the field in the specified order.\n\n  Raises:\n    ValueError: if specified field does not exist or is not of single dimension.\n    ValueError: if the order is not either descend or ascend.\n  \"\"\"\n  if not boxlist.has_field(field):\n    raise ValueError('Field ' + field + ' does not exist')\n  if len(boxlist.get_field(field).shape) != 1:\n    raise ValueError('Field ' + field + 'should be single dimension.')\n  if order != SortOrder.DESCEND and order != SortOrder.ASCEND:\n    raise ValueError('Invalid sort order')\n\n  field_to_sort = boxlist.get_field(field)\n  sorted_indices = np.argsort(field_to_sort)\n  if order == SortOrder.DESCEND:\n    sorted_indices = sorted_indices[::-1]\n  return gather(boxlist, sorted_indices)\n\n\ndef non_max_suppression(boxlist,\n                        max_output_size=10000,\n                        iou_threshold=1.0,\n                        score_threshold=-10.0):\n  \"\"\"Non maximum suppression.\n\n  This op greedily selects a subset of detection bounding boxes, pruning\n  away boxes that have high IOU (intersection over union) overlap (> thresh)\n  with already selected boxes. In each iteration, the detected bounding box with\n  highest score in the available pool is selected.\n\n  Args:\n    boxlist: BoxList holding N boxes.  Must contain a 'scores' field\n      representing detection scores. All scores belong to the same class.\n    max_output_size: maximum number of retained boxes\n    iou_threshold: intersection over union threshold.\n    score_threshold: minimum score threshold. Remove the boxes with scores\n                     less than this value. Default value is set to -10. A very\n                     low threshold to pass pretty much all the boxes, unless\n                     the user sets a different score threshold.\n\n  Returns:\n    a BoxList holding M boxes where M <= max_output_size\n  Raises:\n    ValueError: if 'scores' field does not exist\n    ValueError: if threshold is not in [0, 1]\n    ValueError: if max_output_size < 0\n  \"\"\"\n  if not boxlist.has_field('scores'):\n    raise ValueError('Field scores does not exist')\n  if iou_threshold < 0. or iou_threshold > 1.0:\n    raise ValueError('IOU threshold must be in [0, 1]')\n  if max_output_size < 0:\n    raise ValueError('max_output_size must be bigger than 0.')\n\n  boxlist = filter_scores_greater_than(boxlist, score_threshold)\n  if boxlist.num_boxes() == 0:\n    return boxlist\n\n  boxlist = sort_by_field(boxlist, 'scores')\n\n  # Prevent further computation if NMS is disabled.\n  if iou_threshold == 1.0:\n    if boxlist.num_boxes() > max_output_size:\n      selected_indices = np.arange(max_output_size)\n      return gather(boxlist, selected_indices)\n    else:\n      return boxlist\n\n  boxes = boxlist.get()\n  num_boxes = boxlist.num_boxes()\n  # is_index_valid is True only for all remaining valid boxes,\n  is_index_valid = np.full(num_boxes, 1, dtype=bool)\n  selected_indices = []\n  num_output = 0\n  for i in xrange(num_boxes):\n    if num_output < max_output_size:\n      if is_index_valid[i]:\n        num_output += 1\n        selected_indices.append(i)\n        is_index_valid[i] = False\n        valid_indices = np.where(is_index_valid)[0]\n        if valid_indices.size == 0:\n          break\n\n        intersect_over_union = np_box_ops.iou(\n            np.expand_dims(boxes[i, :], axis=0), boxes[valid_indices, :])\n        intersect_over_union = np.squeeze(intersect_over_union, axis=0)\n        is_index_valid[valid_indices] = np.logical_and(\n            is_index_valid[valid_indices],\n            intersect_over_union <= iou_threshold)\n  return gather(boxlist, np.array(selected_indices))\n\n\ndef multi_class_non_max_suppression(boxlist, score_thresh, iou_thresh,\n                                    max_output_size):\n  \"\"\"Multi-class version of non maximum suppression.\n\n  This op greedily selects a subset of detection bounding boxes, pruning\n  away boxes that have high IOU (intersection over union) overlap (> thresh)\n  with already selected boxes.  It operates independently for each class for\n  which scores are provided (via the scores field of the input box_list),\n  pruning boxes with score less than a provided threshold prior to\n  applying NMS.\n\n  Args:\n    boxlist: BoxList holding N boxes.  Must contain a 'scores' field\n      representing detection scores.  This scores field is a tensor that can\n      be 1 dimensional (in the case of a single class) or 2-dimensional, which\n      which case we assume that it takes the shape [num_boxes, num_classes].\n      We further assume that this rank is known statically and that\n      scores.shape[1] is also known (i.e., the number of classes is fixed\n      and known at graph construction time).\n    score_thresh: scalar threshold for score (low scoring boxes are removed).\n    iou_thresh: scalar threshold for IOU (boxes that that high IOU overlap\n      with previously selected boxes are removed).\n    max_output_size: maximum number of retained boxes per class.\n\n  Returns:\n    a BoxList holding M boxes with a rank-1 scores field representing\n      corresponding scores for each box with scores sorted in decreasing order\n      and a rank-1 classes field representing a class label for each box.\n  Raises:\n    ValueError: if iou_thresh is not in [0, 1] or if input boxlist does not have\n      a valid scores field.\n  \"\"\"\n  if not 0 <= iou_thresh <= 1.0:\n    raise ValueError('thresh must be between 0 and 1')\n  if not isinstance(boxlist, np_box_list.BoxList):\n    raise ValueError('boxlist must be a BoxList')\n  if not boxlist.has_field('scores'):\n    raise ValueError('input boxlist must have \\'scores\\' field')\n  scores = boxlist.get_field('scores')\n  if len(scores.shape) == 1:\n    scores = np.reshape(scores, [-1, 1])\n  elif len(scores.shape) == 2:\n    if scores.shape[1] is None:\n      raise ValueError('scores field must have statically defined second '\n                       'dimension')\n  else:\n    raise ValueError('scores field must be of rank 1 or 2')\n  num_boxes = boxlist.num_boxes()\n  num_scores = scores.shape[0]\n  num_classes = scores.shape[1]\n\n  if num_boxes != num_scores:\n    raise ValueError('Incorrect scores field length: actual vs expected.')\n\n  selected_boxes_list = []\n  for class_idx in range(num_classes):\n    boxlist_and_class_scores = np_box_list.BoxList(boxlist.get())\n    class_scores = np.reshape(scores[0:num_scores, class_idx], [-1])\n    boxlist_and_class_scores.add_field('scores', class_scores)\n    boxlist_filt = filter_scores_greater_than(boxlist_and_class_scores,\n                                              score_thresh)\n    nms_result = non_max_suppression(boxlist_filt,\n                                     max_output_size=max_output_size,\n                                     iou_threshold=iou_thresh,\n                                     score_threshold=score_thresh)\n    nms_result.add_field(\n        'classes', np.zeros_like(nms_result.get_field('scores')) + class_idx)\n    selected_boxes_list.append(nms_result)\n  selected_boxes = concatenate(selected_boxes_list)\n  sorted_boxes = sort_by_field(selected_boxes, 'scores')\n  return sorted_boxes\n\n\ndef scale(boxlist, y_scale, x_scale):\n  \"\"\"Scale box coordinates in x and y dimensions.\n\n  Args:\n    boxlist: BoxList holding N boxes\n    y_scale: float\n    x_scale: float\n\n  Returns:\n    boxlist: BoxList holding N boxes\n  \"\"\"\n  y_min, x_min, y_max, x_max = np.array_split(boxlist.get(), 4, axis=1)\n  y_min = y_scale * y_min\n  y_max = y_scale * y_max\n  x_min = x_scale * x_min\n  x_max = x_scale * x_max\n  scaled_boxlist = np_box_list.BoxList(np.hstack([y_min, x_min, y_max, x_max]))\n\n  fields = boxlist.get_extra_fields()\n  for field in fields:\n    extra_field_data = boxlist.get_field(field)\n    scaled_boxlist.add_field(field, extra_field_data)\n\n  return scaled_boxlist\n\n\ndef clip_to_window(boxlist, window):\n  \"\"\"Clip bounding boxes to a window.\n\n  This op clips input bounding boxes (represented by bounding box\n  corners) to a window, optionally filtering out boxes that do not\n  overlap at all with the window.\n\n  Args:\n    boxlist: BoxList holding M_in boxes\n    window: a numpy array of shape [4] representing the\n            [y_min, x_min, y_max, x_max] window to which the op\n            should clip boxes.\n\n  Returns:\n    a BoxList holding M_out boxes where M_out <= M_in\n  \"\"\"\n  y_min, x_min, y_max, x_max = np.array_split(boxlist.get(), 4, axis=1)\n  win_y_min = window[0]\n  win_x_min = window[1]\n  win_y_max = window[2]\n  win_x_max = window[3]\n  y_min_clipped = np.fmax(np.fmin(y_min, win_y_max), win_y_min)\n  y_max_clipped = np.fmax(np.fmin(y_max, win_y_max), win_y_min)\n  x_min_clipped = np.fmax(np.fmin(x_min, win_x_max), win_x_min)\n  x_max_clipped = np.fmax(np.fmin(x_max, win_x_max), win_x_min)\n  clipped = np_box_list.BoxList(\n      np.hstack([y_min_clipped, x_min_clipped, y_max_clipped, x_max_clipped]))\n  clipped = _copy_extra_fields(clipped, boxlist)\n  areas = area(clipped)\n  nonzero_area_indices = np.reshape(np.nonzero(np.greater(areas, 0.0)),\n                                    [-1]).astype(np.int32)\n  return gather(clipped, nonzero_area_indices)\n\n\ndef prune_non_overlapping_boxes(boxlist1, boxlist2, minoverlap=0.0):\n  \"\"\"Prunes the boxes in boxlist1 that overlap less than thresh with boxlist2.\n\n  For each box in boxlist1, we want its IOA to be more than minoverlap with\n  at least one of the boxes in boxlist2. If it does not, we remove it.\n\n  Args:\n    boxlist1: BoxList holding N boxes.\n    boxlist2: BoxList holding M boxes.\n    minoverlap: Minimum required overlap between boxes, to count them as\n                overlapping.\n\n  Returns:\n    A pruned boxlist with size [N', 4].\n  \"\"\"\n  intersection_over_area = ioa(boxlist2, boxlist1)  # [M, N] tensor\n  intersection_over_area = np.amax(intersection_over_area, axis=0)  # [N] tensor\n  keep_bool = np.greater_equal(intersection_over_area, np.array(minoverlap))\n  keep_inds = np.nonzero(keep_bool)[0]\n  new_boxlist1 = gather(boxlist1, keep_inds)\n  return new_boxlist1\n\n\ndef prune_outside_window(boxlist, window):\n  \"\"\"Prunes bounding boxes that fall outside a given window.\n\n  This function prunes bounding boxes that even partially fall outside the given\n  window. See also ClipToWindow which only prunes bounding boxes that fall\n  completely outside the window, and clips any bounding boxes that partially\n  overflow.\n\n  Args:\n    boxlist: a BoxList holding M_in boxes.\n    window: a numpy array of size 4, representing [ymin, xmin, ymax, xmax]\n            of the window.\n\n  Returns:\n    pruned_corners: a tensor with shape [M_out, 4] where M_out <= M_in.\n    valid_indices: a tensor with shape [M_out] indexing the valid bounding boxes\n     in the input tensor.\n  \"\"\"\n\n  y_min, x_min, y_max, x_max = np.array_split(boxlist.get(), 4, axis=1)\n  win_y_min = window[0]\n  win_x_min = window[1]\n  win_y_max = window[2]\n  win_x_max = window[3]\n  coordinate_violations = np.hstack([np.less(y_min, win_y_min),\n                                     np.less(x_min, win_x_min),\n                                     np.greater(y_max, win_y_max),\n                                     np.greater(x_max, win_x_max)])\n  valid_indices = np.reshape(\n      np.where(np.logical_not(np.max(coordinate_violations, axis=1))), [-1])\n  return gather(boxlist, valid_indices), valid_indices\n\n\ndef concatenate(boxlists, fields=None):\n  \"\"\"Concatenate list of BoxLists.\n\n  This op concatenates a list of input BoxLists into a larger BoxList.  It also\n  handles concatenation of BoxList fields as long as the field tensor shapes\n  are equal except for the first dimension.\n\n  Args:\n    boxlists: list of BoxList objects\n    fields: optional list of fields to also concatenate.  By default, all\n      fields from the first BoxList in the list are included in the\n      concatenation.\n\n  Returns:\n    a BoxList with number of boxes equal to\n      sum([boxlist.num_boxes() for boxlist in BoxList])\n  Raises:\n    ValueError: if boxlists is invalid (i.e., is not a list, is empty, or\n      contains non BoxList objects), or if requested fields are not contained in\n      all boxlists\n  \"\"\"\n  if not isinstance(boxlists, list):\n    raise ValueError('boxlists should be a list')\n  if not boxlists:\n    raise ValueError('boxlists should have nonzero length')\n  for boxlist in boxlists:\n    if not isinstance(boxlist, np_box_list.BoxList):\n      raise ValueError('all elements of boxlists should be BoxList objects')\n  concatenated = np_box_list.BoxList(\n      np.vstack([boxlist.get() for boxlist in boxlists]))\n  if fields is None:\n    fields = boxlists[0].get_extra_fields()\n  for field in fields:\n    first_field_shape = boxlists[0].get_field(field).shape\n    first_field_shape = first_field_shape[1:]\n    for boxlist in boxlists:\n      if not boxlist.has_field(field):\n        raise ValueError('boxlist must contain all requested fields')\n      field_shape = boxlist.get_field(field).shape\n      field_shape = field_shape[1:]\n      if field_shape != first_field_shape:\n        raise ValueError('field %s must have same shape for all boxlists '\n                         'except for the 0th dimension.' % field)\n    concatenated_field = np.concatenate(\n        [boxlist.get_field(field) for boxlist in boxlists], axis=0)\n    concatenated.add_field(field, concatenated_field)\n  return concatenated\n\n\ndef filter_scores_greater_than(boxlist, thresh):\n  \"\"\"Filter to keep only boxes with score exceeding a given threshold.\n\n  This op keeps the collection of boxes whose corresponding scores are\n  greater than the input threshold.\n\n  Args:\n    boxlist: BoxList holding N boxes.  Must contain a 'scores' field\n      representing detection scores.\n    thresh: scalar threshold\n\n  Returns:\n    a BoxList holding M boxes where M <= N\n\n  Raises:\n    ValueError: if boxlist not a BoxList object or if it does not\n      have a scores field\n  \"\"\"\n  if not isinstance(boxlist, np_box_list.BoxList):\n    raise ValueError('boxlist must be a BoxList')\n  if not boxlist.has_field('scores'):\n    raise ValueError('input boxlist must have \\'scores\\' field')\n  scores = boxlist.get_field('scores')\n  if len(scores.shape) > 2:\n    raise ValueError('Scores should have rank 1 or 2')\n  if len(scores.shape) == 2 and scores.shape[1] != 1:\n    raise ValueError('Scores should have rank 1 or have shape '\n                     'consistent with [None, 1]')\n  high_score_indices = np.reshape(np.where(np.greater(scores, thresh)),\n                                  [-1]).astype(np.int32)\n  return gather(boxlist, high_score_indices)\n\n\ndef change_coordinate_frame(boxlist, window):\n  \"\"\"Change coordinate frame of the boxlist to be relative to window's frame.\n\n  Given a window of the form [ymin, xmin, ymax, xmax],\n  changes bounding box coordinates from boxlist to be relative to this window\n  (e.g., the min corner maps to (0,0) and the max corner maps to (1,1)).\n\n  An example use case is data augmentation: where we are given groundtruth\n  boxes (boxlist) and would like to randomly crop the image to some\n  window (window). In this case we need to change the coordinate frame of\n  each groundtruth box to be relative to this new window.\n\n  Args:\n    boxlist: A BoxList object holding N boxes.\n    window: a size 4 1-D numpy array.\n\n  Returns:\n    Returns a BoxList object with N boxes.\n  \"\"\"\n  win_height = window[2] - window[0]\n  win_width = window[3] - window[1]\n  boxlist_new = scale(\n      np_box_list.BoxList(boxlist.get() -\n                          [window[0], window[1], window[0], window[1]]),\n      1.0 / win_height, 1.0 / win_width)\n  _copy_extra_fields(boxlist_new, boxlist)\n\n  return boxlist_new\n\n\ndef _copy_extra_fields(boxlist_to_copy_to, boxlist_to_copy_from):\n  \"\"\"Copies the extra fields of boxlist_to_copy_from to boxlist_to_copy_to.\n\n  Args:\n    boxlist_to_copy_to: BoxList to which extra fields are copied.\n    boxlist_to_copy_from: BoxList from which fields are copied.\n\n  Returns:\n    boxlist_to_copy_to with extra fields.\n  \"\"\"\n  for field in boxlist_to_copy_from.get_extra_fields():\n    boxlist_to_copy_to.add_field(field, boxlist_to_copy_from.get_field(field))\n  return boxlist_to_copy_to\n\n\ndef _update_valid_indices_by_removing_high_iou_boxes(\n    selected_indices, is_index_valid, intersect_over_union, threshold):\n  max_iou = np.max(intersect_over_union[:, selected_indices], axis=1)\n  return np.logical_and(is_index_valid, max_iou <= threshold)\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/np_box_list_ops_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.utils.np_box_list_ops.\"\"\"\n\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.utils import np_box_list\nfrom object_detection.utils import np_box_list_ops\n\n\nclass AreaRelatedTest(tf.test.TestCase):\n\n  def setUp(self):\n    boxes1 = np.array([[4.0, 3.0, 7.0, 5.0], [5.0, 6.0, 10.0, 7.0]],\n                      dtype=float)\n    boxes2 = np.array([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0],\n                       [0.0, 0.0, 20.0, 20.0]],\n                      dtype=float)\n    self.boxlist1 = np_box_list.BoxList(boxes1)\n    self.boxlist2 = np_box_list.BoxList(boxes2)\n\n  def test_area(self):\n    areas = np_box_list_ops.area(self.boxlist1)\n    expected_areas = np.array([6.0, 5.0], dtype=float)\n    self.assertAllClose(expected_areas, areas)\n\n  def test_intersection(self):\n    intersection = np_box_list_ops.intersection(self.boxlist1, self.boxlist2)\n    expected_intersection = np.array([[2.0, 0.0, 6.0], [1.0, 0.0, 5.0]],\n                                     dtype=float)\n    self.assertAllClose(intersection, expected_intersection)\n\n  def test_iou(self):\n    iou = np_box_list_ops.iou(self.boxlist1, self.boxlist2)\n    expected_iou = np.array([[2.0 / 16.0, 0.0, 6.0 / 400.0],\n                             [1.0 / 16.0, 0.0, 5.0 / 400.0]],\n                            dtype=float)\n    self.assertAllClose(iou, expected_iou)\n\n  def test_ioa(self):\n    boxlist1 = np_box_list.BoxList(\n        np.array(\n            [[0.25, 0.25, 0.75, 0.75], [0.0, 0.0, 0.5, 0.75]], dtype=\n            np.float32))\n    boxlist2 = np_box_list.BoxList(\n        np.array(\n            [[0.5, 0.25, 1.0, 1.0], [0.0, 0.0, 1.0, 1.0]], dtype=np.float32))\n    ioa21 = np_box_list_ops.ioa(boxlist2, boxlist1)\n    expected_ioa21 = np.array([[0.5, 0.0],\n                               [1.0, 1.0]],\n                              dtype=np.float32)\n    self.assertAllClose(ioa21, expected_ioa21)\n\n  def test_scale(self):\n    boxlist = np_box_list.BoxList(\n        np.array(\n            [[0.25, 0.25, 0.75, 0.75], [0.0, 0.0, 0.5, 0.75]], dtype=\n            np.float32))\n    boxlist_scaled = np_box_list_ops.scale(boxlist, 2.0, 3.0)\n    expected_boxlist_scaled = np_box_list.BoxList(\n        np.array(\n            [[0.5, 0.75, 1.5, 2.25], [0.0, 0.0, 1.0, 2.25]], dtype=np.float32))\n    self.assertAllClose(expected_boxlist_scaled.get(), boxlist_scaled.get())\n\n  def test_clip_to_window(self):\n    boxlist = np_box_list.BoxList(\n        np.array(\n            [[0.25, 0.25, 0.75, 0.75], [0.0, 0.0, 0.5, 0.75],\n             [-0.2, -0.3, 0.7, 1.5]],\n            dtype=np.float32))\n    boxlist_clipped = np_box_list_ops.clip_to_window(boxlist,\n                                                     [0.0, 0.0, 1.0, 1.0])\n    expected_boxlist_clipped = np_box_list.BoxList(\n        np.array(\n            [[0.25, 0.25, 0.75, 0.75], [0.0, 0.0, 0.5, 0.75],\n             [0.0, 0.0, 0.7, 1.0]],\n            dtype=np.float32))\n    self.assertAllClose(expected_boxlist_clipped.get(), boxlist_clipped.get())\n\n  def test_prune_outside_window(self):\n    boxlist = np_box_list.BoxList(\n        np.array(\n            [[0.25, 0.25, 0.75, 0.75], [0.0, 0.0, 0.5, 0.75],\n             [-0.2, -0.3, 0.7, 1.5]],\n            dtype=np.float32))\n    boxlist_pruned, _ = np_box_list_ops.prune_outside_window(\n        boxlist, [0.0, 0.0, 1.0, 1.0])\n    expected_boxlist_pruned = np_box_list.BoxList(\n        np.array(\n            [[0.25, 0.25, 0.75, 0.75], [0.0, 0.0, 0.5, 0.75]], dtype=\n            np.float32))\n    self.assertAllClose(expected_boxlist_pruned.get(), boxlist_pruned.get())\n\n  def test_concatenate(self):\n    boxlist1 = np_box_list.BoxList(\n        np.array(\n            [[0.25, 0.25, 0.75, 0.75], [0.0, 0.0, 0.5, 0.75]], dtype=\n            np.float32))\n    boxlist2 = np_box_list.BoxList(\n        np.array(\n            [[0.5, 0.25, 1.0, 1.0], [0.0, 0.0, 1.0, 1.0]], dtype=np.float32))\n    boxlists = [boxlist1, boxlist2]\n    boxlist_concatenated = np_box_list_ops.concatenate(boxlists)\n    boxlist_concatenated_expected = np_box_list.BoxList(\n        np.array(\n            [[0.25, 0.25, 0.75, 0.75], [0.0, 0.0, 0.5, 0.75],\n             [0.5, 0.25, 1.0, 1.0], [0.0, 0.0, 1.0, 1.0]],\n            dtype=np.float32))\n    self.assertAllClose(boxlist_concatenated_expected.get(),\n                        boxlist_concatenated.get())\n\n  def test_change_coordinate_frame(self):\n    boxlist = np_box_list.BoxList(\n        np.array(\n            [[0.25, 0.25, 0.75, 0.75], [0.0, 0.0, 0.5, 0.75]], dtype=\n            np.float32))\n    boxlist_coord = np_box_list_ops.change_coordinate_frame(\n        boxlist, np.array([0, 0, 0.5, 0.5], dtype=np.float32))\n    expected_boxlist_coord = np_box_list.BoxList(\n        np.array([[0.5, 0.5, 1.5, 1.5], [0, 0, 1.0, 1.5]], dtype=np.float32))\n    self.assertAllClose(boxlist_coord.get(), expected_boxlist_coord.get())\n\n  def test_filter_scores_greater_than(self):\n    boxlist = np_box_list.BoxList(\n        np.array(\n            [[0.25, 0.25, 0.75, 0.75], [0.0, 0.0, 0.5, 0.75]], dtype=\n            np.float32))\n    boxlist.add_field('scores', np.array([0.8, 0.2], np.float32))\n    boxlist_greater = np_box_list_ops.filter_scores_greater_than(boxlist, 0.5)\n\n    expected_boxlist_greater = np_box_list.BoxList(\n        np.array([[0.25, 0.25, 0.75, 0.75]], dtype=np.float32))\n\n    self.assertAllClose(boxlist_greater.get(), expected_boxlist_greater.get())\n\n\nclass GatherOpsTest(tf.test.TestCase):\n\n  def setUp(self):\n    boxes = np.array([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0],\n                      [0.0, 0.0, 20.0, 20.0]],\n                     dtype=float)\n    self.boxlist = np_box_list.BoxList(boxes)\n    self.boxlist.add_field('scores', np.array([0.5, 0.7, 0.9], dtype=float))\n    self.boxlist.add_field('labels',\n                           np.array([[0, 0, 0, 1, 0], [0, 1, 0, 0, 0],\n                                     [0, 0, 0, 0, 1]],\n                                    dtype=int))\n\n  def test_gather_with_out_of_range_indices(self):\n    indices = np.array([3, 1], dtype=int)\n    boxlist = self.boxlist\n    with self.assertRaises(ValueError):\n      np_box_list_ops.gather(boxlist, indices)\n\n  def test_gather_with_invalid_multidimensional_indices(self):\n    indices = np.array([[0, 1], [1, 2]], dtype=int)\n    boxlist = self.boxlist\n    with self.assertRaises(ValueError):\n      np_box_list_ops.gather(boxlist, indices)\n\n  def test_gather_without_fields_specified(self):\n    indices = np.array([2, 0, 1], dtype=int)\n    boxlist = self.boxlist\n    subboxlist = np_box_list_ops.gather(boxlist, indices)\n\n    expected_scores = np.array([0.9, 0.5, 0.7], dtype=float)\n    self.assertAllClose(expected_scores, subboxlist.get_field('scores'))\n\n    expected_boxes = np.array([[0.0, 0.0, 20.0, 20.0], [3.0, 4.0, 6.0, 8.0],\n                               [14.0, 14.0, 15.0, 15.0]],\n                              dtype=float)\n    self.assertAllClose(expected_boxes, subboxlist.get())\n\n    expected_labels = np.array([[0, 0, 0, 0, 1], [0, 0, 0, 1, 0],\n                                [0, 1, 0, 0, 0]],\n                               dtype=int)\n    self.assertAllClose(expected_labels, subboxlist.get_field('labels'))\n\n  def test_gather_with_invalid_field_specified(self):\n    indices = np.array([2, 0, 1], dtype=int)\n    boxlist = self.boxlist\n\n    with self.assertRaises(ValueError):\n      np_box_list_ops.gather(boxlist, indices, 'labels')\n\n    with self.assertRaises(ValueError):\n      np_box_list_ops.gather(boxlist, indices, ['objectness'])\n\n  def test_gather_with_fields_specified(self):\n    indices = np.array([2, 0, 1], dtype=int)\n    boxlist = self.boxlist\n    subboxlist = np_box_list_ops.gather(boxlist, indices, ['labels'])\n\n    self.assertFalse(subboxlist.has_field('scores'))\n\n    expected_boxes = np.array([[0.0, 0.0, 20.0, 20.0], [3.0, 4.0, 6.0, 8.0],\n                               [14.0, 14.0, 15.0, 15.0]],\n                              dtype=float)\n    self.assertAllClose(expected_boxes, subboxlist.get())\n\n    expected_labels = np.array([[0, 0, 0, 0, 1], [0, 0, 0, 1, 0],\n                                [0, 1, 0, 0, 0]],\n                               dtype=int)\n    self.assertAllClose(expected_labels, subboxlist.get_field('labels'))\n\n\nclass SortByFieldTest(tf.test.TestCase):\n\n  def setUp(self):\n    boxes = np.array([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0],\n                      [0.0, 0.0, 20.0, 20.0]],\n                     dtype=float)\n    self.boxlist = np_box_list.BoxList(boxes)\n    self.boxlist.add_field('scores', np.array([0.5, 0.9, 0.4], dtype=float))\n    self.boxlist.add_field('labels',\n                           np.array([[0, 0, 0, 1, 0], [0, 1, 0, 0, 0],\n                                     [0, 0, 0, 0, 1]],\n                                    dtype=int))\n\n  def test_with_invalid_field(self):\n    with self.assertRaises(ValueError):\n      np_box_list_ops.sort_by_field(self.boxlist, 'objectness')\n    with self.assertRaises(ValueError):\n      np_box_list_ops.sort_by_field(self.boxlist, 'labels')\n\n  def test_with_invalid_sorting_order(self):\n    with self.assertRaises(ValueError):\n      np_box_list_ops.sort_by_field(self.boxlist, 'scores', 'Descending')\n\n  def test_with_descending_sorting(self):\n    sorted_boxlist = np_box_list_ops.sort_by_field(self.boxlist, 'scores')\n\n    expected_boxes = np.array([[14.0, 14.0, 15.0, 15.0], [3.0, 4.0, 6.0, 8.0],\n                               [0.0, 0.0, 20.0, 20.0]],\n                              dtype=float)\n    self.assertAllClose(expected_boxes, sorted_boxlist.get())\n\n    expected_scores = np.array([0.9, 0.5, 0.4], dtype=float)\n    self.assertAllClose(expected_scores, sorted_boxlist.get_field('scores'))\n\n  def test_with_ascending_sorting(self):\n    sorted_boxlist = np_box_list_ops.sort_by_field(\n        self.boxlist, 'scores', np_box_list_ops.SortOrder.ASCEND)\n\n    expected_boxes = np.array([[0.0, 0.0, 20.0, 20.0],\n                               [3.0, 4.0, 6.0, 8.0],\n                               [14.0, 14.0, 15.0, 15.0],],\n                              dtype=float)\n    self.assertAllClose(expected_boxes, sorted_boxlist.get())\n\n    expected_scores = np.array([0.4, 0.5, 0.9], dtype=float)\n    self.assertAllClose(expected_scores, sorted_boxlist.get_field('scores'))\n\n\nclass NonMaximumSuppressionTest(tf.test.TestCase):\n\n  def setUp(self):\n    self._boxes = np.array([[0, 0, 1, 1],\n                            [0, 0.1, 1, 1.1],\n                            [0, -0.1, 1, 0.9],\n                            [0, 10, 1, 11],\n                            [0, 10.1, 1, 11.1],\n                            [0, 100, 1, 101]],\n                           dtype=float)\n    self._boxlist = np_box_list.BoxList(self._boxes)\n\n  def test_with_no_scores_field(self):\n    boxlist = np_box_list.BoxList(self._boxes)\n    max_output_size = 3\n    iou_threshold = 0.5\n\n    with self.assertRaises(ValueError):\n      np_box_list_ops.non_max_suppression(\n          boxlist, max_output_size, iou_threshold)\n\n  def test_nms_disabled_max_output_size_equals_three(self):\n    boxlist = np_box_list.BoxList(self._boxes)\n    boxlist.add_field('scores',\n                      np.array([.9, .75, .6, .95, .2, .3], dtype=float))\n    max_output_size = 3\n    iou_threshold = 1.  # No NMS\n\n    expected_boxes = np.array([[0, 10, 1, 11], [0, 0, 1, 1], [0, 0.1, 1, 1.1]],\n                              dtype=float)\n    nms_boxlist = np_box_list_ops.non_max_suppression(\n        boxlist, max_output_size, iou_threshold)\n    self.assertAllClose(nms_boxlist.get(), expected_boxes)\n\n  def test_select_from_three_clusters(self):\n    boxlist = np_box_list.BoxList(self._boxes)\n    boxlist.add_field('scores',\n                      np.array([.9, .75, .6, .95, .2, .3], dtype=float))\n    max_output_size = 3\n    iou_threshold = 0.5\n\n    expected_boxes = np.array([[0, 10, 1, 11], [0, 0, 1, 1], [0, 100, 1, 101]],\n                              dtype=float)\n    nms_boxlist = np_box_list_ops.non_max_suppression(\n        boxlist, max_output_size, iou_threshold)\n    self.assertAllClose(nms_boxlist.get(), expected_boxes)\n\n  def test_select_at_most_two_from_three_clusters(self):\n    boxlist = np_box_list.BoxList(self._boxes)\n    boxlist.add_field('scores',\n                      np.array([.9, .75, .6, .95, .5, .3], dtype=float))\n    max_output_size = 2\n    iou_threshold = 0.5\n\n    expected_boxes = np.array([[0, 10, 1, 11], [0, 0, 1, 1]], dtype=float)\n    nms_boxlist = np_box_list_ops.non_max_suppression(\n        boxlist, max_output_size, iou_threshold)\n    self.assertAllClose(nms_boxlist.get(), expected_boxes)\n\n  def test_select_at_most_thirty_from_three_clusters(self):\n    boxlist = np_box_list.BoxList(self._boxes)\n    boxlist.add_field('scores',\n                      np.array([.9, .75, .6, .95, .5, .3], dtype=float))\n    max_output_size = 30\n    iou_threshold = 0.5\n\n    expected_boxes = np.array([[0, 10, 1, 11], [0, 0, 1, 1], [0, 100, 1, 101]],\n                              dtype=float)\n    nms_boxlist = np_box_list_ops.non_max_suppression(\n        boxlist, max_output_size, iou_threshold)\n    self.assertAllClose(nms_boxlist.get(), expected_boxes)\n\n  def test_select_from_ten_indentical_boxes(self):\n    boxes = np.array(10 * [[0, 0, 1, 1]], dtype=float)\n    boxlist = np_box_list.BoxList(boxes)\n    boxlist.add_field('scores', np.array(10 * [0.8]))\n    iou_threshold = .5\n    max_output_size = 3\n    expected_boxes = np.array([[0, 0, 1, 1]], dtype=float)\n    nms_boxlist = np_box_list_ops.non_max_suppression(\n        boxlist, max_output_size, iou_threshold)\n    self.assertAllClose(nms_boxlist.get(), expected_boxes)\n\n  def test_different_iou_threshold(self):\n    boxes = np.array([[0, 0, 20, 100], [0, 0, 20, 80], [200, 200, 210, 300],\n                      [200, 200, 210, 250]],\n                     dtype=float)\n    boxlist = np_box_list.BoxList(boxes)\n    boxlist.add_field('scores', np.array([0.9, 0.8, 0.7, 0.6]))\n    max_output_size = 4\n\n    iou_threshold = .4\n    expected_boxes = np.array([[0, 0, 20, 100],\n                               [200, 200, 210, 300],],\n                              dtype=float)\n    nms_boxlist = np_box_list_ops.non_max_suppression(\n        boxlist, max_output_size, iou_threshold)\n    self.assertAllClose(nms_boxlist.get(), expected_boxes)\n\n    iou_threshold = .5\n    expected_boxes = np.array([[0, 0, 20, 100], [200, 200, 210, 300],\n                               [200, 200, 210, 250]],\n                              dtype=float)\n    nms_boxlist = np_box_list_ops.non_max_suppression(\n        boxlist, max_output_size, iou_threshold)\n    self.assertAllClose(nms_boxlist.get(), expected_boxes)\n\n    iou_threshold = .8\n    expected_boxes = np.array([[0, 0, 20, 100], [0, 0, 20, 80],\n                               [200, 200, 210, 300], [200, 200, 210, 250]],\n                              dtype=float)\n    nms_boxlist = np_box_list_ops.non_max_suppression(\n        boxlist, max_output_size, iou_threshold)\n    self.assertAllClose(nms_boxlist.get(), expected_boxes)\n\n  def test_multiclass_nms(self):\n    boxlist = np_box_list.BoxList(\n        np.array(\n            [[0.2, 0.4, 0.8, 0.8], [0.4, 0.2, 0.8, 0.8], [0.6, 0.0, 1.0, 1.0]],\n            dtype=np.float32))\n    scores = np.array([[-0.2, 0.1, 0.5, -0.4, 0.3],\n                       [0.7, -0.7, 0.6, 0.2, -0.9],\n                       [0.4, 0.34, -0.9, 0.2, 0.31]],\n                      dtype=np.float32)\n    boxlist.add_field('scores', scores)\n    boxlist_clean = np_box_list_ops.multi_class_non_max_suppression(\n        boxlist, score_thresh=0.25, iou_thresh=0.1, max_output_size=3)\n\n    scores_clean = boxlist_clean.get_field('scores')\n    classes_clean = boxlist_clean.get_field('classes')\n    boxes = boxlist_clean.get()\n    expected_scores = np.array([0.7, 0.6, 0.34, 0.31])\n    expected_classes = np.array([0, 2, 1, 4])\n    expected_boxes = np.array([[0.4, 0.2, 0.8, 0.8],\n                               [0.4, 0.2, 0.8, 0.8],\n                               [0.6, 0.0, 1.0, 1.0],\n                               [0.6, 0.0, 1.0, 1.0]],\n                              dtype=np.float32)\n    self.assertAllClose(scores_clean, expected_scores)\n    self.assertAllClose(classes_clean, expected_classes)\n    self.assertAllClose(boxes, expected_boxes)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/np_box_list_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.utils.np_box_list_test.\"\"\"\n\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.utils import np_box_list\n\n\nclass BoxListTest(tf.test.TestCase):\n\n  def test_invalid_box_data(self):\n    with self.assertRaises(ValueError):\n      np_box_list.BoxList([0, 0, 1, 1])\n\n    with self.assertRaises(ValueError):\n      np_box_list.BoxList(np.array([[0, 0, 1, 1]], dtype=int))\n\n    with self.assertRaises(ValueError):\n      np_box_list.BoxList(np.array([0, 1, 1, 3, 4], dtype=float))\n\n    with self.assertRaises(ValueError):\n      np_box_list.BoxList(np.array([[0, 1, 1, 3], [3, 1, 1, 5]], dtype=float))\n\n  def test_has_field_with_existed_field(self):\n    boxes = np.array([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0],\n                      [0.0, 0.0, 20.0, 20.0]],\n                     dtype=float)\n    boxlist = np_box_list.BoxList(boxes)\n    self.assertTrue(boxlist.has_field('boxes'))\n\n  def test_has_field_with_nonexisted_field(self):\n    boxes = np.array([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0],\n                      [0.0, 0.0, 20.0, 20.0]],\n                     dtype=float)\n    boxlist = np_box_list.BoxList(boxes)\n    self.assertFalse(boxlist.has_field('scores'))\n\n  def test_get_field_with_existed_field(self):\n    boxes = np.array([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0],\n                      [0.0, 0.0, 20.0, 20.0]],\n                     dtype=float)\n    boxlist = np_box_list.BoxList(boxes)\n    self.assertTrue(np.allclose(boxlist.get_field('boxes'), boxes))\n\n  def test_get_field_with_nonexited_field(self):\n    boxes = np.array([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0],\n                      [0.0, 0.0, 20.0, 20.0]],\n                     dtype=float)\n    boxlist = np_box_list.BoxList(boxes)\n    with self.assertRaises(ValueError):\n      boxlist.get_field('scores')\n\n\nclass AddExtraFieldTest(tf.test.TestCase):\n\n  def setUp(self):\n    boxes = np.array([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0],\n                      [0.0, 0.0, 20.0, 20.0]],\n                     dtype=float)\n    self.boxlist = np_box_list.BoxList(boxes)\n\n  def test_add_already_existed_field(self):\n    with self.assertRaises(ValueError):\n      self.boxlist.add_field('boxes', np.array([[0, 0, 0, 1, 0]], dtype=float))\n\n  def test_add_invalid_field_data(self):\n    with self.assertRaises(ValueError):\n      self.boxlist.add_field('scores', np.array([0.5, 0.7], dtype=float))\n    with self.assertRaises(ValueError):\n      self.boxlist.add_field('scores',\n                             np.array([0.5, 0.7, 0.9, 0.1], dtype=float))\n\n  def test_add_single_dimensional_field_data(self):\n    boxlist = self.boxlist\n    scores = np.array([0.5, 0.7, 0.9], dtype=float)\n    boxlist.add_field('scores', scores)\n    self.assertTrue(np.allclose(scores, self.boxlist.get_field('scores')))\n\n  def test_add_multi_dimensional_field_data(self):\n    boxlist = self.boxlist\n    labels = np.array([[0, 0, 0, 1, 0], [0, 1, 0, 0, 0], [0, 0, 0, 0, 1]],\n                      dtype=int)\n    boxlist.add_field('labels', labels)\n    self.assertTrue(np.allclose(labels, self.boxlist.get_field('labels')))\n\n  def test_get_extra_fields(self):\n    boxlist = self.boxlist\n    self.assertSameElements(boxlist.get_extra_fields(), [])\n\n    scores = np.array([0.5, 0.7, 0.9], dtype=float)\n    boxlist.add_field('scores', scores)\n    self.assertSameElements(boxlist.get_extra_fields(), ['scores'])\n\n    labels = np.array([[0, 0, 0, 1, 0], [0, 1, 0, 0, 0], [0, 0, 0, 0, 1]],\n                      dtype=int)\n    boxlist.add_field('labels', labels)\n    self.assertSameElements(boxlist.get_extra_fields(), ['scores', 'labels'])\n\n  def test_get_coordinates(self):\n    y_min, x_min, y_max, x_max = self.boxlist.get_coordinates()\n\n    expected_y_min = np.array([3.0, 14.0, 0.0], dtype=float)\n    expected_x_min = np.array([4.0, 14.0, 0.0], dtype=float)\n    expected_y_max = np.array([6.0, 15.0, 20.0], dtype=float)\n    expected_x_max = np.array([8.0, 15.0, 20.0], dtype=float)\n\n    self.assertTrue(np.allclose(y_min, expected_y_min))\n    self.assertTrue(np.allclose(x_min, expected_x_min))\n    self.assertTrue(np.allclose(y_max, expected_y_max))\n    self.assertTrue(np.allclose(x_max, expected_x_max))\n\n  def test_num_boxes(self):\n    boxes = np.array([[0., 0., 100., 100.], [10., 30., 50., 70.]], dtype=float)\n    boxlist = np_box_list.BoxList(boxes)\n    expected_num_boxes = 2\n    self.assertEquals(boxlist.num_boxes(), expected_num_boxes)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/np_box_ops.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Operations for [N, 4] numpy arrays representing bounding boxes.\n\nExample box operations that are supported:\n  * Areas: compute bounding box areas\n  * IOU: pairwise intersection-over-union scores\n\"\"\"\nimport numpy as np\n\n\ndef area(boxes):\n  \"\"\"Computes area of boxes.\n\n  Args:\n    boxes: Numpy array with shape [N, 4] holding N boxes\n\n  Returns:\n    a numpy array with shape [N*1] representing box areas\n  \"\"\"\n  return (boxes[:, 2] - boxes[:, 0]) * (boxes[:, 3] - boxes[:, 1])\n\n\ndef intersection(boxes1, boxes2):\n  \"\"\"Compute pairwise intersection areas between boxes.\n\n  Args:\n    boxes1: a numpy array with shape [N, 4] holding N boxes\n    boxes2: a numpy array with shape [M, 4] holding M boxes\n\n  Returns:\n    a numpy array with shape [N*M] representing pairwise intersection area\n  \"\"\"\n  [y_min1, x_min1, y_max1, x_max1] = np.split(boxes1, 4, axis=1)\n  [y_min2, x_min2, y_max2, x_max2] = np.split(boxes2, 4, axis=1)\n\n  all_pairs_min_ymax = np.minimum(y_max1, np.transpose(y_max2))\n  all_pairs_max_ymin = np.maximum(y_min1, np.transpose(y_min2))\n  intersect_heights = np.maximum(\n      np.zeros(all_pairs_max_ymin.shape),\n      all_pairs_min_ymax - all_pairs_max_ymin)\n  all_pairs_min_xmax = np.minimum(x_max1, np.transpose(x_max2))\n  all_pairs_max_xmin = np.maximum(x_min1, np.transpose(x_min2))\n  intersect_widths = np.maximum(\n      np.zeros(all_pairs_max_xmin.shape),\n      all_pairs_min_xmax - all_pairs_max_xmin)\n  return intersect_heights * intersect_widths\n\n\ndef iou(boxes1, boxes2):\n  \"\"\"Computes pairwise intersection-over-union between box collections.\n\n  Args:\n    boxes1: a numpy array with shape [N, 4] holding N boxes.\n    boxes2: a numpy array with shape [M, 4] holding N boxes.\n\n  Returns:\n    a numpy array with shape [N, M] representing pairwise iou scores.\n  \"\"\"\n  intersect = intersection(boxes1, boxes2)\n  area1 = area(boxes1)\n  area2 = area(boxes2)\n  union = np.expand_dims(area1, axis=1) + np.expand_dims(\n      area2, axis=0) - intersect\n  return intersect / union\n\n\ndef ioa(boxes1, boxes2):\n  \"\"\"Computes pairwise intersection-over-area between box collections.\n\n  Intersection-over-area (ioa) between two boxes box1 and box2 is defined as\n  their intersection area over box2's area. Note that ioa is not symmetric,\n  that is, IOA(box1, box2) != IOA(box2, box1).\n\n  Args:\n    boxes1: a numpy array with shape [N, 4] holding N boxes.\n    boxes2: a numpy array with shape [M, 4] holding N boxes.\n\n  Returns:\n    a numpy array with shape [N, M] representing pairwise ioa scores.\n  \"\"\"\n  intersect = intersection(boxes1, boxes2)\n  areas = np.expand_dims(area(boxes2), axis=0)\n  return intersect / areas\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/np_box_ops_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.np_box_ops.\"\"\"\n\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.utils import np_box_ops\n\n\nclass BoxOpsTests(tf.test.TestCase):\n\n  def setUp(self):\n    boxes1 = np.array([[4.0, 3.0, 7.0, 5.0], [5.0, 6.0, 10.0, 7.0]],\n                      dtype=float)\n    boxes2 = np.array([[3.0, 4.0, 6.0, 8.0], [14.0, 14.0, 15.0, 15.0],\n                       [0.0, 0.0, 20.0, 20.0]],\n                      dtype=float)\n    self.boxes1 = boxes1\n    self.boxes2 = boxes2\n\n  def testArea(self):\n    areas = np_box_ops.area(self.boxes1)\n    expected_areas = np.array([6.0, 5.0], dtype=float)\n    self.assertAllClose(expected_areas, areas)\n\n  def testIntersection(self):\n    intersection = np_box_ops.intersection(self.boxes1, self.boxes2)\n    expected_intersection = np.array([[2.0, 0.0, 6.0], [1.0, 0.0, 5.0]],\n                                     dtype=float)\n    self.assertAllClose(intersection, expected_intersection)\n\n  def testIOU(self):\n    iou = np_box_ops.iou(self.boxes1, self.boxes2)\n    expected_iou = np.array([[2.0 / 16.0, 0.0, 6.0 / 400.0],\n                             [1.0 / 16.0, 0.0, 5.0 / 400.0]],\n                            dtype=float)\n    self.assertAllClose(iou, expected_iou)\n\n  def testIOA(self):\n    boxes1 = np.array([[0.25, 0.25, 0.75, 0.75],\n                       [0.0, 0.0, 0.5, 0.75]],\n                      dtype=np.float32)\n    boxes2 = np.array([[0.5, 0.25, 1.0, 1.0],\n                       [0.0, 0.0, 1.0, 1.0]],\n                      dtype=np.float32)\n    ioa21 = np_box_ops.ioa(boxes2, boxes1)\n    expected_ioa21 = np.array([[0.5, 0.0],\n                               [1.0, 1.0]],\n                              dtype=np.float32)\n    self.assertAllClose(ioa21, expected_ioa21)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/object_detection_evaluation.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"object_detection_evaluation module.\n\nObjectDetectionEvaluation is a class which manages ground truth information of a\nobject detection dataset, and computes frequently used detection metrics such as\nPrecision, Recall, CorLoc of the provided detection results.\nIt supports the following operations:\n1) Add ground truth information of images sequentially.\n2) Add detection result of images sequentially.\n3) Evaluate detection metrics on already inserted detection results.\n4) Write evaluation result into a pickle file for future processing or\n   visualization.\n\nNote: This module operates on numpy boxes and box lists.\n\"\"\"\n\nimport logging\nimport numpy as np\n\nfrom object_detection.utils import metrics\nfrom object_detection.utils import per_image_evaluation\n\n\nclass ObjectDetectionEvaluation(object):\n  \"\"\"Evaluate Object Detection Result.\"\"\"\n\n  def __init__(self,\n               num_groundtruth_classes,\n               matching_iou_threshold=0.5,\n               nms_iou_threshold=1.0,\n               nms_max_output_boxes=10000):\n    self.per_image_eval = per_image_evaluation.PerImageEvaluation(\n        num_groundtruth_classes, matching_iou_threshold, nms_iou_threshold,\n        nms_max_output_boxes)\n    self.num_class = num_groundtruth_classes\n\n    self.groundtruth_boxes = {}\n    self.groundtruth_class_labels = {}\n    self.groundtruth_is_difficult_list = {}\n    self.num_gt_instances_per_class = np.zeros(self.num_class, dtype=int)\n    self.num_gt_imgs_per_class = np.zeros(self.num_class, dtype=int)\n\n    self.detection_keys = set()\n    self.scores_per_class = [[] for _ in range(self.num_class)]\n    self.tp_fp_labels_per_class = [[] for _ in range(self.num_class)]\n    self.num_images_correctly_detected_per_class = np.zeros(self.num_class)\n    self.average_precision_per_class = np.empty(self.num_class, dtype=float)\n    self.average_precision_per_class.fill(np.nan)\n    self.precisions_per_class = []\n    self.recalls_per_class = []\n    self.corloc_per_class = np.ones(self.num_class, dtype=float)\n\n  def clear_detections(self):\n    self.detection_keys = {}\n    self.scores_per_class = [[] for _ in range(self.num_class)]\n    self.tp_fp_labels_per_class = [[] for _ in range(self.num_class)]\n    self.num_images_correctly_detected_per_class = np.zeros(self.num_class)\n    self.average_precision_per_class = np.zeros(self.num_class, dtype=float)\n    self.precisions_per_class = []\n    self.recalls_per_class = []\n    self.corloc_per_class = np.ones(self.num_class, dtype=float)\n\n  def add_single_ground_truth_image_info(self,\n                                         image_key,\n                                         groundtruth_boxes,\n                                         groundtruth_class_labels,\n                                         groundtruth_is_difficult_list=None):\n    \"\"\"Add ground truth info of a single image into the evaluation database.\n\n    Args:\n      image_key: sha256 key of image content\n      groundtruth_boxes: A numpy array of shape [M, 4] representing object box\n          coordinates[y_min, x_min, y_max, x_max]\n      groundtruth_class_labels: A 1-d numpy array of length M representing class\n          labels\n      groundtruth_is_difficult_list: A length M numpy boolean array denoting\n          whether a ground truth box is a difficult instance or not. To support\n          the case that no boxes are difficult, it is by default set as None.\n    \"\"\"\n    if image_key in self.groundtruth_boxes:\n      logging.warn(\n          'image %s has already been added to the ground truth database.',\n          image_key)\n      return\n\n    self.groundtruth_boxes[image_key] = groundtruth_boxes\n    self.groundtruth_class_labels[image_key] = groundtruth_class_labels\n    if groundtruth_is_difficult_list is None:\n      num_boxes = groundtruth_boxes.shape[0]\n      groundtruth_is_difficult_list = np.zeros(num_boxes, dtype=bool)\n    self.groundtruth_is_difficult_list[\n        image_key] = groundtruth_is_difficult_list.astype(dtype=bool)\n    self._update_ground_truth_statistics(groundtruth_class_labels,\n                                         groundtruth_is_difficult_list)\n\n  def add_single_detected_image_info(self, image_key, detected_boxes,\n                                     detected_scores, detected_class_labels):\n    \"\"\"Add detected result of a single image into the evaluation database.\n\n    Args:\n      image_key: sha256 key of image content\n      detected_boxes: A numpy array of shape [N, 4] representing detected box\n          coordinates[y_min, x_min, y_max, x_max]\n      detected_scores: A 1-d numpy array of length N representing classification\n          score\n      detected_class_labels: A 1-d numpy array of length N representing class\n          labels\n    Raises:\n      ValueError: if detected_boxes, detected_scores and detected_class_labels\n                  do not have the same length.\n    \"\"\"\n    if (len(detected_boxes) != len(detected_scores) or\n        len(detected_boxes) != len(detected_class_labels)):\n      raise ValueError('detected_boxes, detected_scores and '\n                       'detected_class_labels should all have same lengths. Got'\n                       '[%d, %d, %d]' % len(detected_boxes),\n                       len(detected_scores), len(detected_class_labels))\n\n    if image_key in self.detection_keys:\n      logging.warn(\n          'image %s has already been added to the detection result database',\n          image_key)\n      return\n\n    self.detection_keys.add(image_key)\n    if image_key in self.groundtruth_boxes:\n      groundtruth_boxes = self.groundtruth_boxes[image_key]\n      groundtruth_class_labels = self.groundtruth_class_labels[image_key]\n      groundtruth_is_difficult_list = self.groundtruth_is_difficult_list[\n          image_key]\n    else:\n      groundtruth_boxes = np.empty(shape=[0, 4], dtype=float)\n      groundtruth_class_labels = np.array([], dtype=int)\n      groundtruth_is_difficult_list = np.array([], dtype=bool)\n    scores, tp_fp_labels, is_class_correctly_detected_in_image = (\n        self.per_image_eval.compute_object_detection_metrics(\n            detected_boxes, detected_scores, detected_class_labels,\n            groundtruth_boxes, groundtruth_class_labels,\n            groundtruth_is_difficult_list))\n    for i in range(self.num_class):\n      self.scores_per_class[i].append(scores[i])\n      self.tp_fp_labels_per_class[i].append(tp_fp_labels[i])\n    (self.num_images_correctly_detected_per_class\n    ) += is_class_correctly_detected_in_image\n\n  def _update_ground_truth_statistics(self, groundtruth_class_labels,\n                                      groundtruth_is_difficult_list):\n    \"\"\"Update grouth truth statitistics.\n\n    1. Difficult boxes are ignored when counting the number of ground truth\n    instances as done in Pascal VOC devkit.\n    2. Difficult boxes are treated as normal boxes when computing CorLoc related\n    statitistics.\n\n    Args:\n      groundtruth_class_labels: An integer numpy array of length M,\n          representing M class labels of object instances in ground truth\n      groundtruth_is_difficult_list: A boolean numpy array of length M denoting\n          whether a ground truth box is a difficult instance or not\n    \"\"\"\n    for class_index in range(self.num_class):\n      num_gt_instances = np.sum(groundtruth_class_labels[\n          ~groundtruth_is_difficult_list] == class_index)\n      self.num_gt_instances_per_class[class_index] += num_gt_instances\n      if np.any(groundtruth_class_labels == class_index):\n        self.num_gt_imgs_per_class[class_index] += 1\n\n  def evaluate(self):\n    \"\"\"Compute evaluation result.\n\n    Returns:\n      average_precision_per_class: float numpy array of average precision for\n          each class.\n      mean_ap: mean average precision of all classes, float scalar\n      precisions_per_class: List of precisions, each precision is a float numpy\n          array\n      recalls_per_class: List of recalls, each recall is a float numpy array\n      corloc_per_class: numpy float array\n      mean_corloc: Mean CorLoc score for each class, float scalar\n    \"\"\"\n    if (self.num_gt_instances_per_class == 0).any():\n      logging.warn(\n          'The following classes have no ground truth examples: %s',\n          np.squeeze(np.argwhere(self.num_gt_instances_per_class == 0)))\n    for class_index in range(self.num_class):\n      if self.num_gt_instances_per_class[class_index] == 0:\n        continue\n      scores = np.concatenate(self.scores_per_class[class_index])\n      tp_fp_labels = np.concatenate(self.tp_fp_labels_per_class[class_index])\n      precision, recall = metrics.compute_precision_recall(\n          scores, tp_fp_labels, self.num_gt_instances_per_class[class_index])\n      self.precisions_per_class.append(precision)\n      self.recalls_per_class.append(recall)\n      average_precision = metrics.compute_average_precision(precision, recall)\n      self.average_precision_per_class[class_index] = average_precision\n\n    self.corloc_per_class = metrics.compute_cor_loc(\n        self.num_gt_imgs_per_class,\n        self.num_images_correctly_detected_per_class)\n\n    mean_ap = np.nanmean(self.average_precision_per_class)\n    mean_corloc = np.nanmean(self.corloc_per_class)\n    return (self.average_precision_per_class, mean_ap,\n            self.precisions_per_class, self.recalls_per_class,\n            self.corloc_per_class, mean_corloc)\n\n  def get_eval_result(self):\n    return EvalResult(self.average_precision_per_class,\n                      self.precisions_per_class, self.recalls_per_class,\n                      self.corloc_per_class)\n\n\nclass EvalResult(object):\n\n  def __init__(self, average_precisions, precisions, recalls, all_corloc):\n    self.precisions = precisions\n    self.recalls = recalls\n    self.all_corloc = all_corloc\n    self.average_precisions = average_precisions\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/object_detection_evaluation_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.utils.object_detection_evaluation.\"\"\"\n\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.utils import object_detection_evaluation\n\n\nclass ObjectDetectionEvaluationTest(tf.test.TestCase):\n\n  def setUp(self):\n    num_groundtruth_classes = 3\n    self.od_eval = object_detection_evaluation.ObjectDetectionEvaluation(\n        num_groundtruth_classes)\n\n    image_key1 = \"img1\"\n    groundtruth_boxes1 = np.array([[0, 0, 1, 1], [0, 0, 2, 2], [0, 0, 3, 3]],\n                                  dtype=float)\n    groundtruth_class_labels1 = np.array([0, 2, 0], dtype=int)\n    self.od_eval.add_single_ground_truth_image_info(\n        image_key1, groundtruth_boxes1, groundtruth_class_labels1)\n    image_key2 = \"img2\"\n    groundtruth_boxes2 = np.array([[10, 10, 11, 11], [500, 500, 510, 510],\n                                   [10, 10, 12, 12]], dtype=float)\n    groundtruth_class_labels2 = np.array([0, 0, 2], dtype=int)\n    groundtruth_is_difficult_list2 = np.array([False, True, False], dtype=bool)\n    self.od_eval.add_single_ground_truth_image_info(\n        image_key2, groundtruth_boxes2, groundtruth_class_labels2,\n        groundtruth_is_difficult_list2)\n    image_key3 = \"img3\"\n    groundtruth_boxes3 = np.array([[0, 0, 1, 1]], dtype=float)\n    groundtruth_class_labels3 = np.array([1], dtype=int)\n    self.od_eval.add_single_ground_truth_image_info(\n        image_key3, groundtruth_boxes3, groundtruth_class_labels3)\n\n    image_key = \"img2\"\n    detected_boxes = np.array(\n        [[10, 10, 11, 11], [100, 100, 120, 120], [100, 100, 220, 220]],\n        dtype=float)\n    detected_class_labels = np.array([0, 0, 2], dtype=int)\n    detected_scores = np.array([0.7, 0.8, 0.9], dtype=float)\n    self.od_eval.add_single_detected_image_info(\n        image_key, detected_boxes, detected_scores, detected_class_labels)\n\n  def test_add_single_ground_truth_image_info(self):\n    expected_num_gt_instances_per_class = np.array([3, 1, 2], dtype=int)\n    expected_num_gt_imgs_per_class = np.array([2, 1, 2], dtype=int)\n    self.assertTrue(np.array_equal(expected_num_gt_instances_per_class,\n                                   self.od_eval.num_gt_instances_per_class))\n    self.assertTrue(np.array_equal(expected_num_gt_imgs_per_class,\n                                   self.od_eval.num_gt_imgs_per_class))\n    groundtruth_boxes2 = np.array([[10, 10, 11, 11], [500, 500, 510, 510],\n                                   [10, 10, 12, 12]], dtype=float)\n    self.assertTrue(np.allclose(self.od_eval.groundtruth_boxes[\"img2\"],\n                                groundtruth_boxes2))\n    groundtruth_is_difficult_list2 = np.array([False, True, False], dtype=bool)\n    self.assertTrue(np.allclose(\n        self.od_eval.groundtruth_is_difficult_list[\"img2\"],\n        groundtruth_is_difficult_list2))\n    groundtruth_class_labels1 = np.array([0, 2, 0], dtype=int)\n    self.assertTrue(np.array_equal(self.od_eval.groundtruth_class_labels[\n        \"img1\"], groundtruth_class_labels1))\n\n  def test_add_single_detected_image_info(self):\n    expected_scores_per_class = [[np.array([0.8, 0.7], dtype=float)], [],\n                                 [np.array([0.9], dtype=float)]]\n    expected_tp_fp_labels_per_class = [[np.array([0, 1], dtype=bool)], [],\n                                       [np.array([0], dtype=bool)]]\n    expected_num_images_correctly_detected_per_class = np.array([0, 0, 0],\n                                                                dtype=int)\n    for i in range(self.od_eval.num_class):\n      for j in range(len(expected_scores_per_class[i])):\n        self.assertTrue(np.allclose(expected_scores_per_class[i][j],\n                                    self.od_eval.scores_per_class[i][j]))\n        self.assertTrue(np.array_equal(expected_tp_fp_labels_per_class[i][\n            j], self.od_eval.tp_fp_labels_per_class[i][j]))\n    self.assertTrue(np.array_equal(\n        expected_num_images_correctly_detected_per_class,\n        self.od_eval.num_images_correctly_detected_per_class))\n\n  def test_evaluate(self):\n    (average_precision_per_class, mean_ap, precisions_per_class,\n     recalls_per_class, corloc_per_class,\n     mean_corloc) = self.od_eval.evaluate()\n    expected_precisions_per_class = [np.array([0, 0.5], dtype=float),\n                                     np.array([], dtype=float),\n                                     np.array([0], dtype=float)]\n    expected_recalls_per_class = [\n        np.array([0, 1. / 3.], dtype=float), np.array([], dtype=float),\n        np.array([0], dtype=float)\n    ]\n    expected_average_precision_per_class = np.array([1. / 6., 0, 0],\n                                                    dtype=float)\n    expected_corloc_per_class = np.array([0, np.divide(0, 0), 0], dtype=float)\n    expected_mean_ap = 1. / 18\n    expected_mean_corloc = 0.0\n    for i in range(self.od_eval.num_class):\n      self.assertTrue(np.allclose(expected_precisions_per_class[i],\n                                  precisions_per_class[i]))\n      self.assertTrue(np.allclose(expected_recalls_per_class[i],\n                                  recalls_per_class[i]))\n    self.assertTrue(np.allclose(expected_average_precision_per_class,\n                                average_precision_per_class))\n    self.assertTrue(np.allclose(expected_corloc_per_class, corloc_per_class))\n    self.assertAlmostEqual(expected_mean_ap, mean_ap)\n    self.assertAlmostEqual(expected_mean_corloc, mean_corloc)\n\n\nif __name__ == \"__main__\":\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/ops.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"A module for helper tensorflow ops.\"\"\"\nimport math\n\nimport tensorflow as tf\n\nfrom object_detection.core import box_list\nfrom object_detection.core import box_list_ops\nfrom object_detection.core import standard_fields as fields\nfrom object_detection.utils import static_shape\n\n\ndef expanded_shape(orig_shape, start_dim, num_dims):\n  \"\"\"Inserts multiple ones into a shape vector.\n\n  Inserts an all-1 vector of length num_dims at position start_dim into a shape.\n  Can be combined with tf.reshape to generalize tf.expand_dims.\n\n  Args:\n    orig_shape: the shape into which the all-1 vector is added (int32 vector)\n    start_dim: insertion position (int scalar)\n    num_dims: length of the inserted all-1 vector (int scalar)\n  Returns:\n    An int32 vector of length tf.size(orig_shape) + num_dims.\n  \"\"\"\n  with tf.name_scope('ExpandedShape'):\n    start_dim = tf.expand_dims(start_dim, 0)  # scalar to rank-1\n    before = tf.slice(orig_shape, [0], start_dim)\n    add_shape = tf.ones(tf.reshape(num_dims, [1]), dtype=tf.int32)\n    after = tf.slice(orig_shape, start_dim, [-1])\n    new_shape = tf.concat([before, add_shape, after], 0)\n    return new_shape\n\n\ndef normalized_to_image_coordinates(normalized_boxes, image_shape,\n                                    parallel_iterations=32):\n  \"\"\"Converts a batch of boxes from normal to image coordinates.\n\n  Args:\n    normalized_boxes: a float32 tensor of shape [None, num_boxes, 4] in\n      normalized coordinates.\n    image_shape: a float32 tensor of shape [4] containing the image shape.\n    parallel_iterations: parallelism for the map_fn op.\n\n  Returns:\n    absolute_boxes: a float32 tensor of shape [None, num_boxes, 4] containg the\n      boxes in image coordinates.\n  \"\"\"\n  def _to_absolute_coordinates(normalized_boxes):\n    return box_list_ops.to_absolute_coordinates(\n        box_list.BoxList(normalized_boxes),\n        image_shape[1], image_shape[2], check_range=False).get()\n\n  absolute_boxes = tf.map_fn(\n      _to_absolute_coordinates,\n      elems=(normalized_boxes),\n      dtype=tf.float32,\n      parallel_iterations=parallel_iterations,\n      back_prop=True)\n  return absolute_boxes\n\n\ndef meshgrid(x, y):\n  \"\"\"Tiles the contents of x and y into a pair of grids.\n\n  Multidimensional analog of numpy.meshgrid, giving the same behavior if x and y\n  are vectors. Generally, this will give:\n\n  xgrid(i1, ..., i_m, j_1, ..., j_n) = x(j_1, ..., j_n)\n  ygrid(i1, ..., i_m, j_1, ..., j_n) = y(i_1, ..., i_m)\n\n  Keep in mind that the order of the arguments and outputs is reverse relative\n  to the order of the indices they go into, done for compatibility with numpy.\n  The output tensors have the same shapes.  Specifically:\n\n  xgrid.get_shape() = y.get_shape().concatenate(x.get_shape())\n  ygrid.get_shape() = y.get_shape().concatenate(x.get_shape())\n\n  Args:\n    x: A tensor of arbitrary shape and rank. xgrid will contain these values\n       varying in its last dimensions.\n    y: A tensor of arbitrary shape and rank. ygrid will contain these values\n       varying in its first dimensions.\n  Returns:\n    A tuple of tensors (xgrid, ygrid).\n  \"\"\"\n  with tf.name_scope('Meshgrid'):\n    x = tf.convert_to_tensor(x)\n    y = tf.convert_to_tensor(y)\n    x_exp_shape = expanded_shape(tf.shape(x), 0, tf.rank(y))\n    y_exp_shape = expanded_shape(tf.shape(y), tf.rank(y), tf.rank(x))\n\n    xgrid = tf.tile(tf.reshape(x, x_exp_shape), y_exp_shape)\n    ygrid = tf.tile(tf.reshape(y, y_exp_shape), x_exp_shape)\n    new_shape = y.get_shape().concatenate(x.get_shape())\n    xgrid.set_shape(new_shape)\n    ygrid.set_shape(new_shape)\n\n    return xgrid, ygrid\n\n\ndef pad_to_multiple(tensor, multiple):\n  \"\"\"Returns the tensor zero padded to the specified multiple.\n\n  Appends 0s to the end of the first and second dimension (height and width) of\n  the tensor until both dimensions are a multiple of the input argument\n  'multiple'. E.g. given an input tensor of shape [1, 3, 5, 1] and an input\n  multiple of 4, PadToMultiple will append 0s so that the resulting tensor will\n  be of shape [1, 4, 8, 1].\n\n  Args:\n    tensor: rank 4 float32 tensor, where\n            tensor -> [batch_size, height, width, channels].\n    multiple: the multiple to pad to.\n\n  Returns:\n    padded_tensor: the tensor zero padded to the specified multiple.\n  \"\"\"\n  tensor_shape = tensor.get_shape()\n  batch_size = static_shape.get_batch_size(tensor_shape)\n  tensor_height = static_shape.get_height(tensor_shape)\n  tensor_width = static_shape.get_width(tensor_shape)\n  tensor_depth = static_shape.get_depth(tensor_shape)\n\n  if batch_size is None:\n    batch_size = tf.shape(tensor)[0]\n\n  if tensor_height is None:\n    tensor_height = tf.shape(tensor)[1]\n    padded_tensor_height = tf.to_int32(\n        tf.ceil(tf.to_float(tensor_height) / tf.to_float(multiple))) * multiple\n  else:\n    padded_tensor_height = int(\n        math.ceil(float(tensor_height) / multiple) * multiple)\n\n  if tensor_width is None:\n    tensor_width = tf.shape(tensor)[2]\n    padded_tensor_width = tf.to_int32(\n        tf.ceil(tf.to_float(tensor_width) / tf.to_float(multiple))) * multiple\n  else:\n    padded_tensor_width = int(\n        math.ceil(float(tensor_width) / multiple) * multiple)\n\n  if tensor_depth is None:\n    tensor_depth = tf.shape(tensor)[3]\n\n  # Use tf.concat instead of tf.pad to preserve static shape\n  height_pad = tf.zeros([\n      batch_size, padded_tensor_height - tensor_height, tensor_width,\n      tensor_depth\n  ])\n  padded_tensor = tf.concat([tensor, height_pad], 1)\n  width_pad = tf.zeros([\n      batch_size, padded_tensor_height, padded_tensor_width - tensor_width,\n      tensor_depth\n  ])\n  padded_tensor = tf.concat([padded_tensor, width_pad], 2)\n\n  return padded_tensor\n\n\ndef padded_one_hot_encoding(indices, depth, left_pad):\n  \"\"\"Returns a zero padded one-hot tensor.\n\n  This function converts a sparse representation of indices (e.g., [4]) to a\n  zero padded one-hot representation (e.g., [0, 0, 0, 0, 1] with depth = 4 and\n  left_pad = 1). If `indices` is empty, the result will simply be a tensor of\n  shape (0, depth + left_pad). If depth = 0, then this function just returns\n  `None`.\n\n  Args:\n    indices: an integer tensor of shape [num_indices].\n    depth: depth for the one-hot tensor (integer).\n    left_pad: number of zeros to left pad the one-hot tensor with (integer).\n\n  Returns:\n    padded_onehot: a tensor with shape (num_indices, depth + left_pad). Returns\n      `None` if the depth is zero.\n\n  Raises:\n    ValueError: if `indices` does not have rank 1 or if `left_pad` or `depth are\n      either negative or non-integers.\n\n  TODO: add runtime checks for depth and indices.\n  \"\"\"\n  if depth < 0 or not isinstance(depth, (int, long)):\n    raise ValueError('`depth` must be a non-negative integer.')\n  if left_pad < 0 or not isinstance(left_pad, (int, long)):\n    raise ValueError('`left_pad` must be a non-negative integer.')\n  if depth == 0:\n    return None\n  if len(indices.get_shape().as_list()) != 1:\n    raise ValueError('`indices` must have rank 1')\n\n  def one_hot_and_pad():\n    one_hot = tf.cast(tf.one_hot(tf.cast(indices, tf.int64), depth,\n                                 on_value=1, off_value=0), tf.float32)\n    return tf.pad(one_hot, [[0, 0], [left_pad, 0]], mode='CONSTANT')\n  result = tf.cond(tf.greater(tf.size(indices), 0), one_hot_and_pad,\n                   lambda: tf.zeros((depth + left_pad, 0)))\n  return tf.reshape(result, [-1, depth + left_pad])\n\n\ndef dense_to_sparse_boxes(dense_locations, dense_num_boxes, num_classes):\n  \"\"\"Converts bounding boxes from dense to sparse form.\n\n  Args:\n    dense_locations:  a [max_num_boxes, 4] tensor in which only the first k rows\n      are valid bounding box location coordinates, where k is the sum of\n      elements in dense_num_boxes.\n    dense_num_boxes: a [max_num_classes] tensor indicating the counts of\n       various bounding box classes e.g. [1, 0, 0, 2] means that the first\n       bounding box is of class 0 and the second and third bounding boxes are\n       of class 3. The sum of elements in this tensor is the number of valid\n       bounding boxes.\n    num_classes: number of classes\n\n  Returns:\n    box_locations: a [num_boxes, 4] tensor containing only valid bounding\n       boxes (i.e. the first num_boxes rows of dense_locations)\n    box_classes: a [num_boxes] tensor containing the classes of each bounding\n       box (e.g. dense_num_boxes = [1, 0, 0, 2] => box_classes = [0, 3, 3]\n  \"\"\"\n\n  num_valid_boxes = tf.reduce_sum(dense_num_boxes)\n  box_locations = tf.slice(dense_locations,\n                           tf.constant([0, 0]), tf.stack([num_valid_boxes, 4]))\n  tiled_classes = [tf.tile([i], tf.expand_dims(dense_num_boxes[i], 0))\n                   for i in range(num_classes)]\n  box_classes = tf.concat(tiled_classes, 0)\n  box_locations.set_shape([None, 4])\n  return box_locations, box_classes\n\n\ndef indices_to_dense_vector(indices,\n                            size,\n                            indices_value=1.,\n                            default_value=0,\n                            dtype=tf.float32):\n  \"\"\"Creates dense vector with indices set to specific value and rest to zeros.\n\n  This function exists because it is unclear if it is safe to use\n    tf.sparse_to_dense(indices, [size], 1, validate_indices=False)\n  with indices which are not ordered.\n  This function accepts a dynamic size (e.g. tf.shape(tensor)[0])\n\n  Args:\n    indices: 1d Tensor with integer indices which are to be set to\n        indices_values.\n    size: scalar with size (integer) of output Tensor.\n    indices_value: values of elements specified by indices in the output vector\n    default_value: values of other elements in the output vector.\n    dtype: data type.\n\n  Returns:\n    dense 1D Tensor of shape [size] with indices set to indices_values and the\n        rest set to default_value.\n  \"\"\"\n  size = tf.to_int32(size)\n  zeros = tf.ones([size], dtype=dtype) * default_value\n  values = tf.ones_like(indices, dtype=dtype) * indices_value\n\n  return tf.dynamic_stitch([tf.range(size), tf.to_int32(indices)],\n                           [zeros, values])\n\n\ndef retain_groundtruth(tensor_dict, valid_indices):\n  \"\"\"Retains groundtruth by valid indices.\n\n  Args:\n    tensor_dict: a dictionary of following groundtruth tensors -\n      fields.InputDataFields.groundtruth_boxes\n      fields.InputDataFields.groundtruth_classes\n      fields.InputDataFields.groundtruth_is_crowd\n      fields.InputDataFields.groundtruth_area\n      fields.InputDataFields.groundtruth_label_types\n      fields.InputDataFields.groundtruth_difficult\n    valid_indices: a tensor with valid indices for the box-level groundtruth.\n\n  Returns:\n    a dictionary of tensors containing only the groundtruth for valid_indices.\n\n  Raises:\n    ValueError: If the shape of valid_indices is invalid.\n    ValueError: field fields.InputDataFields.groundtruth_boxes is\n      not present in tensor_dict.\n  \"\"\"\n  input_shape = valid_indices.get_shape().as_list()\n  if not (len(input_shape) == 1 or\n          (len(input_shape) == 2 and input_shape[1] == 1)):\n    raise ValueError('The shape of valid_indices is invalid.')\n  valid_indices = tf.reshape(valid_indices, [-1])\n  valid_dict = {}\n  if fields.InputDataFields.groundtruth_boxes in tensor_dict:\n    # Prevents reshape failure when num_boxes is 0.\n    num_boxes = tf.maximum(tf.shape(\n        tensor_dict[fields.InputDataFields.groundtruth_boxes])[0], 1)\n    for key in tensor_dict:\n      if key in [fields.InputDataFields.groundtruth_boxes,\n                 fields.InputDataFields.groundtruth_classes]:\n        valid_dict[key] = tf.gather(tensor_dict[key], valid_indices)\n      # Input decoder returns empty tensor when these fields are not provided.\n      # Needs to reshape into [num_boxes, -1] for tf.gather() to work.\n      elif key in [fields.InputDataFields.groundtruth_is_crowd,\n                   fields.InputDataFields.groundtruth_area,\n                   fields.InputDataFields.groundtruth_difficult,\n                   fields.InputDataFields.groundtruth_label_types]:\n        valid_dict[key] = tf.reshape(\n            tf.gather(tf.reshape(tensor_dict[key], [num_boxes, -1]),\n                      valid_indices), [-1])\n      # Fields that are not associated with boxes.\n      else:\n        valid_dict[key] = tensor_dict[key]\n  else:\n    raise ValueError('%s not present in input tensor dict.' % (\n        fields.InputDataFields.groundtruth_boxes))\n  return valid_dict\n\n\ndef retain_groundtruth_with_positive_classes(tensor_dict):\n  \"\"\"Retains only groundtruth with positive class ids.\n\n  Args:\n    tensor_dict: a dictionary of following groundtruth tensors -\n      fields.InputDataFields.groundtruth_boxes\n      fields.InputDataFields.groundtruth_classes\n      fields.InputDataFields.groundtruth_is_crowd\n      fields.InputDataFields.groundtruth_area\n      fields.InputDataFields.groundtruth_label_types\n      fields.InputDataFields.groundtruth_difficult\n\n  Returns:\n    a dictionary of tensors containing only the groundtruth with positive\n    classes.\n\n  Raises:\n    ValueError: If groundtruth_classes tensor is not in tensor_dict.\n  \"\"\"\n  if fields.InputDataFields.groundtruth_classes not in tensor_dict:\n    raise ValueError('`groundtruth classes` not in tensor_dict.')\n  keep_indices = tf.where(tf.greater(\n      tensor_dict[fields.InputDataFields.groundtruth_classes], 0))\n  return retain_groundtruth(tensor_dict, keep_indices)\n\n\ndef filter_groundtruth_with_nan_box_coordinates(tensor_dict):\n  \"\"\"Filters out groundtruth with no bounding boxes.\n\n  Args:\n    tensor_dict: a dictionary of following groundtruth tensors -\n      fields.InputDataFields.groundtruth_boxes\n      fields.InputDataFields.groundtruth_classes\n      fields.InputDataFields.groundtruth_is_crowd\n      fields.InputDataFields.groundtruth_area\n      fields.InputDataFields.groundtruth_label_types\n\n  Returns:\n    a dictionary of tensors containing only the groundtruth that have bounding\n    boxes.\n  \"\"\"\n  groundtruth_boxes = tensor_dict[fields.InputDataFields.groundtruth_boxes]\n  nan_indicator_vector = tf.greater(tf.reduce_sum(tf.to_int32(\n      tf.is_nan(groundtruth_boxes)), reduction_indices=[1]), 0)\n  valid_indicator_vector = tf.logical_not(nan_indicator_vector)\n  valid_indices = tf.where(valid_indicator_vector)\n\n  return retain_groundtruth(tensor_dict, valid_indices)\n\n\ndef normalize_to_target(inputs,\n                        target_norm_value,\n                        dim,\n                        epsilon=1e-7,\n                        trainable=True,\n                        scope='NormalizeToTarget',\n                        summarize=True):\n  \"\"\"L2 normalizes the inputs across the specified dimension to a target norm.\n\n  This op implements the L2 Normalization layer introduced in\n  Liu, Wei, et al. \"SSD: Single Shot MultiBox Detector.\"\n  and Liu, Wei, Andrew Rabinovich, and Alexander C. Berg.\n  \"Parsenet: Looking wider to see better.\" and is useful for bringing\n  activations from multiple layers in a convnet to a standard scale.\n\n  Note that the rank of `inputs` must be known and the dimension to which\n  normalization is to be applied should be statically defined.\n\n  TODO: Add option to scale by L2 norm of the entire input.\n\n  Args:\n    inputs: A `Tensor` of arbitrary size.\n    target_norm_value: A float value that specifies an initial target norm or\n      a list of floats (whose length must be equal to the depth along the\n      dimension to be normalized) specifying a per-dimension multiplier\n      after normalization.\n    dim: The dimension along which the input is normalized.\n    epsilon: A small value to add to the inputs to avoid dividing by zero.\n    trainable: Whether the norm is trainable or not\n    scope: Optional scope for variable_scope.\n    summarize: Whether or not to add a tensorflow summary for the op.\n\n  Returns:\n    The input tensor normalized to the specified target norm.\n\n  Raises:\n    ValueError: If dim is smaller than the number of dimensions in 'inputs'.\n    ValueError: If target_norm_value is not a float or a list of floats with\n      length equal to the depth along the dimension to be normalized.\n  \"\"\"\n  with tf.variable_scope(scope, 'NormalizeToTarget', [inputs]):\n    if not inputs.get_shape():\n      raise ValueError('The input rank must be known.')\n    input_shape = inputs.get_shape().as_list()\n    input_rank = len(input_shape)\n    if dim < 0 or dim >= input_rank:\n      raise ValueError(\n          'dim must be non-negative but smaller than the input rank.')\n    if not input_shape[dim]:\n      raise ValueError('input shape should be statically defined along '\n                       'the specified dimension.')\n    depth = input_shape[dim]\n    if not (isinstance(target_norm_value, float) or\n            (isinstance(target_norm_value, list) and\n             len(target_norm_value) == depth) and\n            all([isinstance(val, float) for val in target_norm_value])):\n      raise ValueError('target_norm_value must be a float or a list of floats '\n                       'with length equal to the depth along the dimension to '\n                       'be normalized.')\n    if isinstance(target_norm_value, float):\n      initial_norm = depth * [target_norm_value]\n    else:\n      initial_norm = target_norm_value\n    target_norm = tf.contrib.framework.model_variable(\n        name='weights', dtype=tf.float32,\n        initializer=tf.constant(initial_norm, dtype=tf.float32),\n        trainable=trainable)\n    if summarize:\n      mean = tf.reduce_mean(target_norm)\n      mean = tf.Print(mean, ['NormalizeToTarget:', mean])\n      tf.summary.scalar(tf.get_variable_scope().name, mean)\n    lengths = epsilon + tf.sqrt(tf.reduce_sum(tf.square(inputs), dim, True))\n    mult_shape = input_rank*[1]\n    mult_shape[dim] = depth\n    return tf.reshape(target_norm, mult_shape) * tf.truediv(inputs, lengths)\n\n\ndef position_sensitive_crop_regions(image,\n                                    boxes,\n                                    box_ind,\n                                    crop_size,\n                                    num_spatial_bins,\n                                    global_pool,\n                                    extrapolation_value=None):\n  \"\"\"Position-sensitive crop and pool rectangular regions from a feature grid.\n\n  The output crops are split into `spatial_bins_y` vertical bins\n  and `spatial_bins_x` horizontal bins. For each intersection of a vertical\n  and a horizontal bin the output values are gathered by performing\n  `tf.image.crop_and_resize` (bilinear resampling) on a a separate subset of\n  channels of the image. This reduces `depth` by a factor of\n  `(spatial_bins_y * spatial_bins_x)`.\n\n  When global_pool is True, this function implements a differentiable version\n  of position-sensitive RoI pooling used in\n  [R-FCN detection system](https://arxiv.org/abs/1605.06409).\n\n  When global_pool is False, this function implements a differentiable version\n  of position-sensitive assembling operation used in\n  [instance FCN](https://arxiv.org/abs/1603.08678).\n\n  Args:\n    image: A `Tensor`. Must be one of the following types: `uint8`, `int8`,\n      `int16`, `int32`, `int64`, `half`, `float32`, `float64`.\n      A 4-D tensor of shape `[batch, image_height, image_width, depth]`.\n      Both `image_height` and `image_width` need to be positive.\n    boxes: A `Tensor` of type `float32`.\n      A 2-D tensor of shape `[num_boxes, 4]`. The `i`-th row of the tensor\n      specifies the coordinates of a box in the `box_ind[i]` image and is\n      specified in normalized coordinates `[y1, x1, y2, x2]`. A normalized\n      coordinate value of `y` is mapped to the image coordinate at\n      `y * (image_height - 1)`, so as the `[0, 1]` interval of normalized image\n      height is mapped to `[0, image_height - 1] in image height coordinates.\n      We do allow y1 > y2, in which case the sampled crop is an up-down flipped\n      version of the original image. The width dimension is treated similarly.\n      Normalized coordinates outside the `[0, 1]` range are allowed, in which\n      case we use `extrapolation_value` to extrapolate the input image values.\n    box_ind:  A `Tensor` of type `int32`.\n      A 1-D tensor of shape `[num_boxes]` with int32 values in `[0, batch)`.\n      The value of `box_ind[i]` specifies the image that the `i`-th box refers\n      to.\n    crop_size: A list of two integers `[crop_height, crop_width]`. All\n      cropped image patches are resized to this size. The aspect ratio of the\n      image content is not preserved. Both `crop_height` and `crop_width` need\n      to be positive.\n    num_spatial_bins: A list of two integers `[spatial_bins_y, spatial_bins_x]`.\n      Represents the number of position-sensitive bins in y and x directions.\n      Both values should be >= 1. `crop_height` should be divisible by\n      `spatial_bins_y`, and similarly for width.\n      The number of image channels should be divisible by\n      (spatial_bins_y * spatial_bins_x).\n      Suggested value from R-FCN paper: [3, 3].\n    global_pool: A boolean variable.\n      If True, we perform average global pooling on the features assembled from\n        the position-sensitive score maps.\n      If False, we keep the position-pooled features without global pooling\n        over the spatial coordinates.\n      Note that using global_pool=True is equivalent to but more efficient than\n        running the function with global_pool=False and then performing global\n        average pooling.\n    extrapolation_value: An optional `float`. Defaults to `0`.\n      Value used for extrapolation, when applicable.\n  Returns:\n    position_sensitive_features: A 4-D tensor of shape\n      `[num_boxes, K, K, crop_channels]`,\n      where `crop_channels = depth / (spatial_bins_y * spatial_bins_x)`,\n      where K = 1 when global_pool is True (Average-pooled cropped regions),\n      and K = crop_size when global_pool is False.\n  Raises:\n    ValueError: Raised in four situations:\n      `num_spatial_bins` is not >= 1;\n      `num_spatial_bins` does not divide `crop_size`;\n      `(spatial_bins_y*spatial_bins_x)` does not divide `depth`;\n      `bin_crop_size` is not square when global_pool=False due to the\n        constraint in function space_to_depth.\n  \"\"\"\n  total_bins = 1\n  bin_crop_size = []\n\n  for (num_bins, crop_dim) in zip(num_spatial_bins, crop_size):\n    if num_bins < 1:\n      raise ValueError('num_spatial_bins should be >= 1')\n\n    if crop_dim % num_bins != 0:\n      raise ValueError('crop_size should be divisible by num_spatial_bins')\n\n    total_bins *= num_bins\n    bin_crop_size.append(crop_dim / num_bins)\n\n  if not global_pool and bin_crop_size[0] != bin_crop_size[1]:\n    raise ValueError('Only support square bin crop size for now.')\n\n  ymin, xmin, ymax, xmax = tf.unstack(boxes, axis=1)\n  spatial_bins_y, spatial_bins_x = num_spatial_bins\n\n  # Split each box into spatial_bins_y * spatial_bins_x bins.\n  position_sensitive_boxes = []\n  for bin_y in range(spatial_bins_y):\n    step_y = (ymax - ymin) / spatial_bins_y\n    for bin_x in range(spatial_bins_x):\n      step_x = (xmax - xmin) / spatial_bins_x\n      box_coordinates = [ymin + bin_y * step_y,\n                         xmin + bin_x * step_x,\n                         ymin + (bin_y + 1) * step_y,\n                         xmin + (bin_x + 1) * step_x,\n                        ]\n      position_sensitive_boxes.append(tf.stack(box_coordinates, axis=1))\n\n  image_splits = tf.split(value=image, num_or_size_splits=total_bins, axis=3)\n\n  image_crops = []\n  for (split, box) in zip(image_splits, position_sensitive_boxes):\n    crop = tf.image.crop_and_resize(split, box, box_ind, bin_crop_size,\n                                    extrapolation_value=extrapolation_value)\n    image_crops.append(crop)\n\n  if global_pool:\n    # Average over all bins.\n    position_sensitive_features = tf.add_n(image_crops) / len(image_crops)\n    # Then average over spatial positions within the bins.\n    position_sensitive_features = tf.reduce_mean(\n        position_sensitive_features, [1, 2], keep_dims=True)\n  else:\n    # Reorder height/width to depth channel.\n    block_size = bin_crop_size[0]\n    if block_size >= 2:\n      image_crops = [tf.space_to_depth(\n          crop, block_size=block_size) for crop in image_crops]\n\n    # Pack image_crops so that first dimension is for position-senstive boxes.\n    position_sensitive_features = tf.stack(image_crops, axis=0)\n\n    # Unroll the position-sensitive boxes to spatial positions.\n    position_sensitive_features = tf.squeeze(\n        tf.batch_to_space_nd(position_sensitive_features,\n                             block_shape=[1] + num_spatial_bins,\n                             crops=tf.zeros((3, 2), dtype=tf.int32)),\n        squeeze_dims=[0])\n\n    # Reorder back the depth channel.\n    if block_size >= 2:\n      position_sensitive_features = tf.depth_to_space(\n          position_sensitive_features, block_size=block_size)\n\n  return position_sensitive_features\n\n\ndef reframe_box_masks_to_image_masks(box_masks, boxes, image_height,\n                                     image_width):\n  \"\"\"Transforms the box masks back to full image masks.\n\n  Embeds masks in bounding boxes of larger masks whose shapes correspond to\n  image shape.\n\n  Args:\n    box_masks: A tf.float32 tensor of size [num_masks, mask_height, mask_width].\n    boxes: A tf.float32 tensor of size [num_masks, 4] containing the box\n           corners. Row i contains [ymin, xmin, ymax, xmax] of the box\n           corresponding to mask i. Note that the box corners are in\n           normalized coordinates.\n    image_height: Image height. The output mask will have the same height as\n                  the image height.\n    image_width: Image width. The output mask will have the same width as the\n                 image width.\n\n  Returns:\n    A tf.float32 tensor of size [num_masks, image_height, image_width].\n  \"\"\"\n  # TODO: Make this a public function.\n  def transform_boxes_relative_to_boxes(boxes, reference_boxes):\n    boxes = tf.reshape(boxes, [-1, 2, 2])\n    min_corner = tf.expand_dims(reference_boxes[:, 0:2], 1)\n    max_corner = tf.expand_dims(reference_boxes[:, 2:4], 1)\n    transformed_boxes = (boxes - min_corner) / (max_corner - min_corner)\n    return tf.reshape(transformed_boxes, [-1, 4])\n\n  box_masks = tf.expand_dims(box_masks, axis=3)\n  num_boxes = tf.shape(box_masks)[0]\n  unit_boxes = tf.concat(\n      [tf.zeros([num_boxes, 2]), tf.ones([num_boxes, 2])], axis=1)\n  reverse_boxes = transform_boxes_relative_to_boxes(unit_boxes, boxes)\n  image_masks = tf.image.crop_and_resize(image=box_masks,\n                                         boxes=reverse_boxes,\n                                         box_ind=tf.range(num_boxes),\n                                         crop_size=[image_height, image_width],\n                                         extrapolation_value=0.0)\n  return tf.squeeze(image_masks, axis=3)\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/ops_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.utils.ops.\"\"\"\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.core import standard_fields as fields\nfrom object_detection.utils import ops\n\n\nclass NormalizedToImageCoordinatesTest(tf.test.TestCase):\n\n  def test_normalized_to_image_coordinates(self):\n    normalized_boxes = tf.placeholder(tf.float32, shape=(None, 1, 4))\n    normalized_boxes_np = np.array([[[0.0, 0.0, 1.0, 1.0]],\n                                    [[0.5, 0.5, 1.0, 1.0]]])\n    image_shape = tf.convert_to_tensor([1, 4, 4, 3], dtype=tf.int32)\n    absolute_boxes = ops.normalized_to_image_coordinates(normalized_boxes,\n                                                         image_shape,\n                                                         parallel_iterations=2)\n\n    expected_boxes = np.array([[[0, 0, 4, 4]],\n                               [[2, 2, 4, 4]]])\n    with self.test_session() as sess:\n      absolute_boxes = sess.run(absolute_boxes,\n                                feed_dict={normalized_boxes:\n                                           normalized_boxes_np})\n\n    self.assertAllEqual(absolute_boxes, expected_boxes)\n\n\nclass MeshgridTest(tf.test.TestCase):\n\n  def test_meshgrid_numpy_comparison(self):\n    \"\"\"Tests meshgrid op with vectors, for which it should match numpy.\"\"\"\n    x = np.arange(4)\n    y = np.arange(6)\n    exp_xgrid, exp_ygrid = np.meshgrid(x, y)\n    xgrid, ygrid = ops.meshgrid(x, y)\n    with self.test_session() as sess:\n      xgrid_output, ygrid_output = sess.run([xgrid, ygrid])\n      self.assertAllEqual(xgrid_output, exp_xgrid)\n      self.assertAllEqual(ygrid_output, exp_ygrid)\n\n  def test_meshgrid_multidimensional(self):\n    np.random.seed(18)\n    x = np.random.rand(4, 1, 2).astype(np.float32)\n    y = np.random.rand(2, 3).astype(np.float32)\n\n    xgrid, ygrid = ops.meshgrid(x, y)\n\n    grid_shape = list(y.shape) + list(x.shape)\n    self.assertEqual(xgrid.get_shape().as_list(), grid_shape)\n    self.assertEqual(ygrid.get_shape().as_list(), grid_shape)\n    with self.test_session() as sess:\n      xgrid_output, ygrid_output = sess.run([xgrid, ygrid])\n\n    # Check the shape of the output grids\n    self.assertEqual(xgrid_output.shape, tuple(grid_shape))\n    self.assertEqual(ygrid_output.shape, tuple(grid_shape))\n\n    # Check a few elements\n    test_elements = [((3, 0, 0), (1, 2)),\n                     ((2, 0, 1), (0, 0)),\n                     ((0, 0, 0), (1, 1))]\n    for xind, yind in test_elements:\n      # These are float equality tests, but the meshgrid op should not introduce\n      # rounding.\n      self.assertEqual(xgrid_output[yind + xind], x[xind])\n      self.assertEqual(ygrid_output[yind + xind], y[yind])\n\n\nclass OpsTestPadToMultiple(tf.test.TestCase):\n\n  def test_zero_padding(self):\n    tensor = tf.constant([[[[0.], [0.]], [[0.], [0.]]]])\n    padded_tensor = ops.pad_to_multiple(tensor, 1)\n    with self.test_session() as sess:\n      padded_tensor_out = sess.run(padded_tensor)\n    self.assertEqual((1, 2, 2, 1), padded_tensor_out.shape)\n\n  def test_no_padding(self):\n    tensor = tf.constant([[[[0.], [0.]], [[0.], [0.]]]])\n    padded_tensor = ops.pad_to_multiple(tensor, 2)\n    with self.test_session() as sess:\n      padded_tensor_out = sess.run(padded_tensor)\n    self.assertEqual((1, 2, 2, 1), padded_tensor_out.shape)\n\n  def test_padding(self):\n    tensor = tf.constant([[[[0.], [0.]], [[0.], [0.]]]])\n    padded_tensor = ops.pad_to_multiple(tensor, 4)\n    with self.test_session() as sess:\n      padded_tensor_out = sess.run(padded_tensor)\n    self.assertEqual((1, 4, 4, 1), padded_tensor_out.shape)\n\n\nclass OpsTestPaddedOneHotEncoding(tf.test.TestCase):\n\n  def test_correct_one_hot_tensor_with_no_pad(self):\n    indices = tf.constant([1, 2, 3, 5])\n    one_hot_tensor = ops.padded_one_hot_encoding(indices, depth=6, left_pad=0)\n    expected_tensor = np.array([[0, 1, 0, 0, 0, 0],\n                                [0, 0, 1, 0, 0, 0],\n                                [0, 0, 0, 1, 0, 0],\n                                [0, 0, 0, 0, 0, 1]], np.float32)\n    with self.test_session() as sess:\n      out_one_hot_tensor = sess.run(one_hot_tensor)\n      self.assertAllClose(out_one_hot_tensor, expected_tensor, rtol=1e-10,\n                          atol=1e-10)\n\n  def test_correct_one_hot_tensor_with_pad_one(self):\n    indices = tf.constant([1, 2, 3, 5])\n    one_hot_tensor = ops.padded_one_hot_encoding(indices, depth=6, left_pad=1)\n    expected_tensor = np.array([[0, 0, 1, 0, 0, 0, 0],\n                                [0, 0, 0, 1, 0, 0, 0],\n                                [0, 0, 0, 0, 1, 0, 0],\n                                [0, 0, 0, 0, 0, 0, 1]], np.float32)\n    with self.test_session() as sess:\n      out_one_hot_tensor = sess.run(one_hot_tensor)\n      self.assertAllClose(out_one_hot_tensor, expected_tensor, rtol=1e-10,\n                          atol=1e-10)\n\n  def test_correct_one_hot_tensor_with_pad_three(self):\n    indices = tf.constant([1, 2, 3, 5])\n    one_hot_tensor = ops.padded_one_hot_encoding(indices, depth=6, left_pad=3)\n    expected_tensor = np.array([[0, 0, 0, 0, 1, 0, 0, 0, 0],\n                                [0, 0, 0, 0, 0, 1, 0, 0, 0],\n                                [0, 0, 0, 0, 0, 0, 1, 0, 0],\n                                [0, 0, 0, 0, 0, 0, 0, 0, 1]], np.float32)\n    with self.test_session() as sess:\n      out_one_hot_tensor = sess.run(one_hot_tensor)\n      self.assertAllClose(out_one_hot_tensor, expected_tensor, rtol=1e-10,\n                          atol=1e-10)\n\n  def test_correct_padded_one_hot_tensor_with_empty_indices(self):\n    depth = 6\n    pad = 2\n    indices = tf.constant([])\n    one_hot_tensor = ops.padded_one_hot_encoding(\n        indices, depth=depth, left_pad=pad)\n    expected_tensor = np.zeros((0, depth + pad))\n    with self.test_session() as sess:\n      out_one_hot_tensor = sess.run(one_hot_tensor)\n      self.assertAllClose(out_one_hot_tensor, expected_tensor, rtol=1e-10,\n                          atol=1e-10)\n\n  def test_return_none_on_zero_depth(self):\n    indices = tf.constant([1, 2, 3, 4, 5])\n    one_hot_tensor = ops.padded_one_hot_encoding(indices, depth=0, left_pad=2)\n    self.assertEqual(one_hot_tensor, None)\n\n  def test_raise_value_error_on_rank_two_input(self):\n    indices = tf.constant(1.0, shape=(2, 3))\n    with self.assertRaises(ValueError):\n      ops.padded_one_hot_encoding(indices, depth=6, left_pad=2)\n\n  def test_raise_value_error_on_negative_pad(self):\n    indices = tf.constant(1.0, shape=(2, 3))\n    with self.assertRaises(ValueError):\n      ops.padded_one_hot_encoding(indices, depth=6, left_pad=-1)\n\n  def test_raise_value_error_on_float_pad(self):\n    indices = tf.constant(1.0, shape=(2, 3))\n    with self.assertRaises(ValueError):\n      ops.padded_one_hot_encoding(indices, depth=6, left_pad=0.1)\n\n  def test_raise_value_error_on_float_depth(self):\n    indices = tf.constant(1.0, shape=(2, 3))\n    with self.assertRaises(ValueError):\n      ops.padded_one_hot_encoding(indices, depth=0.1, left_pad=2)\n\n\nclass OpsDenseToSparseBoxesTest(tf.test.TestCase):\n\n  def test_return_all_boxes_when_all_input_boxes_are_valid(self):\n    num_classes = 4\n    num_valid_boxes = 3\n    code_size = 4\n    dense_location_placeholder = tf.placeholder(tf.float32,\n                                                shape=(num_valid_boxes,\n                                                       code_size))\n    dense_num_boxes_placeholder = tf.placeholder(tf.int32, shape=(num_classes))\n    box_locations, box_classes = ops.dense_to_sparse_boxes(\n        dense_location_placeholder, dense_num_boxes_placeholder, num_classes)\n    feed_dict = {dense_location_placeholder: np.random.uniform(\n        size=[num_valid_boxes, code_size]),\n                 dense_num_boxes_placeholder: np.array([1, 0, 0, 2],\n                                                       dtype=np.int32)}\n\n    expected_box_locations = feed_dict[dense_location_placeholder]\n    expected_box_classses = np.array([0, 3, 3])\n    with self.test_session() as sess:\n      box_locations, box_classes = sess.run([box_locations, box_classes],\n                                            feed_dict=feed_dict)\n\n    self.assertAllClose(box_locations, expected_box_locations, rtol=1e-6,\n                        atol=1e-6)\n    self.assertAllEqual(box_classes, expected_box_classses)\n\n  def test_return_only_valid_boxes_when_input_contains_invalid_boxes(self):\n    num_classes = 4\n    num_valid_boxes = 3\n    num_boxes = 10\n    code_size = 4\n\n    dense_location_placeholder = tf.placeholder(tf.float32, shape=(num_boxes,\n                                                                   code_size))\n    dense_num_boxes_placeholder = tf.placeholder(tf.int32, shape=(num_classes))\n    box_locations, box_classes = ops.dense_to_sparse_boxes(\n        dense_location_placeholder, dense_num_boxes_placeholder, num_classes)\n    feed_dict = {dense_location_placeholder: np.random.uniform(\n        size=[num_boxes, code_size]),\n                 dense_num_boxes_placeholder: np.array([1, 0, 0, 2],\n                                                       dtype=np.int32)}\n\n    expected_box_locations = (feed_dict[dense_location_placeholder]\n                              [:num_valid_boxes])\n    expected_box_classses = np.array([0, 3, 3])\n    with self.test_session() as sess:\n      box_locations, box_classes = sess.run([box_locations, box_classes],\n                                            feed_dict=feed_dict)\n\n    self.assertAllClose(box_locations, expected_box_locations, rtol=1e-6,\n                        atol=1e-6)\n    self.assertAllEqual(box_classes, expected_box_classses)\n\n\nclass OpsTestIndicesToDenseVector(tf.test.TestCase):\n\n  def test_indices_to_dense_vector(self):\n    size = 10000\n    num_indices = np.random.randint(size)\n    rand_indices = np.random.permutation(np.arange(size))[0:num_indices]\n\n    expected_output = np.zeros(size, dtype=np.float32)\n    expected_output[rand_indices] = 1.\n\n    tf_rand_indices = tf.constant(rand_indices)\n    indicator = ops.indices_to_dense_vector(tf_rand_indices, size)\n\n    with self.test_session() as sess:\n      output = sess.run(indicator)\n      self.assertAllEqual(output, expected_output)\n      self.assertEqual(output.dtype, expected_output.dtype)\n\n  def test_indices_to_dense_vector_size_at_inference(self):\n    size = 5000\n    num_indices = 250\n    all_indices = np.arange(size)\n    rand_indices = np.random.permutation(all_indices)[0:num_indices]\n\n    expected_output = np.zeros(size, dtype=np.float32)\n    expected_output[rand_indices] = 1.\n\n    tf_all_indices = tf.placeholder(tf.int32)\n    tf_rand_indices = tf.constant(rand_indices)\n    indicator = ops.indices_to_dense_vector(tf_rand_indices,\n                                            tf.shape(tf_all_indices)[0])\n    feed_dict = {tf_all_indices: all_indices}\n\n    with self.test_session() as sess:\n      output = sess.run(indicator, feed_dict=feed_dict)\n      self.assertAllEqual(output, expected_output)\n      self.assertEqual(output.dtype, expected_output.dtype)\n\n  def test_indices_to_dense_vector_int(self):\n    size = 500\n    num_indices = 25\n    rand_indices = np.random.permutation(np.arange(size))[0:num_indices]\n\n    expected_output = np.zeros(size, dtype=np.int64)\n    expected_output[rand_indices] = 1\n\n    tf_rand_indices = tf.constant(rand_indices)\n    indicator = ops.indices_to_dense_vector(\n        tf_rand_indices, size, 1, dtype=tf.int64)\n\n    with self.test_session() as sess:\n      output = sess.run(indicator)\n      self.assertAllEqual(output, expected_output)\n      self.assertEqual(output.dtype, expected_output.dtype)\n\n  def test_indices_to_dense_vector_custom_values(self):\n    size = 100\n    num_indices = 10\n    rand_indices = np.random.permutation(np.arange(size))[0:num_indices]\n    indices_value = np.random.rand(1)\n    default_value = np.random.rand(1)\n\n    expected_output = np.float32(np.ones(size) * default_value)\n    expected_output[rand_indices] = indices_value\n\n    tf_rand_indices = tf.constant(rand_indices)\n    indicator = ops.indices_to_dense_vector(\n        tf_rand_indices,\n        size,\n        indices_value=indices_value,\n        default_value=default_value)\n\n    with self.test_session() as sess:\n      output = sess.run(indicator)\n      self.assertAllClose(output, expected_output)\n      self.assertEqual(output.dtype, expected_output.dtype)\n\n  def test_indices_to_dense_vector_all_indices_as_input(self):\n    size = 500\n    num_indices = 500\n    rand_indices = np.random.permutation(np.arange(size))[0:num_indices]\n\n    expected_output = np.ones(size, dtype=np.float32)\n\n    tf_rand_indices = tf.constant(rand_indices)\n    indicator = ops.indices_to_dense_vector(tf_rand_indices, size)\n\n    with self.test_session() as sess:\n      output = sess.run(indicator)\n      self.assertAllEqual(output, expected_output)\n      self.assertEqual(output.dtype, expected_output.dtype)\n\n  def test_indices_to_dense_vector_empty_indices_as_input(self):\n    size = 500\n    rand_indices = []\n\n    expected_output = np.zeros(size, dtype=np.float32)\n\n    tf_rand_indices = tf.constant(rand_indices)\n    indicator = ops.indices_to_dense_vector(tf_rand_indices, size)\n\n    with self.test_session() as sess:\n      output = sess.run(indicator)\n      self.assertAllEqual(output, expected_output)\n      self.assertEqual(output.dtype, expected_output.dtype)\n\n\nclass GroundtruthFilterTest(tf.test.TestCase):\n\n  def test_filter_groundtruth(self):\n    input_image = tf.placeholder(tf.float32, shape=(None, None, 3))\n    input_boxes = tf.placeholder(tf.float32, shape=(None, 4))\n    input_classes = tf.placeholder(tf.int32, shape=(None,))\n    input_is_crowd = tf.placeholder(tf.bool, shape=(None,))\n    input_area = tf.placeholder(tf.float32, shape=(None,))\n    input_difficult = tf.placeholder(tf.float32, shape=(None,))\n    input_label_types = tf.placeholder(tf.string, shape=(None,))\n    valid_indices = tf.placeholder(tf.int32, shape=(None,))\n    input_tensors = {\n        fields.InputDataFields.image: input_image,\n        fields.InputDataFields.groundtruth_boxes: input_boxes,\n        fields.InputDataFields.groundtruth_classes: input_classes,\n        fields.InputDataFields.groundtruth_is_crowd: input_is_crowd,\n        fields.InputDataFields.groundtruth_area: input_area,\n        fields.InputDataFields.groundtruth_difficult: input_difficult,\n        fields.InputDataFields.groundtruth_label_types: input_label_types\n    }\n    output_tensors = ops.retain_groundtruth(input_tensors, valid_indices)\n\n    image_tensor = np.random.rand(224, 224, 3)\n    feed_dict = {\n        input_image: image_tensor,\n        input_boxes:\n        np.array([[0.2, 0.4, 0.1, 0.8], [0.2, 0.4, 1.0, 0.8]], dtype=np.float),\n        input_classes:\n        np.array([1, 2], dtype=np.int32),\n        input_is_crowd:\n        np.array([False, True], dtype=np.bool),\n        input_area:\n        np.array([32, 48], dtype=np.float32),\n        input_difficult:\n        np.array([True, False], dtype=np.bool),\n        input_label_types:\n        np.array(['APPROPRIATE', 'INCORRECT'], dtype=np.string_),\n        valid_indices:\n        np.array([0], dtype=np.int32)\n    }\n    expected_tensors = {\n        fields.InputDataFields.image:\n        image_tensor,\n        fields.InputDataFields.groundtruth_boxes:\n        [[0.2, 0.4, 0.1, 0.8]],\n        fields.InputDataFields.groundtruth_classes:\n        [1],\n        fields.InputDataFields.groundtruth_is_crowd:\n        [False],\n        fields.InputDataFields.groundtruth_area:\n        [32],\n        fields.InputDataFields.groundtruth_difficult:\n        [True],\n        fields.InputDataFields.groundtruth_label_types:\n        ['APPROPRIATE']\n    }\n    with self.test_session() as sess:\n      output_tensors = sess.run(output_tensors, feed_dict=feed_dict)\n      for key in [fields.InputDataFields.image,\n                  fields.InputDataFields.groundtruth_boxes,\n                  fields.InputDataFields.groundtruth_area]:\n        self.assertAllClose(expected_tensors[key], output_tensors[key])\n      for key in [fields.InputDataFields.groundtruth_classes,\n                  fields.InputDataFields.groundtruth_is_crowd,\n                  fields.InputDataFields.groundtruth_label_types]:\n        self.assertAllEqual(expected_tensors[key], output_tensors[key])\n\n  def test_filter_with_missing_fields(self):\n    input_boxes = tf.placeholder(tf.float32, shape=(None, 4))\n    input_classes = tf.placeholder(tf.int32, shape=(None,))\n    input_tensors = {\n        fields.InputDataFields.groundtruth_boxes: input_boxes,\n        fields.InputDataFields.groundtruth_classes: input_classes\n    }\n    valid_indices = tf.placeholder(tf.int32, shape=(None,))\n\n    feed_dict = {\n        input_boxes:\n        np.array([[0.2, 0.4, 0.1, 0.8], [0.2, 0.4, 1.0, 0.8]], dtype=np.float),\n        input_classes:\n        np.array([1, 2], dtype=np.int32),\n        valid_indices:\n        np.array([0], dtype=np.int32)\n    }\n    expected_tensors = {\n        fields.InputDataFields.groundtruth_boxes:\n        [[0.2, 0.4, 0.1, 0.8]],\n        fields.InputDataFields.groundtruth_classes:\n        [1]\n    }\n\n    output_tensors = ops.retain_groundtruth(input_tensors, valid_indices)\n    with self.test_session() as sess:\n      output_tensors = sess.run(output_tensors, feed_dict=feed_dict)\n      for key in [fields.InputDataFields.groundtruth_boxes]:\n        self.assertAllClose(expected_tensors[key], output_tensors[key])\n      for key in [fields.InputDataFields.groundtruth_classes]:\n        self.assertAllEqual(expected_tensors[key], output_tensors[key])\n\n  def test_filter_with_empty_fields(self):\n    input_boxes = tf.placeholder(tf.float32, shape=(None, 4))\n    input_classes = tf.placeholder(tf.int32, shape=(None,))\n    input_is_crowd = tf.placeholder(tf.bool, shape=(None,))\n    input_area = tf.placeholder(tf.float32, shape=(None,))\n    input_difficult = tf.placeholder(tf.float32, shape=(None,))\n    valid_indices = tf.placeholder(tf.int32, shape=(None,))\n    input_tensors = {\n        fields.InputDataFields.groundtruth_boxes: input_boxes,\n        fields.InputDataFields.groundtruth_classes: input_classes,\n        fields.InputDataFields.groundtruth_is_crowd: input_is_crowd,\n        fields.InputDataFields.groundtruth_area: input_area,\n        fields.InputDataFields.groundtruth_difficult: input_difficult\n    }\n    output_tensors = ops.retain_groundtruth(input_tensors, valid_indices)\n\n    feed_dict = {\n        input_boxes:\n        np.array([[0.2, 0.4, 0.1, 0.8], [0.2, 0.4, 1.0, 0.8]], dtype=np.float),\n        input_classes:\n        np.array([1, 2], dtype=np.int32),\n        input_is_crowd:\n        np.array([False, True], dtype=np.bool),\n        input_area:\n        np.array([], dtype=np.float32),\n        input_difficult:\n        np.array([], dtype=np.float32),\n        valid_indices:\n        np.array([0], dtype=np.int32)\n    }\n    expected_tensors = {\n        fields.InputDataFields.groundtruth_boxes:\n        [[0.2, 0.4, 0.1, 0.8]],\n        fields.InputDataFields.groundtruth_classes:\n        [1],\n        fields.InputDataFields.groundtruth_is_crowd:\n        [False],\n        fields.InputDataFields.groundtruth_area:\n        [],\n        fields.InputDataFields.groundtruth_difficult:\n        []\n    }\n    with self.test_session() as sess:\n      output_tensors = sess.run(output_tensors, feed_dict=feed_dict)\n      for key in [fields.InputDataFields.groundtruth_boxes,\n                  fields.InputDataFields.groundtruth_area]:\n        self.assertAllClose(expected_tensors[key], output_tensors[key])\n      for key in [fields.InputDataFields.groundtruth_classes,\n                  fields.InputDataFields.groundtruth_is_crowd]:\n        self.assertAllEqual(expected_tensors[key], output_tensors[key])\n\n  def test_filter_with_empty_groundtruth_boxes(self):\n    input_boxes = tf.placeholder(tf.float32, shape=(None, 4))\n    input_classes = tf.placeholder(tf.int32, shape=(None,))\n    input_is_crowd = tf.placeholder(tf.bool, shape=(None,))\n    input_area = tf.placeholder(tf.float32, shape=(None,))\n    input_difficult = tf.placeholder(tf.float32, shape=(None,))\n    valid_indices = tf.placeholder(tf.int32, shape=(None,))\n    input_tensors = {\n        fields.InputDataFields.groundtruth_boxes: input_boxes,\n        fields.InputDataFields.groundtruth_classes: input_classes,\n        fields.InputDataFields.groundtruth_is_crowd: input_is_crowd,\n        fields.InputDataFields.groundtruth_area: input_area,\n        fields.InputDataFields.groundtruth_difficult: input_difficult\n    }\n    output_tensors = ops.retain_groundtruth(input_tensors, valid_indices)\n\n    feed_dict = {\n        input_boxes:\n        np.array([], dtype=np.float).reshape(0, 4),\n        input_classes:\n        np.array([], dtype=np.int32),\n        input_is_crowd:\n        np.array([], dtype=np.bool),\n        input_area:\n        np.array([], dtype=np.float32),\n        input_difficult:\n        np.array([], dtype=np.float32),\n        valid_indices:\n        np.array([], dtype=np.int32)\n    }\n    with self.test_session() as sess:\n      output_tensors = sess.run(output_tensors, feed_dict=feed_dict)\n      for key in input_tensors:\n        if key == fields.InputDataFields.groundtruth_boxes:\n          self.assertAllEqual([0, 4], output_tensors[key].shape)\n        else:\n          self.assertAllEqual([0], output_tensors[key].shape)\n\n\nclass RetainGroundTruthWithPositiveClasses(tf.test.TestCase):\n\n  def test_filter_groundtruth_with_positive_classes(self):\n    input_image = tf.placeholder(tf.float32, shape=(None, None, 3))\n    input_boxes = tf.placeholder(tf.float32, shape=(None, 4))\n    input_classes = tf.placeholder(tf.int32, shape=(None,))\n    input_is_crowd = tf.placeholder(tf.bool, shape=(None,))\n    input_area = tf.placeholder(tf.float32, shape=(None,))\n    input_difficult = tf.placeholder(tf.float32, shape=(None,))\n    input_label_types = tf.placeholder(tf.string, shape=(None,))\n    valid_indices = tf.placeholder(tf.int32, shape=(None,))\n    input_tensors = {\n        fields.InputDataFields.image: input_image,\n        fields.InputDataFields.groundtruth_boxes: input_boxes,\n        fields.InputDataFields.groundtruth_classes: input_classes,\n        fields.InputDataFields.groundtruth_is_crowd: input_is_crowd,\n        fields.InputDataFields.groundtruth_area: input_area,\n        fields.InputDataFields.groundtruth_difficult: input_difficult,\n        fields.InputDataFields.groundtruth_label_types: input_label_types\n    }\n    output_tensors = ops.retain_groundtruth_with_positive_classes(input_tensors)\n\n    image_tensor = np.random.rand(224, 224, 3)\n    feed_dict = {\n        input_image: image_tensor,\n        input_boxes:\n        np.array([[0.2, 0.4, 0.1, 0.8], [0.2, 0.4, 1.0, 0.8]], dtype=np.float),\n        input_classes:\n        np.array([1, 0], dtype=np.int32),\n        input_is_crowd:\n        np.array([False, True], dtype=np.bool),\n        input_area:\n        np.array([32, 48], dtype=np.float32),\n        input_difficult:\n        np.array([True, False], dtype=np.bool),\n        input_label_types:\n        np.array(['APPROPRIATE', 'INCORRECT'], dtype=np.string_),\n        valid_indices:\n        np.array([0], dtype=np.int32)\n    }\n    expected_tensors = {\n        fields.InputDataFields.image:\n        image_tensor,\n        fields.InputDataFields.groundtruth_boxes:\n        [[0.2, 0.4, 0.1, 0.8]],\n        fields.InputDataFields.groundtruth_classes:\n        [1],\n        fields.InputDataFields.groundtruth_is_crowd:\n        [False],\n        fields.InputDataFields.groundtruth_area:\n        [32],\n        fields.InputDataFields.groundtruth_difficult:\n        [True],\n        fields.InputDataFields.groundtruth_label_types:\n        ['APPROPRIATE']\n    }\n    with self.test_session() as sess:\n      output_tensors = sess.run(output_tensors, feed_dict=feed_dict)\n      for key in [fields.InputDataFields.image,\n                  fields.InputDataFields.groundtruth_boxes,\n                  fields.InputDataFields.groundtruth_area]:\n        self.assertAllClose(expected_tensors[key], output_tensors[key])\n      for key in [fields.InputDataFields.groundtruth_classes,\n                  fields.InputDataFields.groundtruth_is_crowd,\n                  fields.InputDataFields.groundtruth_label_types]:\n        self.assertAllEqual(expected_tensors[key], output_tensors[key])\n\n\nclass GroundtruthFilterWithNanBoxTest(tf.test.TestCase):\n\n  def test_filter_groundtruth_with_nan_box_coordinates(self):\n    input_tensors = {\n        fields.InputDataFields.groundtruth_boxes:\n        [[np.nan, np.nan, np.nan, np.nan], [0.2, 0.4, 0.1, 0.8]],\n        fields.InputDataFields.groundtruth_classes:\n        [1, 2],\n        fields.InputDataFields.groundtruth_is_crowd:\n        [False, True],\n        fields.InputDataFields.groundtruth_area:\n        [100.0, 238.7]\n    }\n\n    expected_tensors = {\n        fields.InputDataFields.groundtruth_boxes:\n        [[0.2, 0.4, 0.1, 0.8]],\n        fields.InputDataFields.groundtruth_classes:\n        [2],\n        fields.InputDataFields.groundtruth_is_crowd:\n        [True],\n        fields.InputDataFields.groundtruth_area:\n        [238.7]\n    }\n\n    output_tensors = ops.filter_groundtruth_with_nan_box_coordinates(\n        input_tensors)\n    with self.test_session() as sess:\n      output_tensors = sess.run(output_tensors)\n      for key in [fields.InputDataFields.groundtruth_boxes,\n                  fields.InputDataFields.groundtruth_area]:\n        self.assertAllClose(expected_tensors[key], output_tensors[key])\n      for key in [fields.InputDataFields.groundtruth_classes,\n                  fields.InputDataFields.groundtruth_is_crowd]:\n        self.assertAllEqual(expected_tensors[key], output_tensors[key])\n\n\nclass OpsTestNormalizeToTarget(tf.test.TestCase):\n\n  def test_create_normalize_to_target(self):\n    inputs = tf.random_uniform([5, 10, 12, 3])\n    target_norm_value = 4.0\n    dim = 3\n    with self.test_session():\n      output = ops.normalize_to_target(inputs, target_norm_value, dim)\n      self.assertEqual(output.op.name, 'NormalizeToTarget/mul')\n      var_name = tf.contrib.framework.get_variables()[0].name\n      self.assertEqual(var_name, 'NormalizeToTarget/weights:0')\n\n  def test_invalid_dim(self):\n    inputs = tf.random_uniform([5, 10, 12, 3])\n    target_norm_value = 4.0\n    dim = 10\n    with self.assertRaisesRegexp(\n        ValueError,\n        'dim must be non-negative but smaller than the input rank.'):\n      ops.normalize_to_target(inputs, target_norm_value, dim)\n\n  def test_invalid_target_norm_values(self):\n    inputs = tf.random_uniform([5, 10, 12, 3])\n    target_norm_value = [4.0, 4.0]\n    dim = 3\n    with self.assertRaisesRegexp(\n        ValueError, 'target_norm_value must be a float or a list of floats'):\n      ops.normalize_to_target(inputs, target_norm_value, dim)\n\n  def test_correct_output_shape(self):\n    inputs = tf.random_uniform([5, 10, 12, 3])\n    target_norm_value = 4.0\n    dim = 3\n    with self.test_session():\n      output = ops.normalize_to_target(inputs, target_norm_value, dim)\n      self.assertEqual(output.get_shape().as_list(),\n                       inputs.get_shape().as_list())\n\n  def test_correct_initial_output_values(self):\n    inputs = tf.constant([[[[3, 4], [7, 24]],\n                           [[5, -12], [-1, 0]]]], tf.float32)\n    target_norm_value = 10.0\n    dim = 3\n    expected_output = [[[[30/5.0, 40/5.0], [70/25.0, 240/25.0]],\n                        [[50/13.0, -120/13.0], [-10, 0]]]]\n    with self.test_session() as sess:\n      normalized_inputs = ops.normalize_to_target(inputs, target_norm_value,\n                                                  dim)\n      sess.run(tf.global_variables_initializer())\n      output = normalized_inputs.eval()\n      self.assertAllClose(output, expected_output)\n\n  def test_multiple_target_norm_values(self):\n    inputs = tf.constant([[[[3, 4], [7, 24]],\n                           [[5, -12], [-1, 0]]]], tf.float32)\n    target_norm_value = [10.0, 20.0]\n    dim = 3\n    expected_output = [[[[30/5.0, 80/5.0], [70/25.0, 480/25.0]],\n                        [[50/13.0, -240/13.0], [-10, 0]]]]\n    with self.test_session() as sess:\n      normalized_inputs = ops.normalize_to_target(inputs, target_norm_value,\n                                                  dim)\n      sess.run(tf.global_variables_initializer())\n      output = normalized_inputs.eval()\n      self.assertAllClose(output, expected_output)\n\n\nclass OpsTestPositionSensitiveCropRegions(tf.test.TestCase):\n\n  def test_position_sensitive(self):\n    num_spatial_bins = [3, 2]\n    image_shape = [1, 3, 2, 6]\n\n    # First channel is 1's, second channel is 2's, etc.\n    image = tf.constant(range(1, 3 * 2 + 1) * 6, dtype=tf.float32,\n                        shape=image_shape)\n    boxes = tf.random_uniform((2, 4))\n    box_ind = tf.constant([0, 0], dtype=tf.int32)\n\n    # The result for both boxes should be [[1, 2], [3, 4], [5, 6]]\n    # before averaging.\n    expected_output = np.array([3.5, 3.5]).reshape([2, 1, 1, 1])\n\n    for crop_size_mult in range(1, 3):\n      crop_size = [3 * crop_size_mult, 2 * crop_size_mult]\n      ps_crop_and_pool = ops.position_sensitive_crop_regions(\n          image, boxes, box_ind, crop_size, num_spatial_bins, global_pool=True)\n\n      with self.test_session() as sess:\n        output = sess.run(ps_crop_and_pool)\n        self.assertAllClose(output, expected_output)\n\n  def test_position_sensitive_with_equal_channels(self):\n    num_spatial_bins = [2, 2]\n    image_shape = [1, 3, 3, 4]\n    crop_size = [2, 2]\n\n    image = tf.constant(range(1, 3 * 3 + 1), dtype=tf.float32,\n                        shape=[1, 3, 3, 1])\n    tiled_image = tf.tile(image, [1, 1, 1, image_shape[3]])\n    boxes = tf.random_uniform((3, 4))\n    box_ind = tf.constant([0, 0, 0], dtype=tf.int32)\n\n    # All channels are equal so position-sensitive crop and resize should\n    # work as the usual crop and resize for just one channel.\n    crop = tf.image.crop_and_resize(image, boxes, box_ind, crop_size)\n    crop_and_pool = tf.reduce_mean(crop, [1, 2], keep_dims=True)\n\n    ps_crop_and_pool = ops.position_sensitive_crop_regions(\n        tiled_image,\n        boxes,\n        box_ind,\n        crop_size,\n        num_spatial_bins,\n        global_pool=True)\n\n    with self.test_session() as sess:\n      expected_output, output = sess.run((crop_and_pool, ps_crop_and_pool))\n      self.assertAllClose(output, expected_output)\n\n  def test_position_sensitive_with_single_bin(self):\n    num_spatial_bins = [1, 1]\n    image_shape = [2, 3, 3, 4]\n    crop_size = [2, 2]\n\n    image = tf.random_uniform(image_shape)\n    boxes = tf.random_uniform((6, 4))\n    box_ind = tf.constant([0, 0, 0, 1, 1, 1], dtype=tf.int32)\n\n    # When a single bin is used, position-sensitive crop and pool should be\n    # the same as non-position sensitive crop and pool.\n    crop = tf.image.crop_and_resize(image, boxes, box_ind, crop_size)\n    crop_and_pool = tf.reduce_mean(crop, [1, 2], keep_dims=True)\n\n    ps_crop_and_pool = ops.position_sensitive_crop_regions(\n        image, boxes, box_ind, crop_size, num_spatial_bins, global_pool=True)\n\n    with self.test_session() as sess:\n      expected_output, output = sess.run((crop_and_pool, ps_crop_and_pool))\n      self.assertAllClose(output, expected_output)\n\n  def test_raise_value_error_on_num_bins_less_than_one(self):\n    num_spatial_bins = [1, -1]\n    image_shape = [1, 1, 1, 2]\n    crop_size = [2, 2]\n\n    image = tf.constant(1, dtype=tf.float32, shape=image_shape)\n    boxes = tf.constant([[0, 0, 1, 1]], dtype=tf.float32)\n    box_ind = tf.constant([0], dtype=tf.int32)\n\n    with self.assertRaisesRegexp(ValueError, 'num_spatial_bins should be >= 1'):\n      ops.position_sensitive_crop_regions(\n          image, boxes, box_ind, crop_size, num_spatial_bins, global_pool=True)\n\n  def test_raise_value_error_on_non_divisible_crop_size(self):\n    num_spatial_bins = [2, 3]\n    image_shape = [1, 1, 1, 6]\n    crop_size = [3, 2]\n\n    image = tf.constant(1, dtype=tf.float32, shape=image_shape)\n    boxes = tf.constant([[0, 0, 1, 1]], dtype=tf.float32)\n    box_ind = tf.constant([0], dtype=tf.int32)\n\n    with self.assertRaisesRegexp(\n        ValueError, 'crop_size should be divisible by num_spatial_bins'):\n      ops.position_sensitive_crop_regions(\n          image, boxes, box_ind, crop_size, num_spatial_bins, global_pool=True)\n\n  def test_raise_value_error_on_non_divisible_num_channels(self):\n    num_spatial_bins = [2, 2]\n    image_shape = [1, 1, 1, 5]\n    crop_size = [2, 2]\n\n    image = tf.constant(1, dtype=tf.float32, shape=image_shape)\n    boxes = tf.constant([[0, 0, 1, 1]], dtype=tf.float32)\n    box_ind = tf.constant([0], dtype=tf.int32)\n\n    with self.assertRaisesRegexp(\n        ValueError, 'Dimension size must be evenly divisible by 4 but is 5'):\n      ops.position_sensitive_crop_regions(\n          image, boxes, box_ind, crop_size, num_spatial_bins, global_pool=True)\n\n  def test_position_sensitive_with_global_pool_false(self):\n    num_spatial_bins = [3, 2]\n    image_shape = [1, 3, 2, 6]\n    num_boxes = 2\n\n    # First channel is 1's, second channel is 2's, etc.\n    image = tf.constant(range(1, 3 * 2 + 1) * 6, dtype=tf.float32,\n                        shape=image_shape)\n    boxes = tf.random_uniform((num_boxes, 4))\n    box_ind = tf.constant([0, 0], dtype=tf.int32)\n\n    expected_output = []\n\n    # Expected output, when crop_size = [3, 2].\n    expected_output.append(np.expand_dims(\n        np.tile(np.array([[1, 2],\n                          [3, 4],\n                          [5, 6]]), (num_boxes, 1, 1)),\n        axis=-1))\n\n    # Expected output, when crop_size = [6, 4].\n    expected_output.append(np.expand_dims(\n        np.tile(np.array([[1, 1, 2, 2],\n                          [1, 1, 2, 2],\n                          [3, 3, 4, 4],\n                          [3, 3, 4, 4],\n                          [5, 5, 6, 6],\n                          [5, 5, 6, 6]]), (num_boxes, 1, 1)),\n        axis=-1))\n\n    for crop_size_mult in range(1, 3):\n      crop_size = [3 * crop_size_mult, 2 * crop_size_mult]\n      ps_crop = ops.position_sensitive_crop_regions(\n          image, boxes, box_ind, crop_size, num_spatial_bins, global_pool=False)\n      with self.test_session() as sess:\n        output = sess.run(ps_crop)\n\n      self.assertAllEqual(output, expected_output[crop_size_mult - 1])\n\n  def test_position_sensitive_with_global_pool_false_and_known_boxes(self):\n    num_spatial_bins = [2, 2]\n    image_shape = [2, 2, 2, 4]\n    crop_size = [2, 2]\n\n    image = tf.constant(range(1, 2 * 2 * 4  + 1) * 2, dtype=tf.float32,\n                        shape=image_shape)\n\n    # First box contains whole image, and second box contains only first row.\n    boxes = tf.constant(np.array([[0., 0., 1., 1.],\n                                  [0., 0., 0.5, 1.]]), dtype=tf.float32)\n    box_ind = tf.constant([0, 1], dtype=tf.int32)\n\n    expected_output = []\n\n    # Expected output, when the box containing whole image.\n    expected_output.append(\n        np.reshape(np.array([[4, 7],\n                             [10, 13]]),\n                   (1, 2, 2, 1))\n    )\n\n    # Expected output, when the box containing only first row.\n    expected_output.append(\n        np.reshape(np.array([[3, 6],\n                             [7, 10]]),\n                   (1, 2, 2, 1))\n    )\n    expected_output = np.concatenate(expected_output, axis=0)\n\n    ps_crop = ops.position_sensitive_crop_regions(\n        image, boxes, box_ind, crop_size, num_spatial_bins, global_pool=False)\n\n    with self.test_session() as sess:\n      output = sess.run(ps_crop)\n      self.assertAllEqual(output, expected_output)\n\n  def test_position_sensitive_with_global_pool_false_and_single_bin(self):\n    num_spatial_bins = [1, 1]\n    image_shape = [2, 3, 3, 4]\n    crop_size = [1, 1]\n\n    image = tf.random_uniform(image_shape)\n    boxes = tf.random_uniform((6, 4))\n    box_ind = tf.constant([0, 0, 0, 1, 1, 1], dtype=tf.int32)\n\n    # Since single_bin is used and crop_size = [1, 1] (i.e., no crop resize),\n    # the outputs are the same whatever the global_pool value is.\n    ps_crop_and_pool = ops.position_sensitive_crop_regions(\n        image, boxes, box_ind, crop_size, num_spatial_bins, global_pool=True)\n    ps_crop = ops.position_sensitive_crop_regions(\n        image, boxes, box_ind, crop_size, num_spatial_bins, global_pool=False)\n\n    with self.test_session() as sess:\n      pooled_output, unpooled_output = sess.run((ps_crop_and_pool, ps_crop))\n      self.assertAllClose(pooled_output, unpooled_output)\n\n  def test_position_sensitive_with_global_pool_false_and_do_global_pool(self):\n    num_spatial_bins = [3, 2]\n    image_shape = [1, 3, 2, 6]\n    num_boxes = 2\n\n    # First channel is 1's, second channel is 2's, etc.\n    image = tf.constant(range(1, 3 * 2 + 1) * 6, dtype=tf.float32,\n                        shape=image_shape)\n    boxes = tf.random_uniform((num_boxes, 4))\n    box_ind = tf.constant([0, 0], dtype=tf.int32)\n\n    expected_output = []\n\n    # Expected output, when crop_size = [3, 2].\n    expected_output.append(np.mean(\n        np.expand_dims(\n            np.tile(np.array([[1, 2],\n                              [3, 4],\n                              [5, 6]]), (num_boxes, 1, 1)),\n            axis=-1),\n        axis=(1, 2), keepdims=True))\n\n    # Expected output, when crop_size = [6, 4].\n    expected_output.append(np.mean(\n        np.expand_dims(\n            np.tile(np.array([[1, 1, 2, 2],\n                              [1, 1, 2, 2],\n                              [3, 3, 4, 4],\n                              [3, 3, 4, 4],\n                              [5, 5, 6, 6],\n                              [5, 5, 6, 6]]), (num_boxes, 1, 1)),\n            axis=-1),\n        axis=(1, 2), keepdims=True))\n\n    for crop_size_mult in range(1, 3):\n      crop_size = [3 * crop_size_mult, 2 * crop_size_mult]\n\n      # Perform global_pooling after running the function with\n      # global_pool=False.\n      ps_crop = ops.position_sensitive_crop_regions(\n          image, boxes, box_ind, crop_size, num_spatial_bins, global_pool=False)\n      ps_crop_and_pool = tf.reduce_mean(\n          ps_crop, reduction_indices=(1, 2), keep_dims=True)\n\n      with self.test_session() as sess:\n        output = sess.run(ps_crop_and_pool)\n\n      self.assertAllEqual(output, expected_output[crop_size_mult - 1])\n\n  def test_raise_value_error_on_non_square_block_size(self):\n    num_spatial_bins = [3, 2]\n    image_shape = [1, 3, 2, 6]\n    crop_size = [6, 2]\n\n    image = tf.constant(1, dtype=tf.float32, shape=image_shape)\n    boxes = tf.constant([[0, 0, 1, 1]], dtype=tf.float32)\n    box_ind = tf.constant([0], dtype=tf.int32)\n\n    with self.assertRaisesRegexp(\n        ValueError, 'Only support square bin crop size for now.'):\n      ops.position_sensitive_crop_regions(\n          image, boxes, box_ind, crop_size, num_spatial_bins, global_pool=False)\n\n\nclass ReframeBoxMasksToImageMasksTest(tf.test.TestCase):\n\n  def testZeroImageOnEmptyMask(self):\n    box_masks = tf.constant([[[0, 0],\n                              [0, 0]]], dtype=tf.float32)\n    boxes = tf.constant([[0.0, 0.0, 1.0, 1.0]], dtype=tf.float32)\n    image_masks = ops.reframe_box_masks_to_image_masks(box_masks, boxes,\n                                                       image_height=4,\n                                                       image_width=4)\n    np_expected_image_masks = np.array([[[0, 0, 0, 0],\n                                         [0, 0, 0, 0],\n                                         [0, 0, 0, 0],\n                                         [0, 0, 0, 0]]], dtype=np.float32)\n    with self.test_session() as sess:\n      np_image_masks = sess.run(image_masks)\n      self.assertAllClose(np_image_masks, np_expected_image_masks)\n\n  def testMaskIsCenteredInImageWhenBoxIsCentered(self):\n    box_masks = tf.constant([[[1, 1],\n                              [1, 1]]], dtype=tf.float32)\n    boxes = tf.constant([[0.25, 0.25, 0.75, 0.75]], dtype=tf.float32)\n    image_masks = ops.reframe_box_masks_to_image_masks(box_masks, boxes,\n                                                       image_height=4,\n                                                       image_width=4)\n    np_expected_image_masks = np.array([[[0, 0, 0, 0],\n                                         [0, 1, 1, 0],\n                                         [0, 1, 1, 0],\n                                         [0, 0, 0, 0]]], dtype=np.float32)\n    with self.test_session() as sess:\n      np_image_masks = sess.run(image_masks)\n      self.assertAllClose(np_image_masks, np_expected_image_masks)\n\n  def testMaskOffCenterRemainsOffCenterInImage(self):\n    box_masks = tf.constant([[[1, 0],\n                              [0, 1]]], dtype=tf.float32)\n    boxes = tf.constant([[0.25, 0.5, 0.75, 1.0]], dtype=tf.float32)\n    image_masks = ops.reframe_box_masks_to_image_masks(box_masks, boxes,\n                                                       image_height=4,\n                                                       image_width=4)\n    np_expected_image_masks = np.array([[[0, 0, 0, 0],\n                                         [0, 0, 0.6111111, 0.16666669],\n                                         [0, 0, 0.3888889, 0.83333337],\n                                         [0, 0, 0, 0]]], dtype=np.float32)\n    with self.test_session() as sess:\n      np_image_masks = sess.run(image_masks)\n      self.assertAllClose(np_image_masks, np_expected_image_masks)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/per_image_evaluation.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Evaluate Object Detection result on a single image.\n\nAnnotate each detected result as true positives or false positive according to\na predefined IOU ratio. Non Maximum Supression is used by default. Multi class\ndetection is supported by default.\n\"\"\"\nimport numpy as np\n\nfrom object_detection.utils import np_box_list\nfrom object_detection.utils import np_box_list_ops\n\n\nclass PerImageEvaluation(object):\n  \"\"\"Evaluate detection result of a single image.\"\"\"\n\n  def __init__(self,\n               num_groundtruth_classes,\n               matching_iou_threshold=0.5,\n               nms_iou_threshold=0.3,\n               nms_max_output_boxes=50):\n    \"\"\"Initialized PerImageEvaluation by evaluation parameters.\n\n    Args:\n      num_groundtruth_classes: Number of ground truth object classes\n      matching_iou_threshold: A ratio of area intersection to union, which is\n          the threshold to consider whether a detection is true positive or not\n      nms_iou_threshold: IOU threshold used in Non Maximum Suppression.\n      nms_max_output_boxes: Number of maximum output boxes in NMS.\n    \"\"\"\n    self.matching_iou_threshold = matching_iou_threshold\n    self.nms_iou_threshold = nms_iou_threshold\n    self.nms_max_output_boxes = nms_max_output_boxes\n    self.num_groundtruth_classes = num_groundtruth_classes\n\n  def compute_object_detection_metrics(self, detected_boxes, detected_scores,\n                                       detected_class_labels, groundtruth_boxes,\n                                       groundtruth_class_labels,\n                                       groundtruth_is_difficult_lists):\n    \"\"\"Compute Object Detection related metrics from a single image.\n\n    Args:\n      detected_boxes: A float numpy array of shape [N, 4], representing N\n          regions of detected object regions.\n          Each row is of the format [y_min, x_min, y_max, x_max]\n      detected_scores: A float numpy array of shape [N, 1], representing\n          the confidence scores of the detected N object instances.\n      detected_class_labels: A integer numpy array of shape [N, 1], repreneting\n          the class labels of the detected N object instances.\n      groundtruth_boxes: A float numpy array of shape [M, 4], representing M\n          regions of object instances in ground truth\n      groundtruth_class_labels: An integer numpy array of shape [M, 1],\n          representing M class labels of object instances in ground truth\n      groundtruth_is_difficult_lists: A boolean numpy array of length M denoting\n          whether a ground truth box is a difficult instance or not\n\n    Returns:\n      scores: A list of C float numpy arrays. Each numpy array is of\n          shape [K, 1], representing K scores detected with object class\n          label c\n      tp_fp_labels: A list of C boolean numpy arrays. Each numpy array\n          is of shape [K, 1], representing K True/False positive label of\n          object instances detected with class label c\n      is_class_correctly_detected_in_image: a numpy integer array of\n          shape [C, 1], indicating whether the correponding class has a least\n          one instance being correctly detected in the image\n    \"\"\"\n    detected_boxes, detected_scores, detected_class_labels = (\n        self._remove_invalid_boxes(detected_boxes, detected_scores,\n                                   detected_class_labels))\n    scores, tp_fp_labels = self._compute_tp_fp(\n        detected_boxes, detected_scores, detected_class_labels,\n        groundtruth_boxes, groundtruth_class_labels,\n        groundtruth_is_difficult_lists)\n    is_class_correctly_detected_in_image = self._compute_cor_loc(\n        detected_boxes, detected_scores, detected_class_labels,\n        groundtruth_boxes, groundtruth_class_labels)\n    return scores, tp_fp_labels, is_class_correctly_detected_in_image\n\n  def _compute_cor_loc(self, detected_boxes, detected_scores,\n                       detected_class_labels, groundtruth_boxes,\n                       groundtruth_class_labels):\n    \"\"\"Compute CorLoc score for object detection result.\n\n    Args:\n      detected_boxes: A float numpy array of shape [N, 4], representing N\n          regions of detected object regions.\n          Each row is of the format [y_min, x_min, y_max, x_max]\n      detected_scores: A float numpy array of shape [N, 1], representing\n          the confidence scores of the detected N object instances.\n      detected_class_labels: A integer numpy array of shape [N, 1], repreneting\n          the class labels of the detected N object instances.\n      groundtruth_boxes: A float numpy array of shape [M, 4], representing M\n          regions of object instances in ground truth\n      groundtruth_class_labels: An integer numpy array of shape [M, 1],\n          representing M class labels of object instances in ground truth\n    Returns:\n      is_class_correctly_detected_in_image: a numpy integer array of\n          shape [C, 1], indicating whether the correponding class has a least\n          one instance being correctly detected in the image\n    \"\"\"\n    is_class_correctly_detected_in_image = np.zeros(\n        self.num_groundtruth_classes, dtype=int)\n    for i in range(self.num_groundtruth_classes):\n      gt_boxes_at_ith_class = groundtruth_boxes[\n          groundtruth_class_labels == i, :]\n      detected_boxes_at_ith_class = detected_boxes[\n          detected_class_labels == i, :]\n      detected_scores_at_ith_class = detected_scores[detected_class_labels == i]\n      is_class_correctly_detected_in_image[i] = (\n          self._compute_is_aclass_correctly_detected_in_image(\n              detected_boxes_at_ith_class, detected_scores_at_ith_class,\n              gt_boxes_at_ith_class))\n\n    return is_class_correctly_detected_in_image\n\n  def _compute_is_aclass_correctly_detected_in_image(\n      self, detected_boxes, detected_scores, groundtruth_boxes):\n    \"\"\"Compute CorLoc score for a single class.\n\n    Args:\n      detected_boxes: A numpy array of shape [N, 4] representing detected box\n          coordinates\n      detected_scores: A 1-d numpy array of length N representing classification\n          score\n      groundtruth_boxes: A numpy array of shape [M, 4] representing ground truth\n          box coordinates\n\n    Returns:\n      is_class_correctly_detected_in_image: An integer 1 or 0 denoting whether a\n          class is correctly detected in the image or not\n    \"\"\"\n    if detected_boxes.size > 0:\n      if groundtruth_boxes.size > 0:\n        max_score_id = np.argmax(detected_scores)\n        detected_boxlist = np_box_list.BoxList(\n            np.expand_dims(detected_boxes[max_score_id, :], axis=0))\n        gt_boxlist = np_box_list.BoxList(groundtruth_boxes)\n        iou = np_box_list_ops.iou(detected_boxlist, gt_boxlist)\n        if np.max(iou) >= self.matching_iou_threshold:\n          return 1\n    return 0\n\n  def _compute_tp_fp(self, detected_boxes, detected_scores,\n                     detected_class_labels, groundtruth_boxes,\n                     groundtruth_class_labels, groundtruth_is_difficult_lists):\n    \"\"\"Labels true/false positives of detections of an image across all classes.\n\n    Args:\n      detected_boxes: A float numpy array of shape [N, 4], representing N\n          regions of detected object regions.\n          Each row is of the format [y_min, x_min, y_max, x_max]\n      detected_scores: A float numpy array of shape [N, 1], representing\n          the confidence scores of the detected N object instances.\n      detected_class_labels: A integer numpy array of shape [N, 1], repreneting\n          the class labels of the detected N object instances.\n      groundtruth_boxes: A float numpy array of shape [M, 4], representing M\n          regions of object instances in ground truth\n      groundtruth_class_labels: An integer numpy array of shape [M, 1],\n          representing M class labels of object instances in ground truth\n      groundtruth_is_difficult_lists: A boolean numpy array of length M denoting\n          whether a ground truth box is a difficult instance or not\n\n    Returns:\n      result_scores: A list of float numpy arrays. Each numpy array is of\n          shape [K, 1], representing K scores detected with object class\n          label c\n      result_tp_fp_labels: A list of boolean numpy array. Each numpy array is of\n          shape [K, 1], representing K True/False positive label of object\n          instances detected with class label c\n    \"\"\"\n    result_scores = []\n    result_tp_fp_labels = []\n    for i in range(self.num_groundtruth_classes):\n      gt_boxes_at_ith_class = groundtruth_boxes[(groundtruth_class_labels == i\n                                                ), :]\n      groundtruth_is_difficult_list_at_ith_class = (\n          groundtruth_is_difficult_lists[groundtruth_class_labels == i])\n      detected_boxes_at_ith_class = detected_boxes[(detected_class_labels == i\n                                                   ), :]\n      detected_scores_at_ith_class = detected_scores[detected_class_labels == i]\n      scores, tp_fp_labels = self._compute_tp_fp_for_single_class(\n          detected_boxes_at_ith_class, detected_scores_at_ith_class,\n          gt_boxes_at_ith_class, groundtruth_is_difficult_list_at_ith_class)\n      result_scores.append(scores)\n      result_tp_fp_labels.append(tp_fp_labels)\n    return result_scores, result_tp_fp_labels\n\n  def _remove_invalid_boxes(self, detected_boxes, detected_scores,\n                            detected_class_labels):\n    valid_indices = np.logical_and(detected_boxes[:, 0] < detected_boxes[:, 2],\n                                   detected_boxes[:, 1] < detected_boxes[:, 3])\n    return (detected_boxes[valid_indices, :], detected_scores[valid_indices],\n            detected_class_labels[valid_indices])\n\n  def _compute_tp_fp_for_single_class(self, detected_boxes, detected_scores,\n                                      groundtruth_boxes,\n                                      groundtruth_is_difficult_list):\n    \"\"\"Labels boxes detected with the same class from the same image as tp/fp.\n\n    Args:\n      detected_boxes: A numpy array of shape [N, 4] representing detected box\n          coordinates\n      detected_scores: A 1-d numpy array of length N representing classification\n          score\n      groundtruth_boxes: A numpy array of shape [M, 4] representing ground truth\n          box coordinates\n      groundtruth_is_difficult_list: A boolean numpy array of length M denoting\n          whether a ground truth box is a difficult instance or not\n\n    Returns:\n      scores: A numpy array representing the detection scores\n      tp_fp_labels: a boolean numpy array indicating whether a detection is a\n      true positive.\n\n    \"\"\"\n    if detected_boxes.size == 0:\n      return np.array([], dtype=float), np.array([], dtype=bool)\n    detected_boxlist = np_box_list.BoxList(detected_boxes)\n    detected_boxlist.add_field('scores', detected_scores)\n    detected_boxlist = np_box_list_ops.non_max_suppression(\n        detected_boxlist, self.nms_max_output_boxes, self.nms_iou_threshold)\n\n    scores = detected_boxlist.get_field('scores')\n\n    if groundtruth_boxes.size == 0:\n      return scores, np.zeros(detected_boxlist.num_boxes(), dtype=bool)\n    gt_boxlist = np_box_list.BoxList(groundtruth_boxes)\n\n    iou = np_box_list_ops.iou(detected_boxlist, gt_boxlist)\n    max_overlap_gt_ids = np.argmax(iou, axis=1)\n    is_gt_box_detected = np.zeros(gt_boxlist.num_boxes(), dtype=bool)\n    tp_fp_labels = np.zeros(detected_boxlist.num_boxes(), dtype=bool)\n    is_matched_to_difficult_box = np.zeros(\n        detected_boxlist.num_boxes(), dtype=bool)\n    for i in range(detected_boxlist.num_boxes()):\n      gt_id = max_overlap_gt_ids[i]\n      if iou[i, gt_id] >= self.matching_iou_threshold:\n        if not groundtruth_is_difficult_list[gt_id]:\n          if not is_gt_box_detected[gt_id]:\n            tp_fp_labels[i] = True\n            is_gt_box_detected[gt_id] = True\n        else:\n          is_matched_to_difficult_box[i] = True\n    return scores[~is_matched_to_difficult_box], tp_fp_labels[\n        ~is_matched_to_difficult_box]\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/per_image_evaluation_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.utils.per_image_evaluation.\"\"\"\n\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.utils import per_image_evaluation\n\n\nclass SingleClassTpFpWithDifficultBoxesTest(tf.test.TestCase):\n\n  def setUp(self):\n    num_groundtruth_classes = 1\n    matching_iou_threshold = 0.5\n    nms_iou_threshold = 1.0\n    nms_max_output_boxes = 10000\n    self.eval = per_image_evaluation.PerImageEvaluation(\n        num_groundtruth_classes, matching_iou_threshold, nms_iou_threshold,\n        nms_max_output_boxes)\n\n    self.detected_boxes = np.array([[0, 0, 1, 1], [0, 0, 2, 2], [0, 0, 3, 3]],\n                                   dtype=float)\n    self.detected_scores = np.array([0.6, 0.8, 0.5], dtype=float)\n    self.groundtruth_boxes = np.array([[0, 0, 1, 1], [0, 0, 10, 10]],\n                                      dtype=float)\n\n  def test_match_to_not_difficult_box(self):\n    groundtruth_groundtruth_is_difficult_list = np.array([False, True],\n                                                         dtype=bool)\n    scores, tp_fp_labels = self.eval._compute_tp_fp_for_single_class(\n        self.detected_boxes, self.detected_scores, self.groundtruth_boxes,\n        groundtruth_groundtruth_is_difficult_list)\n    expected_scores = np.array([0.8, 0.6, 0.5], dtype=float)\n    expected_tp_fp_labels = np.array([False, True, False], dtype=bool)\n    self.assertTrue(np.allclose(expected_scores, scores))\n    self.assertTrue(np.allclose(expected_tp_fp_labels, tp_fp_labels))\n\n  def test_match_to_difficult_box(self):\n    groundtruth_groundtruth_is_difficult_list = np.array([True, False],\n                                                         dtype=bool)\n    scores, tp_fp_labels = self.eval._compute_tp_fp_for_single_class(\n        self.detected_boxes, self.detected_scores, self.groundtruth_boxes,\n        groundtruth_groundtruth_is_difficult_list)\n    expected_scores = np.array([0.8, 0.5], dtype=float)\n    expected_tp_fp_labels = np.array([False, False], dtype=bool)\n    self.assertTrue(np.allclose(expected_scores, scores))\n    self.assertTrue(np.allclose(expected_tp_fp_labels, tp_fp_labels))\n\n\nclass SingleClassTpFpNoDifficultBoxesTest(tf.test.TestCase):\n\n  def setUp(self):\n    num_groundtruth_classes = 1\n    matching_iou_threshold1 = 0.5\n    matching_iou_threshold2 = 0.1\n    nms_iou_threshold = 1.0\n    nms_max_output_boxes = 10000\n    self.eval1 = per_image_evaluation.PerImageEvaluation(\n        num_groundtruth_classes, matching_iou_threshold1, nms_iou_threshold,\n        nms_max_output_boxes)\n\n    self.eval2 = per_image_evaluation.PerImageEvaluation(\n        num_groundtruth_classes, matching_iou_threshold2, nms_iou_threshold,\n        nms_max_output_boxes)\n\n    self.detected_boxes = np.array([[0, 0, 1, 1], [0, 0, 2, 2], [0, 0, 3, 3]],\n                                   dtype=float)\n    self.detected_scores = np.array([0.6, 0.8, 0.5], dtype=float)\n\n  def test_no_true_positives(self):\n    groundtruth_boxes = np.array([[100, 100, 105, 105]], dtype=float)\n    groundtruth_groundtruth_is_difficult_list = np.zeros(1, dtype=bool)\n    scores, tp_fp_labels = self.eval1._compute_tp_fp_for_single_class(\n        self.detected_boxes, self.detected_scores, groundtruth_boxes,\n        groundtruth_groundtruth_is_difficult_list)\n    expected_scores = np.array([0.8, 0.6, 0.5], dtype=float)\n    expected_tp_fp_labels = np.array([False, False, False], dtype=bool)\n    self.assertTrue(np.allclose(expected_scores, scores))\n    self.assertTrue(np.allclose(expected_tp_fp_labels, tp_fp_labels))\n\n  def test_one_true_positives_with_large_iou_threshold(self):\n    groundtruth_boxes = np.array([[0, 0, 1, 1]], dtype=float)\n    groundtruth_groundtruth_is_difficult_list = np.zeros(1, dtype=bool)\n    scores, tp_fp_labels = self.eval1._compute_tp_fp_for_single_class(\n        self.detected_boxes, self.detected_scores, groundtruth_boxes,\n        groundtruth_groundtruth_is_difficult_list)\n    expected_scores = np.array([0.8, 0.6, 0.5], dtype=float)\n    expected_tp_fp_labels = np.array([False, True, False], dtype=bool)\n    self.assertTrue(np.allclose(expected_scores, scores))\n    self.assertTrue(np.allclose(expected_tp_fp_labels, tp_fp_labels))\n\n  def test_one_true_positives_with_very_small_iou_threshold(self):\n    groundtruth_boxes = np.array([[0, 0, 1, 1]], dtype=float)\n    groundtruth_groundtruth_is_difficult_list = np.zeros(1, dtype=bool)\n    scores, tp_fp_labels = self.eval2._compute_tp_fp_for_single_class(\n        self.detected_boxes, self.detected_scores, groundtruth_boxes,\n        groundtruth_groundtruth_is_difficult_list)\n    expected_scores = np.array([0.8, 0.6, 0.5], dtype=float)\n    expected_tp_fp_labels = np.array([True, False, False], dtype=bool)\n    self.assertTrue(np.allclose(expected_scores, scores))\n    self.assertTrue(np.allclose(expected_tp_fp_labels, tp_fp_labels))\n\n  def test_two_true_positives_with_large_iou_threshold(self):\n    groundtruth_boxes = np.array([[0, 0, 1, 1], [0, 0, 3.5, 3.5]], dtype=float)\n    groundtruth_groundtruth_is_difficult_list = np.zeros(2, dtype=bool)\n    scores, tp_fp_labels = self.eval1._compute_tp_fp_for_single_class(\n        self.detected_boxes, self.detected_scores, groundtruth_boxes,\n        groundtruth_groundtruth_is_difficult_list)\n    expected_scores = np.array([0.8, 0.6, 0.5], dtype=float)\n    expected_tp_fp_labels = np.array([False, True, True], dtype=bool)\n    self.assertTrue(np.allclose(expected_scores, scores))\n    self.assertTrue(np.allclose(expected_tp_fp_labels, tp_fp_labels))\n\n\nclass MultiClassesTpFpTest(tf.test.TestCase):\n\n  def test_tp_fp(self):\n    num_groundtruth_classes = 3\n    matching_iou_threshold = 0.5\n    nms_iou_threshold = 1.0\n    nms_max_output_boxes = 10000\n    eval1 = per_image_evaluation.PerImageEvaluation(num_groundtruth_classes,\n                                                    matching_iou_threshold,\n                                                    nms_iou_threshold,\n                                                    nms_max_output_boxes)\n    detected_boxes = np.array([[0, 0, 1, 1], [10, 10, 5, 5], [0, 0, 2, 2],\n                               [5, 10, 10, 5], [10, 5, 5, 10], [0, 0, 3, 3]],\n                              dtype=float)\n    detected_scores = np.array([0.8, 0.1, 0.8, 0.9, 0.7, 0.8], dtype=float)\n    detected_class_labels = np.array([0, 1, 1, 2, 0, 2], dtype=int)\n    groundtruth_boxes = np.array([[0, 0, 1, 1], [0, 0, 3.5, 3.5]], dtype=float)\n    groundtruth_class_labels = np.array([0, 2], dtype=int)\n    groundtruth_groundtruth_is_difficult_list = np.zeros(2, dtype=float)\n    scores, tp_fp_labels, _ = eval1.compute_object_detection_metrics(\n        detected_boxes, detected_scores, detected_class_labels,\n        groundtruth_boxes, groundtruth_class_labels,\n        groundtruth_groundtruth_is_difficult_list)\n    expected_scores = [np.array([0.8], dtype=float)] * 3\n    expected_tp_fp_labels = [np.array([True]), np.array([False]), np.array([True\n                                                                           ])]\n    for i in range(len(expected_scores)):\n      self.assertTrue(np.allclose(expected_scores[i], scores[i]))\n      self.assertTrue(np.array_equal(expected_tp_fp_labels[i], tp_fp_labels[i]))\n\n\nclass CorLocTest(tf.test.TestCase):\n\n  def test_compute_corloc_with_normal_iou_threshold(self):\n    num_groundtruth_classes = 3\n    matching_iou_threshold = 0.5\n    nms_iou_threshold = 1.0\n    nms_max_output_boxes = 10000\n    eval1 = per_image_evaluation.PerImageEvaluation(num_groundtruth_classes,\n                                                    matching_iou_threshold,\n                                                    nms_iou_threshold,\n                                                    nms_max_output_boxes)\n    detected_boxes = np.array([[0, 0, 1, 1], [0, 0, 2, 2], [0, 0, 3, 3],\n                               [0, 0, 5, 5]], dtype=float)\n    detected_scores = np.array([0.9, 0.9, 0.1, 0.9], dtype=float)\n    detected_class_labels = np.array([0, 1, 0, 2], dtype=int)\n    groundtruth_boxes = np.array([[0, 0, 1, 1], [0, 0, 3, 3], [0, 0, 6, 6]],\n                                 dtype=float)\n    groundtruth_class_labels = np.array([0, 0, 2], dtype=int)\n\n    is_class_correctly_detected_in_image = eval1._compute_cor_loc(\n        detected_boxes, detected_scores, detected_class_labels,\n        groundtruth_boxes, groundtruth_class_labels)\n    expected_result = np.array([1, 0, 1], dtype=int)\n    self.assertTrue(np.array_equal(expected_result,\n                                   is_class_correctly_detected_in_image))\n\n  def test_compute_corloc_with_very_large_iou_threshold(self):\n    num_groundtruth_classes = 3\n    matching_iou_threshold = 0.9\n    nms_iou_threshold = 1.0\n    nms_max_output_boxes = 10000\n    eval1 = per_image_evaluation.PerImageEvaluation(num_groundtruth_classes,\n                                                    matching_iou_threshold,\n                                                    nms_iou_threshold,\n                                                    nms_max_output_boxes)\n    detected_boxes = np.array([[0, 0, 1, 1], [0, 0, 2, 2], [0, 0, 3, 3],\n                               [0, 0, 5, 5]], dtype=float)\n    detected_scores = np.array([0.9, 0.9, 0.1, 0.9], dtype=float)\n    detected_class_labels = np.array([0, 1, 0, 2], dtype=int)\n    groundtruth_boxes = np.array([[0, 0, 1, 1], [0, 0, 3, 3], [0, 0, 6, 6]],\n                                 dtype=float)\n    groundtruth_class_labels = np.array([0, 0, 2], dtype=int)\n\n    is_class_correctly_detected_in_image = eval1._compute_cor_loc(\n        detected_boxes, detected_scores, detected_class_labels,\n        groundtruth_boxes, groundtruth_class_labels)\n    expected_result = np.array([1, 0, 0], dtype=int)\n    self.assertTrue(np.array_equal(expected_result,\n                                   is_class_correctly_detected_in_image))\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/shape_utils.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Utils used to manipulate tensor shapes.\"\"\"\n\nimport tensorflow as tf\n\n\ndef _is_tensor(t):\n  \"\"\"Returns a boolean indicating whether the input is a tensor.\n\n  Args:\n    t: the input to be tested.\n\n  Returns:\n    a boolean that indicates whether t is a tensor.\n  \"\"\"\n  return isinstance(t, (tf.Tensor, tf.SparseTensor, tf.Variable))\n\n\ndef _set_dim_0(t, d0):\n  \"\"\"Sets the 0-th dimension of the input tensor.\n\n  Args:\n    t: the input tensor, assuming the rank is at least 1.\n    d0: an integer indicating the 0-th dimension of the input tensor.\n\n  Returns:\n    the tensor t with the 0-th dimension set.\n  \"\"\"\n  t_shape = t.get_shape().as_list()\n  t_shape[0] = d0\n  t.set_shape(t_shape)\n  return t\n\n\ndef pad_tensor(t, length):\n  \"\"\"Pads the input tensor with 0s along the first dimension up to the length.\n\n  Args:\n    t: the input tensor, assuming the rank is at least 1.\n    length: a tensor of shape [1]  or an integer, indicating the first dimension\n      of the input tensor t after padding, assuming length <= t.shape[0].\n\n  Returns:\n    padded_t: the padded tensor, whose first dimension is length. If the length\n      is an integer, the first dimension of padded_t is set to length\n      statically.\n  \"\"\"\n  t_rank = tf.rank(t)\n  t_shape = tf.shape(t)\n  t_d0 = t_shape[0]\n  pad_d0 = tf.expand_dims(length - t_d0, 0)\n  pad_shape = tf.cond(\n      tf.greater(t_rank, 1), lambda: tf.concat([pad_d0, t_shape[1:]], 0),\n      lambda: tf.expand_dims(length - t_d0, 0))\n  padded_t = tf.concat([t, tf.zeros(pad_shape, dtype=t.dtype)], 0)\n  if not _is_tensor(length):\n    padded_t = _set_dim_0(padded_t, length)\n  return padded_t\n\n\ndef clip_tensor(t, length):\n  \"\"\"Clips the input tensor along the first dimension up to the length.\n\n  Args:\n    t: the input tensor, assuming the rank is at least 1.\n    length: a tensor of shape [1]  or an integer, indicating the first dimension\n      of the input tensor t after clipping, assuming length <= t.shape[0].\n\n  Returns:\n    clipped_t: the clipped tensor, whose first dimension is length. If the\n      length is an integer, the first dimension of clipped_t is set to length\n      statically.\n  \"\"\"\n  clipped_t = tf.gather(t, tf.range(length))\n  if not _is_tensor(length):\n    clipped_t = _set_dim_0(clipped_t, length)\n  return clipped_t\n\n\ndef pad_or_clip_tensor(t, length):\n  \"\"\"Pad or clip the input tensor along the first dimension.\n\n  Args:\n    t: the input tensor, assuming the rank is at least 1.\n    length: a tensor of shape [1]  or an integer, indicating the first dimension\n      of the input tensor t after processing.\n\n  Returns:\n    processed_t: the processed tensor, whose first dimension is length. If the\n      length is an integer, the first dimension of the processed tensor is set\n      to length statically.\n  \"\"\"\n  processed_t = tf.cond(\n      tf.greater(tf.shape(t)[0], length),\n      lambda: clip_tensor(t, length),\n      lambda: pad_tensor(t, length))\n  if not _is_tensor(length):\n    processed_t = _set_dim_0(processed_t, length)\n  return processed_t\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/shape_utils_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.utils.shape_utils.\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.utils import shape_utils\n\n\nclass UtilTest(tf.test.TestCase):\n\n  def test_pad_tensor_using_integer_input(self):\n    t1 = tf.constant([1], dtype=tf.int32)\n    pad_t1 = shape_utils.pad_tensor(t1, 2)\n    t2 = tf.constant([[0.1, 0.2]], dtype=tf.float32)\n    pad_t2 = shape_utils.pad_tensor(t2, 2)\n\n    self.assertEqual(2, pad_t1.get_shape()[0])\n    self.assertEqual(2, pad_t2.get_shape()[0])\n\n    with self.test_session() as sess:\n      pad_t1_result, pad_t2_result = sess.run([pad_t1, pad_t2])\n      self.assertAllEqual([1, 0], pad_t1_result)\n      self.assertAllClose([[0.1, 0.2], [0, 0]], pad_t2_result)\n\n  def test_pad_tensor_using_tensor_input(self):\n    t1 = tf.constant([1], dtype=tf.int32)\n    pad_t1 = shape_utils.pad_tensor(t1, tf.constant(2))\n    t2 = tf.constant([[0.1, 0.2]], dtype=tf.float32)\n    pad_t2 = shape_utils.pad_tensor(t2, tf.constant(2))\n\n    with self.test_session() as sess:\n      pad_t1_result, pad_t2_result = sess.run([pad_t1, pad_t2])\n      self.assertAllEqual([1, 0], pad_t1_result)\n      self.assertAllClose([[0.1, 0.2], [0, 0]], pad_t2_result)\n\n  def test_clip_tensor_using_integer_input(self):\n    t1 = tf.constant([1, 2, 3], dtype=tf.int32)\n    clip_t1 = shape_utils.clip_tensor(t1, 2)\n    t2 = tf.constant([[0.1, 0.2], [0.2, 0.4], [0.5, 0.8]], dtype=tf.float32)\n    clip_t2 = shape_utils.clip_tensor(t2, 2)\n\n    self.assertEqual(2, clip_t1.get_shape()[0])\n    self.assertEqual(2, clip_t2.get_shape()[0])\n\n    with self.test_session() as sess:\n      clip_t1_result, clip_t2_result = sess.run([clip_t1, clip_t2])\n      self.assertAllEqual([1, 2], clip_t1_result)\n      self.assertAllClose([[0.1, 0.2], [0.2, 0.4]], clip_t2_result)\n\n  def test_clip_tensor_using_tensor_input(self):\n    t1 = tf.constant([1, 2, 3], dtype=tf.int32)\n    clip_t1 = shape_utils.clip_tensor(t1, tf.constant(2))\n    t2 = tf.constant([[0.1, 0.2], [0.2, 0.4], [0.5, 0.8]], dtype=tf.float32)\n    clip_t2 = shape_utils.clip_tensor(t2, tf.constant(2))\n\n    with self.test_session() as sess:\n      clip_t1_result, clip_t2_result = sess.run([clip_t1, clip_t2])\n      self.assertAllEqual([1, 2], clip_t1_result)\n      self.assertAllClose([[0.1, 0.2], [0.2, 0.4]], clip_t2_result)\n\n  def test_pad_or_clip_tensor_using_integer_input(self):\n    t1 = tf.constant([1], dtype=tf.int32)\n    tt1 = shape_utils.pad_or_clip_tensor(t1, 2)\n    t2 = tf.constant([[0.1, 0.2]], dtype=tf.float32)\n    tt2 = shape_utils.pad_or_clip_tensor(t2, 2)\n\n    t3 = tf.constant([1, 2, 3], dtype=tf.int32)\n    tt3 = shape_utils.clip_tensor(t3, 2)\n    t4 = tf.constant([[0.1, 0.2], [0.2, 0.4], [0.5, 0.8]], dtype=tf.float32)\n    tt4 = shape_utils.clip_tensor(t4, 2)\n\n    self.assertEqual(2, tt1.get_shape()[0])\n    self.assertEqual(2, tt2.get_shape()[0])\n    self.assertEqual(2, tt3.get_shape()[0])\n    self.assertEqual(2, tt4.get_shape()[0])\n\n    with self.test_session() as sess:\n      tt1_result, tt2_result, tt3_result, tt4_result = sess.run(\n          [tt1, tt2, tt3, tt4])\n      self.assertAllEqual([1, 0], tt1_result)\n      self.assertAllClose([[0.1, 0.2], [0, 0]], tt2_result)\n      self.assertAllEqual([1, 2], tt3_result)\n      self.assertAllClose([[0.1, 0.2], [0.2, 0.4]], tt4_result)\n\n  def test_pad_or_clip_tensor_using_tensor_input(self):\n    t1 = tf.constant([1], dtype=tf.int32)\n    tt1 = shape_utils.pad_or_clip_tensor(t1, tf.constant(2))\n    t2 = tf.constant([[0.1, 0.2]], dtype=tf.float32)\n    tt2 = shape_utils.pad_or_clip_tensor(t2, tf.constant(2))\n\n    t3 = tf.constant([1, 2, 3], dtype=tf.int32)\n    tt3 = shape_utils.clip_tensor(t3, tf.constant(2))\n    t4 = tf.constant([[0.1, 0.2], [0.2, 0.4], [0.5, 0.8]], dtype=tf.float32)\n    tt4 = shape_utils.clip_tensor(t4, tf.constant(2))\n\n    with self.test_session() as sess:\n      tt1_result, tt2_result, tt3_result, tt4_result = sess.run(\n          [tt1, tt2, tt3, tt4])\n      self.assertAllEqual([1, 0], tt1_result)\n      self.assertAllClose([[0.1, 0.2], [0, 0]], tt2_result)\n      self.assertAllEqual([1, 2], tt3_result)\n      self.assertAllClose([[0.1, 0.2], [0.2, 0.4]], tt4_result)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/static_shape.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Helper functions to access TensorShape values.\n\nThe rank 4 tensor_shape must be of the form [batch_size, height, width, depth].\n\"\"\"\n\n\ndef get_batch_size(tensor_shape):\n  \"\"\"Returns batch size from the tensor shape.\n\n  Args:\n    tensor_shape: A rank 4 TensorShape.\n\n  Returns:\n    An integer representing the batch size of the tensor.\n  \"\"\"\n  tensor_shape.assert_has_rank(rank=4)\n  return tensor_shape[0].value\n\n\ndef get_height(tensor_shape):\n  \"\"\"Returns height from the tensor shape.\n\n  Args:\n    tensor_shape: A rank 4 TensorShape.\n\n  Returns:\n    An integer representing the height of the tensor.\n  \"\"\"\n  tensor_shape.assert_has_rank(rank=4)\n  return tensor_shape[1].value\n\n\ndef get_width(tensor_shape):\n  \"\"\"Returns width from the tensor shape.\n\n  Args:\n    tensor_shape: A rank 4 TensorShape.\n\n  Returns:\n    An integer representing the width of the tensor.\n  \"\"\"\n  tensor_shape.assert_has_rank(rank=4)\n  return tensor_shape[2].value\n\n\ndef get_depth(tensor_shape):\n  \"\"\"Returns depth from the tensor shape.\n\n  Args:\n    tensor_shape: A rank 4 TensorShape.\n\n  Returns:\n    An integer representing the depth of the tensor.\n  \"\"\"\n  tensor_shape.assert_has_rank(rank=4)\n  return tensor_shape[3].value\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/static_shape_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.utils.static_shape.\"\"\"\n\nimport tensorflow as tf\n\nfrom object_detection.utils import static_shape\n\n\nclass StaticShapeTest(tf.test.TestCase):\n\n  def test_return_correct_batchSize(self):\n    tensor_shape = tf.TensorShape(dims=[32, 299, 384, 3])\n    self.assertEqual(32, static_shape.get_batch_size(tensor_shape))\n\n  def test_return_correct_height(self):\n    tensor_shape = tf.TensorShape(dims=[32, 299, 384, 3])\n    self.assertEqual(299, static_shape.get_height(tensor_shape))\n\n  def test_return_correct_width(self):\n    tensor_shape = tf.TensorShape(dims=[32, 299, 384, 3])\n    self.assertEqual(384, static_shape.get_width(tensor_shape))\n\n  def test_return_correct_depth(self):\n    tensor_shape = tf.TensorShape(dims=[32, 299, 384, 3])\n    self.assertEqual(3, static_shape.get_depth(tensor_shape))\n\n  def test_die_on_tensor_shape_with_rank_three(self):\n    tensor_shape = tf.TensorShape(dims=[32, 299, 384])\n    with self.assertRaises(ValueError):\n      static_shape.get_batch_size(tensor_shape)\n      static_shape.get_height(tensor_shape)\n      static_shape.get_width(tensor_shape)\n      static_shape.get_depth(tensor_shape)\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/test_utils.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Contains functions which are convenient for unit testing.\"\"\"\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.core import anchor_generator\nfrom object_detection.core import box_coder\nfrom object_detection.core import box_list\nfrom object_detection.core import box_predictor\nfrom object_detection.core import matcher\n\n\nclass MockBoxCoder(box_coder.BoxCoder):\n  \"\"\"Simple `difference` BoxCoder.\"\"\"\n\n  @property\n  def code_size(self):\n    return 4\n\n  def _encode(self, boxes, anchors):\n    return boxes.get() - anchors.get()\n\n  def _decode(self, rel_codes, anchors):\n    return box_list.BoxList(rel_codes + anchors.get())\n\n\nclass MockBoxPredictor(box_predictor.BoxPredictor):\n  \"\"\"Simple box predictor that ignores inputs and outputs all zeros.\"\"\"\n\n  def __init__(self, is_training, num_classes):\n    super(MockBoxPredictor, self).__init__(is_training, num_classes)\n\n  def _predict(self, image_features, num_predictions_per_location):\n    batch_size = image_features.get_shape().as_list()[0]\n    num_anchors = (image_features.get_shape().as_list()[1]\n                   * image_features.get_shape().as_list()[2])\n    code_size = 4\n    zero = tf.reduce_sum(0 * image_features)\n    box_encodings = zero + tf.zeros(\n        (batch_size, num_anchors, 1, code_size), dtype=tf.float32)\n    class_predictions_with_background = zero + tf.zeros(\n        (batch_size, num_anchors, self.num_classes + 1), dtype=tf.float32)\n    return {box_predictor.BOX_ENCODINGS: box_encodings,\n            box_predictor.CLASS_PREDICTIONS_WITH_BACKGROUND:\n            class_predictions_with_background}\n\n\nclass MockAnchorGenerator(anchor_generator.AnchorGenerator):\n  \"\"\"Mock anchor generator.\"\"\"\n\n  def name_scope(self):\n    return 'MockAnchorGenerator'\n\n  def num_anchors_per_location(self):\n    return [1]\n\n  def _generate(self, feature_map_shape_list):\n    num_anchors = sum([shape[0] * shape[1] for shape in feature_map_shape_list])\n    return box_list.BoxList(tf.zeros((num_anchors, 4), dtype=tf.float32))\n\n\nclass MockMatcher(matcher.Matcher):\n  \"\"\"Simple matcher that matches first anchor to first groundtruth box.\"\"\"\n\n  def _match(self, similarity_matrix):\n    return tf.constant([0, -1, -1, -1], dtype=tf.int32)\n\n\ndef create_diagonal_gradient_image(height, width, depth):\n  \"\"\"Creates pyramid image. Useful for testing.\n\n  For example, pyramid_image(5, 6, 1) looks like:\n  # [[[ 5.  4.  3.  2.  1.  0.]\n  #   [ 6.  5.  4.  3.  2.  1.]\n  #   [ 7.  6.  5.  4.  3.  2.]\n  #   [ 8.  7.  6.  5.  4.  3.]\n  #   [ 9.  8.  7.  6.  5.  4.]]]\n\n  Args:\n    height: height of image\n    width: width of image\n    depth: depth of image\n\n  Returns:\n    pyramid image\n  \"\"\"\n  row = np.arange(height)\n  col = np.arange(width)[::-1]\n  image_layer = np.expand_dims(row, 1) + col\n  image_layer = np.expand_dims(image_layer, 2)\n\n  image = image_layer\n  for i in range(1, depth):\n    image = np.concatenate((image, image_layer * pow(10, i)), 2)\n\n  return image.astype(np.float32)\n\n\ndef create_random_boxes(num_boxes, max_height, max_width):\n  \"\"\"Creates random bounding boxes of specific maximum height and width.\n\n  Args:\n    num_boxes: number of boxes.\n    max_height: maximum height of boxes.\n    max_width: maximum width of boxes.\n\n  Returns:\n    boxes: numpy array of shape [num_boxes, 4]. Each row is in form\n        [y_min, x_min, y_max, x_max].\n  \"\"\"\n\n  y_1 = np.random.uniform(size=(1, num_boxes)) * max_height\n  y_2 = np.random.uniform(size=(1, num_boxes)) * max_height\n  x_1 = np.random.uniform(size=(1, num_boxes)) * max_width\n  x_2 = np.random.uniform(size=(1, num_boxes)) * max_width\n\n  boxes = np.zeros(shape=(num_boxes, 4))\n  boxes[:, 0] = np.minimum(y_1, y_2)\n  boxes[:, 1] = np.minimum(x_1, x_2)\n  boxes[:, 2] = np.maximum(y_1, y_2)\n  boxes[:, 3] = np.maximum(x_1, x_2)\n\n  return boxes.astype(np.float32)\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/test_utils_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.utils.test_utils.\"\"\"\n\nimport numpy as np\nimport tensorflow as tf\n\nfrom object_detection.utils import test_utils\n\n\nclass TestUtilsTest(tf.test.TestCase):\n\n  def test_diagonal_gradient_image(self):\n    \"\"\"Tests if a good pyramid image is created.\"\"\"\n    pyramid_image = test_utils.create_diagonal_gradient_image(3, 4, 2)\n\n    # Test which is easy to understand.\n    expected_first_channel = np.array([[3, 2, 1, 0],\n                                       [4, 3, 2, 1],\n                                       [5, 4, 3, 2]], dtype=np.float32)\n    self.assertAllEqual(np.squeeze(pyramid_image[:, :, 0]),\n                        expected_first_channel)\n\n    # Actual test.\n    expected_image = np.array([[[3, 30],\n                                [2, 20],\n                                [1, 10],\n                                [0, 0]],\n                               [[4, 40],\n                                [3, 30],\n                                [2, 20],\n                                [1, 10]],\n                               [[5, 50],\n                                [4, 40],\n                                [3, 30],\n                                [2, 20]]], dtype=np.float32)\n\n    self.assertAllEqual(pyramid_image, expected_image)\n\n  def test_random_boxes(self):\n    \"\"\"Tests if valid random boxes are created.\"\"\"\n    num_boxes = 1000\n    max_height = 3\n    max_width = 5\n    boxes = test_utils.create_random_boxes(num_boxes,\n                                           max_height,\n                                           max_width)\n\n    true_column = np.ones(shape=(num_boxes)) == 1\n    self.assertAllEqual(boxes[:, 0] < boxes[:, 2], true_column)\n    self.assertAllEqual(boxes[:, 1] < boxes[:, 3], true_column)\n\n    self.assertTrue(boxes[:, 0].min() >= 0)\n    self.assertTrue(boxes[:, 1].min() >= 0)\n    self.assertTrue(boxes[:, 2].max() <= max_height)\n    self.assertTrue(boxes[:, 3].max() <= max_width)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/variables_helper.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Helper functions for manipulating collections of variables during training.\n\"\"\"\nimport logging\nimport re\n\nimport tensorflow as tf\n\nslim = tf.contrib.slim\n\n\n# TODO: Consider replacing with tf.contrib.filter_variables in\n# tensorflow/contrib/framework/python/ops/variables.py\ndef filter_variables(variables, filter_regex_list, invert=False):\n  \"\"\"Filters out the variables matching the filter_regex.\n\n  Filter out the variables whose name matches the any of the regular\n  expressions in filter_regex_list and returns the remaining variables.\n  Optionally, if invert=True, the complement set is returned.\n\n  Args:\n    variables: a list of tensorflow variables.\n    filter_regex_list: a list of string regular expressions.\n    invert: (boolean).  If True, returns the complement of the filter set; that\n      is, all variables matching filter_regex are kept and all others discarded.\n\n  Returns:\n    a list of filtered variables.\n  \"\"\"\n  kept_vars = []\n  variables_to_ignore_patterns = filter(None, filter_regex_list)\n  for var in variables:\n    add = True\n    for pattern in variables_to_ignore_patterns:\n      if re.match(pattern, var.op.name):\n        add = False\n        break\n    if add != invert:\n      kept_vars.append(var)\n  return kept_vars\n\n\ndef multiply_gradients_matching_regex(grads_and_vars, regex_list, multiplier):\n  \"\"\"Multiply gradients whose variable names match a regular expression.\n\n  Args:\n    grads_and_vars: A list of gradient to variable pairs (tuples).\n    regex_list: A list of string regular expressions.\n    multiplier: A (float) multiplier to apply to each gradient matching the\n      regular expression.\n\n  Returns:\n    grads_and_vars: A list of gradient to variable pairs (tuples).\n  \"\"\"\n  variables = [pair[1] for pair in grads_and_vars]\n  matching_vars = filter_variables(variables, regex_list, invert=True)\n  for var in matching_vars:\n    logging.info('Applying multiplier %f to variable [%s]',\n                 multiplier, var.op.name)\n  grad_multipliers = {var: float(multiplier) for var in matching_vars}\n  return slim.learning.multiply_gradients(grads_and_vars,\n                                          grad_multipliers)\n\n\ndef freeze_gradients_matching_regex(grads_and_vars, regex_list):\n  \"\"\"Freeze gradients whose variable names match a regular expression.\n\n  Args:\n    grads_and_vars: A list of gradient to variable pairs (tuples).\n    regex_list: A list of string regular expressions.\n\n  Returns:\n    grads_and_vars: A list of gradient to variable pairs (tuples) that do not\n      contain the variables and gradients matching the regex.\n  \"\"\"\n  variables = [pair[1] for pair in grads_and_vars]\n  matching_vars = filter_variables(variables, regex_list, invert=True)\n  kept_grads_and_vars = [pair for pair in grads_and_vars\n                         if pair[1] not in matching_vars]\n  for var in matching_vars:\n    logging.info('Freezing variable [%s]', var.op.name)\n  return kept_grads_and_vars\n\n\ndef get_variables_available_in_checkpoint(variables, checkpoint_path):\n  \"\"\"Returns the subset of variables available in the checkpoint.\n\n  Inspects given checkpoint and returns the subset of variables that are\n  available in it.\n\n  TODO: force input and output to be a dictionary.\n\n  Args:\n    variables: a list or dictionary of variables to find in checkpoint.\n    checkpoint_path: path to the checkpoint to restore variables from.\n\n  Returns:\n    A list or dictionary of variables.\n  Raises:\n    ValueError: if `variables` is not a list or dict.\n  \"\"\"\n  if isinstance(variables, list):\n    variable_names_map = {variable.op.name: variable for variable in variables}\n  elif isinstance(variables, dict):\n    variable_names_map = variables\n  else:\n    raise ValueError('`variables` is expected to be a list or dict.')\n  ckpt_reader = tf.train.NewCheckpointReader(checkpoint_path)\n  ckpt_vars = ckpt_reader.get_variable_to_shape_map().keys()\n  vars_in_ckpt = {}\n  for variable_name, variable in sorted(variable_names_map.iteritems()):\n    if variable_name in ckpt_vars:\n      vars_in_ckpt[variable_name] = variable\n    else:\n      logging.warning('Variable [%s] not available in checkpoint',\n                      variable_name)\n  if isinstance(variables, list):\n    return vars_in_ckpt.values()\n  return vars_in_ckpt\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/variables_helper_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for object_detection.utils.variables_helper.\"\"\"\nimport os\n\nimport tensorflow as tf\n\nfrom object_detection.utils import variables_helper\n\n\nclass FilterVariablesTest(tf.test.TestCase):\n\n  def _create_variables(self):\n    return [tf.Variable(1.0, name='FeatureExtractor/InceptionV3/weights'),\n            tf.Variable(1.0, name='FeatureExtractor/InceptionV3/biases'),\n            tf.Variable(1.0, name='StackProposalGenerator/weights'),\n            tf.Variable(1.0, name='StackProposalGenerator/biases')]\n\n  def test_return_all_variables_when_empty_regex(self):\n    variables = self._create_variables()\n    out_variables = variables_helper.filter_variables(variables, [''])\n    self.assertItemsEqual(out_variables, variables)\n\n  def test_return_variables_which_do_not_match_single_regex(self):\n    variables = self._create_variables()\n    out_variables = variables_helper.filter_variables(variables,\n                                                      ['FeatureExtractor/.*'])\n    self.assertItemsEqual(out_variables, variables[2:])\n\n  def test_return_variables_which_do_not_match_any_regex_in_list(self):\n    variables = self._create_variables()\n    out_variables = variables_helper.filter_variables(variables, [\n        'FeatureExtractor.*biases', 'StackProposalGenerator.*biases'\n    ])\n    self.assertItemsEqual(out_variables, [variables[0], variables[2]])\n\n  def test_return_variables_matching_empty_regex_list(self):\n    variables = self._create_variables()\n    out_variables = variables_helper.filter_variables(\n        variables, [''], invert=True)\n    self.assertItemsEqual(out_variables, [])\n\n  def test_return_variables_matching_some_regex_in_list(self):\n    variables = self._create_variables()\n    out_variables = variables_helper.filter_variables(\n        variables,\n        ['FeatureExtractor.*biases', 'StackProposalGenerator.*biases'],\n        invert=True)\n    self.assertItemsEqual(out_variables, [variables[1], variables[3]])\n\n\nclass MultiplyGradientsMatchingRegexTest(tf.test.TestCase):\n\n  def _create_grads_and_vars(self):\n    return [(tf.constant(1.0),\n             tf.Variable(1.0, name='FeatureExtractor/InceptionV3/weights')),\n            (tf.constant(2.0),\n             tf.Variable(2.0, name='FeatureExtractor/InceptionV3/biases')),\n            (tf.constant(3.0),\n             tf.Variable(3.0, name='StackProposalGenerator/weights')),\n            (tf.constant(4.0),\n             tf.Variable(4.0, name='StackProposalGenerator/biases'))]\n\n  def test_multiply_all_feature_extractor_variables(self):\n    grads_and_vars = self._create_grads_and_vars()\n    regex_list = ['FeatureExtractor/.*']\n    multiplier = 0.0\n    grads_and_vars = variables_helper.multiply_gradients_matching_regex(\n        grads_and_vars, regex_list, multiplier)\n    exp_output = [(0.0, 1.0), (0.0, 2.0), (3.0, 3.0), (4.0, 4.0)]\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      output = sess.run(grads_and_vars)\n      self.assertItemsEqual(output, exp_output)\n\n  def test_multiply_all_bias_variables(self):\n    grads_and_vars = self._create_grads_and_vars()\n    regex_list = ['.*/biases']\n    multiplier = 0.0\n    grads_and_vars = variables_helper.multiply_gradients_matching_regex(\n        grads_and_vars, regex_list, multiplier)\n    exp_output = [(1.0, 1.0), (0.0, 2.0), (3.0, 3.0), (0.0, 4.0)]\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      output = sess.run(grads_and_vars)\n      self.assertItemsEqual(output, exp_output)\n\n\nclass FreezeGradientsMatchingRegexTest(tf.test.TestCase):\n\n  def _create_grads_and_vars(self):\n    return [(tf.constant(1.0),\n             tf.Variable(1.0, name='FeatureExtractor/InceptionV3/weights')),\n            (tf.constant(2.0),\n             tf.Variable(2.0, name='FeatureExtractor/InceptionV3/biases')),\n            (tf.constant(3.0),\n             tf.Variable(3.0, name='StackProposalGenerator/weights')),\n            (tf.constant(4.0),\n             tf.Variable(4.0, name='StackProposalGenerator/biases'))]\n\n  def test_freeze_all_feature_extractor_variables(self):\n    grads_and_vars = self._create_grads_and_vars()\n    regex_list = ['FeatureExtractor/.*']\n    grads_and_vars = variables_helper.freeze_gradients_matching_regex(\n        grads_and_vars, regex_list)\n    exp_output = [(3.0, 3.0), (4.0, 4.0)]\n    init_op = tf.global_variables_initializer()\n    with self.test_session() as sess:\n      sess.run(init_op)\n      output = sess.run(grads_and_vars)\n      self.assertItemsEqual(output, exp_output)\n\n\nclass GetVariablesAvailableInCheckpointTest(tf.test.TestCase):\n\n  def test_return_all_variables_from_checkpoint(self):\n    variables = [\n        tf.Variable(1.0, name='weights'),\n        tf.Variable(1.0, name='biases')\n    ]\n    checkpoint_path = os.path.join(self.get_temp_dir(), 'graph.pb')\n    init_op = tf.global_variables_initializer()\n    saver = tf.train.Saver(variables)\n    with self.test_session() as sess:\n      sess.run(init_op)\n      saver.save(sess, checkpoint_path)\n    out_variables = variables_helper.get_variables_available_in_checkpoint(\n        variables, checkpoint_path)\n    self.assertItemsEqual(out_variables, variables)\n\n  def test_return_variables_available_in_checkpoint(self):\n    checkpoint_path = os.path.join(self.get_temp_dir(), 'graph.pb')\n    graph1_variables = [\n        tf.Variable(1.0, name='weights'),\n    ]\n    init_op = tf.global_variables_initializer()\n    saver = tf.train.Saver(graph1_variables)\n    with self.test_session() as sess:\n      sess.run(init_op)\n      saver.save(sess, checkpoint_path)\n\n    graph2_variables = graph1_variables + [tf.Variable(1.0, name='biases')]\n    out_variables = variables_helper.get_variables_available_in_checkpoint(\n        graph2_variables, checkpoint_path)\n    self.assertItemsEqual(out_variables, graph1_variables)\n\n  def test_return_variables_available_an_checkpoint_with_dict_inputs(self):\n    checkpoint_path = os.path.join(self.get_temp_dir(), 'graph.pb')\n    graph1_variables = [\n        tf.Variable(1.0, name='ckpt_weights'),\n    ]\n    init_op = tf.global_variables_initializer()\n    saver = tf.train.Saver(graph1_variables)\n    with self.test_session() as sess:\n      sess.run(init_op)\n      saver.save(sess, checkpoint_path)\n\n    graph2_variables_dict = {\n        'ckpt_weights': tf.Variable(1.0, name='weights'),\n        'ckpt_biases': tf.Variable(1.0, name='biases')\n    }\n    out_variables = variables_helper.get_variables_available_in_checkpoint(\n        graph2_variables_dict, checkpoint_path)\n    self.assertTrue(isinstance(out_variables, dict))\n    self.assertItemsEqual(out_variables.keys(), ['ckpt_weights'])\n    self.assertTrue(out_variables['ckpt_weights'].op.name == 'weights')\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/visualization_utils.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"A set of functions that are used for visualization.\n\nThese functions often receive an image, perform some visualization on the image.\nThe functions do not return a value, instead they modify the image itself.\n\n\"\"\"\nimport collections\nimport numpy as np\nimport PIL.Image as Image\nimport PIL.ImageColor as ImageColor\nimport PIL.ImageDraw as ImageDraw\nimport PIL.ImageFont as ImageFont\nimport six\nimport tensorflow as tf\n\n\n_TITLE_LEFT_MARGIN = 10\n_TITLE_TOP_MARGIN = 10\nSTANDARD_COLORS = [\n    'AliceBlue', 'Chartreuse', 'Aqua', 'Aquamarine', 'Azure', 'Beige', 'Bisque',\n    'BlanchedAlmond', 'BlueViolet', 'BurlyWood', 'CadetBlue', 'AntiqueWhite',\n    'Chocolate', 'Coral', 'CornflowerBlue', 'Cornsilk', 'Crimson', 'Cyan',\n    'DarkCyan', 'DarkGoldenRod', 'DarkGrey', 'DarkKhaki', 'DarkOrange',\n    'DarkOrchid', 'DarkSalmon', 'DarkSeaGreen', 'DarkTurquoise', 'DarkViolet',\n    'DeepPink', 'DeepSkyBlue', 'DodgerBlue', 'FireBrick', 'FloralWhite',\n    'ForestGreen', 'Fuchsia', 'Gainsboro', 'GhostWhite', 'Gold', 'GoldenRod',\n    'Salmon', 'Tan', 'HoneyDew', 'HotPink', 'IndianRed', 'Ivory', 'Khaki',\n    'Lavender', 'LavenderBlush', 'LawnGreen', 'LemonChiffon', 'LightBlue',\n    'LightCoral', 'LightCyan', 'LightGoldenRodYellow', 'LightGray', 'LightGrey',\n    'LightGreen', 'LightPink', 'LightSalmon', 'LightSeaGreen', 'LightSkyBlue',\n    'LightSlateGray', 'LightSlateGrey', 'LightSteelBlue', 'LightYellow', 'Lime',\n    'LimeGreen', 'Linen', 'Magenta', 'MediumAquaMarine', 'MediumOrchid',\n    'MediumPurple', 'MediumSeaGreen', 'MediumSlateBlue', 'MediumSpringGreen',\n    'MediumTurquoise', 'MediumVioletRed', 'MintCream', 'MistyRose', 'Moccasin',\n    'NavajoWhite', 'OldLace', 'Olive', 'OliveDrab', 'Orange', 'OrangeRed',\n    'Orchid', 'PaleGoldenRod', 'PaleGreen', 'PaleTurquoise', 'PaleVioletRed',\n    'PapayaWhip', 'PeachPuff', 'Peru', 'Pink', 'Plum', 'PowderBlue', 'Purple',\n    'Red', 'RosyBrown', 'RoyalBlue', 'SaddleBrown', 'Green', 'SandyBrown',\n    'SeaGreen', 'SeaShell', 'Sienna', 'Silver', 'SkyBlue', 'SlateBlue',\n    'SlateGray', 'SlateGrey', 'Snow', 'SpringGreen', 'SteelBlue', 'GreenYellow',\n    'Teal', 'Thistle', 'Tomato', 'Turquoise', 'Violet', 'Wheat', 'White',\n    'WhiteSmoke', 'Yellow', 'YellowGreen'\n]\n\n\ndef save_image_array_as_png(image, output_path):\n  \"\"\"Saves an image (represented as a numpy array) to PNG.\n\n  Args:\n    image: a numpy array with shape [height, width, 3].\n    output_path: path to which image should be written.\n  \"\"\"\n  image_pil = Image.fromarray(np.uint8(image)).convert('RGB')\n  with tf.gfile.Open(output_path, 'w') as fid:\n    image_pil.save(fid, 'PNG')\n\n\ndef encode_image_array_as_png_str(image):\n  \"\"\"Encodes a numpy array into a PNG string.\n\n  Args:\n    image: a numpy array with shape [height, width, 3].\n\n  Returns:\n    PNG encoded image string.\n  \"\"\"\n  image_pil = Image.fromarray(np.uint8(image))\n  output = six.StringIO()\n  image_pil.save(output, format='PNG')\n  png_string = output.getvalue()\n  output.close()\n  return png_string\n\n\ndef draw_bounding_box_on_image_array(image,\n                                     ymin,\n                                     xmin,\n                                     ymax,\n                                     xmax,\n                                     color='red',\n                                     thickness=4,\n                                     display_str_list=(),\n                                     use_normalized_coordinates=True):\n  \"\"\"Adds a bounding box to an image (numpy array).\n\n  Args:\n    image: a numpy array with shape [height, width, 3].\n    ymin: ymin of bounding box in normalized coordinates (same below).\n    xmin: xmin of bounding box.\n    ymax: ymax of bounding box.\n    xmax: xmax of bounding box.\n    color: color to draw bounding box. Default is red.\n    thickness: line thickness. Default value is 4.\n    display_str_list: list of strings to display in box\n                      (each to be shown on its own line).\n    use_normalized_coordinates: If True (default), treat coordinates\n      ymin, xmin, ymax, xmax as relative to the image.  Otherwise treat\n      coordinates as absolute.\n  \"\"\"\n  image_pil = Image.fromarray(np.uint8(image)).convert('RGB')\n  draw_bounding_box_on_image(image_pil, ymin, xmin, ymax, xmax, color,\n                             thickness, display_str_list,\n                             use_normalized_coordinates)\n  np.copyto(image, np.array(image_pil))\n\n\ndef draw_bounding_box_on_image(image,\n                               ymin,\n                               xmin,\n                               ymax,\n                               xmax,\n                               color='red',\n                               thickness=4,\n                               display_str_list=(),\n                               use_normalized_coordinates=True):\n  \"\"\"Adds a bounding box to an image.\n\n  Each string in display_str_list is displayed on a separate line above the\n  bounding box in black text on a rectangle filled with the input 'color'.\n\n  Args:\n    image: a PIL.Image object.\n    ymin: ymin of bounding box.\n    xmin: xmin of bounding box.\n    ymax: ymax of bounding box.\n    xmax: xmax of bounding box.\n    color: color to draw bounding box. Default is red.\n    thickness: line thickness. Default value is 4.\n    display_str_list: list of strings to display in box\n                      (each to be shown on its own line).\n    use_normalized_coordinates: If True (default), treat coordinates\n      ymin, xmin, ymax, xmax as relative to the image.  Otherwise treat\n      coordinates as absolute.\n  \"\"\"\n  draw = ImageDraw.Draw(image)\n  im_width, im_height = image.size\n  if use_normalized_coordinates:\n    (left, right, top, bottom) = (xmin * im_width, xmax * im_width,\n                                  ymin * im_height, ymax * im_height)\n  else:\n    (left, right, top, bottom) = (xmin, xmax, ymin, ymax)\n  draw.line([(left, top), (left, bottom), (right, bottom),\n             (right, top), (left, top)], width=thickness, fill=color)\n  try:\n    font = ImageFont.truetype('arial.ttf', 24)\n  except IOError:\n    font = ImageFont.load_default()\n\n  text_bottom = top\n  # Reverse list and print from bottom to top.\n  for display_str in display_str_list[::-1]:\n    text_width, text_height = font.getsize(display_str)\n    margin = np.ceil(0.05 * text_height)\n    draw.rectangle(\n        [(left, text_bottom - text_height - 2 * margin), (left + text_width,\n                                                          text_bottom)],\n        fill=color)\n    draw.text(\n        (left + margin, text_bottom - text_height - margin),\n        display_str,\n        fill='black',\n        font=font)\n    text_bottom -= text_height - 2 * margin\n\n\ndef draw_bounding_boxes_on_image_array(image,\n                                       boxes,\n                                       color='red',\n                                       thickness=4,\n                                       display_str_list_list=()):\n  \"\"\"Draws bounding boxes on image (numpy array).\n\n  Args:\n    image: a numpy array object.\n    boxes: a 2 dimensional numpy array of [N, 4]: (ymin, xmin, ymax, xmax).\n           The coordinates are in normalized format between [0, 1].\n    color: color to draw bounding box. Default is red.\n    thickness: line thickness. Default value is 4.\n    display_str_list_list: list of list of strings.\n                           a list of strings for each bounding box.\n                           The reason to pass a list of strings for a\n                           bounding box is that it might contain\n                           multiple labels.\n\n  Raises:\n    ValueError: if boxes is not a [N, 4] array\n  \"\"\"\n  image_pil = Image.fromarray(image)\n  draw_bounding_boxes_on_image(image_pil, boxes, color, thickness,\n                               display_str_list_list)\n  np.copyto(image, np.array(image_pil))\n\n\ndef draw_bounding_boxes_on_image(image,\n                                 boxes,\n                                 color='red',\n                                 thickness=4,\n                                 display_str_list_list=()):\n  \"\"\"Draws bounding boxes on image.\n\n  Args:\n    image: a PIL.Image object.\n    boxes: a 2 dimensional numpy array of [N, 4]: (ymin, xmin, ymax, xmax).\n           The coordinates are in normalized format between [0, 1].\n    color: color to draw bounding box. Default is red.\n    thickness: line thickness. Default value is 4.\n    display_str_list_list: list of list of strings.\n                           a list of strings for each bounding box.\n                           The reason to pass a list of strings for a\n                           bounding box is that it might contain\n                           multiple labels.\n\n  Raises:\n    ValueError: if boxes is not a [N, 4] array\n  \"\"\"\n  boxes_shape = boxes.shape\n  if not boxes_shape:\n    return\n  if len(boxes_shape) != 2 or boxes_shape[1] != 4:\n    raise ValueError('Input must be of size [N, 4]')\n  for i in range(boxes_shape[0]):\n    display_str_list = ()\n    if display_str_list_list:\n      display_str_list = display_str_list_list[i]\n    draw_bounding_box_on_image(image, boxes[i, 0], boxes[i, 1], boxes[i, 2],\n                               boxes[i, 3], color, thickness, display_str_list)\n\n\ndef draw_keypoints_on_image_array(image,\n                                  keypoints,\n                                  color='red',\n                                  radius=2,\n                                  use_normalized_coordinates=True):\n  \"\"\"Draws keypoints on an image (numpy array).\n\n  Args:\n    image: a numpy array with shape [height, width, 3].\n    keypoints: a numpy array with shape [num_keypoints, 2].\n    color: color to draw the keypoints with. Default is red.\n    radius: keypoint radius. Default value is 2.\n    use_normalized_coordinates: if True (default), treat keypoint values as\n      relative to the image.  Otherwise treat them as absolute.\n  \"\"\"\n  image_pil = Image.fromarray(np.uint8(image)).convert('RGB')\n  draw_keypoints_on_image(image_pil, keypoints, color, radius,\n                          use_normalized_coordinates)\n  np.copyto(image, np.array(image_pil))\n\n\ndef draw_keypoints_on_image(image,\n                            keypoints,\n                            color='red',\n                            radius=2,\n                            use_normalized_coordinates=True):\n  \"\"\"Draws keypoints on an image.\n\n  Args:\n    image: a PIL.Image object.\n    keypoints: a numpy array with shape [num_keypoints, 2].\n    color: color to draw the keypoints with. Default is red.\n    radius: keypoint radius. Default value is 2.\n    use_normalized_coordinates: if True (default), treat keypoint values as\n      relative to the image.  Otherwise treat them as absolute.\n  \"\"\"\n  draw = ImageDraw.Draw(image)\n  im_width, im_height = image.size\n  keypoints_x = [k[1] for k in keypoints]\n  keypoints_y = [k[0] for k in keypoints]\n  if use_normalized_coordinates:\n    keypoints_x = tuple([im_width * x for x in keypoints_x])\n    keypoints_y = tuple([im_height * y for y in keypoints_y])\n  for keypoint_x, keypoint_y in zip(keypoints_x, keypoints_y):\n    draw.ellipse([(keypoint_x - radius, keypoint_y - radius),\n                  (keypoint_x + radius, keypoint_y + radius)],\n                 outline=color, fill=color)\n\n\ndef draw_mask_on_image_array(image, mask, color='red', alpha=0.7):\n  \"\"\"Draws mask on an image.\n\n  Args:\n    image: uint8 numpy array with shape (img_height, img_height, 3)\n    mask: a float numpy array of shape (img_height, img_height) with\n      values between 0 and 1\n    color: color to draw the keypoints with. Default is red.\n    alpha: transparency value between 0 and 1. (default: 0.7)\n\n  Raises:\n    ValueError: On incorrect data type for image or masks.\n  \"\"\"\n  if image.dtype != np.uint8:\n    raise ValueError('`image` not of type np.uint8')\n  if mask.dtype != np.float32:\n    raise ValueError('`mask` not of type np.float32')\n  if np.any(np.logical_or(mask > 1.0, mask < 0.0)):\n    raise ValueError('`mask` elements should be in [0, 1]')\n  rgb = ImageColor.getrgb(color)\n  pil_image = Image.fromarray(image)\n\n  solid_color = np.expand_dims(\n      np.ones_like(mask), axis=2) * np.reshape(list(rgb), [1, 1, 3])\n  pil_solid_color = Image.fromarray(np.uint8(solid_color)).convert('RGBA')\n  pil_mask = Image.fromarray(np.uint8(255.0*alpha*mask)).convert('L')\n  pil_image = Image.composite(pil_solid_color, pil_image, pil_mask)\n  np.copyto(image, np.array(pil_image.convert('RGB')))\n\n\ndef visualize_boxes_and_labels_on_image_array(image,\n                                              boxes,\n                                              classes,\n                                              scores,\n                                              category_index,\n                                              instance_masks=None,\n                                              keypoints=None,\n                                              use_normalized_coordinates=False,\n                                              max_boxes_to_draw=20,\n                                              min_score_thresh=.5,\n                                              agnostic_mode=False,\n                                              line_thickness=4):\n  \"\"\"Overlay labeled boxes on an image with formatted scores and label names.\n\n  This function groups boxes that correspond to the same location\n  and creates a display string for each detection and overlays these\n  on the image.  Note that this function modifies the image array in-place\n  and does not return anything.\n\n  Args:\n    image: uint8 numpy array with shape (img_height, img_width, 3)\n    boxes: a numpy array of shape [N, 4]\n    classes: a numpy array of shape [N]\n    scores: a numpy array of shape [N] or None.  If scores=None, then\n      this function assumes that the boxes to be plotted are groundtruth\n      boxes and plot all boxes as black with no classes or scores.\n    category_index: a dict containing category dictionaries (each holding\n      category index `id` and category name `name`) keyed by category indices.\n    instance_masks: a numpy array of shape [N, image_height, image_width], can\n      be None\n    keypoints: a numpy array of shape [N, num_keypoints, 2], can\n      be None\n    use_normalized_coordinates: whether boxes is to be interpreted as\n      normalized coordinates or not.\n    max_boxes_to_draw: maximum number of boxes to visualize.  If None, draw\n      all boxes.\n    min_score_thresh: minimum score threshold for a box to be visualized\n    agnostic_mode: boolean (default: False) controlling whether to evaluate in\n      class-agnostic mode or not.  This mode will display scores but ignore\n      classes.\n    line_thickness: integer (default: 4) controlling line width of the boxes.\n  \"\"\"\n  # Create a display string (and color) for every box location, group any boxes\n  # that correspond to the same location.\n  box_to_display_str_map = collections.defaultdict(list)\n  box_to_color_map = collections.defaultdict(str)\n  box_to_instance_masks_map = {}\n  box_to_keypoints_map = collections.defaultdict(list)\n  if not max_boxes_to_draw:\n    max_boxes_to_draw = boxes.shape[0]\n  for i in range(min(max_boxes_to_draw, boxes.shape[0])):\n    if scores is None or scores[i] > min_score_thresh:\n      box = tuple(boxes[i].tolist())\n      if instance_masks is not None:\n        box_to_instance_masks_map[box] = instance_masks[i]\n      if keypoints is not None:\n        box_to_keypoints_map[box].extend(keypoints[i])\n      if scores is None:\n        box_to_color_map[box] = 'black'\n      else:\n        if not agnostic_mode:\n          if classes[i] in category_index.keys():\n            class_name = category_index[classes[i]]['name']\n          else:\n            class_name = 'N/A'\n          display_str = '{}: {}%'.format(\n              class_name,\n              int(100*scores[i]))\n        else:\n          display_str = 'score: {}%'.format(int(100 * scores[i]))\n        box_to_display_str_map[box].append(display_str)\n        if agnostic_mode:\n          box_to_color_map[box] = 'DarkOrange'\n        else:\n          box_to_color_map[box] = STANDARD_COLORS[\n              classes[i] % len(STANDARD_COLORS)]\n\n  # Draw all boxes onto image.\n  for box, color in six.iteritems(box_to_color_map):\n    ymin, xmin, ymax, xmax = box\n    if instance_masks is not None:\n      draw_mask_on_image_array(\n          image,\n          box_to_instance_masks_map[box],\n          color=color\n      )\n    draw_bounding_box_on_image_array(\n        image,\n        ymin,\n        xmin,\n        ymax,\n        xmax,\n        color=color,\n        thickness=line_thickness,\n        display_str_list=box_to_display_str_map[box],\n        use_normalized_coordinates=use_normalized_coordinates)\n    if keypoints is not None:\n      draw_keypoints_on_image_array(\n          image,\n          box_to_keypoints_map[box],\n          color=color,\n          radius=line_thickness / 2,\n          use_normalized_coordinates=use_normalized_coordinates)\n"
  },
  {
    "path": "object_detector_app/object_detection/utils/visualization_utils_test.py",
    "content": "# Copyright 2017 The TensorFlow Authors. All Rights Reserved.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n# ==============================================================================\n\n\"\"\"Tests for image.understanding.object_detection.core.visualization_utils.\n\nTesting with visualization in the following colab:\nhttps://drive.google.com/a/google.com/file/d/0B5HnKS_hMsNARERpU3MtU3I5RFE/view?usp=sharing\n\n\"\"\"\n\n\nimport numpy as np\nimport PIL.Image as Image\nimport tensorflow as tf\n\nfrom object_detection.utils import visualization_utils\n\n\nclass VisualizationUtilsTest(tf.test.TestCase):\n\n  def create_colorful_test_image(self):\n    \"\"\"This function creates an image that can be used to test vis functions.\n\n    It makes an image composed of four colored rectangles.\n\n    Returns:\n      colorful test numpy array image.\n    \"\"\"\n    ch255 = np.full([100, 200, 1], 255, dtype=np.uint8)\n    ch128 = np.full([100, 200, 1], 128, dtype=np.uint8)\n    ch0 = np.full([100, 200, 1], 0, dtype=np.uint8)\n    imr = np.concatenate((ch255, ch128, ch128), axis=2)\n    img = np.concatenate((ch255, ch255, ch0), axis=2)\n    imb = np.concatenate((ch255, ch0, ch255), axis=2)\n    imw = np.concatenate((ch128, ch128, ch128), axis=2)\n    imu = np.concatenate((imr, img), axis=1)\n    imd = np.concatenate((imb, imw), axis=1)\n    image = np.concatenate((imu, imd), axis=0)\n    return image\n\n  def test_draw_bounding_box_on_image(self):\n    test_image = self.create_colorful_test_image()\n    test_image = Image.fromarray(test_image)\n    width_original, height_original = test_image.size\n    ymin = 0.25\n    ymax = 0.75\n    xmin = 0.4\n    xmax = 0.6\n\n    visualization_utils.draw_bounding_box_on_image(test_image, ymin, xmin, ymax,\n                                                   xmax)\n    width_final, height_final = test_image.size\n\n    self.assertEqual(width_original, width_final)\n    self.assertEqual(height_original, height_final)\n\n  def test_draw_bounding_box_on_image_array(self):\n    test_image = self.create_colorful_test_image()\n    width_original = test_image.shape[0]\n    height_original = test_image.shape[1]\n    ymin = 0.25\n    ymax = 0.75\n    xmin = 0.4\n    xmax = 0.6\n\n    visualization_utils.draw_bounding_box_on_image_array(\n        test_image, ymin, xmin, ymax, xmax)\n    width_final = test_image.shape[0]\n    height_final = test_image.shape[1]\n\n    self.assertEqual(width_original, width_final)\n    self.assertEqual(height_original, height_final)\n\n  def test_draw_bounding_boxes_on_image(self):\n    test_image = self.create_colorful_test_image()\n    test_image = Image.fromarray(test_image)\n    width_original, height_original = test_image.size\n    boxes = np.array([[0.25, 0.75, 0.4, 0.6],\n                      [0.1, 0.1, 0.9, 0.9]])\n\n    visualization_utils.draw_bounding_boxes_on_image(test_image, boxes)\n    width_final, height_final = test_image.size\n\n    self.assertEqual(width_original, width_final)\n    self.assertEqual(height_original, height_final)\n\n  def test_draw_bounding_boxes_on_image_array(self):\n    test_image = self.create_colorful_test_image()\n    width_original = test_image.shape[0]\n    height_original = test_image.shape[1]\n    boxes = np.array([[0.25, 0.75, 0.4, 0.6],\n                      [0.1, 0.1, 0.9, 0.9]])\n\n    visualization_utils.draw_bounding_boxes_on_image_array(test_image, boxes)\n    width_final = test_image.shape[0]\n    height_final = test_image.shape[1]\n\n    self.assertEqual(width_original, width_final)\n    self.assertEqual(height_original, height_final)\n\n  def test_draw_keypoints_on_image(self):\n    test_image = self.create_colorful_test_image()\n    test_image = Image.fromarray(test_image)\n    width_original, height_original = test_image.size\n    keypoints = [[0.25, 0.75], [0.4, 0.6], [0.1, 0.1], [0.9, 0.9]]\n\n    visualization_utils.draw_keypoints_on_image(test_image, keypoints)\n    width_final, height_final = test_image.size\n\n    self.assertEqual(width_original, width_final)\n    self.assertEqual(height_original, height_final)\n\n  def test_draw_keypoints_on_image_array(self):\n    test_image = self.create_colorful_test_image()\n    width_original = test_image.shape[0]\n    height_original = test_image.shape[1]\n    keypoints = [[0.25, 0.75], [0.4, 0.6], [0.1, 0.1], [0.9, 0.9]]\n\n    visualization_utils.draw_keypoints_on_image_array(test_image, keypoints)\n    width_final = test_image.shape[0]\n    height_final = test_image.shape[1]\n\n    self.assertEqual(width_original, width_final)\n    self.assertEqual(height_original, height_final)\n\n  def test_draw_mask_on_image_array(self):\n    test_image = np.asarray([[[0, 0, 0], [0, 0, 0]],\n                             [[0, 0, 0], [0, 0, 0]]], dtype=np.uint8)\n    mask = np.asarray([[0.0, 1.0],\n                       [1.0, 1.0]], dtype=np.float32)\n    expected_result = np.asarray([[[0, 0, 0], [0, 0, 127]],\n                                  [[0, 0, 127], [0, 0, 127]]], dtype=np.uint8)\n    visualization_utils.draw_mask_on_image_array(test_image, mask,\n                                                 color='Blue', alpha=.5)\n    self.assertAllEqual(test_image, expected_result)\n\n\nif __name__ == '__main__':\n  tf.test.main()\n"
  },
  {
    "path": "object_detector_app/object_detection_app.py",
    "content": "import os\nimport cv2\nimport time\nimport argparse\nimport multiprocessing\nimport numpy as np\nimport tensorflow as tf\nimport sys\n\nfrom utils.app_utils import FPS, WebcamVideoStream\nfrom multiprocessing import Queue, Pool\nfrom object_detection.utils import label_map_util\nfrom object_detection.utils import visualization_utils as vis_util\n\nCWD_PATH = os.getcwd()\n\n# Path to frozen detection graph. This is the actual model that is used for the object detection.\nMODEL_NAME = 'ssd_mobilenet_v1_coco_11_06_2017'\nPATH_TO_CKPT = os.path.join(CWD_PATH, 'object_detection', MODEL_NAME, 'frozen_inference_graph.pb')\n\n# List of the strings that is used to add correct label for each box.\nPATH_TO_LABELS = os.path.join(CWD_PATH, 'object_detection', 'data', 'mscoco_label_map.pbtxt')\n\nNUM_CLASSES = 90\n\n# Loading label map\nlabel_map = label_map_util.load_labelmap(PATH_TO_LABELS)\ncategories = label_map_util.convert_label_map_to_categories(label_map, max_num_classes=NUM_CLASSES,\n                                                            use_display_name=True)\ncategory_index = label_map_util.create_category_index(categories)\n\n\ndef detect_objects(image_np, sess, detection_graph):\n    # Expand dimensions since the model expects images to have shape: [1, None, None, 3]\n    image_np_expanded = np.expand_dims(image_np, axis=0)\n    image_tensor = detection_graph.get_tensor_by_name('image_tensor:0')\n\n    # Each box represents a part of the image where a particular object was detected.\n    boxes = detection_graph.get_tensor_by_name('detection_boxes:0')\n\n    # Each score represent how level of confidence for each of the objects.\n    # Score is shown on the result image, together with the class label.\n    scores = detection_graph.get_tensor_by_name('detection_scores:0')\n    classes = detection_graph.get_tensor_by_name('detection_classes:0')\n    num_detections = detection_graph.get_tensor_by_name('num_detections:0')\n\n    # Actual detection.\n    (boxes, scores, classes, num_detections) = sess.run(\n        [boxes, scores, classes, num_detections],\n        feed_dict={image_tensor: image_np_expanded})\n\n    # Visualization of the results of a detection.\n    vis_util.visualize_boxes_and_labels_on_image_array(\n        image_np,\n        np.squeeze(boxes),\n        np.squeeze(classes).astype(np.int32),\n        np.squeeze(scores),\n        category_index,\n        use_normalized_coordinates=True,\n        line_thickness=8)\n    return image_np\n\n\ndef worker(input_q, output_q):\n    # Load a (frozen) Tensorflow model into memory.\n    detection_graph = tf.Graph()\n    with detection_graph.as_default():\n        od_graph_def = tf.GraphDef()\n        with tf.gfile.GFile(PATH_TO_CKPT, 'rb') as fid:\n            serialized_graph = fid.read()\n            od_graph_def.ParseFromString(serialized_graph)\n            tf.import_graph_def(od_graph_def, name='')\n\n        sess = tf.Session(graph=detection_graph)\n\n    fps = FPS().start()\n    while True:\n        fps.update()\n        frame = input_q.get()\n        frame_rgb = cv2.cvtColor(frame, cv2.COLOR_BGR2RGB)\n        output_q.put(detect_objects(frame_rgb, sess, detection_graph))\n\n    fps.stop()\n    sess.close()\n\n\nif __name__ == '__main__':\n    parser = argparse.ArgumentParser()\n    parser.add_argument('-src', '--source', dest='video_source', type=int,\n                        default=-1, help='Device index of the camera.')\n    parser.add_argument('-wd', '--width', dest='width', type=int,\n                        default=1280, help='Width of the frames in the video stream.')\n    parser.add_argument('-ht', '--height', dest='height', type=int,\n                        default=720, help='Height of the frames in the video stream.')\n    parser.add_argument('-num-w', '--num-workers', dest='num_workers', type=int,\n                        default=2, help='Number of workers.')\n    parser.add_argument('-q-size', '--queue-size', dest='queue_size', type=int,\n                        default=2, help='Size of the queue.')\n    args = parser.parse_args()\n\n    logger = multiprocessing.log_to_stderr()\n    logger.setLevel(multiprocessing.SUBDEBUG)\n\n    input_q = Queue(maxsize=args.queue_size)\n    output_q = Queue(maxsize=args.queue_size)\n    pool = Pool(args.num_workers, worker, (input_q, output_q))\n\n    video_capture = WebcamVideoStream(src=args.video_source,\n                                      width=args.width,\n                                      height=args.height).start()\n    fps = FPS().start()\n    print('4', sys.path)\n    while True:  # fps._numFrames < 120\n\n        frame = video_capture.read()\n        input_q.put(frame)\n        #print('frame', frame)\n\n        t = time.time()\n\n        output_rgb = cv2.cvtColor(output_q.get(), cv2.COLOR_RGB2BGR)\n        cv2.imshow('Video', output_rgb)\n        fps.update()\n\n        print('[INFO] elapsed time: {:.2f}'.format(time.time() - t))\n\n        if cv2.waitKey(1) & 0xFF == ord('q'):\n            break\n\n    fps.stop()\n    print('[INFO] elapsed time (total): {:.2f}'.format(fps.elapsed()))\n    print('[INFO] approx. FPS: {:.2f}'.format(fps.fps()))\n\n    pool.terminate()\n    video_capture.stop()\n    cv2.destroyAllWindows()\n"
  },
  {
    "path": "object_detector_app/object_detection_multithreading.py",
    "content": "import os\nimport cv2\nimport time\nimport argparse\nimport numpy as np\nimport tensorflow as tf\nimport zmq\n\nfrom queue import Queue\nfrom threading import Thread\nfrom multiprocessing import Process, Queue, Pool\nfrom utils.app_utils import FPS, WebcamVideoStream, draw_boxes_and_labels\nfrom object_detection.utils import label_map_util\n\nCWD_PATH = os.getcwd()\n\n# Path to frozen detection graph. This is the actual model that is used for the object detection.\nMODEL_NAME = 'ssd_mobilenet_v1_coco_11_06_2017'\nPATH_TO_CKPT = os.path.join(CWD_PATH, 'object_detection', MODEL_NAME, 'frozen_inference_graph.pb')\n\n# List of the strings that is used to add correct label for each box.\nPATH_TO_LABELS = os.path.join(CWD_PATH, 'object_detection', 'data', 'mscoco_label_map.pbtxt')\n\nNUM_CLASSES = 90\n\n# Loading label map\nlabel_map = label_map_util.load_labelmap(PATH_TO_LABELS)\ncategories = label_map_util.convert_label_map_to_categories(label_map, max_num_classes=NUM_CLASSES,\n                                                            use_display_name=True)\ncategory_index = label_map_util.create_category_index(categories)\n\n\ndef detect_objects(image_np, sess, detection_graph):\n    # Expand dimensions since the model expects images to have shape: [1, None, None, 3]\n    image_np_expanded = np.expand_dims(image_np, axis=0)\n    image_tensor = detection_graph.get_tensor_by_name('image_tensor:0')\n\n    # Each box represents a part of the image where a particular object was detected.\n    boxes = detection_graph.get_tensor_by_name('detection_boxes:0')\n\n    # Each score represent how level of confidence for each of the objects.\n    # Score is shown on the result image, together with the class label.\n    scores = detection_graph.get_tensor_by_name('detection_scores:0')\n    classes = detection_graph.get_tensor_by_name('detection_classes:0')\n    num_detections = detection_graph.get_tensor_by_name('num_detections:0')\n\n    # Actual detection.\n    (boxes, scores, classes, num_detections) = sess.run(\n        [boxes, scores, classes, num_detections],\n        feed_dict={image_tensor: image_np_expanded})\n\n    # Visualization of the results of a detection.\n    rect_points, class_names, class_colors = draw_boxes_and_labels(\n        boxes=np.squeeze(boxes),\n        classes=np.squeeze(classes).astype(np.int32),\n        scores=np.squeeze(scores),\n        category_index=category_index,\n        min_score_thresh=.5\n    )\n    return dict(rect_points=rect_points, class_names=class_names, class_colors=class_colors)\n\n\ndef worker(input_q, output_q):\n    # Load a (frozen) Tensorflow model into memory.\n    detection_graph = tf.Graph()\n    with detection_graph.as_default():\n        od_graph_def = tf.GraphDef()\n        with tf.gfile.GFile(PATH_TO_CKPT, 'rb') as fid:\n            serialized_graph = fid.read()\n            od_graph_def.ParseFromString(serialized_graph)\n            tf.import_graph_def(od_graph_def, name='')\n\n        sess = tf.Session(graph=detection_graph)\n\n    fps = FPS().start()\n    while True:\n        fps.update()\n        frame = input_q.get()\n        frame_rgb = cv2.cvtColor(frame, cv2.COLOR_BGR2RGB)\n        output_q.put(detect_objects(frame_rgb, sess, detection_graph))\n\n    fps.stop()\n    sess.close()\n\n\n#publish information about detected objects via zmq\ndef publish_detected_object():\n    context = zmq.Context()\n    socket = context.socket(zmq.PUB)\n    addr = '127.0.0.1'  # remote ip or localhost\n    port = \"5556\"  # same as in the pupil remote gui\n    socket.bind(\"tcp://{}:{}\".format(addr, port))\n    time.sleep(1)\n\n    while True:\n        #publish the label only if there is a fixation and label    \n        label_conf = label_q.get()\n        print('label',label_conf.split())\n\n        if label_conf:\n            #print(self.label, self.fixation_norm_pos)\n            topic = 'detected_object'\n            # this only works for one and 2 word objects for now \n            if len(label_conf.split())==2:\n                label = label_conf.split()[0][:-1]\n                confidence = label_conf.split()[1][:-1]\n            if len(label_conf.split())==3:\n                label = label_conf.split()[0] + ' ' + label_conf.split()[1][:-1]\n                confidence = label_conf.split()[2][:-1]\n\n            print ('%s %s %s' % (topic, label, confidence))\n            try:\n                socket.send_string('%s %s %s' % (topic, label, confidence))\n            except TypeError:\n                socket.send('%s %s' % (topic, label, confidence))\n\n\n\nif __name__ == '__main__':\n    parser = argparse.ArgumentParser()\n    parser.add_argument('-src', '--source', dest='video_source', type=int,\n                        default=-1, help='Device index of the camera.')\n    parser.add_argument('-wd', '--width', dest='width', type=int,\n                        default=1280, help='Width of the frames in the video stream.')\n    parser.add_argument('-ht', '--height', dest='height', type=int,\n                        default=720, help='Height of the frames in the video stream.')\n    args = parser.parse_args()\n\n    input_q = Queue(2)  # fps is better if queue is higher but then more lags\n    output_q = Queue()\n    label_q = Queue()\n    for i in range(1):\n        t = Thread(target=worker, args=(input_q, output_q))\n        t.daemon = True\n        t.start()\n\n        p = Process(target=publish_detected_object)\n        p.daemon=  True\n        p.start()\n\n    video_capture = WebcamVideoStream(src=args.video_source,\n                                      width=args.width,\n                                      height=args.height).start()\n    fps = FPS().start()\n\n    while True:\n        frame = video_capture.read()\n        input_q.put(frame)\n\n        t = time.time()\n\n        if output_q.empty():\n            pass  # fill up queue\n        else:\n            font = cv2.FONT_HERSHEY_SIMPLEX\n            data = output_q.get()\n            rec_points = data['rect_points']\n            class_names = data['class_names']\n            class_colors = data['class_colors']\n            for point, name, color in zip(rec_points, class_names, class_colors):\n                #print(point, name, color)\n                print(\"name[0]\", name[0])\n                label_q.put(name[0])\n                cv2.rectangle(frame, (int(point['xmin'] * args.width), int(point['ymin'] * args.height)),\n                              (int(point['xmax'] * args.width), int(point['ymax'] * args.height)), color, 3)\n                cv2.rectangle(frame, (int(point['xmin'] * args.width), int(point['ymin'] * args.height)),\n                              (int(point['xmin'] * args.width) + len(name[0]) * 6,\n                               int(point['ymin'] * args.height) - 10), color, -1, cv2.LINE_AA)\n                cv2.putText(frame, name[0], (int(point['xmin'] * args.width), int(point['ymin'] * args.height)), font,\n                            0.3, (0, 0, 0), 1)\n            cv2.imshow('Video', frame)\n\n        fps.update()\n\n        print('[INFO] elapsed time: {:.2f}'.format(time.time() - t))\n\n        if cv2.waitKey(1) & 0xFF == ord('q'):\n            break\n\n    fps.stop()\n    print('[INFO] elapsed time (total): {:.2f}'.format(fps.elapsed()))\n    print('[INFO] approx. FPS: {:.2f}'.format(fps.fps()))\n\n    video_capture.stop()\n    cv2.destroyAllWindows()\n"
  },
  {
    "path": "object_detector_app/utils/__init__.py",
    "content": ""
  },
  {
    "path": "object_detector_app/utils/app_utils.py",
    "content": "# From http://www.pyimagesearch.com/2015/12/21/increasing-webcam-fps-with-python-and-opencv/\n\nimport struct\nimport six\nimport collections\nimport cv2\nimport datetime\nfrom threading import Thread\nfrom matplotlib import colors\n\n\nclass FPS:\n    def __init__(self):\n        # store the start time, end time, and total number of frames\n        # that were examined between the start and end intervals\n        self._start = None\n        self._end = None\n        self._numFrames = 0\n\n    def start(self):\n        # start the timer\n        self._start = datetime.datetime.now()\n        return self\n\n    def stop(self):\n        # stop the timer\n        self._end = datetime.datetime.now()\n\n    def update(self):\n        # increment the total number of frames examined during the\n        # start and end intervals\n        self._numFrames += 1\n\n    def elapsed(self):\n        # return the total number of seconds between the start and\n        # end interval\n        return (self._end - self._start).total_seconds()\n\n    def fps(self):\n        # compute the (approximate) frames per second\n        return self._numFrames / self.elapsed()\n\n\nclass WebcamVideoStream:\n    def __init__(self, src, width, height):\n        # initialize the video camera stream and read the first frame\n        # from the stream\n        self.stream = cv2.VideoCapture(src)\n        self.stream.set(cv2.CAP_PROP_FRAME_WIDTH, width)\n        self.stream.set(cv2.CAP_PROP_FRAME_HEIGHT, height)\n        (self.grabbed, self.frame) = self.stream.read()\n\n        # initialize the variable used to indicate if the thread should\n        # be stopped\n        self.stopped = False\n\n    def start(self):\n        # start the thread to read frames from the video stream\n        Thread(target=self.update, args=()).start()\n        return self\n\n    def update(self):\n        # keep looping infinitely until the thread is stopped\n        while True:\n            # if the thread indicator variable is set, stop the thread\n            if self.stopped:\n                return\n\n            # otherwise, read the next frame from the stream\n            (self.grabbed, self.frame) = self.stream.read()\n\n    def read(self):\n        # return the frame most recently read\n        return self.frame\n\n    def stop(self):\n        # indicate that the thread should be stopped\n        self.stopped = True\n\n\ndef standard_colors():\n    colors = [\n        'AliceBlue', 'Chartreuse', 'Aqua', 'Aquamarine', 'Azure', 'Beige', 'Bisque',\n        'BlanchedAlmond', 'BlueViolet', 'BurlyWood', 'CadetBlue', 'AntiqueWhite',\n        'Chocolate', 'Coral', 'CornflowerBlue', 'Cornsilk', 'Crimson', 'Cyan',\n        'DarkCyan', 'DarkGoldenRod', 'DarkGrey', 'DarkKhaki', 'DarkOrange',\n        'DarkOrchid', 'DarkSalmon', 'DarkSeaGreen', 'DarkTurquoise', 'DarkViolet',\n        'DeepPink', 'DeepSkyBlue', 'DodgerBlue', 'FireBrick', 'FloralWhite',\n        'ForestGreen', 'Fuchsia', 'Gainsboro', 'GhostWhite', 'Gold', 'GoldenRod',\n        'Salmon', 'Tan', 'HoneyDew', 'HotPink', 'IndianRed', 'Ivory', 'Khaki',\n        'Lavender', 'LavenderBlush', 'LawnGreen', 'LemonChiffon', 'LightBlue',\n        'LightCoral', 'LightCyan', 'LightGoldenRodYellow', 'LightGray', 'LightGrey',\n        'LightGreen', 'LightPink', 'LightSalmon', 'LightSeaGreen', 'LightSkyBlue',\n        'LightSlateGray', 'LightSlateGrey', 'LightSteelBlue', 'LightYellow', 'Lime',\n        'LimeGreen', 'Linen', 'Magenta', 'MediumAquaMarine', 'MediumOrchid',\n        'MediumPurple', 'MediumSeaGreen', 'MediumSlateBlue', 'MediumSpringGreen',\n        'MediumTurquoise', 'MediumVioletRed', 'MintCream', 'MistyRose', 'Moccasin',\n        'NavajoWhite', 'OldLace', 'Olive', 'OliveDrab', 'Orange', 'OrangeRed',\n        'Orchid', 'PaleGoldenRod', 'PaleGreen', 'PaleTurquoise', 'PaleVioletRed',\n        'PapayaWhip', 'PeachPuff', 'Peru', 'Pink', 'Plum', 'PowderBlue', 'Purple',\n        'Red', 'RosyBrown', 'RoyalBlue', 'SaddleBrown', 'Green', 'SandyBrown',\n        'SeaGreen', 'SeaShell', 'Sienna', 'Silver', 'SkyBlue', 'SlateBlue',\n        'SlateGray', 'SlateGrey', 'Snow', 'SpringGreen', 'SteelBlue', 'GreenYellow',\n        'Teal', 'Thistle', 'Tomato', 'Turquoise', 'Violet', 'Wheat', 'White',\n        'WhiteSmoke', 'Yellow', 'YellowGreen'\n    ]\n    return colors\n\n\ndef color_name_to_rgb():\n    colors_rgb = []\n    for key, value in colors.cnames.items():\n        colors_rgb.append((key, struct.unpack('BBB', bytes.fromhex(value.replace('#', '')))))\n    return dict(colors_rgb)\n\n\ndef draw_boxes_and_labels(\n        boxes,\n        classes,\n        scores,\n        category_index,\n        instance_masks=None,\n        keypoints=None,\n        max_boxes_to_draw=20,\n        min_score_thresh=.5,\n        agnostic_mode=False):\n    \"\"\"Returns boxes coordinates, class names and colors\n\n    Args:\n      boxes: a numpy array of shape [N, 4]\n      classes: a numpy array of shape [N]\n      scores: a numpy array of shape [N] or None.  If scores=None, then\n        this function assumes that the boxes to be plotted are groundtruth\n        boxes and plot all boxes as black with no classes or scores.\n      category_index: a dict containing category dictionaries (each holding\n        category index `id` and category name `name`) keyed by category indices.\n      instance_masks: a numpy array of shape [N, image_height, image_width], can\n        be None\n      keypoints: a numpy array of shape [N, num_keypoints, 2], can\n        be None\n      max_boxes_to_draw: maximum number of boxes to visualize.  If None, draw\n        all boxes.\n      min_score_thresh: minimum score threshold for a box to be visualized\n      agnostic_mode: boolean (default: False) controlling whether to evaluate in\n        class-agnostic mode or not.  This mode will display scores but ignore\n        classes.\n    \"\"\"\n    # Create a display string (and color) for every box location, group any boxes\n    # that correspond to the same location.\n    box_to_display_str_map = collections.defaultdict(list)\n    box_to_color_map = collections.defaultdict(str)\n    box_to_instance_masks_map = {}\n    box_to_keypoints_map = collections.defaultdict(list)\n    if not max_boxes_to_draw:\n        max_boxes_to_draw = boxes.shape[0]\n    for i in range(min(max_boxes_to_draw, boxes.shape[0])):\n        if scores is None or scores[i] > min_score_thresh:\n            box = tuple(boxes[i].tolist())\n            if instance_masks is not None:\n                box_to_instance_masks_map[box] = instance_masks[i]\n            if keypoints is not None:\n                box_to_keypoints_map[box].extend(keypoints[i])\n            if scores is None:\n                box_to_color_map[box] = 'black'\n            else:\n                if not agnostic_mode:\n                    if classes[i] in category_index.keys():\n                        class_name = category_index[classes[i]]['name']\n                    else:\n                        class_name = 'N/A'\n                    display_str = '{}: {}%'.format(\n                        class_name,\n                        int(100 * scores[i]))\n                else:\n                    display_str = 'score: {}%'.format(int(100 * scores[i]))\n                box_to_display_str_map[box].append(display_str)\n                if agnostic_mode:\n                    box_to_color_map[box] = 'DarkOrange'\n                else:\n                    box_to_color_map[box] = standard_colors()[\n                        classes[i] % len(standard_colors())]\n\n    # Store all the coordinates of the boxes, class names and colors\n    color_rgb = color_name_to_rgb()\n    rect_points = []\n    class_names = []\n    class_colors = []\n    for box, color in six.iteritems(box_to_color_map):\n        ymin, xmin, ymax, xmax = box\n        rect_points.append(dict(ymin=ymin, xmin=xmin, ymax=ymax, xmax=xmax))\n        class_names.append(box_to_display_str_map[box])\n        class_colors.append(color_rgb[color.lower()])\n    return rect_points, class_names, class_colors\n"
  },
  {
    "path": "object_detector_app/utils/test_app_utils.py",
    "content": "import unittest\nfrom object_detector_app.utils.app_utils import color_name_to_rgb, standard_colors\n\n\nclass TestUtils(unittest.TestCase):\n    def setUp(self):\n        self.colors = color_name_to_rgb()\n        self.standard_colors = standard_colors()\n\n    def test_all_colors(self):\n        \"\"\"Test that manual defined colors are also in the matplotlib color name space.\"\"\"\n        color_list = set(sorted(list(self.colors.keys())))\n        standard_color_list = set(sorted([color.lower() for color in self.standard_colors]))\n        color_common = standard_color_list.intersection(color_list)\n        self.assertEqual(len(color_common), len(standard_color_list))\n"
  }
]