Closed why-freedom closed 1 year ago
Are you using the opencv_demo
or your own code? Just from your code, I can tell that you have to free info
and pose
.
Are you using the
opencv_demo
or your own code? Just from your code, I can tell that you have to freeinfo
andpose
.
- Can you run this with ASAN and valgrind and report back any memory issues?
- Can you provide a complete example (code, build script, input data) to reproduce this?
==3967== 808 bytes in 1 blocks are definitely lost in loss record 261 of 293 ==3967== at 0x4849788: malloc (vg_replace_malloc.c:381) ==3967== by 0x490AEE7: quad_segment_maxima (in /usr/lib/libapriltag.so.3) ==3967== by 0x490BD4B: fit_quad (in /usr/lib/libapriltag.so.3) ==3967== by 0x490C48B: do_quad_task (in /usr/lib/libapriltag.so.3) ==3967== by 0x49265F7: workerpool_run_single (in /usr/lib/libapriltag.so.3) ==3967== by 0x491015F: fit_quads (in /usr/lib/libapriltag.so.3) ==3967== by 0x4910383: apriltag_quad_thresh (in /usr/lib/libapriltag.so.3) ==3967== by 0x49073C7: apriltag_detector_detect (in /usr/lib/libapriltag.so.3) ==3967== by 0x40714B: main (in /root/install/bin/opencv_demo)
/* Copyright (C) 2013-2016, The Regents of The University of Michigan.
All rights reserved.
This software was developed in the APRIL Robotics Lab under the
direction of Edwin Olson, ebolson@umich.edu. This software may be
available under alternative licensing terms; contact the address above.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR
ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
The views and conclusions contained in the software and documentation are those
of the authors and should not be interpreted as representing official policies,
either expressed or implied, of the Regents of The University of Michigan.
*/
#include <iostream>
#include "opencv2/opencv.hpp"
#include "apriltag_pose.h"
#include <eigen3/Eigen/Dense>
extern "C" {
#include "apriltag.h"
#include "tag36h11.h"
#include "tag25h9.h"
#include "tag16h5.h"
#include "tagCircle21h7.h"
#include "tagCircle49h12.h"
#include "tagCustom48h12.h"
#include "tagStandard41h12.h"
#include "tagStandard52h13.h"
#include "common/getopt.h"
}
using namespace std;
using namespace cv;
int main(int argc, char *argv[])
{
getopt_t *getopt = getopt_create();
getopt_add_bool(getopt, 'h', "help", 0, "Show this help");
getopt_add_bool(getopt, 'd', "debug", 0, "Enable debugging output (slow)");
getopt_add_bool(getopt, 'q', "quiet", 0, "Reduce output");
getopt_add_string(getopt, 'f', "family", "tag36h11", "Tag family to use");
getopt_add_int(getopt, 't', "threads", "1", "Use this many CPU threads");
getopt_add_double(getopt, 'x', "decimate", "2.0", "Decimate input image by this factor");
getopt_add_double(getopt, 'b', "blur", "0.0", "Apply low-pass blur to input");
getopt_add_bool(getopt, '0', "refine-edges", 1, "Spend more time trying to align edges of tags");
if (!getopt_parse(getopt, argc, argv, 1) || getopt_get_bool(getopt, "help")) {
printf("Usage: %s [options]\n", argv[0]);
getopt_do_usage(getopt);
exit(0);
}
cout << "Enabling video capture" << endl;
TickMeter meter;
meter.start();
// Initialize camera
VideoCapture cap(0);
if (!cap.isOpened()) {
cerr << "Couldn't open video capture device" << endl;
return -1;
}
// Initialize tag detector with options
apriltag_family_t *tf = NULL;
const char *famname = getopt_get_string(getopt, "family");
if (!strcmp(famname, "tag36h11")) {
tf = tag36h11_create();
} else if (!strcmp(famname, "tag25h9")) {
tf = tag25h9_create();
} else if (!strcmp(famname, "tag16h5")) {
tf = tag16h5_create();
} else if (!strcmp(famname, "tagCircle21h7")) {
tf = tagCircle21h7_create();
} else if (!strcmp(famname, "tagCircle49h12")) {
tf = tagCircle49h12_create();
} else if (!strcmp(famname, "tagStandard41h12")) {
tf = tagStandard41h12_create();
} else if (!strcmp(famname, "tagStandard52h13")) {
tf = tagStandard52h13_create();
} else if (!strcmp(famname, "tagCustom48h12")) {
tf = tagCustom48h12_create();
} else {
printf("Unrecognized tag family name. Use e.g. \"tag36h11\".\n");
exit(-1);
}
apriltag_detector_t *td = apriltag_detector_create();
apriltag_detector_add_family(td, tf);
td->quad_decimate = getopt_get_double(getopt, "decimate");
td->quad_sigma = getopt_get_double(getopt, "blur");
td->nthreads = getopt_get_int(getopt, "threads");
td->debug = getopt_get_bool(getopt, "debug");
td->refine_edges = getopt_get_bool(getopt, "refine-edges");
float frame_counter = 0.0f;
meter.stop();
cout << "Detector " << famname << " initialized in " << std::fixed << std::setprecision(3) << meter.getTimeSec()
<< " seconds" << endl;
cout << " " << cap.get(CAP_PROP_FRAME_WIDTH) << "x" << cap.get(CAP_PROP_FRAME_HEIGHT) << " @"
<< cap.get(CAP_PROP_FPS) << "FPS" << endl;
meter.reset();
Mat frame, gray;
while (true) {
cap >> frame;
cvtColor(frame, gray, COLOR_BGR2GRAY);
// Make an image_u8_t header for the Mat data
image_u8_t im = {.width = gray.cols, .height = gray.rows, .stride = gray.cols, .buf = gray.data};
zarray_t *detections = apriltag_detector_detect(td, &im);
// Draw detection outlines
for (int i = 0; i < zarray_size(detections); i++) {
apriltag_detection_t *det;
zarray_get(detections, i, &det);
std::cout << "det id is " << det->id << std::endl;
/**
apriltag_detection_info_t *info = (apriltag_detection_info_t *)calloc(1, sizeof(apriltag_detection_info_t));
apriltag_pose_t *pose = (apriltag_pose_t *)calloc(1, sizeof(apriltag_pose_t));
info->det = det;
info->tagsize = 0.1;
info->fx = 387.852;
info->fy = 387.586;
info->cx = 319.157;
info->cy = 235.818;
info->det = det;
double err = estimate_tag_pose(info, pose);
// Pose To SE(3),but this is not necessary.
Eigen::Matrix4d aprilTagRtMat;
aprilTagRtMat(0, 0) = pose->R->data[0];
aprilTagRtMat(0, 1) = pose->R->data[1];
aprilTagRtMat(0, 2) = pose->R->data[2];
aprilTagRtMat(0, 3) = pose->t->data[0];
aprilTagRtMat(1, 0) = pose->R->data[3];
aprilTagRtMat(1, 1) = pose->R->data[4];
aprilTagRtMat(1, 2) = pose->R->data[5];
aprilTagRtMat(1, 3) = pose->t->data[1];
aprilTagRtMat(2, 0) = pose->R->data[6];
aprilTagRtMat(2, 1) = pose->R->data[7];
aprilTagRtMat(2, 2) = pose->R->data[8];
aprilTagRtMat(2, 3) = pose->t->data[2];
aprilTagRtMat(3, 0) = 0;
aprilTagRtMat(3, 1) = 0;
aprilTagRtMat(3, 2) = 0;
aprilTagRtMat(3, 3) = 1;
cout << aprilTagRtMat << endl;
**/
/**
int sizeScale = 1; // axis scale.
for (int k = 2; k > -1; k--) {
line(frame, Point(det->p[0][0], det->p[0][1]), Point(det->p[1][0], det->p[1][1]), Scalar(0, 0xff, 0), 1);
line(frame, Point(det->p[0][0], det->p[0][1]), Point(det->p[3][0], det->p[3][1]), Scalar(0, 0, 0xff), 1);
line(frame, Point(det->p[1][0], det->p[1][1]), Point(det->p[2][0], det->p[2][1]), Scalar(0xff, 0, 0), 1);
line(frame, Point(det->p[2][0], det->p[2][1]), Point(det->p[3][0], det->p[3][1]), Scalar(0xff, 0, 0), 1);
// calculate axis's end point in camera coordinate.
double x_end = aprilTagRtMat(0, k) * info->tagsize * sizeScale + aprilTagRtMat(0, 3);
double y_end = aprilTagRtMat(1, k) * info->tagsize * sizeScale + aprilTagRtMat(1, 3);
double z_end = aprilTagRtMat(2, k) * info->tagsize * sizeScale + aprilTagRtMat(2, 3);
// normalize
x_end = x_end / z_end;
y_end = y_end / z_end;
// transform point to pixel coordinate,this needs camera intrinsics
x_end = x_end * info->fx + info->cx;
y_end = y_end * info->fy + info->cy;
if (k == 0) {
// X axis
arrowedLine(frame, Point(det->c[0], det->c[1]), Point(int(x_end), int(y_end)), Scalar(0, 0, 255), 2);
putText(frame, "x", Point(int(x_end), int(y_end)), 2, 1.0, Scalar(0, 0, 255));
}
if (k == 1) {
// Y axis
arrowedLine(frame, Point(det->c[0], det->c[1]), Point(int(x_end), int(y_end)), Scalar(0, 255, 0), 2);
putText(frame, "y", Point(int(x_end), int(y_end)), 2, 1.0, Scalar(0, 255, 0));
}
if (k == 2) {
// Z axis
arrowedLine(frame, Point(det->c[0], det->c[1]), Point(int(x_end), int(y_end)), Scalar(255, 0, 0), 2);
putText(frame, "z", Point(int(x_end), int(y_end)), 2, 1.0, Scalar(255, 0, 0));
}
}
stringstream ss;
ss << det->id;
String text = ss.str();
int fontface = FONT_HERSHEY_SCRIPT_SIMPLEX;
double fontscale = 1.0;
int baseline;
Size textsize = getTextSize(text, fontface, fontscale, 2, &baseline);
putText(frame, text, Point(det->c[0] - textsize.width / 2, det->c[1] + textsize.height / 2), fontface,
fontscale, Scalar(0xff, 0x99, 0), 2);
// 显示tag中心坐标
stringstream ss_centor;
ss_centor << det->c[0], det->c[1];
String text_centor = ss_centor.str();
putText(frame, text_centor, Point(det->c[0], det->c[1]), fontface, fontscale, Scalar(0xff, 0x99, 0), 1);
**/
// free(info);
// free(pose);
}
apriltag_detections_destroy(detections);
// imshow("Tag Detections", frame);
// waitKey(1);
// if (waitKey(30) >= 0)
// break;
} // end while
apriltag_detector_destroy(td);
if (!strcmp(famname, "tag36h11")) {
tag36h11_destroy(tf);
} else if (!strcmp(famname, "tag25h9")) {
tag25h9_destroy(tf);
} else if (!strcmp(famname, "tag16h5")) {
tag16h5_destroy(tf);
} else if (!strcmp(famname, "tagCircle21h7")) {
tagCircle21h7_destroy(tf);
} else if (!strcmp(famname, "tagCircle49h12")) {
tagCircle49h12_destroy(tf);
} else if (!strcmp(famname, "tagStandard41h12")) {
tagStandard41h12_destroy(tf);
} else if (!strcmp(famname, "tagStandard52h13")) {
tagStandard52h13_destroy(tf);
} else if (!strcmp(famname, "tagCustom48h12")) {
tagCustom48h12_destroy(tf);
}
getopt_destroy(getopt);
return 0;
}
time,pid,cpu,memory 02:41:10,11901,109,47.8555, 02:42:11,11901,111,48.3711, ... 15:10:45,11901,60.6,150.344, 15:11:45,11901,60.7,151.117,
I slove the problem, thank you!
Thanks for the update - can you please confirm what the problem was?
Describe the bug when i use estimate_tag_pose, the memory grow up slowly, I use opencv_demo.
my code
result
time, pid, cpu, memory 21:56:20,6330,104,48.1016, 21:57:20,6330,103,48.3594, 21:58:21,6330,103,48.875, 21:59:21,6330,103,49.1328, 22:00:21,6330,104,49.6484, 22:01:21,6330,104,49.9062, 22:02:21,6330,103,50.1641, 22:03:21,6330,103,50.4219, 22:04:21,6330,103,50.9375, 22:05:21,6330,104,51.1953, 22:06:21,6330,104,51.7109, 22:07:21,6330,104,51.9688,
Operating Sytem Ubuntu18.04 Installation Method source README, cmake .. make Code version use master