Пример #1
0
    update_config(config)
    print(f'\nUsing \'{config}\' according to the trained_model.\n')

    with torch.no_grad():
        if cuda:
            cudnn.benchmark = True
            cudnn.fastest = True
            torch.set_default_tensor_type('torch.cuda.FloatTensor')
        else:
            torch.set_default_tensor_type('torch.FloatTensor')

        dataset = COCODetection(cfg.dataset.valid_images,
                                cfg.dataset.valid_info,
                                augmentation=BaseTransform())

        net = Yolact()
        # net=onnx.load("yolact.onnx")
        # net= torch.jit.script(net)
        net.load_weights('weights/' + args.trained_model, cuda)
        net.eval()
        if (args.onnx):
            ONNX_util.save_yolact(net, dataset, "yolact.onnx")
        print('\nModel loaded.\n')

        if cuda:
            net = net.cuda()

        evaluate(net, dataset, args.max_num, False, args.cocoapi,
                 args.traditional_nms)
Пример #2
0
    def __init__(self):

        parser = argparse.ArgumentParser(description='YOLACT Predict in ROS')
        parser.add_argument(
            '--visual_top_k',
            default=100,
            type=int,
            help='Further restrict the number of predictions to parse')
        parser.add_argument('--traditional_nms',
                            default=False,
                            action='store_true',
                            help='Whether to use traditional nms.')
        parser.add_argument('--hide_mask',
                            default=False,
                            action='store_true',
                            help='Whether to display masks')
        parser.add_argument('--hide_bbox',
                            default=True,
                            action='store_true',
                            help='Whether to display bboxes')
        parser.add_argument('--hide_score',
                            default=True,
                            action='store_true',
                            help='Whether to display scores')
        parser.add_argument(
            '--show_lincomb',
            default=False,
            action='store_true',
            help='Whether to show the generating process of masks.')
        parser.add_argument(
            '--no_crop',
            default=False,
            action='store_true',
            help='Do not crop output masks with the predicted bounding box.')
        parser.add_argument('--real_time',
                            default=True,
                            action='store_true',
                            help='Show the detection results real-timely.')
        parser.add_argument(
            '--visual_thre',
            default=0.3,
            type=float,
            help='Detections with a score under this threshold will be removed.'
        )
        self.args = parser.parse_args()

        r = rospkg.RosPack()
        self.bridge = CvBridge()

        self.path = r.get_path('yolact_prediction')
        model_name = "/src/weights/best_89.48_res101_custom_610000.pth"
        strs = model_name.split('_')
        config = strs[-3] + "_" + strs[-2] + "_config"
        update_config(config)
        print("Using " + config + " according to the trained_model.")

        with torch.no_grad():

            self.cuda = torch.cuda.is_available()
            if self.cuda:
                cudnn.benchmark = True
                cudnn.fastest = True
                torch.set_default_tensor_type('torch.cuda.FloatTensor')
            else:
                torch.set_default_tensor_type('torch.FloatTensor')

            self.net = Yolact()
            self.net.load_weights(self.path + model_name, self.cuda)
            print('Model loaded.')

            if self.cuda:
                self.net = self.net.cuda()

            self.time_here = 0
            self.frame_times = MovingAverage()

            #### Publisher
            self.rgb_pub = rospy.Publisher("Yolact_predict_img/",
                                           Image,
                                           queue_size=1)

            image_sub = rospy.Subscriber("/camera/color/image_raw",
                                         Image,
                                         self.img_cb,
                                         queue_size=1)

            print("============ Ready ============")
Пример #3
0
        fn_bbox=my_eval(dets,gt_bbox)
        fn_bbox=fn_bbox.astype(np.int)
        if len(fn_bbox)!=0:
            outimg=ori_img.astype(np.uint8)
            for j in range(len(fn_bbox)):
                outimg = cv2.rectangle(img=outimg, pt1=(fn_bbox[j][0], fn_bbox[j][1]), pt2=(fn_bbox[j][2], fn_bbox[j][3]), color=(0,0,255),thickness=1, )
            dets=dets.astype(np.int)
            for j in range(len(dets)):
                outimg = cv2.rectangle(img=outimg, pt1=(dets[j][0], dets[j][1]),
                                       pt2=(dets[j][2], dets[j][3]), color=(255, 0, 0), thickness=1, )
            #cv2.imwrite(os.path.join('error',os.path.basename(img_files[i])),outimg)
            shutil.copy(img_files[i],os.path.join('error',os.path.basename(img_files[i])))
            # json_path=img_files[i].split('.')[0]+'.json'
            #shutil.copy(json_path,os.path.join('error',os.path.basename(json_path)))
    my_eval.eval()
    

if __name__=='__main__':
    from modules.build_yolact import Yolact

    cuda = torch.cuda.is_available()
    device = torch.device("cuda:0" if torch.cuda.is_available() else "cpu")
    if cuda:
        torch.set_default_tensor_type('torch.cuda.FloatTensor')
    else:
        torch.set_default_tensor_type('torch.FloatTensor')
    net = Yolact(freeze_bn=False)
    net.load_state_dict(torch.load('CKPT/labelmodel_coor.pkl'), strict=True)
    net.eval()
    net = net.to(device)
    evaluate(net,['/media/wsl/SB@data/dataset/hoke/wp/dataset/单字符检测/train/','/media/wsl/SB@data/字符识别/数据集/标注/lab/'])
Пример #4
0
class yolact_prediction(object):
    def __init__(self):

        parser = argparse.ArgumentParser(description='YOLACT Predict in ROS')
        parser.add_argument(
            '--visual_top_k',
            default=100,
            type=int,
            help='Further restrict the number of predictions to parse')
        parser.add_argument('--traditional_nms',
                            default=False,
                            action='store_true',
                            help='Whether to use traditional nms.')
        parser.add_argument('--hide_mask',
                            default=False,
                            action='store_true',
                            help='Whether to display masks')
        parser.add_argument('--hide_bbox',
                            default=True,
                            action='store_true',
                            help='Whether to display bboxes')
        parser.add_argument('--hide_score',
                            default=True,
                            action='store_true',
                            help='Whether to display scores')
        parser.add_argument(
            '--show_lincomb',
            default=False,
            action='store_true',
            help='Whether to show the generating process of masks.')
        parser.add_argument(
            '--no_crop',
            default=False,
            action='store_true',
            help='Do not crop output masks with the predicted bounding box.')
        parser.add_argument('--real_time',
                            default=True,
                            action='store_true',
                            help='Show the detection results real-timely.')
        parser.add_argument(
            '--visual_thre',
            default=0.3,
            type=float,
            help='Detections with a score under this threshold will be removed.'
        )
        self.args = parser.parse_args()

        r = rospkg.RosPack()
        self.bridge = CvBridge()

        self.path = r.get_path('yolact_prediction')
        model_name = "/src/weights/best_89.48_res101_custom_610000.pth"
        strs = model_name.split('_')
        config = strs[-3] + "_" + strs[-2] + "_config"
        update_config(config)
        print("Using " + config + " according to the trained_model.")

        with torch.no_grad():

            self.cuda = torch.cuda.is_available()
            if self.cuda:
                cudnn.benchmark = True
                cudnn.fastest = True
                torch.set_default_tensor_type('torch.cuda.FloatTensor')
            else:
                torch.set_default_tensor_type('torch.FloatTensor')

            self.net = Yolact()
            self.net.load_weights(self.path + model_name, self.cuda)
            print('Model loaded.')

            if self.cuda:
                self.net = self.net.cuda()

            self.time_here = 0
            self.frame_times = MovingAverage()

            #### Publisher
            self.rgb_pub = rospy.Publisher("Yolact_predict_img/",
                                           Image,
                                           queue_size=1)

            image_sub = rospy.Subscriber("/camera/color/image_raw",
                                         Image,
                                         self.img_cb,
                                         queue_size=1)

            print("============ Ready ============")

    def img_cb(self, rgb_data):

        self.rgb_data = rgb_data

        if self.rgb_data is not None:
            cv_image = self.bridge.imgmsg_to_cv2(self.rgb_data, "bgr8")

            predict_img = self.predict(cv_image)

            self.rgb_pub.publish(self.bridge.cv2_to_imgmsg(
                predict_img, "bgr8"))

            self.rgb_data = None

    def predict(self, img):

        rgb_origin = img
        img_numpy = img

        img = torch.from_numpy(img.copy()).float()
        img = img.cuda()

        img_h, img_w = img.shape[0], img.shape[1]
        img_trans = FastBaseTransform()(img.unsqueeze(0))

        net_outs = self.net(img_trans)
        nms_outs = NMS(net_outs, 0)

        results = after_nms(nms_outs,
                            img_h,
                            img_w,
                            crop_masks=not self.args.no_crop,
                            visual_thre=self.args.visual_thre)
        torch.cuda.synchronize()

        temp = self.time_here
        self.time_here = time.time()

        self.frame_times.add(self.time_here - temp)
        fps = 1 / self.frame_times.get_avg()

        frame_numpy = draw_img(results,
                               img,
                               self.args,
                               class_color=True,
                               fps=fps)

        return frame_numpy

    def onShutdown(self):
        rospy.loginfo("Shutdown.")
        torch.cuda.empty_cache()
Пример #5
0
args = parser.parse_args()
update_config(args.config, args.batch_size, args.img_size)
print('\n' + '-' * 30 + 'Configs' + '-' * 30)
for k, v in vars(cfg).items():
    print(f'{k}: {v}')

# Don't use the timer during training, there's a race condition with multiple GPUs.
timer.disable_all()

cuda = torch.cuda.is_available()
if cuda:
    torch.set_default_tensor_type('torch.cuda.FloatTensor')
else:
    torch.set_default_tensor_type('torch.FloatTensor')

net = Yolact()
net.train()

if args.resume == 'latest':
    weight = glob.glob('weights/latest*')[0]
    net.load_weights(weight)
    resume_step = int(weight.split('.pth')[0].split('_')[-1])
    print(f'\nResume training with \'{weight}\'.\n')
elif args.resume and 'yolact' in args.resume:
    net.load_weights('weights/' + args.resume)
    resume_step = int(args.resume.split('.pth')[0].split('_')[-1])
    print(f'\nResume training with \'{args.resume}\'.\n')
else:
    net.init_weights(backbone_path='weights/' + cfg.backbone.path)
    print('\nTraining from begining, weights initialized.\n')
Пример #6
0
parser.add_argument('--real_time',
                    default=False,
                    action='store_true',
                    help='Show the detection results real-timely.')
parser.add_argument(
    '--visual_thre',
    default=0.3,
    type=float,
    help='Detections with a score under this threshold will be removed.')

args = parser.parse_args()
args.cfg = re.findall(r'res.+_[a-z]+', args.weight)[0]
cfg = get_config(args, mode='detect')
cuda = torch.cuda.is_available()

net = Yolact(cfg)
net.load_weights(cfg.weight, cuda)
net.eval()
print(f'Model loaded with {cfg.weight}.\n')

if cuda:
    cudnn.benchmark = True
    cudnn.fastest = True
    net = net.cuda()

with torch.no_grad():
    # detect images
    if cfg.image is not None:
        dataset = COCODetection(cfg, mode='detect')
        data_loader = data.DataLoader(dataset,
                                      1,
Пример #7
0
else:
    config = 'yolact_resnet50_config'

update_config(config)
print(f'\nUsing \'{config}\' according to the trained_model.\n')

with torch.no_grad():
    cuda = torch.cuda.is_available()
    if cuda:
        cudnn.benchmark = True
        cudnn.fastest = True
        torch.set_default_tensor_type('torch.cuda.FloatTensor')
    else:
        torch.set_default_tensor_type('torch.FloatTensor')

    net = Yolact()
    net.load_weights(args.trained_model)
    net.eval()
    print('Model loaded.\n')

    if cuda:
        net = net.cuda()

    # detect images
    if args.image is not None:
        images = glob.glob(args.image + '/*.jpg')
        num = len(images)

        for i, one_img in enumerate(images):
            img_name = one_img.split('/')[-1]
            img_origin = torch.from_numpy(cv2.imread(one_img)).cuda().float()
Пример #8
0
class NetWithLoss(nn.Module):
    def __init__(self, net, loss):
        super().__init__()
        self.net = net
        self.loss = loss

    def forward(self, images, box_classes, masks_gt, num_crowds):
        predictions = self.net(images)
        return self.loss(predictions, box_classes, masks_gt, num_crowds)


args = parser.parse_args()
cfg = get_config(args, mode='train')
cuda = torch.cuda.is_available()

net = Yolact(cfg)
net.train()
optimizer = optim.SGD(net.parameters(),
                      lr=cfg.lr,
                      momentum=0.9,
                      weight_decay=5e-4)
criterion = Multi_Loss(cfg)

if args.resume == 'latest':
    weight = glob.glob('weights/latest*')[0]
    net.load_weights(weight, cuda)
    start_step = int(weight.split('.pth')[0].split('_')[-1])
    print(f'\nResume training with \'{weight}\'.\n')
elif args.resume and 'yolact' in args.resume:
    net.load_weights(cfg.weight, cuda)
    start_step = int(cfg.weight.split('.pth')[0].split('_')[-1])