changed the package name from ball_detector to op3_ball_detector
This commit is contained in:
parent
1c1871ec43
commit
454128b199
@ -2,7 +2,7 @@
|
||||
# Set minimum required version of cmake, project name and compile options
|
||||
################################################################################
|
||||
cmake_minimum_required(VERSION 2.8.3)
|
||||
project(ball_detector)
|
||||
project(op3_ball_detector)
|
||||
|
||||
################################################################################
|
||||
# Find catkin packages and libraries for catkin and system dependencies
|
2
ball_detector/cfg/DetectorParams.cfg → op3_ball_detector/cfg/DetectorParams.cfg
Executable file → Normal file
2
ball_detector/cfg/DetectorParams.cfg → op3_ball_detector/cfg/DetectorParams.cfg
Executable file → Normal file
@ -1,5 +1,5 @@
|
||||
#!/usr/bin/env python
|
||||
PACKAGE='ball_detector'
|
||||
PACKAGE='op3_ball_detector'
|
||||
|
||||
from dynamic_reconfigure.parameter_generator_catkin import *
|
||||
|
@ -1,5 +1,5 @@
|
||||
#!/usr/bin/env python
|
||||
PACKAGE='ball_detector'
|
||||
PACKAGE='op3_ball_detector'
|
||||
|
||||
from dynamic_reconfigure.parameter_generator_catkin import *
|
||||
|
@ -1,5 +1,5 @@
|
||||
#!/usr/bin/env python
|
||||
PACKAGE='ball_detector'
|
||||
PACKAGE='op3_ball_detector'
|
||||
|
||||
from dynamic_reconfigure.parameter_generator_catkin import *
|
||||
|
@ -36,13 +36,12 @@
|
||||
#include <boost/thread.hpp>
|
||||
#include <yaml-cpp/yaml.h>
|
||||
|
||||
#include "ball_detector/DetectorParamsConfig.h"
|
||||
#include "op3_ball_detector/ball_detector_config.h"
|
||||
|
||||
#include "ball_detector/ball_detector_config.h"
|
||||
|
||||
#include "ball_detector/CircleSetStamped.h"
|
||||
#include "ball_detector/GetParameters.h"
|
||||
#include "ball_detector/SetParameters.h"
|
||||
#include "op3_ball_detector/DetectorParamsConfig.h"
|
||||
#include "op3_ball_detector/CircleSetStamped.h"
|
||||
#include "op3_ball_detector/GetParameters.h"
|
||||
#include "op3_ball_detector/SetParameters.h"
|
||||
|
||||
namespace robotis_op
|
||||
{
|
||||
@ -74,12 +73,12 @@ class BallDetector
|
||||
//callbacks to camera info subscription
|
||||
void cameraInfoCallback(const sensor_msgs::CameraInfo & msg);
|
||||
|
||||
void dynParamCallback(ball_detector::DetectorParamsConfig &config, uint32_t level);
|
||||
void dynParamCallback(op3_ball_detector::DetectorParamsConfig &config, uint32_t level);
|
||||
void enableCallback(const std_msgs::Bool::ConstPtr &msg);
|
||||
|
||||
void paramCommandCallback(const std_msgs::String::ConstPtr &msg);
|
||||
bool setParamCallback(ball_detector::SetParameters::Request &req, ball_detector::SetParameters::Response &res);
|
||||
bool getParamCallback(ball_detector::GetParameters::Request &req, ball_detector::GetParameters::Response &res);
|
||||
bool setParamCallback(op3_ball_detector::SetParameters::Request &req, op3_ball_detector::SetParameters::Response &res);
|
||||
bool getParamCallback(op3_ball_detector::GetParameters::Request &req, op3_ball_detector::GetParameters::Response &res);
|
||||
void resetParameter();
|
||||
void publishParam();
|
||||
|
||||
@ -115,7 +114,7 @@ class BallDetector
|
||||
int not_found_count_;
|
||||
|
||||
//circle set publisher
|
||||
ball_detector::CircleSetStamped circles_msg_;
|
||||
op3_ball_detector::CircleSetStamped circles_msg_;
|
||||
ros::Publisher circles_pub_;
|
||||
|
||||
//camera info subscriber
|
||||
@ -157,8 +156,8 @@ class BallDetector
|
||||
cv::Mat in_image_;
|
||||
cv::Mat out_image_;
|
||||
|
||||
dynamic_reconfigure::Server<ball_detector::DetectorParamsConfig> param_server_;
|
||||
dynamic_reconfigure::Server<ball_detector::DetectorParamsConfig>::CallbackType callback_fnc_;
|
||||
dynamic_reconfigure::Server<op3_ball_detector::DetectorParamsConfig> param_server_;
|
||||
dynamic_reconfigure::Server<op3_ball_detector::DetectorParamsConfig>::CallbackType callback_fnc_;
|
||||
};
|
||||
|
||||
} // namespace robotis_op
|
@ -1,9 +1,9 @@
|
||||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
<arg name="config_path" default="$(find ball_detector)/config/ball_detector_params.yaml"/>
|
||||
<arg name="config_path" default="$(find op3_ball_detector)/config/ball_detector_params.yaml"/>
|
||||
|
||||
<!-- ball detector -->
|
||||
<node pkg="ball_detector" type="ball_detector_node" name="ball_detector_node" args="" output="screen">
|
||||
<node pkg="op3_ball_detector" type="ball_detector_node" name="ball_detector_node" args="" output="screen">
|
||||
<rosparam command="load" file="$(arg config_path)"/>
|
||||
<param name="yaml_path" type="string" value="$(arg config_path)"/>
|
||||
<remap from="/ball_detector_node/image_in" to="/usb_cam_node/image_raw" />
|
@ -23,5 +23,5 @@
|
||||
</node>
|
||||
|
||||
<!-- ball detector -->
|
||||
<include file="$(find ball_detector)/launch/ball_detector.launch" />
|
||||
<include file="$(find op3_ball_detector)/launch/ball_detector.launch" />
|
||||
</launch>
|
@ -25,6 +25,6 @@
|
||||
<!-- <param name="white_balance_temperature" value="2800" /> -->
|
||||
|
||||
<!-- ball detector -->
|
||||
<include file="$(find ball_detector)/launch/ball_detector.launch" />
|
||||
<include file="$(find op3_ball_detector)/launch/ball_detector.launch" />
|
||||
</launch>
|
||||
|
@ -1,6 +1,6 @@
|
||||
<?xml version="1.0"?>
|
||||
<package format="2">
|
||||
<name>ball_detector</name>
|
||||
<name>op3_ball_detector</name>
|
||||
<version>0.1.0</version>
|
||||
<description>
|
||||
This package implements a circle-like shape detector of the input image.
|
@ -18,7 +18,7 @@
|
||||
|
||||
#include <fstream>
|
||||
|
||||
#include "ball_detector/ball_detector.h"
|
||||
#include "op3_ball_detector/ball_detector.h"
|
||||
|
||||
namespace robotis_op
|
||||
{
|
||||
@ -71,7 +71,7 @@ BallDetector::BallDetector()
|
||||
|
||||
//sets publishers
|
||||
image_pub_ = it_.advertise("image_out", 100);
|
||||
circles_pub_ = nh_.advertise<ball_detector::CircleSetStamped>("circle_set", 100);
|
||||
circles_pub_ = nh_.advertise<op3_ball_detector::CircleSetStamped>("circle_set", 100);
|
||||
camera_info_pub_ = nh_.advertise<sensor_msgs::CameraInfo>("camera_info", 100);
|
||||
|
||||
//sets subscribers
|
||||
@ -87,7 +87,7 @@ BallDetector::BallDetector()
|
||||
param_server_.setCallback(callback_fnc_);
|
||||
|
||||
// web setting
|
||||
param_pub_ = nh_.advertise<ball_detector::BallDetectorParams>("current_params", 1);
|
||||
param_pub_ = nh_.advertise<op3_ball_detector::BallDetectorParams>("current_params", 1);
|
||||
param_command_sub_ = nh_.subscribe("param_command", 1, &BallDetector::paramCommandCallback, this);
|
||||
set_param_client_ = nh_.advertiseService("set_param", &BallDetector::setParamCallback, this);
|
||||
get_param_client_ = nh_.advertiseService("get_param", &BallDetector::getParamCallback, this);
|
||||
@ -233,7 +233,7 @@ void BallDetector::imageCallback(const sensor_msgs::ImageConstPtr & msg)
|
||||
return;
|
||||
}
|
||||
|
||||
void BallDetector::dynParamCallback(ball_detector::DetectorParamsConfig &config, uint32_t level)
|
||||
void BallDetector::dynParamCallback(op3_ball_detector::DetectorParamsConfig &config, uint32_t level)
|
||||
{
|
||||
params_config_.gaussian_blur_size = config.gaussian_blur_size;
|
||||
params_config_.gaussian_blur_sigma = config.gaussian_blur_sigma;
|
||||
@ -296,7 +296,7 @@ void BallDetector::paramCommandCallback(const std_msgs::String::ConstPtr &msg)
|
||||
}
|
||||
}
|
||||
|
||||
bool BallDetector::setParamCallback(ball_detector::SetParameters::Request &req, ball_detector::SetParameters::Response &res)
|
||||
bool BallDetector::setParamCallback(op3_ball_detector::SetParameters::Request &req, op3_ball_detector::SetParameters::Response &res)
|
||||
{
|
||||
params_config_.gaussian_blur_size = req.params.gaussian_blur_size;
|
||||
params_config_.gaussian_blur_sigma = req.params.gaussian_blur_sigma;
|
||||
@ -321,7 +321,7 @@ bool BallDetector::setParamCallback(ball_detector::SetParameters::Request &req,
|
||||
return true;
|
||||
}
|
||||
|
||||
bool BallDetector:: getParamCallback(ball_detector::GetParameters::Request &req, ball_detector::GetParameters::Response &res)
|
||||
bool BallDetector:: getParamCallback(op3_ball_detector::GetParameters::Request &req, op3_ball_detector::GetParameters::Response &res)
|
||||
{
|
||||
res.returns.gaussian_blur_size = params_config_.gaussian_blur_size;
|
||||
res.returns.gaussian_blur_sigma = params_config_.gaussian_blur_sigma;
|
||||
@ -396,7 +396,7 @@ void BallDetector::resetParameter()
|
||||
|
||||
void BallDetector::publishParam()
|
||||
{
|
||||
ball_detector::BallDetectorParams params;
|
||||
op3_ball_detector::BallDetectorParams params;
|
||||
|
||||
params.gaussian_blur_size = params_config_.gaussian_blur_size;
|
||||
params.gaussian_blur_sigma = params_config_.gaussian_blur_sigma;
|
@ -16,7 +16,7 @@
|
||||
|
||||
/* Author: Kayman Jung */
|
||||
|
||||
#include "ball_detector/ball_detector.h"
|
||||
#include "op3_ball_detector/ball_detector.h"
|
||||
|
||||
//node main
|
||||
int main(int argc, char **argv)
|
@ -18,7 +18,7 @@ find_package(catkin REQUIRED COMPONENTS
|
||||
op3_action_module_msgs
|
||||
cmake_modules
|
||||
robotis_math
|
||||
ball_detector
|
||||
op3_ball_detector
|
||||
)
|
||||
|
||||
find_package(Boost REQUIRED COMPONENTS thread)
|
||||
@ -71,7 +71,7 @@ catkin_package(
|
||||
op3_action_module_msgs
|
||||
cmake_modules
|
||||
robotis_math
|
||||
ball_detector
|
||||
op3_ball_detector
|
||||
DEPENDS Boost EIGEN3
|
||||
)
|
||||
|
||||
|
@ -29,7 +29,7 @@
|
||||
#include <yaml-cpp/yaml.h>
|
||||
|
||||
#include "robotis_controller_msgs/JointCtrlModule.h"
|
||||
#include "ball_detector/CircleSetStamped.h"
|
||||
#include "op3_ball_detector/CircleSetStamped.h"
|
||||
#include "op3_walking_module_msgs/WalkingParam.h"
|
||||
#include "op3_walking_module_msgs/GetWalkingParam.h"
|
||||
|
||||
|
@ -29,7 +29,7 @@
|
||||
#include <yaml-cpp/yaml.h>
|
||||
|
||||
#include "robotis_controller_msgs/JointCtrlModule.h"
|
||||
#include "ball_detector/CircleSetStamped.h"
|
||||
#include "op3_ball_detector/CircleSetStamped.h"
|
||||
#include "op3_walking_module_msgs/WalkingParam.h"
|
||||
#include "op3_walking_module_msgs/GetWalkingParam.h"
|
||||
|
||||
@ -79,7 +79,7 @@ protected:
|
||||
const int WAITING_THRESHOLD;
|
||||
const bool DEBUG_PRINT;
|
||||
|
||||
void ballPositionCallback(const ball_detector::CircleSetStamped::ConstPtr &msg);
|
||||
void ballPositionCallback(const op3_ball_detector::CircleSetStamped::ConstPtr &msg);
|
||||
void ballTrackerCommandCallback(const std_msgs::String::ConstPtr &msg);
|
||||
void publishHeadJoint(double pan, double tilt);
|
||||
void scanBall();
|
||||
|
@ -4,7 +4,7 @@
|
||||
<include file="$(find op3_manager)/launch/op3_manager.launch"/>
|
||||
|
||||
<!-- Camera and Ball detector -->
|
||||
<include file="$(find ball_detector)/launch/ball_detector_from_usb_cam.launch"/>
|
||||
<include file="$(find op3_ball_detector)/launch/ball_detector_from_usb_cam.launch"/>
|
||||
|
||||
<!-- face tracking -->
|
||||
<include file="$(find op3_demo)/launch/face_detection_op3.launch" />
|
||||
|
@ -5,7 +5,7 @@
|
||||
<include file="$(find op3_manager)/launch/op3_manager.launch"/>
|
||||
|
||||
<!-- Camera and Ball detector -->
|
||||
<include file="$(find ball_detector)/launch/ball_detector_from_usb_cam.launch"/>
|
||||
<include file="$(find op3_ball_detector)/launch/ball_detector_from_usb_cam.launch"/>
|
||||
|
||||
<!-- face tracking -->
|
||||
<include file="$(find op3_demo)/launch/face_detection_op3.launch" />
|
||||
|
@ -24,7 +24,7 @@
|
||||
<depend>op3_action_module_msgs</depend>
|
||||
<depend>cmake_modules</depend>
|
||||
<depend>robotis_math</depend>
|
||||
<depend>ball_detector</depend>
|
||||
<depend>op3_ball_detector</depend>
|
||||
<depend>boost</depend>
|
||||
<depend>eigen</depend>
|
||||
<depend>yaml-cpp</depend>
|
||||
|
@ -59,7 +59,7 @@ BallTracker::~BallTracker()
|
||||
|
||||
}
|
||||
|
||||
void BallTracker::ballPositionCallback(const ball_detector::CircleSetStamped::ConstPtr &msg)
|
||||
void BallTracker::ballPositionCallback(const op3_ball_detector::CircleSetStamped::ConstPtr &msg)
|
||||
{
|
||||
for (int idx = 0; idx < msg->circles.size(); idx++)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user