From 9aa46132bc12db6928045a024c5b73bb03e64bb8 Mon Sep 17 00:00:00 2001 From: Marco Andarcia Date: Wed, 23 Nov 2016 16:11:23 +0900 Subject: [PATCH] now using yocs_msgs --- yocs_diff_drive_pose_controller/CMakeLists.txt | 4 ++-- .../diff_drive_pose_controller_ros.hpp | 12 ++++++------ yocs_diff_drive_pose_controller/package.xml | 5 +++-- .../src/diff_drive_pose_controller_ros.cpp | 6 +++--- 4 files changed, 14 insertions(+), 13 deletions(-) diff --git a/yocs_diff_drive_pose_controller/CMakeLists.txt b/yocs_diff_drive_pose_controller/CMakeLists.txt index c87453ef..2524411e 100644 --- a/yocs_diff_drive_pose_controller/CMakeLists.txt +++ b/yocs_diff_drive_pose_controller/CMakeLists.txt @@ -4,7 +4,6 @@ project(yocs_diff_drive_pose_controller) find_package(catkin REQUIRED COMPONENTS ecl_threads dynamic_reconfigure geometry_msgs - gopher_navi_msgs nodelet pluginlib roscpp @@ -13,6 +12,7 @@ find_package(catkin REQUIRED COMPONENTS ecl_threads tf yocs_controllers yocs_math_toolkit + yocs_msgs ) catkin_package(INCLUDE_DIRS include @@ -20,7 +20,6 @@ catkin_package(INCLUDE_DIRS include CATKIN_DEPENDS ecl_threads dynamic_reconfigure geometry_msgs - gopher_navi_msgs nodelet pluginlib roscpp @@ -29,6 +28,7 @@ catkin_package(INCLUDE_DIRS include tf yocs_controllers yocs_math_toolkit + yocs_msgs ) include_directories(include ${catkin_INCLUDE_DIRS}) diff --git a/yocs_diff_drive_pose_controller/include/yocs_diff_drive_pose_controller/diff_drive_pose_controller_ros.hpp b/yocs_diff_drive_pose_controller/include/yocs_diff_drive_pose_controller/diff_drive_pose_controller_ros.hpp index c41d3063..7d17c84d 100644 --- a/yocs_diff_drive_pose_controller/include/yocs_diff_drive_pose_controller/diff_drive_pose_controller_ros.hpp +++ b/yocs_diff_drive_pose_controller/include/yocs_diff_drive_pose_controller/diff_drive_pose_controller_ros.hpp @@ -44,10 +44,8 @@ #include #include #include -#include -#include #include - +#include #include "yocs_diff_drive_pose_controller/diff_drive_pose_controller.hpp" @@ -138,7 +136,7 @@ class DiffDrivePoseControllerROS : public DiffDrivePoseController */ void disableCB(const std_msgs::EmptyConstPtr msg); - void reconfigCB(gopher_navi_msgs::PoseControllerConfig &config, uint32_t level); + void reconfigCB(yocs_msgs::PoseControllerConfig &config, uint32_t level); // basics ros::NodeHandle nh_; @@ -166,10 +164,12 @@ class DiffDrivePoseControllerROS : public DiffDrivePoseController std::string goal_frame_name_; ///dynamic reconfigure server - boost::shared_ptr > reconfig_server_; + boost::shared_ptr > reconfig_server_; ///dynamic reconfigure server callback type - dynamic_reconfigure::Server::CallbackType reconfig_callback_func_; + dynamic_reconfigure::Server::CallbackType reconfig_callback_func_; + + yocs_msgs::PoseControllerConfig test_; ecl::Mutex dynamic_reconfig_mutex_; diff --git a/yocs_diff_drive_pose_controller/package.xml b/yocs_diff_drive_pose_controller/package.xml index 182ee2c7..2d678b15 100644 --- a/yocs_diff_drive_pose_controller/package.xml +++ b/yocs_diff_drive_pose_controller/package.xml @@ -18,7 +18,6 @@ ecl_threads dynamic_reconfigure geometry_msgs - gopher_navi_msgs nodelet pluginlib roscpp @@ -27,11 +26,12 @@ tf yocs_controllers yocs_math_toolkit + yocs_msgs + ecl_threads dynamic_reconfigure geometry_msgs - gopher_navi_msgs nodelet pluginlib roscpp @@ -40,6 +40,7 @@ tf yocs_controllers yocs_math_toolkit + yocs_msgs diff --git a/yocs_diff_drive_pose_controller/src/diff_drive_pose_controller_ros.cpp b/yocs_diff_drive_pose_controller/src/diff_drive_pose_controller_ros.cpp index 7c1087b8..50394912 100644 --- a/yocs_diff_drive_pose_controller/src/diff_drive_pose_controller_ros.cpp +++ b/yocs_diff_drive_pose_controller/src/diff_drive_pose_controller_ros.cpp @@ -134,8 +134,8 @@ bool DiffDrivePoseControllerROS::init() ROS_DEBUG_STREAM( "v_max = " << v_max_ <<", k_1 = " << k_1_ << ", k_2 = " << k_2_ << ", beta = " << beta_ << ", lambda = " << lambda_ << ", dist_thres = " << dist_thres_ << ", orient_thres = " << orient_thres_ <<" [" << name_ <<"]"); - reconfig_server_ = boost::shared_ptr >( - new dynamic_reconfigure::Server(nh_)); + reconfig_server_ = boost::shared_ptr >( + new dynamic_reconfigure::Server(nh_)); reconfig_callback_func_ = boost::bind(&DiffDrivePoseControllerROS::reconfigCB, this, _1, _2); reconfig_server_->setCallback(reconfig_callback_func_); @@ -254,7 +254,7 @@ void DiffDrivePoseControllerROS::disableCB(const std_msgs::EmptyConstPtr msg) } } -void DiffDrivePoseControllerROS::reconfigCB(gopher_navi_msgs::PoseControllerConfig &config, uint32_t level) +void DiffDrivePoseControllerROS::reconfigCB(yocs_msgs::PoseControllerConfig &config, uint32_t level) { dynamic_reconfig_mutex_.lock(); v_min_movement_ = config.v_min;