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

12
op3_demo/CHANGELOG.rst Normal file
View File

@@ -0,0 +1,12 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package op3_demo
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
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, Yoshimaru Tanaka, Pyo

View File

@@ -1,28 +1,32 @@
################################################################################
# CMake
# Set minimum required version of cmake, project name and compile options
################################################################################
cmake_minimum_required(VERSION 2.8.3)
project(op3_demo)
################################################################################
# Packages
# Find catkin packages and libraries for catkin and system dependencies
################################################################################
find_package(catkin REQUIRED COMPONENTS
roscpp
roslib
std_msgs
sensor_msgs
ball_detector
geometry_msgs
robotis_controller_msgs
op3_walking_module_msgs
op3_action_module_msgs
robotis_controller_msgs
cmake_modules
robotis_math
ball_detector
)
find_package(Boost REQUIRED COMPONENTS thread)
find_package(Eigen3 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
@@ -39,6 +43,10 @@ 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
################################################################################
@@ -48,12 +56,23 @@ endif(NOT ${YAML_CPP_VERSION} VERSION_LESS "0.5")
################################################################################
################################################################################
# Catkin specific configuration
# Declare catkin specific configuration to be passed to dependent projects
################################################################################
catkin_package(
INCLUDE_DIRS include
CATKIN_DEPENDS roscpp sensor_msgs cmake_modules
DEPENDS EIGEN3
CATKIN_DEPENDS
roscpp
roslib
std_msgs
sensor_msgs
geometry_msgs
robotis_controller_msgs
op3_walking_module_msgs
op3_action_module_msgs
cmake_modules
robotis_math
ball_detector
DEPENDS Boost EIGEN3
)
################################################################################
@@ -62,6 +81,7 @@ catkin_package(
include_directories(
include
${catkin_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
${YAML_CPP_INCLUDE_DIRS}
)
@@ -76,11 +96,16 @@ add_executable(op_demo_node
src/vision/face_tracker.cpp
)
add_dependencies(op_demo_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
add_dependencies(op_demo_node
${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS}
)
target_link_libraries(op_demo_node
${catkin_LIBRARIES}
yaml-cpp
${Boost_LIBRARIES}
${Eigen3_LIBRARIES}
${YAML_CPP_LIBRARIES}
)
add_executable(self_test_node
@@ -95,48 +120,32 @@ add_executable(self_test_node
src/test/mic_test.cpp
)
add_dependencies(self_test_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
add_dependencies(self_test_node
${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS}
)
target_link_libraries(self_test_node
${catkin_LIBRARIES}
${Eigen3_LIBRARIES}
${Boost_LIBRARIES}
${Eigen3_LIBRARIES}
${YAML_CPP_LIBRARIES}
)
################################################################################
# Install
################################################################################
install(TARGETS op_demo_node self_test_node
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
)
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# install(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables and/or libraries for installation
# install(TARGETS ball_tracking ball_tracking_node
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
install(DIRECTORY data launch list
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
################################################################################
# Test

View File

@@ -19,14 +19,14 @@
#ifndef ACTION_DEMO_H_
#define ACTION_DEMO_H_
#include <boost/thread.hpp>
#include <yaml-cpp/yaml.h>
#include <ros/ros.h>
#include <ros/package.h>
#include <std_msgs/Int32.h>
#include <std_msgs/String.h>
#include <boost/thread.hpp>
#include <yaml-cpp/yaml.h>
#include "op3_demo/op_demo.h"
#include "robotis_controller_msgs/JointCtrlModule.h"
#include "robotis_controller_msgs/SetModule.h"

View File

@@ -20,16 +20,16 @@
#define BALL_FOLLOWER_H_
#include <math.h>
#include <yaml-cpp/yaml.h>
#include <ros/ros.h>
#include <ros/package.h>
#include <std_msgs/String.h>
#include <std_msgs/Int32.h>
#include <sensor_msgs/JointState.h>
#include <geometry_msgs/Point.h>
#include <yaml-cpp/yaml.h>
#include "robotis_controller_msgs/JointCtrlModule.h"
#include "ball_detector/circleSetStamped.h"
#include "ball_detector/CircleSetStamped.h"
#include "op3_walking_module_msgs/WalkingParam.h"
#include "op3_walking_module_msgs/GetWalkingParam.h"

View File

@@ -20,17 +20,16 @@
#define BALL_TRACKING_H_
#include <math.h>
#include <yaml-cpp/yaml.h>
#include <ros/ros.h>
#include <ros/package.h>
#include <std_msgs/String.h>
#include <std_msgs/Int32.h>
//#include <std_msgs/Float64MultiArray.h>
#include <sensor_msgs/JointState.h>
#include <geometry_msgs/Point.h>
#include <yaml-cpp/yaml.h>
#include "robotis_controller_msgs/JointCtrlModule.h"
#include "ball_detector/circleSetStamped.h"
#include "ball_detector/CircleSetStamped.h"
#include "op3_walking_module_msgs/WalkingParam.h"
#include "op3_walking_module_msgs/GetWalkingParam.h"
@@ -80,7 +79,7 @@ protected:
const int WAITING_THRESHOLD;
const bool DEBUG_PRINT;
void ballPositionCallback(const ball_detector::circleSetStamped::ConstPtr &msg);
void ballPositionCallback(const ball_detector::CircleSetStamped::ConstPtr &msg);
void ballTrackerCommandCallback(const std_msgs::String::ConstPtr &msg);
void publishHeadJoint(double pan, double tilt);
void scanBall();

View File

@@ -19,14 +19,12 @@
#ifndef BUTTON_TEST_H_
#define BUTTON_TEST_H_
#include <boost/thread.hpp>
#include <ros/ros.h>
#include <ros/package.h>
#include <std_msgs/String.h>
#include <boost/thread.hpp>
#include "op3_demo/op_demo.h"
#include "robotis_controller_msgs/SyncWriteItem.h"
namespace robotis_op

View File

@@ -20,8 +20,6 @@
#define FACE_TRACKING_H_
#include <math.h>
#include <yaml-cpp/yaml.h>
#include <ros/ros.h>
#include <ros/package.h>
#include <std_msgs/Bool.h>
@@ -29,6 +27,7 @@
#include <std_msgs/Int32.h>
#include <sensor_msgs/JointState.h>
#include <geometry_msgs/Point.h>
#include <yaml-cpp/yaml.h>
namespace robotis_op
{

View File

@@ -20,14 +20,12 @@
#define MIC_TEST_H_
#include <signal.h>
#include <boost/thread.hpp>
#include <ros/ros.h>
#include <ros/package.h>
#include <std_msgs/String.h>
#include <boost/thread.hpp>
#include "op3_demo/op_demo.h"
#include "robotis_controller_msgs/SyncWriteItem.h"
namespace robotis_op

View File

@@ -23,15 +23,18 @@
#include <std_msgs/String.h>
#include <sensor_msgs/Imu.h>
#include <boost/thread.hpp>
#include <eigen3/Eigen/Eigen>
#include <yaml-cpp/yaml.h>
#include "op3_action_module_msgs/IsRunning.h"
#include "robotis_controller_msgs/SyncWriteItem.h"
#include "robotis_controller_msgs/JointCtrlModule.h"
#include "robotis_controller_msgs/SetJointModule.h"
#include "op3_demo/op_demo.h"
#include "op3_demo/ball_tracker.h"
#include "op3_demo/ball_follower.h"
#include "robotis_math/robotis_linear_algebra.h"
#include "op3_action_module_msgs/IsRunning.h"
#include "robotis_controller_msgs/SyncWriteItem.h"
#include "robotis_controller_msgs/JointCtrlModule.h"
#include "robotis_controller_msgs/SetJointModule.h"
namespace robotis_op
{

View File

@@ -19,19 +19,18 @@
#ifndef VISION_DEMO_H_
#define VISION_DEMO_H_
#include <boost/thread.hpp>
#include <ros/ros.h>
#include <std_msgs/String.h>
#include <std_msgs/Int32MultiArray.h>
#include <geometry_msgs/Point.h>
#include "op3_demo/op_demo.h"
#include "op3_demo/face_tracker.h"
#include <boost/thread.hpp>
#include "robotis_controller_msgs/SyncWriteItem.h"
#include "robotis_controller_msgs/SetModule.h"
#include "op3_demo/op_demo.h"
#include "op3_demo/face_tracker.h"
namespace robotis_op
{

View File

@@ -1,7 +1,5 @@
<?xml version="1.0"?>
<launch>
<!-- robotis op3 manager -->
<include file="$(find op3_manager)/launch/op3_manager.launch"/>

View File

@@ -7,16 +7,16 @@
<arg name="face_cascade_name_4" default="$(find face_detection)/include/face_detection/lbpCascades/lbpcascade_frontalface.xml" />
<node pkg="face_detection" type="face_tracking" name="face_tracking"
args="$(arg face_cascade_name_0)
$(arg face_cascade_name_1)
$(arg face_cascade_name_2)
$(arg face_cascade_name_3)
$(arg face_cascade_name_4)"
output="screen">
<param name="imageInput" type="string" value="/usb_cam_node/image_raw" />
<param name="displayed_Image" type="int" value="0" />
<!-- <param name="publish" type="int" value="2" /> -->
<param name="publish" type="int" value="3" />
args="$(arg face_cascade_name_0)
$(arg face_cascade_name_1)
$(arg face_cascade_name_2)
$(arg face_cascade_name_3)
$(arg face_cascade_name_4)"
output="screen">
<param name="imageInput" type="string" value="/usb_cam_node/image_raw" />
<param name="displayed_Image" type="int" value="0" />
<!-- <param name="publish" type="int" value="2" /> -->
<param name="publish" type="int" value="3" />
<param name="start_condition" type="bool" value="false" />
</node>
</launch>

View File

@@ -1,30 +1,29 @@
<?xml version="1.0"?>
<!-- Launches an UVC camera, the ball detector and its visualization -->
<launch>
<!-- robotis op3 manager -->
<include file="$(find op3_manager)/launch/op3_manager.launch"/>
<!-- robotis op3 manager -->
<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"/>
<!-- Camera and Ball detector -->
<include file="$(find ball_detector)/launch/ball_detector_from_usb_cam.launch"/>
<!-- face tracking -->
<include file="$(find op3_demo)/launch/face_detection_op3.launch" />
<!-- face tracking -->
<include file="$(find op3_demo)/launch/face_detection_op3.launch" />
<!-- camera setting tool -->
<include file="$(find op3_camera_setting_tool)/launch/op3_camera_setting_tool.launch" />
<!-- camera setting tool -->
<include file="$(find op3_camera_setting_tool)/launch/op3_camera_setting_tool.launch" />
<!-- sound player -->
<node pkg="ros_madplay_player" type="ros_madplay_player" name="ros_madplay_player" output="screen"/>
<!-- sound player -->
<node pkg="ros_madplay_player" type="ros_madplay_player" name="ros_madplay_player" output="screen"/>
<!-- web setting -->
<include file="$(find op3_web_setting_tool)/launch/web_setting_server.launch" />
<!-- web setting -->
<include file="$(find op3_web_setting_tool)/launch/web_setting_server.launch" />
<!-- robotis op3 self test demo -->
<node pkg="op3_demo" type="self_test_node" name="op3_self_test" output="screen">
<param name="grass_demo" type="bool" value="False" />
<param name="p_gain" value="0.45" />
<param name="d_gain" value="0.045" />
</node>
<!-- robotis op3 self test demo -->
<node pkg="op3_demo" type="self_test_node" name="op3_self_test" output="screen">
<param name="grass_demo" type="bool" value="False" />
<param name="p_gain" value="0.45" />
<param name="d_gain" value="0.045" />
</node>
</launch>

View File

@@ -0,0 +1,23 @@
# combination action page number and mp3 file path
action_and_sound:
4 : "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Thank you.mp3"
41: "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Introduction.mp3"
24: "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Wow.mp3"
23: "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Yes go.mp3"
15: "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Sit down.mp3"
1: "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Stand up.mp3"
54: "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Clap please.mp3"
27: "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Oops.mp3"
38: "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Bye bye.mp3"
# 101 : "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Oops.mp3"
110 : ""
111 : "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Intro01.mp3"
115 : "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Intro02.mp3"
118 : "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Intro03.mp3"
# play list
prev_default: [4, 41, 24, 23, 15, 1, 54, 27, 38]
default: [4, 110, 111, 115, 118, 24, 54, 27, 38]
# example of play list
#certification: [101]

View File

@@ -1,15 +1,15 @@
# combination action page number and mp3 file path
action_and_sound:
4 : "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Thank you.mp3"
41: "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Introduction.mp3"
24: "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Wow.mp3"
23: "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Yes go.mp3"
15: "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Sit down.mp3"
1: "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Stand up.mp3"
54: "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Clap please.mp3"
27: "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Oops.mp3"
38: "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Bye bye.mp3"
101 : "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Oops.mp3"
4 : "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Thank you.mp3"
41: "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Introduction.mp3"
24: "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Wow.mp3"
23: "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Yes go.mp3"
15: "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Sit down.mp3"
1: "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Stand up.mp3"
54: "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Clap please.mp3"
27: "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Oops.mp3"
38: "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Bye bye.mp3"
101 : "/home/robotis/catkin_ws/src/ROBOTIS-OP3/ROBOTIS-OP3-Demo/op3_demo/data/mp3/Oops.mp3"
# play list
default: [4, 41, 24, 23, 15, 1, 54, 27, 38]

View File

@@ -1,25 +1,36 @@
<?xml version="1.0"?>
<package format="2">
<name>op3_demo</name>
<version>0.1.1</version>
<version>0.1.0</version>
<description>
op3 default demo
OP3 default demo
It includes three demontrations(soccer demo, vision demo, action script demo)
</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>
<maintainer email="pyo@robotis.com">Pyo</maintainer>
<url type="website">http://wiki.ros.org/op3_demo</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>roscpp</depend>
<depend>roslib</depend>
<depend>std_msgs</depend>
<depend>sensor_msgs</depend>
<depend>ball_detector</depend>
<depend>geometry_msgs</depend>
<depend>robotis_controller_msgs</depend>
<depend>op3_walking_module_msgs</depend>
<depend>op3_action_module_msgs</depend>
<depend>cmake_modules</depend>
<depend>robotis_math</depend>
<depend>ball_detector</depend>
<depend>boost</depend>
<depend>eigen</depend>
<depend>yaml-cpp</depend>
<exec_depend>op3_manager</exec_depend>
<exec_depend>op3_camera_setting_tool</exec_depend>
<exec_depend>op3_web_setting_tool</exec_depend>
<exec_depend>ros_madplay_player</exec_depend>
<!-- <exec_depend>face_detection</exec_depend> -->
</package>

View File

@@ -1,23 +0,0 @@
# combination action page number and mp3 file path
action_and_sound:
4 : "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Thank you.mp3"
41: "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Introduction.mp3"
24: "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Wow.mp3"
23: "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Yes go.mp3"
15: "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Sit down.mp3"
1: "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Stand up.mp3"
54: "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Clap please.mp3"
27: "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Oops.mp3"
38: "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Bye bye.mp3"
# 101 : "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Oops.mp3"
110 : ""
111 : "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Intro01.mp3"
115 : "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Intro02.mp3"
118 : "/home/robotis/catkin_ws/src/ROBOTIS-OP3-Demo/op3_demo/Data/mp3/Intro03.mp3"
# play list
prev_default: [4, 41, 24, 23, 15, 1, 54, 27, 38]
default: [4, 110, 111, 115, 118, 24, 54, 27, 38]
# example of play list
#certification: [101]

View File

@@ -31,7 +31,7 @@ ActionDemo::ActionDemo()
ros::NodeHandle nh(ros::this_node::getName());
std::string default_path = ros::package::getPath("op3_demo") + "/script/action_script.yaml";
std::string default_path = ros::package::getPath("op3_demo") + "/list/action_script.yaml";
script_path_ = nh.param<std::string>("action_script", default_path);
std::string default_play_list = "default";

View File

@@ -77,7 +77,7 @@ int main(int argc, char **argv)
ros::Subscriber buttuon_sub = nh.subscribe("/robotis/open_cr/button", 1, buttonHandlerCallback);
ros::Subscriber mode_command_sub = nh.subscribe("/robotis/mode_command", 1, demoModeCommandCallback);
default_mp3_path = ros::package::getPath("op3_demo") + "/Data/mp3/";
default_mp3_path = ros::package::getPath("op3_demo") + "/data/mp3/";
ros::start();

View File

@@ -59,7 +59,7 @@ BallTracker::~BallTracker()
}
void BallTracker::ballPositionCallback(const ball_detector::circleSetStamped::ConstPtr &msg)
void BallTracker::ballPositionCallback(const ball_detector::CircleSetStamped::ConstPtr &msg)
{
for (int idx = 0; idx < msg->circles.size(); idx++)
{

View File

@@ -33,7 +33,7 @@ ButtonTest::ButtonTest()
boost::thread queue_thread = boost::thread(boost::bind(&ButtonTest::callbackThread, this));
boost::thread process_thread = boost::thread(boost::bind(&ButtonTest::processThread, this));
default_mp3_path_ = ros::package::getPath("op3_demo") + "/Data/mp3/test/";
default_mp3_path_ = ros::package::getPath("op3_demo") + "/data/mp3/test/";
}
ButtonTest::~ButtonTest()

View File

@@ -36,8 +36,8 @@ MicTest::MicTest()
boost::thread queue_thread = boost::thread(boost::bind(&MicTest::callbackThread, this));
boost::thread process_thread = boost::thread(boost::bind(&MicTest::processThread, this));
recording_file_name_ = ros::package::getPath("op3_demo") + "/Data/mp3/test/mic-test.wav";
default_mp3_path_ = ros::package::getPath("op3_demo") + "/Data/mp3/test/";
recording_file_name_ = ros::package::getPath("op3_demo") + "/data/mp3/test/mic-test.wav";
default_mp3_path_ = ros::package::getPath("op3_demo") + "/data/mp3/test/";
start_time_ = ros::Time::now();
}

View File

@@ -84,7 +84,7 @@ int main(int argc, char **argv)
ros::Subscriber buttuon_sub = nh.subscribe("/robotis/open_cr/button", 1, buttonHandlerCallback);
ros::Subscriber mode_command_sub = nh.subscribe("/robotis/mode_command", 1, demoModeCommandCallback);
default_mp3_path = ros::package::getPath("op3_demo") + "/Data/mp3/";
default_mp3_path = ros::package::getPath("op3_demo") + "/data/mp3/";
ros::start();