00001 /****************************************************************************** 00002 Copyright (c) 2016, Intel Corporation 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 1. Redistributions of source code must retain the above copyright notice, this 00009 list of conditions and the following disclaimer. 00010 00011 2. Redistributions in binary form must reproduce the above copyright notice, 00012 this list of conditions and the following disclaimer in the documentation 00013 and/or other materials provided with the distribution. 00014 00015 3. Neither the name of the copyright holder nor the names of its contributors 00016 may be used to endorse or promote products derived from this software without 00017 specific prior written permission. 00018 00019 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00020 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00021 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00022 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 00023 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 00024 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 00025 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00026 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 00027 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 00028 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00029 *******************************************************************************/ 00030 00031 #pragma once 00032 #ifndef REALSENSE_CAMERA_ZR300_NODELET_H 00033 #define REALSENSE_CAMERA_ZR300_NODELET_H 00034 00035 #include <string> 00036 #include <vector> 00037 00038 #include <dynamic_reconfigure/server.h> 00039 #include <sensor_msgs/Imu.h> 00040 00041 #include <realsense_camera/zr300_paramsConfig.h> 00042 #include <realsense_camera/IMUInfo.h> 00043 #include <realsense_camera/GetIMUInfo.h> 00044 #include <realsense_camera/base_nodelet.h> 00045 00046 namespace realsense_camera 00047 { 00048 class ZR300Nodelet: public realsense_camera::BaseNodelet 00049 { 00050 public: 00051 ~ZR300Nodelet(); 00052 void onInit(); 00053 00054 protected: 00055 // Member Variables. 00056 ros::ServiceServer get_imu_info_; 00057 boost::shared_ptr<dynamic_reconfigure::Server<realsense_camera::zr300_paramsConfig>> dynamic_reconf_server_; 00058 bool enable_imu_; 00059 std::string imu_frame_id_; 00060 std::string imu_optical_frame_id_; 00061 geometry_msgs::Vector3 imu_angular_vel_; 00062 geometry_msgs::Vector3 imu_linear_accel_; 00063 double imu_ts_; 00064 double prev_imu_ts_; 00065 ros::Publisher imu_publisher_; 00066 boost::shared_ptr<boost::thread> imu_thread_; 00067 std::function<void(rs::motion_data)> motion_handler_; 00068 std::function<void(rs::timestamp_data)> timestamp_handler_; 00069 std::mutex imu_mutex_; 00070 00071 rs_extrinsics color2ir2_extrinsic_; // color frame is base frame 00072 rs_extrinsics color2fisheye_extrinsic_; // color frame is base frame 00073 rs_extrinsics color2imu_extrinsic_; // color frame is base frame 00074 00075 // Member Functions. 00076 void getParameters(); 00077 void advertiseTopics(); 00078 void advertiseServices(); 00079 bool getIMUInfo(realsense_camera::GetIMUInfo::Request & req, realsense_camera::GetIMUInfo::Response & res); 00080 std::vector<std::string> setDynamicReconfServer(); 00081 void startDynamicReconfCallback(); 00082 void setDynamicReconfigDepthControlPreset(int preset); 00083 std::string setDynamicReconfigDepthControlIndividuals(); 00084 void configCallback(realsense_camera::zr300_paramsConfig &config, uint32_t level); 00085 void getCameraExtrinsics(); 00086 void publishStaticTransforms(); 00087 void publishDynamicTransforms(); 00088 void publishIMU(); 00089 void setStreams(); 00090 void setIMUCallbacks(); 00091 void setFrameCallbacks(); 00092 std::function<void(rs::frame f)> fisheye_frame_handler_, ir2_frame_handler_; 00093 void stopIMU(); 00094 }; 00095 } // namespace realsense_camera 00096 #endif // REALSENSE_CAMERA_ZR300_NODELET_H