added msg and srv for web setting tool

applied test code
This commit is contained in:
Kayman 2018-02-23 14:14:32 +09:00
parent 0880029ac2
commit 72afe216cc
6 changed files with 53 additions and 1 deletions

View File

@ -24,6 +24,13 @@ find_package(catkin REQUIRED COMPONENTS
add_message_files(
FILES
circleSetStamped.msg
BallDetectorParams.msg
)
add_service_files(
FILES
GetParameters.srv
SetParameters.srv
)
generate_messages(
@ -70,4 +77,4 @@ target_link_libraries(ball_detector_node
################################################################################
# Test
################################################################################
################################################################################

View File

@ -27,6 +27,7 @@
//ros dependencies
#include <ros/ros.h>
#include <std_msgs/Bool.h>
#include <std_msgs/String.h>
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/CameraInfo.h>
@ -70,6 +71,8 @@ class BallDetector
void dynParamCallback(ball_detector::detectorParamsConfig &config, uint32_t level);
void enableCallback(const std_msgs::Bool::ConstPtr &msg);
void paramCommandCallback(const std_msgs::String::ConstPtr &msg);
void printConfig();
void saveConfig();
void setInputImage(const cv::Mat & inIm);
@ -86,6 +89,7 @@ class BallDetector
ros::NodeHandle nh_;
ros::Subscriber enable_sub_;
ros::Subscriber param_command_sub_;
//image publisher/subscriber
image_transport::ImageTransport it_;

View File

@ -0,0 +1,16 @@
# This represents the parameters of ball_detector
uint32 gaussian_blur_size # only odd number, 1 - 11
float32 gaussian_blur_sigma # 1 - 5
float32 canny_edge_th # 50 - 200
float32 hough_accum_resolution # 1 - 8
float32 hough_accum_th # 10 - 200
float32 min_circle_dist # 10 - 200
uint32 min_radius # 10 - 200
uint32 max_radius # 100 - 600
uint32 filter_h_min # 0 - 359
uint32 filter_h_max
uint32 filter_s_min # 0 - 255
uint32 filter_s_max
uint32 filter_v_min # 0 - 255
uint32 filter_v_max

View File

@ -79,6 +79,7 @@ BallDetector::BallDetector()
enable_sub_ = nh_.subscribe("enable", 1, &BallDetector::enableCallback, this);
image_sub_ = it_.subscribe("image_in", 1, &BallDetector::imageCallback, this);
camera_info_sub_ = nh_.subscribe("cameraInfo_in", 100, &BallDetector::cameraInfoCallback, this);
param_command_sub_ = nh_.subscribe("param_command", 1, &BallDetector::paramCommandCallback, this);
//initializes newImageFlag
new_image_flag_ = false;
@ -260,6 +261,24 @@ void BallDetector::cameraInfoCallback(const sensor_msgs::CameraInfo & msg)
camera_info_msg_ = msg;
}
void BallDetector::paramCommandCallback(const std_msgs::String::ConstPtr &msg)
{
if(msg->data == "debug")
{
params_config_.debug = true;
saveConfig();
}
else if(msg->data == "normal")
{
params_config_.debug = false;
saveConfig();
}
else if(msg->data == "reset")
{
// load default parameters and apply
}
}
void BallDetector::printConfig()
{
if (init_param_ == false)

View File

@ -0,0 +1,3 @@
---
BallDetectorParams returns

View File

@ -0,0 +1,3 @@
BallDetectorParams params
---
BallDetectorParams returns