tilt_laser_listener.h
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 
00037 #ifndef JSK_PCL_ROS_TILT_LASER_LISTENER_H_
00038 #define JSK_PCL_ROS_TILT_LASER_LISTENER_H_
00039 
00040 #include <jsk_topic_tools/diagnostic_nodelet.h>
00041 #include <sensor_msgs/JointState.h>
00042 #include <jsk_recognition_msgs/TimeRange.h>
00043 #include "jsk_pcl_ros/line_segment_collector.h"
00044 #include <std_srvs/Empty.h>
00045 #include <geometry_msgs/TwistStamped.h>
00046 
00047 namespace jsk_pcl_ros
00048 {
00049   class StampedJointAngle
00050   {
00051   public:
00052     typedef boost::shared_ptr<StampedJointAngle> Ptr;
00053     StampedJointAngle(const std_msgs::Header& header_arg, const double& value);
00054     virtual ~StampedJointAngle() {}
00055     std_msgs::Header header;
00056     virtual double getValue() { return value_; }
00057   protected:
00058     double value_;
00059   private:
00060     
00061   };
00062   
00063   class TiltLaserListener: public jsk_topic_tools::DiagnosticNodelet
00064   {
00065   public:
00066     TiltLaserListener(): DiagnosticNodelet("TiltLaserListener") { };
00067     enum LaserType {
00068       INFINITE_SPINDLE, INFINITE_SPINDLE_HALF, TILT, TILT_HALF_UP, TILT_HALF_DOWN
00069     };
00070   protected:
00072     // methods
00074     virtual void onInit();
00075     virtual void subscribe();
00076     virtual void unsubscribe();
00077     virtual void updateDiagnostic(
00078       diagnostic_updater::DiagnosticStatusWrapper &stat);
00079     virtual void jointCallback(const sensor_msgs::JointState::ConstPtr& msg);
00080     virtual void processTiltHalfUp(const ros::Time& stamp, const double& value);
00081     virtual void processTiltHalfDown(const ros::Time& stamp, const double& value);
00082     virtual void processTilt(const ros::Time& stamp, const double& value);
00083     virtual void processInfiniteSpindle(
00084       const ros::Time& stamp, const double& joint_angle, const double& velocity,
00085       const double& threshold);
00086     virtual void publishTimeRange(const ros::Time& stamp,
00087                                   const ros::Time& start,
00088                                   const ros::Time& end);
00089     virtual bool clearCacheCallback(
00090       std_srvs::Empty::Request& req,
00091       std_srvs::Empty::Response& res);
00092     virtual void cloudCallback(
00093       const sensor_msgs::PointCloud2::ConstPtr& msg);
00094     virtual void getPointCloudFromLocalBuffer(
00095       const std::vector<sensor_msgs::PointCloud2::ConstPtr>& target_clouds,
00096       sensor_msgs::PointCloud2& output_cloud);
00098     // ROS variables
00100     ros::Subscriber sub_;
00101     ros::Subscriber sub_cloud_;
00102     ros::Publisher trigger_pub_;
00103     ros::Publisher cloud_pub_;
00104     ros::Publisher twist_pub_;
00105     ros::ServiceServer clear_cache_service_;
00106     ros::ServiceClient assemble_cloud_srv_;
00107     jsk_topic_tools::VitalChecker::Ptr cloud_vital_checker_;
00108 
00110     // parameters
00112     LaserType laser_type_;
00113     std::string joint_name_;
00114     double prev_angle_;
00115     double prev_velocity_;
00116     double start_angle_;
00117     double overwrap_angle_;
00118     ros::Time start_time_;
00119     bool use_laser_assembler_;
00120     bool not_use_laser_assembler_service_;
00121     bool clear_assembled_scans_;
00122     boost::mutex mutex_;
00123     boost::mutex cloud_mutex_;
00124     TimeStampedVector<StampedJointAngle::Ptr> buffer_;
00125     TimeStampedVector<sensor_msgs::PointCloud2::ConstPtr> cloud_buffer_;
00126     int skip_number_;
00127     int skip_counter_;
00128     int max_queue_size_;
00129     std::string twist_frame_id_;
00130   private:
00131     
00132   };
00133 }
00134 
00135 #endif


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:48