Skip to content
Snippets Groups Projects
Commit b723fd0e authored by User expired's avatar User expired :spy_tone1:
Browse files

minibot_vision: added service to update hyperparams

parent f39f06f2
No related branches found
No related tags found
No related merge requests found
__pycache__
......@@ -18,7 +18,7 @@ Changes made by the sliders are directly updated at the param server, however,
The following hotkeys are supported:
- p: Toggle patch visualization [default: True]
- d: Load default parameters (specified within `config/sign_detector_default.yaml`). This will neither override `config/sign_detector.yaml` nor the ros-params.
- s: Save the current parameters persistent to `config/sign_detector.yaml`. This will also upload to ros-param.
- s: Save the current parameters persistent to `config/sign_detector.yaml`. This will also upload to ros-param and update any running SignDetector.
The functionality of this tool is also available via ros.
The two hyper-params are on the param server as `sign_detector/canny_param1` and `sign_detector/canny_param2`
......@@ -54,6 +54,8 @@ Check the Topics section for more details.
- **sign_detector/enable**: Enables the classification pipeline for the sign detection (default: enabled).
If disabled visualization is still possible, but the label will be set to -1.
- **sign_detector/update_rosparams**: Fetches new hyperparams needed by `SegmentSign.py` from the param-server.
- **capture_imgs/enable**: Enables the capture images stream (default: disabled).
- **capture_imgs/toggle_hough_detection**: Enables autofocus for each patch on signs in the camera image (default: enabled).
......
sign_detector: {canny_param1: 47, canny_param2: 46, img_height: 480, img_width: 640,
sign_detector: {canny_param1: 99, canny_param2: 50, img_height: 480, img_width: 640,
max_depth: 1.0, max_radius: 128, min_depth: 0.2, min_radius: 15, visualize: false,
zoom_threshold: 1.15}
......@@ -42,6 +42,20 @@ def empty(d):
pass
def fetch_rosparams():
global canny, accum_thresh, ZOOM_THREASHOLD, MIN_DEPTH, MAX_DEPTH, MIN_RADIUS, MAX_RADIUS
canny = rospy.get_param("sign_detector/canny_param1")
accum_thresh = rospy.get_param("sign_detector/canny_param2")
ZOOM_THREASHOLD = rospy.get_param("sign_detector/zoom_threshold")
MIN_DEPTH = rospy.get_param("sign_detector/min_depth")
MAX_DEPTH = rospy.get_param("sign_detector/max_depth")
MIN_RADIUS = rospy.get_param("sign_detector/min_radius")
MAX_RADIUS = rospy.get_param("sign_detector/max_radius")
def image_color_callback(data):
global img_rgb_stream, cv_bridge
......@@ -200,6 +214,16 @@ def filter_duplicate_keypoints(keypoints):
return required_keypoints
def call_fetch_rosparams():
service = "sign_detector/update_rosparams"
try:
call_place = rospy.ServiceProxy(service, std_srvs.srv.Trigger())
response = call_place.call()
except rospy.ServiceException as e:
print("Service call failed: %s" % e)
def save_params():
"""
During VISUALIZE mode.
......@@ -227,7 +251,9 @@ def save_params():
# save to rosparam
rospy.set_param("sign_detector/canny_param1", canny)
rospy.get_param("sign_detector/canny_param2", accum_thresh)
rospy.set_param("sign_detector/canny_param2", accum_thresh)
call_fetch_rosparams()
rospy.loginfo("({}) Saved new params persistent".format(rospy.get_name()))
......
......@@ -190,6 +190,13 @@ def enable_sign_detector_callback(req):
return True, ""
def update_rosparams_callback(req):
SegmentSign.fetch_rosparams()
rospy.loginfo("({}) new hyperparams from param server fetched".format(rospy.get_name()))
return True, ""
if __name__ == "__main__":
rospy.init_node("sign_detector")
......@@ -200,8 +207,8 @@ if __name__ == "__main__":
rospy.Subscriber(img_depth_topic, Image, image_depth_callback, queue_size=1)
rospy.Service('sign_detector/set_model', set_url, set_model_callback)
rospy.Service('sign_detector/set_visualize', std_srvs.srv.SetBool, set_visualize_callback)
# TODO enable sign detection
rospy.Service('sign_detector/enable', std_srvs.srv.SetBool, enable_sign_detector_callback)
rospy.Service('sign_detector/update_rosparams', std_srvs.srv.Trigger, update_rosparams_callback)
pub_keypoint = rospy.Publisher('sign_detector/keypoints', Detection2D, queue_size=10)
pub_result_img = rospy.Publisher("sign_detector/result_image/compressed", CompressedImage, queue_size=10)
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment