From c064c779e1158eb73240c5ea8e59666d7ef601e5 Mon Sep 17 00:00:00 2001 From: Kayman Date: Fri, 23 Feb 2018 21:03:49 +0900 Subject: [PATCH] added missing parameter --- ball_detector/launch/ball_detector_params_default.yaml | 4 ++-- ball_detector/msg/BallDetectorParams.msg | 1 + ball_detector/src/ball_detector.cpp | 3 +++ 3 files changed, 6 insertions(+), 2 deletions(-) diff --git a/ball_detector/launch/ball_detector_params_default.yaml b/ball_detector/launch/ball_detector_params_default.yaml index a97969a..be36dee 100644 --- a/ball_detector/launch/ball_detector_params_default.yaml +++ b/ball_detector/launch/ball_detector_params_default.yaml @@ -12,7 +12,7 @@ filter_s_min: 220 filter_s_max: 255 filter_v_min: 30 filter_v_max: 255 -use_second_filter: true +use_second_filter: false filter2_h_min: 30 filter2_h_max: 355 filter2_s_min: 0 @@ -20,4 +20,4 @@ filter2_s_max: 40 filter2_v_min: 200 filter2_v_max: 255 ellipse_size: 1 -filter_debug: false \ No newline at end of file +filter_debug: false diff --git a/ball_detector/msg/BallDetectorParams.msg b/ball_detector/msg/BallDetectorParams.msg index e72a4ad..cd1c210 100644 --- a/ball_detector/msg/BallDetectorParams.msg +++ b/ball_detector/msg/BallDetectorParams.msg @@ -14,3 +14,4 @@ uint32 filter_s_min # 0 - 255 uint32 filter_s_max uint32 filter_v_min # 0 - 255 uint32 filter_v_max +uint32 ellipse_size # 1 - 9 diff --git a/ball_detector/src/ball_detector.cpp b/ball_detector/src/ball_detector.cpp index 945654b..a38c2b7 100644 --- a/ball_detector/src/ball_detector.cpp +++ b/ball_detector/src/ball_detector.cpp @@ -302,6 +302,7 @@ bool BallDetector::setParamCallback(ball_detector::SetParameters::Request &req, params_config_.filter_threshold.s_max = req.params.filter_s_max; params_config_.filter_threshold.v_min = req.params.filter_v_min; params_config_.filter_threshold.v_max = req.params.filter_v_max; + params_config_.ellipse_size = req.params.ellipse_size; saveConfig(); @@ -326,6 +327,7 @@ bool BallDetector:: getParamCallback(ball_detector::GetParameters::Request &req, res.returns.filter_s_max = params_config_.filter_threshold.s_max; res.returns.filter_v_min = params_config_.filter_threshold.v_min; res.returns.filter_v_max = params_config_.filter_threshold.v_max; + res.returns.ellipse_size = params_config_.ellipse_size; return true; } @@ -400,6 +402,7 @@ void BallDetector::publishParam() params.filter_s_max = params_config_.filter_threshold.s_max; params.filter_v_min = params_config_.filter_threshold.v_min; params.filter_v_max = params_config_.filter_threshold.v_max; + params.filter_v_max = params_config_.ellipse_size; param_pub_.publish(params); }