Merge "Automatically sign off commits when rewriting for gerrit"
diff --git a/aos/events/logging/logfile_utils_test.cc b/aos/events/logging/logfile_utils_test.cc
index e1e2ebd..9be70c6 100644
--- a/aos/events/logging/logfile_utils_test.cc
+++ b/aos/events/logging/logfile_utils_test.cc
@@ -479,6 +479,7 @@
     ++queue_index_[channel_index];
 
     flatbuffers::FlatBufferBuilder fbb;
+    fbb.ForceDefaults(true);
     fbb.FinishSizePrefixed(
         PackMessage(&fbb, context, channel_index, LogType::kLogMessage));
 
diff --git a/frc971/config/setup_roborio.sh b/frc971/config/setup_roborio.sh
index 2cd4bd5..0a70e27 100755
--- a/frc971/config/setup_roborio.sh
+++ b/frc971/config/setup_roborio.sh
@@ -34,6 +34,7 @@
   ssh "admin@${ROBOT_HOSTNAME}" ln -s /media/sda1/aos_log-current robot_code/aos_log-current
   echo "Adding aos_dump autocomplete to profile"
   ssh "admin@${ROBOT_HOSTNAME}" 'echo "if [ -f /home/admin/robot_code/aos_dump_autocomplete.sh ]; then source /home/admin/robot_code/aos_dump_autocomplete.sh; fi;" >> /etc/profile'
+  ssh "admin@${ROBOT_HOSTNAME}" 'echo "export PATH=\"\${PATH}:/home/admin/robot_code:/home/admin/bin\"" >> /etc/profile'
 fi
 
 if [[ "$(ssh admin@${ROBOT_HOSTNAME} uname -r)" != "4.14.87-rt49-cg-7.0.0f0-xilinx-zynq-189" ]]; then
diff --git a/frc971/control_loops/drivetrain/distance_spline.cc b/frc971/control_loops/drivetrain/distance_spline.cc
index 5c05fe4..ab38980 100644
--- a/frc971/control_loops/drivetrain/distance_spline.cc
+++ b/frc971/control_loops/drivetrain/distance_spline.cc
@@ -15,7 +15,7 @@
 
   if (splines_.size() > 1) {
     // We've got a multispline to follow!
-    // Confirm that the ends line up to the correct number of derivitives.
+    // Confirm that the ends line up to the correct number of derivatives.
     for (size_t i = 1; i < splines_.size(); ++i) {
       const Spline &spline0 = splines_[i - 1];
       const Spline &spline1 = splines_[i];
@@ -36,7 +36,7 @@
       if (!dend0.isApprox(dstart1, 1e-6)) {
         AOS_LOG(
             ERROR,
-            "Splines %d and %d don't line up in the first derivitive.  [%f, "
+            "Splines %d and %d don't line up in the first derivative.  [%f, "
             "%f] != [%f, %f]\n",
             static_cast<int>(i - 1), static_cast<int>(i), dend0(0, 0),
             dend0(1, 0), dstart1(0, 0), dstart1(1, 0));
@@ -48,7 +48,7 @@
       if (!ddend0.isApprox(ddstart1, 1e-6)) {
         AOS_LOG(
             ERROR,
-            "Splines %d and %d don't line up in the second derivitive.  [%f, "
+            "Splines %d and %d don't line up in the second derivative.  [%f, "
             "%f] != [%f, %f]\n",
             static_cast<int>(i - 1), static_cast<int>(i), ddend0(0, 0),
             ddend0(1, 0), ddstart1(0, 0), ddstart1(1, 0));
diff --git a/tools/cherry-pick-merge.sh b/tools/cherry-pick-merge.sh
new file mode 100755
index 0000000..547fecf
--- /dev/null
+++ b/tools/cherry-pick-merge.sh
@@ -0,0 +1,20 @@
+#!/bin/bash
+#
+# The script replays a merge based on its first parent.
+# This will create a new merge with the same message and second parent, but with
+# its first parent as the current commit.
+#
+# It is advised for now to backup your repo before running this command and
+# make sure the git history is what you want until we use it more.
+
+set -e
+set -o pipefail
+
+COMMIT=$1
+
+MESSAGE=$(git show -s --format=%B ${COMMIT})
+
+git cherry-pick -m1 ${COMMIT}
+git reset --soft HEAD~
+echo ${COMMIT}^2 > .git/MERGE_HEAD
+git commit --message="${MESSAGE}"
diff --git a/y2020/vision/camera_reader.cc b/y2020/vision/camera_reader.cc
index 9bc9ba9..e908a47 100644
--- a/y2020/vision/camera_reader.cc
+++ b/y2020/vision/camera_reader.cc
@@ -45,13 +45,12 @@
             event_loop->MakeSender<sift::ImageMatchResult>("/camera")),
         detailed_result_sender_(
             event_loop->MakeSender<sift::ImageMatchResult>("/camera/detailed")),
-        read_image_timer_(event_loop->AddTimer([this]() { ReadImage(); })),
-        prev_R_camera_field_vec_(cv::Mat::zeros(3, 1, CV_32F)),
-        prev_T_camera_field_(cv::Mat::zeros(3, 1, CV_32F)) {
+        read_image_timer_(event_loop->AddTimer([this]() { ReadImage(); })) {
     for (int ii = 0; ii < number_training_images(); ++ii) {
       matchers_.push_back(cv::FlannBasedMatcher(index_params, search_params));
+      prev_camera_field_R_vec_list_.push_back(cv::Mat::zeros(3, 1, CV_32F));
+      prev_camera_field_T_list_.push_back(cv::Mat::zeros(3, 1, CV_32F));
     }
-
     CopyTrainingFeatures();
 
     for (auto &matcher : matchers_) {
@@ -172,8 +171,8 @@
   aos::TimerHandler *const read_image_timer_;
 
   // Storage for when we want to use the previous estimates of pose
-  cv::Mat prev_R_camera_field_vec_;
-  cv::Mat prev_T_camera_field_;
+  std::vector<cv::Mat> prev_camera_field_R_vec_list_;
+  std::vector<cv::Mat> prev_camera_field_T_list_;
 
   const std::unique_ptr<frc971::vision::SIFT971_Impl> sift_{
       new frc971::vision::SIFT971_Impl()};
@@ -382,8 +381,8 @@
   for (size_t i = 0; i < per_image_matches.size(); ++i) {
     const PerImageMatches &per_image = per_image_matches[i];
 
-    VLOG(2) << "Number of matches to start: " << per_image.matches.size()
-            << "\n";
+    VLOG(2) << "Number of matches to start for training image: " << i
+            << " is: " << per_image.matches.size() << "\n";
     // If we don't have enough matches to start, skip this set of matches
     if (per_image.matches.size() < kMinimumMatchCount) {
       continue;
@@ -402,8 +401,8 @@
     }
     homography_feature_counts.push_back(homography_feature_count);
 
-    VLOG(2) << "Number of matches after homography: " << cv::countNonZero(mask)
-            << "\n";
+    VLOG(2) << "Number of matches after homography for training image: " << i
+            << " is " << cv::countNonZero(mask) << "\n";
 
     // Fill our match info for each good match based on homography result
     PerImageMatches per_image_good_match;
@@ -431,7 +430,7 @@
     // Returns from opencv are doubles (CV_64F), which don't play well
     // with our floats
     homography.convertTo(homography, CV_32F);
-    per_image_good_match.homography = homography;
+    per_image_good_match.homography = homography.clone();
 
     CHECK_GT(per_image_good_match.matches.size(), 0u);
 
@@ -472,8 +471,10 @@
     // near the previous pose helps it converge to the previous pose
     // estimate (assuming it's valid).
     if (FLAGS_use_prev_pose) {
-      R_camera_field_vec = prev_R_camera_field_vec_.clone();
-      T_camera_field = prev_T_camera_field_.clone();
+      R_camera_field_vec = prev_camera_field_R_vec_list_[i].clone();
+      T_camera_field = prev_camera_field_T_list_[i].clone();
+      VLOG(2) << "Using previous match for training image " << i
+              << " with T of : " << T_camera_field;
     }
 
     // Compute the pose of the camera (global origin relative to camera)
@@ -502,11 +503,11 @@
           << T_camera_field << "\nR: " << R_camera_field_vec
           << "\nNumber of matches is: "
           << per_image_good_match.query_points.size();
-      LOG(INFO) << "Resetting previous values to zero, from: R_prev: "
-                << prev_R_camera_field_vec_
-                << ", T_prev: " << prev_T_camera_field_;
-      prev_R_camera_field_vec_ = cv::Mat::zeros(3, 1, CV_32F);
-      prev_T_camera_field_ = cv::Mat::zeros(3, 1, CV_32F);
+      VLOG(2) << "Resetting previous values to zero, from: R_prev: "
+              << prev_camera_field_R_vec_list_[i]
+              << ", T_prev: " << prev_camera_field_T_list_[i];
+      prev_camera_field_R_vec_list_[i] = cv::Mat::zeros(3, 1, CV_32F);
+      prev_camera_field_T_list_[i] = cv::Mat::zeros(3, 1, CV_32F);
 
       continue;
     }
@@ -575,16 +576,16 @@
                     "T_camera_target = "
                  << T_camera_target
                  << "\nAnd T_field_camera = " << T_field_camera;
-      LOG(INFO) << "Resetting previous values to zero, from: R_prev: "
-                << prev_R_camera_field_vec_
-                << ", T_prev: " << prev_T_camera_field_;
-      prev_R_camera_field_vec_ = cv::Mat::zeros(3, 1, CV_32F);
-      prev_T_camera_field_ = cv::Mat::zeros(3, 1, CV_32F);
+      VLOG(2) << "Resetting previous values to zero, from: R_prev: "
+              << prev_camera_field_R_vec_list_[i]
+              << ", T_prev: " << prev_camera_field_T_list_[i];
+      prev_camera_field_R_vec_list_[i] = cv::Mat::zeros(3, 1, CV_32F);
+      prev_camera_field_T_list_[i] = cv::Mat::zeros(3, 1, CV_32F);
       continue;
     }
 
-    prev_R_camera_field_vec_ = R_camera_field_vec.clone();
-    prev_T_camera_field_ = T_camera_field.clone();
+    prev_camera_field_R_vec_list_[i] = R_camera_field_vec.clone();
+    prev_camera_field_T_list_[i] = T_camera_field.clone();
   }
   // Now, send our two messages-- one large, with details for remote
   // debugging(features), and one smaller
diff --git a/y2020/vision/tools/python_code/target_definition.py b/y2020/vision/tools/python_code/target_definition.py
index 2b403d6..e518c8c 100644
--- a/y2020/vision/tools/python_code/target_definition.py
+++ b/y2020/vision/tools/python_code/target_definition.py
@@ -135,9 +135,8 @@
         "target_definitions/ideal_power_port_red.json",
         "target_definitions/ideal_power_port_blue.json")
     training_target_list = TargetData.from_jsons(
-        "target_definitions/training_target_power_port_taped.json",
-        "target_definitions/training_target_power_port_red.json",
-        "target_definitions/training_target_power_port_blue.json")
+        "target_definitions/cc_power_port_red_base_2021-10-29_15-08-50.json",
+        "target_definitions/cc_power_port_blue_base_2021-10-29_15-14-21.json")
     return ideal_target_list, training_target_list
 
 
diff --git a/y2020/vision/tools/python_code/target_definitions/cc_power_port_blue_base.json b/y2020/vision/tools/python_code/target_definitions/cc_power_port_blue_base.json
new file mode 100644
index 0000000..5c44063
--- /dev/null
+++ b/y2020/vision/tools/python_code/target_definitions/cc_power_port_blue_base.json
@@ -0,0 +1 @@
+{"image_filename": "test_images/train_power_port_red.png", "polygon_list": [[[451, 679], [451, 304], [100, 302], [451, 74], [689, 74], [689, 302], [689, 679]]], "polygon_list_3d": [[[7.9915, -1.0795, 0.0], [7.9915, -1.0795, 1.93548], [7.9915, 0.127, 1.93548], [7.9915, -1.0795, 3.1038799999999998], [7.9915, -2.2986999999999997, 3.1038799999999998], [7.9915, -2.2986999999999997, 1.93548], [7.9915, -2.2986999999999997, 0.0]]], "target_rotation": [[-1.0, -0.0, -0.0], [-0.0, -1.0, -0.0], [-0.0, -0.0, 1.0]], "target_position": [7.9915, -1.759, 2.494], "target_point_2d": [[[570.0, 192.0]]], "target_radius": 12.0}
diff --git a/y2020/vision/tools/python_code/target_definitions/cc_power_port_blue_base_2021-10-29_15-14-21.json b/y2020/vision/tools/python_code/target_definitions/cc_power_port_blue_base_2021-10-29_15-14-21.json
new file mode 100644
index 0000000..b001e80
--- /dev/null
+++ b/y2020/vision/tools/python_code/target_definitions/cc_power_port_blue_base_2021-10-29_15-14-21.json
@@ -0,0 +1 @@
+{"image_filename": "test_images/cc_power_port_blue-2021-10-29.png", "polygon_list": [[[256, 393], [258, 210], [156, 209], [266, 111], [374, 110], [376, 209], [380, 397]]], "polygon_list_3d": [[[7.9915, -1.0795, 0.0], [7.9915, -1.0795, 1.93548], [7.9915, 0.127, 1.93548], [7.9915, -1.0795, 3.1038799999999998], [7.9915, -2.2986999999999997, 3.1038799999999998], [7.9915, -2.2986999999999997, 1.93548], [7.9915, -2.2986999999999997, 0.0]]], "target_rotation": [[-1.0, -0.0, -0.0], [-0.0, -1.0, -0.0], [-0.0, -0.0, 1.0]], "target_position": [7.9915, -1.759, 2.494], "target_point_2d": [[[318.0, 162.0]]], "target_radius": 12.0}
\ No newline at end of file
diff --git a/y2020/vision/tools/python_code/target_definitions/cc_power_port_red_base.json b/y2020/vision/tools/python_code/target_definitions/cc_power_port_red_base.json
new file mode 100644
index 0000000..1967533
--- /dev/null
+++ b/y2020/vision/tools/python_code/target_definitions/cc_power_port_red_base.json
@@ -0,0 +1 @@
+{"image_filename": "test_images/train_power_port_red.png", "polygon_list": [[[451, 679], [451, 304], [100, 302], [451, 74], [689, 74], [689, 302], [689, 679]]], "polygon_list_3d": [[[-7.9915, 1.0795, 0.0], [-7.9915, 1.0795, 1.93548], [-7.9915, -0.127, 1.93548], [-7.9915, 1.0795, 3.1038799999999998], [-7.9915, 2.2986999999999997, 3.1038799999999998], [-7.9915, 2.2986999999999997, 1.93548], [-7.9915, 2.2986999999999997, 0.0]]], "target_rotation": [[-1.0, -0.0, -0.0], [-0.0, -1.0, -0.0], [-0.0, -0.0, 1.0]], "target_position": [-7.9915, 1.759, 2.494], "target_point_2d": [[[570.0, 192.0]]], "target_radius": 12.0}
diff --git a/y2020/vision/tools/python_code/target_definitions/cc_power_port_red_base_2021-10-29_15-08-50.json b/y2020/vision/tools/python_code/target_definitions/cc_power_port_red_base_2021-10-29_15-08-50.json
new file mode 100644
index 0000000..90c42ba
--- /dev/null
+++ b/y2020/vision/tools/python_code/target_definitions/cc_power_port_red_base_2021-10-29_15-08-50.json
@@ -0,0 +1 @@
+{"image_filename": "test_images/cc_power_port_red-2021-10-29.png", "polygon_list": [[[247, 377], [242, 168], [112, 168], [245, 45], [372, 41], [381, 162], [386, 374]]], "polygon_list_3d": [[[-7.9915, 1.0795, 0.0], [-7.9915, 1.0795, 1.93548], [-7.9915, -0.127, 1.93548], [-7.9915, 1.0795, 3.1038799999999998], [-7.9915, 2.2986999999999997, 3.1038799999999998], [-7.9915, 2.2986999999999997, 1.93548], [-7.9915, 2.2986999999999997, 0.0]]], "target_rotation": [[-1.0, -0.0, -0.0], [-0.0, -1.0, -0.0], [-0.0, -0.0, 1.0]], "target_position": [-7.9915, 1.759, 2.494], "target_point_2d": [[[308.0, 107.0]]], "target_radius": 12.0}
\ No newline at end of file
diff --git a/y2020/vision/tools/python_code/test_images/cc_loading_bay_blue-2021-10-29.png b/y2020/vision/tools/python_code/test_images/cc_loading_bay_blue-2021-10-29.png
new file mode 100644
index 0000000..7331ef0
--- /dev/null
+++ b/y2020/vision/tools/python_code/test_images/cc_loading_bay_blue-2021-10-29.png
Binary files differ
diff --git a/y2020/vision/tools/python_code/test_images/cc_loading_bay_red-2021-10-29.png b/y2020/vision/tools/python_code/test_images/cc_loading_bay_red-2021-10-29.png
new file mode 100644
index 0000000..4f9dc55
--- /dev/null
+++ b/y2020/vision/tools/python_code/test_images/cc_loading_bay_red-2021-10-29.png
Binary files differ
diff --git a/y2020/vision/tools/python_code/test_images/cc_power_port_blue-2021-10-29.png b/y2020/vision/tools/python_code/test_images/cc_power_port_blue-2021-10-29.png
new file mode 100644
index 0000000..d60867d
--- /dev/null
+++ b/y2020/vision/tools/python_code/test_images/cc_power_port_blue-2021-10-29.png
Binary files differ
diff --git a/y2020/vision/tools/python_code/test_images/cc_power_port_red-2021-10-29.png b/y2020/vision/tools/python_code/test_images/cc_power_port_red-2021-10-29.png
new file mode 100644
index 0000000..9b44b31
--- /dev/null
+++ b/y2020/vision/tools/python_code/test_images/cc_power_port_red-2021-10-29.png
Binary files differ