diff --git a/yocs_diff_drive_pose_controller/CMakeLists.txt b/yocs_diff_drive_pose_controller/CMakeLists.txt index 94bec739..2524411e 100644 --- a/yocs_diff_drive_pose_controller/CMakeLists.txt +++ b/yocs_diff_drive_pose_controller/CMakeLists.txt @@ -2,6 +2,7 @@ cmake_minimum_required(VERSION 2.8.3) project(yocs_diff_drive_pose_controller) find_package(catkin REQUIRED COMPONENTS ecl_threads + dynamic_reconfigure geometry_msgs nodelet pluginlib @@ -11,11 +12,13 @@ find_package(catkin REQUIRED COMPONENTS ecl_threads tf yocs_controllers yocs_math_toolkit + yocs_msgs ) catkin_package(INCLUDE_DIRS include LIBRARIES yocs_diff_drive_pose_controller yocs_diff_drive_pose_controller_nodelet CATKIN_DEPENDS ecl_threads + dynamic_reconfigure geometry_msgs nodelet pluginlib @@ -25,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.hpp b/yocs_diff_drive_pose_controller/include/yocs_diff_drive_pose_controller/diff_drive_pose_controller.hpp index 8398c550..94829fb8 100644 --- a/yocs_diff_drive_pose_controller/include/yocs_diff_drive_pose_controller/diff_drive_pose_controller.hpp +++ b/yocs_diff_drive_pose_controller/include/yocs_diff_drive_pose_controller/diff_drive_pose_controller.hpp @@ -3,6 +3,7 @@ #include #include +#include namespace yocs { @@ -171,6 +172,8 @@ class DiffDrivePoseController : public Controller double orient_eps_; /// Enable or disable ros messages. bool verbose_; + + ecl::Mutex controller_mutex_; }; } /* end namespace */ 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 07103bb3..6ea8b2ac 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 @@ -38,10 +38,14 @@ ** Includes *****************************************************************************/ #include +#include #include #include #include #include +#include +#include +#include #include "yocs_diff_drive_pose_controller/diff_drive_pose_controller.hpp" @@ -132,6 +136,8 @@ class DiffDrivePoseControllerROS : public DiffDrivePoseController */ void disableCB(const std_msgs::EmptyConstPtr msg); + void reconfigCB(yocs_msgs::PoseControllerConfig &config, uint32_t level); + // basics ros::NodeHandle nh_; std::string name_; @@ -156,6 +162,10 @@ class DiffDrivePoseControllerROS : public DiffDrivePoseController std::string base_frame_name_; /// frame name of the goal (pose) std::string goal_frame_name_; + + ///dynamic reconfigure server + boost::shared_ptr > reconfig_server_; + }; } // namespace yocs diff --git a/yocs_diff_drive_pose_controller/package.xml b/yocs_diff_drive_pose_controller/package.xml index d872eeb8..2d678b15 100644 --- a/yocs_diff_drive_pose_controller/package.xml +++ b/yocs_diff_drive_pose_controller/package.xml @@ -12,10 +12,11 @@ http://ros.org/wiki/yocs_diff_drive_pose_controller https://github.com/yujinrobot/yujin_ocs https://github.com/yujinrobot/yujin_ocs/issues - + catkin ecl_threads + dynamic_reconfigure geometry_msgs nodelet pluginlib @@ -25,8 +26,11 @@ tf yocs_controllers yocs_math_toolkit + yocs_msgs + ecl_threads + dynamic_reconfigure geometry_msgs nodelet pluginlib @@ -36,7 +40,8 @@ tf yocs_controllers yocs_math_toolkit - + yocs_msgs + diff --git a/yocs_diff_drive_pose_controller/src/diff_drive_pose_controller.cpp b/yocs_diff_drive_pose_controller/src/diff_drive_pose_controller.cpp index a385f015..fe5d8639 100644 --- a/yocs_diff_drive_pose_controller/src/diff_drive_pose_controller.cpp +++ b/yocs_diff_drive_pose_controller/src/diff_drive_pose_controller.cpp @@ -62,6 +62,7 @@ bool DiffDrivePoseController::step() void DiffDrivePoseController::calculateControls() { + controller_mutex_.lock(); double angle_diff = mtk::wrapAngle(theta_ - delta_); if (r_ > dist_thres_) @@ -97,6 +98,7 @@ void DiffDrivePoseController::calculateControls() } } } + controller_mutex_.unlock(); } void DiffDrivePoseController::controlPose() @@ -126,7 +128,6 @@ void DiffDrivePoseController::controlPose() void DiffDrivePoseController::controlOrientation(double angle_difference) { - w_ = orientation_gain_ * (angle_difference); //enforce limits on angular velocity 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 222440c1..53e5e983 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 @@ -133,6 +133,17 @@ bool DiffDrivePoseControllerROS::init() "base_frame_name = " << base_frame_name_ <<", goal_frame_name = " << goal_frame_name_ << " [" << name_ <<"]"); 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_)); + + ///dynamic reconfigure server callback type + dynamic_reconfigure::Server::CallbackType reconfig_callback_func; + + reconfig_callback_func = boost::bind(&DiffDrivePoseControllerROS::reconfigCB, this, _1, _2); + + reconfig_server_->setCallback(reconfig_callback_func); + return true; } @@ -248,4 +259,22 @@ void DiffDrivePoseControllerROS::disableCB(const std_msgs::EmptyConstPtr msg) } } +void DiffDrivePoseControllerROS::reconfigCB(yocs_msgs::PoseControllerConfig &config, uint32_t level) +{ + controller_mutex_.lock(); + v_min_movement_ = config.v_min; + v_max_ = config.v_max; + w_max_ = config.w_max; + w_min_ = config.w_min; + k_1_ = config.k_1; + k_2_ = config.k_2; + beta_ = config.beta; + lambda_ = config.lambda; + dist_thres_ = config.dist_thres; + orient_thres_ = config.orient_thres; + dist_eps_ = config.dist_eps; + orient_eps_ = config.orient_eps; + controller_mutex_.unlock(); +} + } // namespace yocs