Skip to content

Commit 9aa4613

Browse files
now using yocs_msgs
1 parent fbef275 commit 9aa4613

File tree

4 files changed

+14
-13
lines changed

4 files changed

+14
-13
lines changed

yocs_diff_drive_pose_controller/CMakeLists.txt

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,6 @@ project(yocs_diff_drive_pose_controller)
44
find_package(catkin REQUIRED COMPONENTS ecl_threads
55
dynamic_reconfigure
66
geometry_msgs
7-
gopher_navi_msgs
87
nodelet
98
pluginlib
109
roscpp
@@ -13,14 +12,14 @@ find_package(catkin REQUIRED COMPONENTS ecl_threads
1312
tf
1413
yocs_controllers
1514
yocs_math_toolkit
15+
yocs_msgs
1616
)
1717

1818
catkin_package(INCLUDE_DIRS include
1919
LIBRARIES yocs_diff_drive_pose_controller yocs_diff_drive_pose_controller_nodelet
2020
CATKIN_DEPENDS ecl_threads
2121
dynamic_reconfigure
2222
geometry_msgs
23-
gopher_navi_msgs
2423
nodelet
2524
pluginlib
2625
roscpp
@@ -29,6 +28,7 @@ catkin_package(INCLUDE_DIRS include
2928
tf
3029
yocs_controllers
3130
yocs_math_toolkit
31+
yocs_msgs
3232
)
3333

3434
include_directories(include ${catkin_INCLUDE_DIRS})

yocs_diff_drive_pose_controller/include/yocs_diff_drive_pose_controller/diff_drive_pose_controller_ros.hpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -44,10 +44,8 @@
4444
#include <std_msgs/String.h>
4545
#include <tf/transform_listener.h>
4646
#include <boost/shared_ptr.hpp>
47-
#include <gopher_navi_msgs/PoseControllerConfig.h>
48-
#include <gopher_navi_msgs/GopherNaviConfig.h>
4947
#include <dynamic_reconfigure/server.h>
50-
48+
#include <yocs_msgs/PoseControllerConfig.h>
5149

5250
#include "yocs_diff_drive_pose_controller/diff_drive_pose_controller.hpp"
5351

@@ -138,7 +136,7 @@ class DiffDrivePoseControllerROS : public DiffDrivePoseController
138136
*/
139137
void disableCB(const std_msgs::EmptyConstPtr msg);
140138

141-
void reconfigCB(gopher_navi_msgs::PoseControllerConfig &config, uint32_t level);
139+
void reconfigCB(yocs_msgs::PoseControllerConfig &config, uint32_t level);
142140

143141
// basics
144142
ros::NodeHandle nh_;
@@ -166,10 +164,12 @@ class DiffDrivePoseControllerROS : public DiffDrivePoseController
166164
std::string goal_frame_name_;
167165

168166
///dynamic reconfigure server
169-
boost::shared_ptr<dynamic_reconfigure::Server<gopher_navi_msgs::PoseControllerConfig> > reconfig_server_;
167+
boost::shared_ptr<dynamic_reconfigure::Server<yocs_msgs::PoseControllerConfig> > reconfig_server_;
170168

171169
///dynamic reconfigure server callback type
172-
dynamic_reconfigure::Server<gopher_navi_msgs::PoseControllerConfig>::CallbackType reconfig_callback_func_;
170+
dynamic_reconfigure::Server<yocs_msgs::PoseControllerConfig>::CallbackType reconfig_callback_func_;
171+
172+
yocs_msgs::PoseControllerConfig test_;
173173

174174
ecl::Mutex dynamic_reconfig_mutex_;
175175

yocs_diff_drive_pose_controller/package.xml

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@
1818
<build_depend>ecl_threads</build_depend>
1919
<build_depend>dynamic_reconfigure</build_depend>
2020
<build_depend>geometry_msgs</build_depend>
21-
<build_depend>gopher_navi_msgs</build_depend>
2221
<build_depend>nodelet</build_depend>
2322
<build_depend>pluginlib</build_depend>
2423
<build_depend>roscpp</build_depend>
@@ -27,11 +26,12 @@
2726
<build_depend>tf</build_depend>
2827
<build_depend>yocs_controllers</build_depend>
2928
<build_depend>yocs_math_toolkit</build_depend>
29+
<build_depend>yocs_msgs</build_depend>
30+
3031

3132
<run_depend>ecl_threads</run_depend>
3233
<run_depend>dynamic_reconfigure</run_depend>
3334
<run_depend>geometry_msgs</run_depend>
34-
<run_depend>gopher_navi_msgs</run_depend>
3535
<run_depend>nodelet</run_depend>
3636
<run_depend>pluginlib</run_depend>
3737
<run_depend>roscpp</run_depend>
@@ -40,6 +40,7 @@
4040
<run_depend>tf</run_depend>
4141
<run_depend>yocs_controllers</run_depend>
4242
<run_depend>yocs_math_toolkit</run_depend>
43+
<run_depend>yocs_msgs</run_depend>
4344

4445
<export>
4546
<nodelet plugin="${prefix}/plugins/nodelets.xml"/>

yocs_diff_drive_pose_controller/src/diff_drive_pose_controller_ros.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -134,8 +134,8 @@ bool DiffDrivePoseControllerROS::init()
134134
ROS_DEBUG_STREAM(
135135
"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_ <<"]");
136136

137-
reconfig_server_ = boost::shared_ptr<dynamic_reconfigure::Server<gopher_navi_msgs::PoseControllerConfig> >(
138-
new dynamic_reconfigure::Server<gopher_navi_msgs::PoseControllerConfig>(nh_));
137+
reconfig_server_ = boost::shared_ptr<dynamic_reconfigure::Server<yocs_msgs::PoseControllerConfig> >(
138+
new dynamic_reconfigure::Server<yocs_msgs::PoseControllerConfig>(nh_));
139139
reconfig_callback_func_ = boost::bind(&DiffDrivePoseControllerROS::reconfigCB, this, _1, _2);
140140
reconfig_server_->setCallback(reconfig_callback_func_);
141141

@@ -254,7 +254,7 @@ void DiffDrivePoseControllerROS::disableCB(const std_msgs::EmptyConstPtr msg)
254254
}
255255
}
256256

257-
void DiffDrivePoseControllerROS::reconfigCB(gopher_navi_msgs::PoseControllerConfig &config, uint32_t level)
257+
void DiffDrivePoseControllerROS::reconfigCB(yocs_msgs::PoseControllerConfig &config, uint32_t level)
258258
{
259259
dynamic_reconfig_mutex_.lock();
260260
v_min_movement_ = config.v_min;

0 commit comments

Comments
 (0)