Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Create thresholding node to red using HSV #165

Open
wants to merge 2 commits into
base: develop
Choose a base branch
from

Conversation

TheronAma
Copy link
Contributor

Wrote starter task node that thresholds for red in HSV colorspace.

Currently unsure about how to properly set up launch files / service.

@TheronAma TheronAma requested a review from theochemel November 1, 2023 23:22
@TheronAma TheronAma self-assigned this Nov 1, 2023
Copy link
Contributor

@theochemel theochemel left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Looks great! Nice job type hinting and implementing the service. I would suggest loading the thresholds from ros params. SetThreshold.srv should go in tauv_msgs/srv, and also make sure that you add a line for it to CMakeLists.txt so it gets compiled.

self._cv_bridge : CvBridge = CvBridge()
self._publisher : rospy.Publisher = rospy.Publisher('starter_task/thresholded_img', Image, queue_size=5)

rospy.Subscriber('/kf/vehicle/oakd_bottom/stereo/right/image_color', Image, self.filter)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Shouldn't need to hardcode /kf here. Using vehicle/... (no leading /) will set the /kf automatically using ROS namespacing if the launch file is set up properly.

self._publisher.publish(result)

def set_threshold(self, req):
self._lower_threshold = np.array([req.hue, req.saturation, req.value])
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Very nice touch with the service

print("running!")
rospy.init_node('starter_threshold')

self._lower_threshold : np.ndarray = LOWER_THRESHOLD
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good style with naming, underscores, and type hints

from cv_bridge import CvBridge
from tauv_common.srv import SetThresholdRequest, SetThresholdResponse

LOWER_THRESHOLD = np.array([0, 60, 60]) # TODO: figure out typing for threshold
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Try moving these to be ros params

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants