Skip to content

Commit

Permalink
chore: fix mypi.ini and format
Browse files Browse the repository at this point in the history
  • Loading branch information
HiroIshida committed Jan 31, 2025
1 parent 15a25c0 commit f4b49be
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 4 deletions.
2 changes: 2 additions & 0 deletions mypy.ini
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,8 @@ ignore_missing_imports = True
ignore_missing_imports = True
[mypy-std_msgs.*]
ignore_missing_imports = True
[mypy-std_srvs.*]
ignore_missing_imports = True
[mypy-jsk_recognition_msgs.*]
ignore_missing_imports = True
[mypy-cv2]
Expand Down
15 changes: 11 additions & 4 deletions node_script/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,17 +2,23 @@
from typing import Optional

import rospy
import torch
from jsk_recognition_msgs.msg import LabelArray, VectorArray
from node_config import NodeConfig
from rospy import Publisher, Subscriber
from sensor_msgs.msg import Image
import torch
from std_srvs.srv import Empty, EmptyRequest, EmptyResponse
from wrapper import DeticWrapper

from detic_ros.msg import SegmentationInfo
from detic_ros.srv import DeticSeg, DeticSegRequest, DeticSegResponse
from detic_ros.srv import CustomVocabulary, CustomVocabularyRequest, CustomVocabularyResponse
from std_srvs.srv import Empty, EmptyRequest, EmptyResponse
from detic_ros.srv import (
CustomVocabulary,
CustomVocabularyRequest,
CustomVocabularyResponse,
DeticSeg,
DeticSegRequest,
DeticSegResponse,
)


class DeticRosNode:
Expand Down Expand Up @@ -129,6 +135,7 @@ def default_vocab_srv(self, req: EmptyRequest) -> EmptyResponse:
res = EmptyResponse()
return res


if __name__ == '__main__':
rospy.init_node('detic_node', anonymous=True)
node = DeticRosNode()
Expand Down

0 comments on commit f4b49be

Please sign in to comment.