00001 /* 00002 * Copyright (c) 2013, Yujin Robot. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of Yujin Robot nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00040 /***************************************************************************** 00041 ** Ifdefs 00042 *****************************************************************************/ 00043 00044 #ifndef PANORAMA_H_ 00045 #define PANORAMA_H_ 00046 00047 #include <ros/ros.h> 00048 #include <actionlib/client/simple_action_client.h> 00049 #include <actionlib/client/terminal_state.h> 00050 #include <pano_ros/PanoCaptureAction.h> 00051 #include <image_transport/image_transport.h> 00052 #include <sensor_msgs/Image.h> 00053 #include <std_msgs/Empty.h> 00054 #include <std_msgs/String.h> 00055 #include <nav_msgs/Odometry.h> 00056 #include <geometry_msgs/Twist.h> 00057 #include "geometry.h" 00058 #include <turtlebot_panorama/TakePano.h> 00059 00060 #include <std_srvs/Empty.h> 00061 00062 namespace turtlebot_panorama 00063 { 00064 00068 class PanoApp 00069 { 00070 public: 00071 PanoApp(); 00072 ~PanoApp(); 00073 00074 void init(); 00075 void spin(); 00076 00081 void log(std::string msg); 00082 00083 private: 00084 ros::NodeHandle nh; 00085 ros::NodeHandle priv_nh; 00086 std::map<std::string, std::string> params; 00087 std_msgs::Empty empty_msg; 00088 geometry_msgs::Twist cmd_vel, zero_cmd_vel; 00089 double snap_interval; 00090 double angle, last_angle, given_angle, ang_vel_cur; 00091 // panorama creation mode (continuously rotating while taking snapshots or rotate, stop, snapshot, rotate, ...) 00092 bool continuous; 00093 00094 // public API 00095 // Service for starting the creation of a panorama picture 00096 ros::ServiceServer srv_start_pano; 00097 // Subscriber for starting the creation of a panorama picture 00098 ros::Subscriber sub_start_pano; 00099 // Subscriber for stopping the creation of a panorama picture 00100 ros::Subscriber sub_stop_pano; 00101 // Sends out the result of the stitched panorama picture 00102 image_transport::Publisher pub_stitched; 00103 00104 // worker functions 00105 // for extra logging out via a ROS topic 00106 ros::Publisher pub_log; 00107 // for turning the robot 00108 ros::Publisher pub_cmd_vel; 00109 // for retrieving the odometry of robot 00110 ros::Subscriber sub_odom; 00111 00112 // pano_ros API 00113 // client for the pano_ros action server (does the actual work) 00114 actionlib::SimpleActionClient<pano_ros::PanoCaptureAction>* pano_ros_client; 00115 // trigger snapshot taking by pano_ros 00116 ros::Publisher pub_action_snap; 00120 ros::Publisher pub_action_stop; 00121 // recevices the stitched image from pano_ros 00122 image_transport::Subscriber sub_stitched; 00126 bool is_active; 00132 bool go_active; 00136 int default_mode; 00140 double default_pano_angle; 00144 double default_snap_interval; 00148 double default_rotation_velocity; 00149 00156 bool takePanoServiceCb(TakePano::Request& request, TakePano::Response& response); 00157 // bool takePanoServiceCb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response); 00158 00163 void takePanoCb(const std_msgs::EmptyConstPtr& msg); 00164 00169 void stopPanoCb(const std_msgs::EmptyConstPtr& msg); 00170 00174 void snap(); 00175 00179 void rotate(); 00180 00184 bool hasReachedAngle(); 00185 00190 void odomCb(const nav_msgs::OdometryConstPtr& msg); 00191 00195 void startPanoAction(); 00196 00200 void stopPanoAction(); 00201 // Note: pano_ros throws an error, when it hasn't taken a snapshot yet. 00202 // TODO: Try to find a way to check, when stitching is possible and when the action goal needs to be cancelled. 00203 00207 void activeCb(); 00208 00213 void feedbackCb(const pano_ros::PanoCaptureFeedbackConstPtr& feedback); 00214 00220 void doneCb(const actionlib::SimpleClientGoalState& state, const pano_ros::PanoCaptureResultConstPtr& result); 00221 00226 void stitchedImageCb(const sensor_msgs::ImageConstPtr& msg); 00227 }; 00228 00229 } //namespace turtlebot_panorama 00230 00231 #endif /* PANORAMA_H_ */