34bool Equal(
float x,
float target,
float eps = 1e-6f);
35bool Equal(
double x,
double target,
double eps = 1e-6);
42 return inter.
Area() / rect1.
Area() > thresh;
48 if (inter.Area() > 0) {
57 if (inter.Area() > 0) {
64bool Contain(
const std::vector<T> &array,
const T &element) {
65 for (
const auto &item : array) {
66 if (item == element) {
75 const T border_size = 0) {
76 if (box.
xmin < border_size || box.
ymin < border_size) {
79 if (box.
xmax + border_size > width || box.
ymax + border_size > height) {
86 const T border_size = 0) {
99 box_out->
width += box_out->
x;
102 if (box_out->
y < 0) {
106 if (box_out->
x >= width) {
110 if (box_out->
y >= height) {
115 : width - box_out->
x;
118 : height - box_out->
y;
119 if (box_out->
width < 0) {
122 if (box_out->
height < 0) {
138bool LoadAnchors(
const std::string &path, std::vector<float> *anchors);
140 std::vector<base::ObjectSubType> *types);
141bool LoadExpand(
const std::string &path, std::vector<float> *expands);
152 if (!mean || !variance) {
160 T sum = std::accumulate(data.begin(), data.end(),
static_cast<T
>(0));
161 *mean = sum / data.size();
163 std::vector<T> diff(data.size());
164 std::transform(data.begin(), data.end(), diff.begin(),
165 [mean](T x) { return x - *mean; });
166 T sum_of_diff_sqrs = std::inner_product(diff.begin(), diff.end(),
167 diff.begin(),
static_cast<T
>(0));
168 *variance = sum_of_diff_sqrs / data.size();
A wrapper around SyncedMemory holders serving as the basic computational unit for images,...
bool Equal(double x, double target, double eps)
bool Contain(const std::vector< T > &array, const T &element)
bool IsCoveredVertical(const base::Rect< T > &rect1, const base::Rect< T > &rect2, float thresh)
bool ResizeCPU(const base::Blob< uint8_t > &src_blob, std::shared_ptr< base::Blob< float > > dst_blob, int stepwidth, int start_axis)
void CalculateMeanAndVariance(const std::vector< T > &data, T *mean, T *variance)
bool LoadTypes(const std::string &path, std::vector< base::ObjectSubType > *types)
bool IsCoveredHorizon(const base::Rect< T > &rect1, const base::Rect< T > &rect2, float thresh)
void FillObjectPolygonFromBBox3D(base::Object *object_ptr)
bool OutOfValidRegion(const base::BBox2D< T > box, const T width, const T height, const T border_size=0)
void RefineBox(const base::Rect< T > &box_in, const T width, const T height, base::Rect< T > *box_out)
bool LoadAnchors(const std::string &path, std::vector< float > *anchors)
bool IsCovered(const base::Rect< T > &rect1, const base::Rect< T > &rect2, float thresh)
bool LoadExpand(const std::string &path, std::vector< float > *expands)