merged with master

added op3_bringup package
This commit is contained in:
Kayman
2018-04-16 17:47:15 +09:00
parent 2122f8c493
commit 66f3b91ce9
48 changed files with 1024 additions and 263 deletions

View File

@ -0,0 +1,12 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package ball_detector
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
0.1.0 (2018-03-30)
------------------
* first release
* added launch files in order to move the camera setting to op3_camera_setting package
* added missing package in find_package()
* refacoring to release
* splited repositoryfrom ROBOTIS-OP3
* Contributors: Kayman, Zerom, Pyo

View File

@ -1,26 +1,30 @@
################################################################################
# CMake
# Set minimum required version of cmake, project name and compile options
################################################################################
cmake_minimum_required(VERSION 2.8.3)
project(ball_detector)
################################################################################
# Packages
# Find catkin packages and libraries for catkin and system dependencies
################################################################################
find_package(catkin REQUIRED COMPONENTS
roslib
cv_bridge
geometry_msgs
image_transport
roscpp
rospy
roslib
std_msgs
sensor_msgs
geometry_msgs
dynamic_reconfigure
cv_bridge
image_transport
message_generation
)
find_package(Boost REQUIRED COMPONENTS thread)
find_package(OpenCV 3 REQUIRED)
## Resolve system dependency on yaml-cpp, which apparently does not
## provide a CMake find_package() module.
## Insert your header file compatible specified path like '#include <yaml-cpp/yaml.h>'
find_package(PkgConfig REQUIRED)
pkg_check_modules(YAML_CPP REQUIRED yaml-cpp)
find_path(YAML_CPP_INCLUDE_DIR
@ -36,12 +40,17 @@ link_directories(${YAML_CPP_LIBRARY_DIRS})
if(NOT ${YAML_CPP_VERSION} VERSION_LESS "0.5")
add_definitions(-DHAVE_NEW_YAMLCPP)
endif(NOT ${YAML_CPP_VERSION} VERSION_LESS "0.5")
################################################################################
# Setup for python modules and scripts
################################################################################
################################################################################
# Declare ROS messages, services and actions
################################################################################
add_message_files(
FILES
circleSetStamped.msg
CircleSetStamped.msg
BallDetectorParams.msg
)
@ -53,21 +62,34 @@ add_service_files(
generate_messages(
DEPENDENCIES
geometry_msgs std_msgs
std_msgs
geometry_msgs
)
################################################################################
# Declare ROS dynamic reconfigure parameters
################################################################################
generate_dynamic_reconfigure_options(cfg/DetectorParams.cfg)
generate_dynamic_reconfigure_options(
cfg/DetectorParams.cfg
)
################################################################################
# Catkin specific configuration
################################################################################
# Declare catkin specific configuration to be passed to dependent projects
##################################################################################
catkin_package(
INCLUDE_DIRS include
CATKIN_DEPENDS cv_bridge geometry_msgs image_transport roscpp rospy std_msgs dynamic_reconfigure
CATKIN_DEPENDS
roscpp
roslib
std_msgs
sensor_msgs
geometry_msgs
dynamic_reconfigure
cv_bridge
image_transport
message_runtime
DEPENDS Boost OpenCV
)
################################################################################
@ -76,22 +98,39 @@ catkin_package(
include_directories(
include
${catkin_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${YAML_CPP_INCLUDE_DIRS}
)
add_executable(ball_detector_node
src/ball_detector.cpp
src/ball_detector_node.cpp)
src/ball_detector_node.cpp
)
add_dependencies(ball_detector_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
add_dependencies(ball_detector_node ${PROJECT_NAME}_gencfg ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(ball_detector_node
${catkin_LIBRARIES}
${Boost_LIBRARIES}
${OpenCV_LIBRARIES}
${YAML_CPP_LIBRARIES}
)
################################################################################
# Install
################################################################################
install(TARGETS ball_detector_node
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
)
install(DIRECTORY config launch rviz
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
################################################################################
# Test

View File

@ -30,4 +30,4 @@ gen.add("filter2_v_max",int_t , -1, "Threshold of V filter", 255, 0, 255)
gen.add("ellipse_size",int_t , -1, "Ellipse size", 2, 1, 9)
gen.add("debug_image", bool_t, 0, "Show filtered image to debug", False)
exit(gen.generate(PACKAGE, "ball_detector_node", "detectorParams"))
exit(gen.generate(PACKAGE, "ball_detector_node", "DetectorParamsBlue"))

View File

@ -30,4 +30,4 @@ gen.add("filter2_v_max",int_t , -1, "Threshold of V filter", 255, 0, 255)
gen.add("ellipse_size",int_t , -1, "Ellipse size", 5, 1, 9)
gen.add("debug_image", bool_t, 0, "Show filtered image to debug", False)
exit(gen.generate(PACKAGE, "ball_detector_node", "detectorParams"))
exit(gen.generate(PACKAGE, "ball_detector_node", "DetectorParamsRed"))

View File

@ -21,23 +21,26 @@
#include <string>
#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc.hpp>
//ros dependencies
#include <ros/ros.h>
#include <ros/package.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>
#include <sensor_msgs/image_encodings.h>
#include <dynamic_reconfigure/server.h>
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <boost/thread.hpp>
#include <yaml-cpp/yaml.h>
#include "ball_detector/circleSetStamped.h"
#include "ball_detector/ball_detector_config.h"
#include "ball_detector/DetectorParamsConfig.h"
#include "ball_detector/ball_detector_config.h"
#include "ball_detector/CircleSetStamped.h"
#include "ball_detector/GetParameters.h"
#include "ball_detector/SetParameters.h"
@ -112,7 +115,7 @@ class BallDetector
int not_found_count_;
//circle set publisher
ball_detector::circleSetStamped circles_msg_;
ball_detector::CircleSetStamped circles_msg_;
ros::Publisher circles_pub_;
//camera info subscriber

View File

@ -1,13 +1,13 @@
<?xml version="1.0"?>
<launch>
<arg name="config_path" default="$(find ball_detector)/launch/ball_detector_params.yaml"/>
<arg name="config_path" default="$(find ball_detector)/config/ball_detector_params.yaml"/>
<!-- ball detector -->
<node pkg="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" />
<remap from="/ball_detector_node/cameraInfo_in" to="/usb_cam_node/camera_info" />
</node>
<!-- ball detector -->
<node pkg="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" />
<remap from="/ball_detector_node/cameraInfo_in" to="/usb_cam_node/camera_info" />
</node>
</launch>

View File

@ -1,28 +1,27 @@
<?xml version="1.0"?>
<!-- Launches an UVC camera, the ball detector and its visualization -->
<launch>
<!-- UVC camera -->
<node pkg="usb_cam" type="usb_cam_node" name="usb_cam_node" output="screen">
<param name="video_device" type="string" value="/dev/video0" />
<param name="image_width" type="int" value="1280" />
<param name="image_height" type="int" value="720" />
<param name="framerate " type="int" value="30" />
<param name="camera_frame_id" type="string" value="cam_link" />
<param name="camera_name" type="string" value="camera" />
<!-- <param name="autofocus" type="bool" value="False" /> -->
<!-- <param name="autoexposure" type="bool" value="False" /> -->
<!-- <param name="auto_white_balance" type="bool" value="False" /> -->
<!-- <param name="gain" value="255" /> -->
<!-- <param name="brightness" value="64" /> -->
<!-- <param name="exposure" value="80" /> -->
<!-- <param name="auto_exposure" type="bool" value="False" /> -->
<!-- <param name="exposure_absolute" value="1000" /> -->
<!-- <param name="auto_white_balance" type="bool" value="False" /> -->
<!-- <param name="white_balance_temperature" value="2800" /> -->
<!-- <param name="camera_info_url" type="string" value="file://$(find ar_pose)/data/camera_1280720.yaml" /> -->
</node>
<!-- ball detector -->
<include file="$(find ball_detector)/launch/ball_detector.launch" />
<!-- UVC camera -->
<node pkg="usb_cam" type="usb_cam_node" name="usb_cam_node" output="screen">
<param name="video_device" type="string" value="/dev/video0" />
<param name="image_width" type="int" value="1280" />
<param name="image_height" type="int" value="720" />
<param name="framerate " type="int" value="30" />
<param name="camera_frame_id" type="string" value="cam_link" />
<param name="camera_name" type="string" value="camera" />
<!-- <param name="autofocus" type="bool" value="False" /> -->
<!-- <param name="autoexposure" type="bool" value="False" /> -->
<!-- <param name="auto_white_balance" type="bool" value="False" /> -->
<!-- <param name="gain" value="255" /> -->
<!-- <param name="brightness" value="64" /> -->
<!-- <param name="exposure" value="80" /> -->
<!-- <param name="auto_exposure" type="bool" value="False" /> -->
<!-- <param name="exposure_absolute" value="1000" /> -->
<!-- <param name="auto_white_balance" type="bool" value="False" /> -->
<!-- <param name="white_balance_temperature" value="2800" /> -->
<!-- <param name="camera_info_url" type="string" value="file://$(find ar_pose)/data/camera_1280720.yaml" /> -->
</node>
<!-- ball detector -->
<include file="$(find ball_detector)/launch/ball_detector.launch" />
</launch>

View File

@ -1,30 +1,30 @@
<?xml version="1.0"?>
<!-- Launches an UVC camera, the ball detector and its visualization -->
<launch>
<!-- UVC camera -->
<node pkg="uvc_camera" type="uvc_camera_node" name="uvc_camera_node" output="screen">
<param name="device" type="string" value="/dev/video0" />
<param name="width" type="int" value="800" />
<param name="height" type="int" value="600" />
<param name="fps" type="int" value="30" />
<param name="auto_gain" value="false" />
<param name="gain" type="int" value="120" />
<param name="exposure" value="100" />
</node>
<!-- <param name="gain" value="255" />
<param name="auto_exposure" type="bool" value="False" />
<param name="exposure_absolute" value="1000" />
<param name="brightness" value="127" />
<param name="auto_white_balance" type="bool" value="False" />
<param name="white_balance_temperature" value="2800" /> -->
<!-- <param name="auto_exposure" type="bool" value="False" /> -->
<!-- <param name="exposure_absolute" value="1000" /> -->
<!-- <param name="brightness" value="64" /> -->
<!-- <param name="auto_white_balance" type="bool" value="False" /> -->
<!-- <param name="white_balance_temperature" value="2800" /> -->
<!-- ball detector -->
<include file="$(find ball_detector)/launch/ball_detector.launch" />
<!-- UVC camera -->
<node pkg="uvc_camera" type="uvc_camera_node" name="uvc_camera_node" output="screen">
<param name="device" type="string" value="/dev/video0" />
<param name="width" type="int" value="800" />
<param name="height" type="int" value="600" />
<param name="fps" type="int" value="30" />
<param name="auto_gain" value="false" />
<param name="gain" type="int" value="120" />
<param name="exposure" value="100" />
</node>
<!-- <param name="gain" value="255" />
<param name="auto_exposure" type="bool" value="False" />
<param name="exposure_absolute" value="1000" />
<param name="brightness" value="127" />
<param name="auto_white_balance" type="bool" value="False" />
<param name="white_balance_temperature" value="2800" /> -->
<!-- <param name="auto_exposure" type="bool" value="False" /> -->
<!-- <param name="exposure_absolute" value="1000" /> -->
<!-- <param name="brightness" value="64" /> -->
<!-- <param name="auto_white_balance" type="bool" value="False" /> -->
<!-- <param name="white_balance_temperature" value="2800" /> -->
<!-- ball detector -->
<include file="$(find ball_detector)/launch/ball_detector.launch" />
</launch>

View File

@ -1,30 +1,35 @@
<?xml version="1.0"?>
<package format="2">
<name>ball_detector</name>
<version>0.1.1</version>
<version>0.1.0</version>
<description>
This package implements a circle-like shape detector of the input image.
It requires and input image and publish, at frame rate, a marked image
and a stamped array of circle centers and radius.
This package implements a circle-like shape detector of the input image.
It requires and input image and publish, at frame rate, a marked image
and a stamped array of circle centers and radius.
</description>
<license>Apache License 2.0</license>
<author email="kmjung@robotis.com">kayman</author>
<license>Apache 2.0</license>
<author email="kmjung@robotis.com">Kayman</author>
<author email="zerom@robotis.com">Zerom</author>
<maintainer email="pyo@robotis.com">Pyo</maintainer>
<url type="website">http://wiki.ros.org/ball_detector</url>
<url type="emanual">http://emanual.robotis.com/docs/en/platform/op3/introduction/</url>
<url type="repository">https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-Demo</url>
<url type="bugtracker">https://github.com/ROBOTIS-GIT/ROBOTIS-OP3-Demo/issues</url>
<buildtool_depend>catkin</buildtool_depend>
<depend>roslib</depend>
<depend>cv_bridge</depend>
<depend>geometry_msgs</depend>
<depend>image_transport</depend>
<depend>roscpp</depend>
<depend>rospy</depend>
<depend>roslib</depend>
<depend>std_msgs</depend>
<depend>cmake_modules</depend>
<depend>sensor_msgs</depend>
<depend>geometry_msgs</depend>
<depend>dynamic_reconfigure</depend>
<depend>cv_bridge</depend>
<depend>image_transport</depend>
<depend>boost</depend>
<depend>opencv3</depend>
<depend>yaml-cpp</depend>
<build_depend>message_generation</build_depend>
<build_export_depend>message_runtime</build_export_depend>
<exec_depend>message_runtime</exec_depend>
<build_depend>dynamic_reconfigure</build_depend>
<build_export_depend>dynamic_reconfigure</build_export_depend>
<exec_depend>dynamic_reconfigure</exec_depend>
<exec_depend>usb_cam</exec_depend>
<exec_depend>uvc_camera</exec_depend>
</package>

View File

@ -16,7 +16,6 @@
/* Author: Kayman Jung */
#include <yaml-cpp/yaml.h>
#include <fstream>
#include "ball_detector/ball_detector.h"
@ -72,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<ball_detector::CircleSetStamped>("circle_set", 100);
camera_info_pub_ = nh_.advertise<sensor_msgs::CameraInfo>("camera_info", 100);
//sets subscribers
@ -92,7 +91,7 @@ BallDetector::BallDetector()
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);
default_setting_path_ = ros::package::getPath(ROS_PACKAGE_NAME) + "/launch/ball_detector_params_default.yaml";
default_setting_path_ = ros::package::getPath(ROS_PACKAGE_NAME) + "/config/ball_detector_params_default.yaml";
//sets config and prints it
params_config_ = detect_config;