6 Commits

Author SHA1 Message Date
AiYangSky
f2a62e4126 fix video file read 2023-12-26 17:02:42 +08:00
AiYangSky
5f656487a1 Hardware decoding G1 2023-12-26 16:35:02 +08:00
jario
182c2d9f0b add RTSP, VIDEO to sv::CameraType 2023-12-25 15:00:35 +08:00
jario-jin
c20cd83f1c improve create_marker 2023-12-20 13:51:53 +08:00
jario
20814d15d2 fix 4k draw slow prob 2023-12-16 20:24:54 +08:00
jario-jin
c74319529c add aruco member funs 2023-12-15 22:13:32 +08:00
6 changed files with 174 additions and 23 deletions

View File

@@ -80,6 +80,12 @@ ArucoDetector::ArucoDetector()
}
void ArucoDetector::getIdsWithLengths(std::vector<int>& ids_, std::vector<double>& lengths_)
{
ids_ = this->_ids_need;
lengths_ = this->_lengths_need;
}
void ArucoDetector::_load()
{
JsonValue all_value;

View File

@@ -46,6 +46,7 @@ class ArucoDetector : public CameraAlgorithm
public:
ArucoDetector();
void detect(cv::Mat img_, TargetsInFrame& tgts_);
void getIdsWithLengths(std::vector<int>& ids_, std::vector<double>& lengths_);
private:
void _load();
bool _params_loaded;

View File

@@ -128,6 +128,7 @@ public:
bool getBox(Box& b);
bool getAruco(int& id, std::vector<cv::Point2f> &corners);
bool getAruco(int& id, std::vector<cv::Point2f> &corners, cv::Vec3d &rvecs, cv::Vec3d &tvecs);
bool getEllipse(double& xc_, double& yc_, double& a_, double& b_, double& rad_);
std::string getJsonStr();
@@ -326,7 +327,7 @@ protected:
};
enum class CameraType {NONE, WEBCAM, V4L2CAM, G1, Q10, MIPI, GX40};
enum class CameraType {NONE, WEBCAM, V4L2CAM, MIPI, RTSP, VIDEO, G1, Q10, GX40};
class CameraBase {
public:
@@ -350,6 +351,8 @@ public:
void setWH(int width, int height);
void setFps(int fps);
void setIp(std::string ip);
void setRtspUrl(std::string rtsp_url);
void setVideoPath(std::string video_path);
void setPort(int port);
void setBrightness(double brightness);
void setContrast(double contrast);
@@ -372,6 +375,8 @@ protected:
int _height;
int _fps;
std::string _ip;
std::string _rtsp_url;
std::string _video_path;
int _port;
double _brightness;
double _contrast;
@@ -393,6 +398,16 @@ void drawTargetsInFrame(
bool with_aruco=false,
bool with_yaw=false
);
cv::Mat drawTargetsInFrame(
const cv::Mat img_,
const TargetsInFrame& tgts_,
const double scale,
bool with_all=true,
bool with_category=false,
bool with_tid=false,
bool with_seg=false,
bool with_box=false
);
std::string get_home();
bool is_file_exist(std::string& fn);
void list_dir(std::string dir, std::vector<std::string>& files, std::string suffixs="", bool r=false);

View File

@@ -97,7 +97,8 @@ int main(int argc, char *argv[]) {
if (landingPadUnit > 0) {
Mat markerImgBIG = Mat::ones(landingPadUnit * 62, landingPadUnit * 62, CV_8UC1) * 255;
markerId = 0;
// markerId = 0;
markerId --;
markerSize = landingPadUnit * 4;
borderSize = landingPadUnit;
int newSize = markerSize + borderSize * 2;
@@ -222,7 +223,7 @@ int main(int argc, char *argv[]) {
markerImg = create_marker_with_borders(dictionary, markerId, markerSize, borderBits, borderSize);
markerImg.copyTo(markerImgBIG(Rect(landingPadUnit * 10, landingPadUnit * 28, newSize, newSize)));
markerId = 90;
// markerId = 90;
markerSize = landingPadUnit * 4 * 4;
borderSize = landingPadUnit * 4;
newSize = markerSize + borderSize * 2;

View File

@@ -454,6 +454,71 @@ void drawTargetsInFrame(
}
}
cv::Mat drawTargetsInFrame(
const cv::Mat img_,
const TargetsInFrame& tgts_,
const double scale,
bool with_all,
bool with_category,
bool with_tid,
bool with_seg,
bool with_box
)
{
cv::Mat img_show;
cv::resize(img_, img_show, cv::Size(0, 0), scale, scale);
if (tgts_.rois.size() > 0)
{
cv::Mat image_ret;
cv::addWeighted(img_show, 0.5, cv::Mat::zeros(cv::Size(img_show.cols, img_show.rows), CV_8UC3), 0, 0, image_ret);
cv::Rect roi = cv::Rect((int)(tgts_.rois[0].x1*scale), (int)(tgts_.rois[0].y1*scale), (int)((tgts_.rois[0].x2 - tgts_.rois[0].x1)*scale), (int)((tgts_.rois[0].y2 - tgts_.rois[0].y1)*scale));
img_show(roi).copyTo(image_ret(roi));
image_ret.copyTo(img_show);
}
for (Target tgt : tgts_.targets)
{
cv::circle(img_show, cv::Point(int(tgt.cx * tgts_.width * scale), int(tgt.cy * tgts_.height * scale)), 4, cv::Scalar(0,255,0), 2);
if ((with_all || with_box) && tgt.has_box)
{
Box b;
tgt.getBox(b);
cv::rectangle(img_show, cv::Rect((int)(b.x1 * scale), (int)(b.y1 * scale), (int)((b.x2-b.x1+1)*scale), (int)((b.y2-b.y1+1)*scale)), cv::Scalar(0,0,255), 1, 1, 0);
if ((with_all || with_category) && tgt.has_category)
{
cv::putText(img_show, tgt.category, cv::Point((int)(b.x1*scale), (int)(b.y1*scale)-4), cv::FONT_HERSHEY_DUPLEX, 0.4, cv::Scalar(255,0,0));
}
if ((with_all || with_tid) && tgt.has_tid)
{
char tmp[32];
sprintf(tmp, "TID: %d", tgt.tracked_id);
cv::putText(img_show, tmp, cv::Point((int)(b.x1*scale), (int)(b.y1*scale)-14), cv::FONT_HERSHEY_DUPLEX, 0.4, cv::Scalar(0,0,255));
}
}
if ((with_all || with_seg) && tgt.has_seg)
{
cv::Mat mask = tgt.getMask() * 255;
cv::threshold(mask, mask, 127, 255, cv::THRESH_BINARY);
mask.convertTo(mask, CV_8UC1);
cv::resize(mask, mask, cv::Size(img_show.cols, img_show.rows));
std::vector<std::vector<cv::Point> > contours;
std::vector<cv::Vec4i> hierarchy;
cv::findContours(mask, contours, hierarchy, cv::RETR_EXTERNAL, cv::CHAIN_APPROX_SIMPLE);
cv::Mat mask_disp = img_show.clone();
cv::fillPoly(mask_disp, contours, cv::Scalar(255,255,255), cv::LINE_AA);
cv::polylines(img_show, contours, true, cv::Scalar(255,255,255), 2, cv::LINE_AA);
double alpha = 0.6;
cv::addWeighted(img_show, alpha, mask_disp, 1.0-alpha, 0, img_show);
}
}
return img_show;
}
std::string Target::getJsonStr()
{
std::string json_str = "{";
@@ -588,6 +653,15 @@ bool Target::getAruco(int& id, std::vector<cv::Point2f> &corners)
return this->has_aruco;
}
bool Target::getAruco(int& id, std::vector<cv::Point2f> &corners, cv::Vec3d &rvecs, cv::Vec3d &tvecs)
{
id = this->_a_id;
corners = this->_a_corners;
rvecs = this->_a_rvecs;
tvecs = this->_a_tvecs;
return this->has_aruco;
}
bool Target::getBox(Box& b)
{
b = this->_b_box;
@@ -1006,6 +1080,14 @@ void CameraBase::setIp(std::string ip)
{
this->_ip = ip;
}
void CameraBase::setRtspUrl(std::string rtsp_url)
{
this->_rtsp_url = rtsp_url;
}
void CameraBase::setVideoPath(std::string video_path)
{
this->_video_path = video_path;
}
void CameraBase::setPort(int port)
{
this->_port = port;
@@ -1090,9 +1172,12 @@ void CameraBase::open(CameraType type, int id)
if (this->_cap.isOpened())
{
std::cout << "Camera opened!" << std::endl;
this->_is_running = true;
this->_tt = std::thread(&CameraBase::_run, this);
this->_tt.detach();
if(type != CameraType::VIDEO)
{
this->_is_running = true;
this->_tt = std::thread(&CameraBase::_run, this);
this->_tt.detach();
}
}
else if (type != CameraType::NONE)
{
@@ -1112,19 +1197,26 @@ bool CameraBase::read(cv::Mat& image)
{
if (this->_type != CameraType::NONE)
{
int n_try = 0;
while (n_try < 5000)
if(this->_type == CameraType::VIDEO)
{
if (this->_is_updated)
{
this->_is_updated = false;
this->_frame.copyTo(image);
break;
}
std::this_thread::sleep_for(std::chrono::milliseconds(20));
n_try ++;
this->_cap >> image;
}
}
else
{
int n_try = 0;
while (n_try < 5000)
{
if (this->_is_updated)
{
this->_is_updated = false;
this->_frame.copyTo(image);
break;
}
std::this_thread::sleep_for(std::chrono::milliseconds(20));
n_try ++;
}
}
}
if (image.cols == 0 || image.rows == 0)
{
throw std::runtime_error("SpireCV (101) Camera cannot OPEN, check CAMERA_ID!");

View File

@@ -19,6 +19,7 @@ void Camera::openImpl()
if (this->_type == CameraType::V4L2CAM)
{
this->_cap.open(this->_camera_id, cv::CAP_V4L2);
// this->_cap.set(cv::CAP_PROP_FOURCC, cv::VideoWriter::fourcc('Y', 'U', 'Y', 'V'));
}
if (this->_type == CameraType::WEBCAM)
{
@@ -71,14 +72,19 @@ void Camera::openImpl()
this->_fps = 30;
}
#ifdef PLATFORM_X86_CUDA
sprintf(pipe, "rtsp://%s:%d/H264?W=%d&H=%d&FPS=%d&BR=4000000", this->_ip.c_str(), this->_port, this->_width, this->_height, this->_fps);
this->_cap.open(pipe);
#endif
#ifdef PLATFORM_JETSON
sprintf(pipe, "rtspsrc location=rtsp://%s:%d/H264?W=%d&H=%d&FPS=%d&BR=4000000 latency=100 ! application/x-rtp,media=video ! rtph264depay ! parsebin ! nvv4l2decoder enable-max-performancegst=1 ! nvvidconv ! video/x-raw,format=(string)BGRx ! videoconvert ! appsink sync=false", this->_ip.c_str(), this->_port, this->_width, this->_height, this->_fps);
this->_cap.open(pipe, cv::CAP_GSTREAMER);
sprintf(pipe, "rtspsrc location=rtsp://%s:%d/H264?W=%d&H=%d&FPS=%d&BR=4000000 latency=100 ! \
application/x-rtp,media=video ! rtph264depay ! parsebin ! nvv4l2decoder enable-max-performancegst=1 ! \
nvvidconv ! video/x-raw,format=(string)BGRx ! videoconvert ! appsink sync=false",
this->_ip.c_str(), this->_port, this->_width, this->_height, this->_fps);
#else
sprintf(pipe, "rtspsrc location=rtsp://%s:%d/H264?W=%d&H=%d&FPS=%d&BR=4000000 latency=100 ! \
application/x-rtp,media=video ! rtph264depay ! parsebin ! avdec_h264 ! \
videoconvert ! appsink sync=false",
this->_ip.c_str(), this->_port, this->_width, this->_height, this->_fps);
#endif
printf("%s\r\n",pipe);
this->_cap.open(pipe, cv::CAP_GSTREAMER);
}
else if (this->_type == CameraType::GX40)
{
@@ -127,6 +133,36 @@ void Camera::openImpl()
sprintf(pipe, "nvarguscamerasrc sensor-id=%d ! video/x-raw(memory:NVMM), width=(int)%d, height=(int)%d, format=(string)NV12, framerate=(fraction)%d/1 ! nvvidconv flip-method=0 ! video/x-raw, width=(int)%d, height=(int)%d, format=(string)BGRx ! videoconvert ! video/x-raw, format=(string)BGR ! appsink", this->_camera_id, this->_width, this->_height, this->_fps, this->_width, this->_height);
this->_cap.open(pipe, cv::CAP_GSTREAMER);
}
else if (this->_type == CameraType::RTSP)
{
char pipe[512];
if (this->_width <= 0 || this->_height <= 0)
{
this->_width = 1280;
this->_height = 720;
}
if (this->_port <= 0)
{
this->_port = 554;
}
if (this->_fps <= 0)
{
this->_fps = 30;
}
#ifdef PLATFORM_X86_CUDA
sprintf(pipe, "%s?W=%d&H=%d&FPS=%d", this->_rtsp_url.c_str(), this->_width, this->_height, this->_fps);
this->_cap.open(pipe);
#endif
#ifdef PLATFORM_JETSON
sprintf(pipe, "rtspsrc location=%s?W=%d&H=%d&FPS=%d latency=100 ! application/x-rtp,media=video ! rtph264depay ! parsebin ! nvv4l2decoder enable-max-performancegst=1 ! nvvidconv ! video/x-raw,format=(string)BGRx ! videoconvert ! appsink sync=false", this->_rtsp_url.c_str(), this->_width, this->_height, this->_fps);
this->_cap.open(pipe, cv::CAP_GSTREAMER);
#endif
}
else if (this->_type == CameraType::VIDEO)
{
this->_cap.open(this->_video_path);
}
}
}