Skip to content
This repository was archived by the owner on Jan 7, 2023. It is now read-only.
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,8 @@ class TrackerKCFImpl
{
public:
TrackerKCFImpl();
void setFeatureExtractor(void (* f)(const cv::Mat, const cv::Rect2d, cv::Mat &),
void setFeatureExtractor(
void (* f)(const cv::Mat, const cv::Rect2d, cv::Mat &),
bool pca_func = false);
Params params;
bool isInit;
Expand All @@ -121,7 +122,8 @@ class TrackerKCFImpl
*/
bool initImpl(const cv::Mat & image, cv::Rect2d & boundingBox);

bool detectImpl(const cv::Mat & image, cv::Rect2d & boundingBox, float & confidence,
bool detectImpl(
const cv::Mat & image, cv::Rect2d & boundingBox, float & confidence,
bool debug = false);

bool updateWithTrackImpl(
Expand All @@ -137,7 +139,8 @@ class TrackerKCFImpl
*/
bool extractFeature(const cv::Mat & image, cv::Rect2d u_roi, cv::Mat & featureSet);

bool extractKernelMap(const cv::Mat & srcFeature, const cv::Mat & dstFeature,
bool extractKernelMap(
const cv::Mat & srcFeature, const cv::Mat & dstFeature,
cv::Mat & kernelMap);

bool extractCovar(
Expand Down Expand Up @@ -174,7 +177,8 @@ class TrackerKCFImpl
* KCF functions and vars
*/
void createHanningWindow(cv::OutputArray dest, const cv::Size winSize, const int type) const;
void inline fft2(const cv::Mat src, std::vector<cv::Mat> & dest,
void inline fft2(
const cv::Mat src, std::vector<cv::Mat> & dest,
std::vector<cv::Mat> & layers_data) const;
void inline fft2(const cv::Mat src, cv::Mat & dest) const;
void inline ifft2(const cv::Mat src, cv::Mat & dest) const;
Expand All @@ -189,7 +193,7 @@ class TrackerKCFImpl
cv::Mat pca_data, cv::Mat new_cov, cv::Mat w, cv::Mat u, cv::Mat vt);
void inline compress(
const cv::Mat proj_matrix, const cv::Mat src, cv::Mat & dest, cv::Mat & data,
cv::Mat & compressed) const;
cv::Mat & compressed) const;
bool getSubWindow(
const cv::Mat img, const cv::Rect2d roi, cv::Mat & feat, cv::Mat & patch,
MODE desc = GRAY) const;
Expand All @@ -204,14 +208,14 @@ class TrackerKCFImpl
void denseGaussKernel(
const float sigma, const cv::Mat, const cv::Mat y_data, cv::Mat & k_data,
std::vector<cv::Mat> & layers_data, std::vector<cv::Mat> & xf_data,
std::vector<cv::Mat> & yf_data, std::vector<cv::Mat> xyf_v,
cv::Mat xy, cv::Mat xyf) const;
std::vector<cv::Mat> & yf_data, std::vector<cv::Mat> xyf_v,
cv::Mat xy, cv::Mat xyf) const;
void calcResponse(
const cv::Mat alphaf_data, const cv::Mat kf_data, cv::Mat & response_data,
cv::Mat & spec_data) const;
cv::Mat & spec_data) const;
void calcResponse(
const cv::Mat alphaf_data, const cv::Mat alphaf_den_data, const cv::Mat kf_data,
cv::Mat & response_data, cv::Mat & spec_data, cv::Mat & spec2_data) const;
cv::Mat & response_data, cv::Mat & spec_data, cv::Mat & spec2_data) const;

void shiftRows(cv::Mat & mat) const;
void shiftRows(cv::Mat & mat, int n) const;
Expand All @@ -221,30 +225,41 @@ class TrackerKCFImpl
#endif

private:
float output_sigma;
cv::Rect2d roi;
cv::Mat hann; // hann window filter
cv::Mat hann_cn; // 10 dimensional hann-window filter for CN features,

cv::Mat y, yf; // training response and its FFT
cv::Mat x; // observation and its FFT
cv::Mat k, kf; // dense gaussian kernel and its FFT
cv::Mat kf_lambda; // kf+lambda
cv::Mat new_alphaf, alphaf; // training coefficients
cv::Mat new_alphaf_den, alphaf_den; // for splitted training coefficients
cv::Mat z; // model
cv::Mat response; // detection result
cv::Mat old_cov_mtx, proj_mtx; // for feature compression
float output_sigma;
cv::Rect2d roi;
// hann window filter
cv::Mat hann;
// 10 dimensional hann-window filter for CN features
cv::Mat hann_cn;

// training response and its FFT
cv::Mat y, yf;
// observation and its FFT
cv::Mat x;
// dense gaussian kernel and its FFT
cv::Mat k, kf;
// kf+lambda
cv::Mat kf_lambda;
// training coefficients
cv::Mat new_alphaf, alphaf;
// for splitted training coefficients
cv::Mat new_alphaf_den, alphaf_den;
// model
cv::Mat z;
// detection result
cv::Mat response;
// for feature compression
cv::Mat old_cov_mtx, proj_mtx;

// pre-defined Mat variables for optimization of private functions
cv::Mat spec, spec2;
cv::Mat spec, spec2;
std::vector<cv::Mat> layers;
std::vector<cv::Mat> vxf, vyf, vxyf;
cv::Mat xy_data, xyf_data;
cv::Mat data_temp, compress_data;
cv::Mat xy_data, xyf_data;
cv::Mat data_temp, compress_data;
std::vector<cv::Mat> layers_pca_data;
std::vector<cv::Scalar> average_data;
cv::Mat img_Patch;
cv::Mat img_Patch;

// storage of the extracted features
std::vector<cv::Mat> features_pca;
Expand All @@ -253,7 +268,7 @@ class TrackerKCFImpl
std::vector<MODE> descriptors_npca;

// optimization variables for updateProjectionMatrix
cv::Mat data_pca, new_covar, w_data, u_data, vt_data;
cv::Mat data_pca, new_covar, w_data, u_data, vt_data;

// custom feature extractor
bool use_custom_extractor_pca;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -185,4 +185,3 @@ class TrackingManager
} // namespace tracker

#endif // OBJECT_ANALYTICS_NODE__TRACKER__TRACKING_MANAGER_HPP_

2 changes: 1 addition & 1 deletion object_analytics_node/src/tracker/tracking.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ void Tracking::updateTracker(
tracked_rect_, probability_, debug);

if (!ret) {
TRACE_INFO( "Tracker(%d) update stamp(%f), det(%d), failed since of match fail!!!!",
TRACE_INFO("Tracker(%d) update stamp(%f), det(%d), failed since of match fail!!!!",
tracking_id_, lstamp, det);

state_ = LOST;
Expand Down
42 changes: 21 additions & 21 deletions object_analytics_node/src/visualizer/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,15 +22,15 @@ endif()

####################################
## to use C++11
set (CMAKE_CXX_STANDARD 11)
set (CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_CXX_STANDARD 11)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_CXX_FLAGS "-std=c++11 ${CMAKE_CXX_FLAGS}")
####################################

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
# we dont use add_compile_options with pedantic in message packages
# because the Python C extensions dont comply with it
# set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wpedantic")
# set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wpedantic")
endif()

find_package(Pangolin REQUIRED)
Expand All @@ -39,32 +39,32 @@ find_package(OpenCV 3.2 REQUIRED)
include_directories(
include
utils
device
render_object
device
render_object
view
control
data
data/dataset
model
model/stat
model/sample
$(CMAKE_CURRENT_SOURCE_DIR)
$(CMAKE_CURRENT_SOURCE_DIR)
)

add_executable(oa_viewer
main.cpp
add_executable(oa_viewer
main.cpp
view/view.cpp
control/control.cpp
control/control_ds.cpp
device/stream_cap.cpp
device/stream_device.cpp
device/stream_vid.cpp
device/stream_ds.cpp
render_object/render_object.cpp
render_object/render_image.cpp
render_object/render_lines.cpp
render_object/render_rect.cpp
render_object/render_ellipse.cpp
device/stream_cap.cpp
device/stream_device.cpp
device/stream_vid.cpp
device/stream_ds.cpp
render_object/render_object.cpp
render_object/render_image.cpp
render_object/render_lines.cpp
render_object/render_rect.cpp
render_object/render_ellipse.cpp
data/frame.cpp
data/frame_obj.cpp
data/dataset/tr_dataset.cpp
Expand All @@ -78,10 +78,10 @@ add_executable(oa_viewer
model/sample/sample_model.cpp
model/sample/uniform_sample.cpp
model/sample/rw_sample.cpp
)
)

target_link_libraries(oa_viewer
${PCL_COMMON_LIBRARIES}
${Pangolin_LIBRARIES}
${OpenCV_LIBRARIES}
${PCL_COMMON_LIBRARIES}
${Pangolin_LIBRARIES}
${OpenCV_LIBRARIES}
)
Binary file not shown.
Original file line number Diff line number Diff line change
Expand Up @@ -13,10 +13,12 @@
// limitations under the License.

#include <omp.h>
#include <fstream>
#include <opencv2/highgui.hpp>

#include <fstream>
#include <string>
#include <vector>

#include "track_dataset.hpp"

namespace datasets
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "track_dataset.hpp"

#include <omp.h>
#include <fstream>
#include <opencv2/highgui.hpp>

#include <string>
#include <vector>
#include "track_dataset.hpp"
#include <fstream>

namespace datasets
{
Expand Down
3 changes: 3 additions & 0 deletions object_analytics_node/src/visualizer/device/stream_cap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,9 @@

#include "stream_cap.hpp"

#include <memory>
#include <string>

stream_cap::stream_cap() {TRACE_INFO();}

stream_cap::~stream_cap() {TRACE_INFO();}
Expand Down
5 changes: 3 additions & 2 deletions object_analytics_node/src/visualizer/device/stream_cap.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,15 +14,16 @@

#pragma once

#include <opencv2/opencv.hpp>

#include <chrono>
#include <fstream>
#include <iostream>
#include <iterator>
#include <random>
#include <string>
#include <vector>

#include <opencv2/opencv.hpp>
#include <memory>

#include "stream_device.hpp"

Expand Down
4 changes: 4 additions & 0 deletions object_analytics_node/src/visualizer/device/stream_device.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,10 @@
// limitations under the License.

#include "stream_device.hpp"

#include <string>
#include <memory>

#include "stream_cap.hpp"
#include "stream_ds.hpp"
#include "stream_vid.hpp"
Expand Down
5 changes: 3 additions & 2 deletions object_analytics_node/src/visualizer/device/stream_device.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#pragma once

#include <opencv2/opencv.hpp>

#include <atomic>
#include <chrono>
#include <condition_variable>
Expand All @@ -27,8 +29,7 @@
#include <string>
#include <thread>
#include <vector>

#include <opencv2/opencv.hpp>
#include <utility>

#include "frame.hpp"
#include "utility.hpp"
Expand Down
4 changes: 4 additions & 0 deletions object_analytics_node/src/visualizer/device/stream_ds.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,10 @@
// limitations under the License.

#include "stream_ds.hpp"

#include <string>
#include <momery>

#include "frame_obj.hpp"
#include "object.hpp"

Expand Down
5 changes: 3 additions & 2 deletions object_analytics_node/src/visualizer/device/stream_ds.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,16 +14,17 @@

#pragma once

#include <opencv2/opencv.hpp>

#include <chrono>
#include <fstream>
#include <iostream>
#include <iterator>
#include <random>
#include <string>
#include <memory>
#include <vector>

#include <opencv2/opencv.hpp>

#include "stream_device.hpp"
#include "track_dataset.hpp"

Expand Down
4 changes: 2 additions & 2 deletions object_analytics_node/src/visualizer/device/stream_render.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#pragma once

#include <opencv2/opencv.hpp>

#include <chrono>
#include <fstream>
#include <iostream>
Expand All @@ -23,8 +25,6 @@
#include <string>
#include <vector>

#include <opencv2/opencv.hpp>

class stream_render
{
public:
Expand Down
3 changes: 3 additions & 0 deletions object_analytics_node/src/visualizer/device/stream_vid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,9 @@

#include "stream_vid.hpp"

#include <string>
#include <momery>

stream_vid::stream_vid() {TRACE_INFO();}

stream_vid::~stream_vid() {TRACE_INFO();}
Expand Down
4 changes: 2 additions & 2 deletions object_analytics_node/src/visualizer/device/stream_vid.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#pragma once

#include <opencv2/opencv.hpp>

#include <chrono>
#include <fstream>
#include <iostream>
Expand All @@ -22,8 +24,6 @@
#include <string>
#include <vector>

#include <opencv2/opencv.hpp>

#include "stream_device.hpp"

class stream_vid : public stream_device
Expand Down
Loading