Skip to content

Commit

Permalink
now using yocs_msgs
Browse files Browse the repository at this point in the history
  • Loading branch information
Marco-Andarcia committed Nov 23, 2016
1 parent fbef275 commit 9aa4613
Show file tree
Hide file tree
Showing 4 changed files with 14 additions and 13 deletions.
4 changes: 2 additions & 2 deletions yocs_diff_drive_pose_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -13,14 +12,14 @@ 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
gopher_navi_msgs
nodelet
pluginlib
roscpp
Expand All @@ -29,6 +28,7 @@ catkin_package(INCLUDE_DIRS include
tf
yocs_controllers
yocs_math_toolkit
yocs_msgs
)

include_directories(include ${catkin_INCLUDE_DIRS})
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,10 +44,8 @@
#include <std_msgs/String.h>
#include <tf/transform_listener.h>
#include <boost/shared_ptr.hpp>
#include <gopher_navi_msgs/PoseControllerConfig.h>
#include <gopher_navi_msgs/GopherNaviConfig.h>
#include <dynamic_reconfigure/server.h>

#include <yocs_msgs/PoseControllerConfig.h>

#include "yocs_diff_drive_pose_controller/diff_drive_pose_controller.hpp"

Expand Down Expand Up @@ -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_;
Expand Down Expand Up @@ -166,10 +164,12 @@ class DiffDrivePoseControllerROS : public DiffDrivePoseController
std::string goal_frame_name_;

///dynamic reconfigure server
boost::shared_ptr<dynamic_reconfigure::Server<gopher_navi_msgs::PoseControllerConfig> > reconfig_server_;
boost::shared_ptr<dynamic_reconfigure::Server<yocs_msgs::PoseControllerConfig> > reconfig_server_;

///dynamic reconfigure server callback type
dynamic_reconfigure::Server<gopher_navi_msgs::PoseControllerConfig>::CallbackType reconfig_callback_func_;
dynamic_reconfigure::Server<yocs_msgs::PoseControllerConfig>::CallbackType reconfig_callback_func_;

yocs_msgs::PoseControllerConfig test_;

ecl::Mutex dynamic_reconfig_mutex_;

Expand Down
5 changes: 3 additions & 2 deletions yocs_diff_drive_pose_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
<build_depend>ecl_threads</build_depend>
<build_depend>dynamic_reconfigure</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>gopher_navi_msgs</build_depend>
<build_depend>nodelet</build_depend>
<build_depend>pluginlib</build_depend>
<build_depend>roscpp</build_depend>
Expand All @@ -27,11 +26,12 @@
<build_depend>tf</build_depend>
<build_depend>yocs_controllers</build_depend>
<build_depend>yocs_math_toolkit</build_depend>
<build_depend>yocs_msgs</build_depend>


<run_depend>ecl_threads</run_depend>
<run_depend>dynamic_reconfigure</run_depend>
<run_depend>geometry_msgs</run_depend>
<run_depend>gopher_navi_msgs</run_depend>
<run_depend>nodelet</run_depend>
<run_depend>pluginlib</run_depend>
<run_depend>roscpp</run_depend>
Expand All @@ -40,6 +40,7 @@
<run_depend>tf</run_depend>
<run_depend>yocs_controllers</run_depend>
<run_depend>yocs_math_toolkit</run_depend>
<run_depend>yocs_msgs</run_depend>

<export>
<nodelet plugin="${prefix}/plugins/nodelets.xml"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<dynamic_reconfigure::Server<gopher_navi_msgs::PoseControllerConfig> >(
new dynamic_reconfigure::Server<gopher_navi_msgs::PoseControllerConfig>(nh_));
reconfig_server_ = boost::shared_ptr<dynamic_reconfigure::Server<yocs_msgs::PoseControllerConfig> >(
new dynamic_reconfigure::Server<yocs_msgs::PoseControllerConfig>(nh_));
reconfig_callback_func_ = boost::bind(&DiffDrivePoseControllerROS::reconfigCB, this, _1, _2);
reconfig_server_->setCallback(reconfig_callback_func_);

Expand Down Expand Up @@ -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;
Expand Down

0 comments on commit 9aa4613

Please sign in to comment.