37 #ifndef JSK_PCL_ROS_TILT_LASER_LISTENER_H_ 38 #define JSK_PCL_ROS_TILT_LASER_LISTENER_H_ 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> 68 INFINITE_SPINDLE, INFINITE_SPINDLE_HALF, TILT,
TILT_HALF_UP, TILT_HALF_DOWN, PERIODIC
74 virtual void onInit();
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);
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);
bool clear_assembled_scans_
jsk_topic_tools::VitalChecker::Ptr cloud_vital_checker_
virtual double getValue()
std::string twist_frame_id_
ros::Subscriber sub_cloud_
ros::Publisher trigger_pub_
StampedJointAngle(const std_msgs::Header &header_arg, const double &value)
boost::mutex cloud_mutex_
ros::Publisher twist_pub_
boost::shared_ptr< StampedJointAngle > Ptr
ros::Timer periodic_timer_
bool use_laser_assembler_
TimeStampedVector< StampedJointAngle::Ptr > buffer_
ros::Publisher cloud_pub_
bool not_use_laser_assembler_service_
virtual ~StampedJointAngle()
boost::mutex mutex
global mutex.
ros::ServiceClient assemble_cloud_srv_
ros::ServiceServer clear_cache_service_
TimeStampedVector< sensor_msgs::PointCloud2::ConstPtr > cloud_buffer_