Skip to content

Commit ee4aef4

Browse files
authored
Merge pull request #18 from ROBOTIS-GIT/master
merge for sync kinetic-devel and master branch
2 parents e632876 + 2ee92cb commit ee4aef4

File tree

5 files changed

+11
-11
lines changed

5 files changed

+11
-11
lines changed

turtlebot3_panorama/CMakeLists.txt

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@ find_package(catkin REQUIRED COMPONENTS
1515
sensor_msgs
1616
geometry_msgs
1717
nav_msgs
18-
turtlebot3_msgs
18+
turtlebot3_applications_msgs
1919
cv_bridge
2020
image_transport
2121
cmake_modules
@@ -38,7 +38,7 @@ find_package(OpenCV REQUIRED)
3838
################################################################################
3939
catkin_package(
4040
INCLUDE_DIRS include
41-
CATKIN_DEPENDS roscpp rospy std_msgs std_srvs sensor_msgs geometry_msgs nav_msgs turtlebot3_msgs cv_bridge image_transport cmake_modules
41+
CATKIN_DEPENDS roscpp rospy std_msgs std_srvs sensor_msgs geometry_msgs nav_msgs turtlebot3_applications_msgs cv_bridge image_transport cmake_modules
4242
DEPENDS Boost Eigen3 OpenCV
4343
)
4444

turtlebot3_panorama/include/turtlebot3_panorama/panorama.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@
5151
#include <geometry_msgs/Twist.h>
5252
#include <nav_msgs/Odometry.h>
5353
#include <image_transport/image_transport.h>
54-
#include <turtlebot3_msgs/TakePanorama.h>
54+
#include <turtlebot3_applications_msgs/TakePanorama.h>
5555

5656
#include "geometry.h"
5757

@@ -137,8 +137,8 @@ class PanoApp
137137
* @param response the current state of the app (started, in progress, stopped)
138138
* @return true, if service call was successful
139139
*/
140-
bool takePanoServiceCb(turtlebot3_msgs::TakePanorama::Request& request,
141-
turtlebot3_msgs::TakePanorama::Response& response);
140+
bool takePanoServiceCb(turtlebot3_applications_msgs::TakePanorama::Request& request,
141+
turtlebot3_applications_msgs::TakePanorama::Response& response);
142142

143143
void snap();
144144

turtlebot3_panorama/launch/panorama.launch

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<!-- Camera Image Transport to raw--> I
33
<node pkg="image_transport" type="republish" name="republish" output="screen" args="compressed in:=/raspicam_node/image raw out:=/camera/rgb/image_raw" />
44

5-
<node pkg="turtlebot3_panorama" type="turtlebot3_panorama" name="turtlebot3_panorama">
5+
<node pkg="turtlebot3_panorama" type="turtlebot3_panorama" name="turtlebot3_panorama" respawn="false" output="screen">
66
<param name="default_mode" value="1"/>
77
<param name="default_pano_angle" value="6.28318530718"/> <!-- 2 * Pi -->
88
<param name="default_snap_interval" value="2.0"/>

turtlebot3_panorama/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@
2323
<depend>sensor_msgs</depend>
2424
<depend>geometry_msgs</depend>
2525
<depend>nav_msgs</depend>
26-
<depend>turtlebot3_msgs</depend>
26+
<depend>turtlebot3_applications_msgs</depend>
2727
<depend>cv_bridge</depend>
2828
<depend>image_transport</depend>
2929
<depend>cmake_modules</depend>

turtlebot3_panorama/src/panorama.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -151,7 +151,7 @@ void PanoApp::spin()
151151
}
152152
if (take_snapshot)
153153
{
154-
if (std::abs(ang_vel_cur) <= 0.000001) // wait until robot has stopped
154+
if (std::abs(ang_vel_cur) <= 0.01) // wait until robot has stopped
155155
{
156156
snap();
157157
take_snapshot = false;
@@ -232,8 +232,8 @@ void PanoApp::odomCb(const nav_msgs::OdometryConstPtr& msg)
232232
//*************************
233233
// Public interface
234234
//*************************
235-
bool PanoApp::takePanoServiceCb(turtlebot3_msgs::TakePanorama::Request& request,
236-
turtlebot3_msgs::TakePanorama::Response& response)
235+
bool PanoApp::takePanoServiceCb(turtlebot3_applications_msgs::TakePanorama::Request& request,
236+
turtlebot3_applications_msgs::TakePanorama::Response& response)
237237
{
238238
if (is_active && (request.mode == request.CONTINUOUS || request.mode == request.SNAPANDROTATE))
239239
{
@@ -276,7 +276,7 @@ bool PanoApp::takePanoServiceCb(turtlebot3_msgs::TakePanorama::Request& request,
276276
snap_interval = request.snap_interval;
277277
cmd_vel.angular.z = request.rot_vel;
278278
}
279-
if (request.mode == turtlebot3_msgs::TakePanoramaRequest::CONTINUOUS)
279+
if (request.mode == turtlebot3_applications_msgs::TakePanoramaRequest::CONTINUOUS)
280280
{
281281
continuous = true;
282282
}

0 commit comments

Comments
 (0)