Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
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, PERIODIC
00069 };
00070 protected:
00072
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);
00097 virtual void timerCallback(const ros::TimerEvent& e);
00099
00101 ros::Subscriber sub_;
00102 ros::Subscriber sub_cloud_;
00103 ros::Publisher trigger_pub_;
00104 ros::Publisher cloud_pub_;
00105 ros::Publisher twist_pub_;
00106 ros::ServiceServer clear_cache_service_;
00107 ros::ServiceClient assemble_cloud_srv_;
00108 jsk_topic_tools::VitalChecker::Ptr cloud_vital_checker_;
00109 ros::Timer periodic_timer_;
00110
00112
00114 LaserType laser_type_;
00115 std::string joint_name_;
00116 double prev_angle_;
00117 double prev_velocity_;
00118 double start_angle_;
00119 double overwrap_angle_;
00120 ros::Time start_time_;
00121 bool use_laser_assembler_;
00122 bool not_use_laser_assembler_service_;
00123 bool clear_assembled_scans_;
00124 boost::mutex mutex_;
00125 boost::mutex cloud_mutex_;
00126 TimeStampedVector<StampedJointAngle::Ptr> buffer_;
00127 TimeStampedVector<sensor_msgs::PointCloud2::ConstPtr> cloud_buffer_;
00128 int skip_number_;
00129 int skip_counter_;
00130 int max_queue_size_;
00131 double publish_rate_;
00132 std::string twist_frame_id_;
00133 private:
00134
00135 };
00136 }
00137
00138 #endif