tilt_laser_listener.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 
37 #ifndef JSK_PCL_ROS_TILT_LASER_LISTENER_H_
38 #define JSK_PCL_ROS_TILT_LASER_LISTENER_H_
39 
41 #include <sensor_msgs/JointState.h>
42 #include <jsk_recognition_msgs/TimeRange.h>
44 #include <std_srvs/Empty.h>
45 #include <geometry_msgs/TwistStamped.h>
46 
47 namespace jsk_pcl_ros
48 {
50  {
51  public:
53  StampedJointAngle(const std_msgs::Header& header_arg, const double& value);
54  virtual ~StampedJointAngle() {}
55  std_msgs::Header header;
56  virtual double getValue() { return value_; }
57  protected:
58  double value_;
59  private:
60 
61  };
62 
64  {
65  public:
66  TiltLaserListener(): DiagnosticNodelet("TiltLaserListener") { };
67  enum LaserType {
68  INFINITE_SPINDLE, INFINITE_SPINDLE_HALF, TILT, TILT_HALF_UP, TILT_HALF_DOWN, PERIODIC
69  };
70  protected:
72  // methods
74  virtual void onInit();
75  virtual void subscribe();
76  virtual void unsubscribe();
77  virtual void updateDiagnostic(
79  virtual void jointCallback(const sensor_msgs::JointState::ConstPtr& msg);
80  virtual void processTiltHalfUp(const ros::Time& stamp, const double& value);
81  virtual void processTiltHalfDown(const ros::Time& stamp, const double& value);
82  virtual void processTilt(const ros::Time& stamp, const double& value);
83  virtual void processInfiniteSpindle(
84  const ros::Time& stamp, const double& joint_angle, const double& velocity,
85  const double& threshold);
86  virtual void publishTimeRange(const ros::Time& stamp,
87  const ros::Time& start,
88  const ros::Time& end);
89  virtual bool clearCacheCallback(
90  std_srvs::Empty::Request& req,
91  std_srvs::Empty::Response& res);
92  virtual void cloudCallback(
93  const sensor_msgs::PointCloud2::ConstPtr& msg);
94  virtual void getPointCloudFromLocalBuffer(
95  const std::vector<sensor_msgs::PointCloud2::ConstPtr>& target_clouds,
96  sensor_msgs::PointCloud2& output_cloud);
97  virtual void timerCallback(const ros::TimerEvent& e);
99  // ROS variables
110 
112  // parameters
115  std::string joint_name_;
116  double prev_angle_;
118  double start_angle_;
132  std::string twist_frame_id_;
133  private:
134 
135  };
136 }
137 
138 #endif
jsk_topic_tools::VitalChecker::Ptr cloud_vital_checker_
StampedJointAngle(const std_msgs::Header &header_arg, const double &value)
def timerCallback(event)
void subscribe()
boost::shared_ptr< StampedJointAngle > Ptr
TimeStampedVector< StampedJointAngle::Ptr > buffer_
boost::mutex mutex
global mutex.
TimeStampedVector< sensor_msgs::PointCloud2::ConstPtr > cloud_buffer_


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47