static_polygon_array_publisher.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/or 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 #ifndef JSK_PCL_ROS_UTILS_STATIC_POLYGON_ARRAY_PUBLISHER_H_
37 #define JSK_PCL_ROS_UTILS_STATIC_POLYGON_ARRAY_PUBLISHER_H_
38 
39 #include <ros/ros.h>
40 #include <ros/names.h>
41 #include <sensor_msgs/PointCloud2.h>
42 
43 #include <pcl_ros/pcl_nodelet.h>
44 #include <jsk_recognition_msgs/PolygonArray.h>
45 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
46 
47 #include <nodelet/nodelet.h>
49 
54 
55 #include <jsk_recognition_msgs/Int32Stamped.h>
56 #include <std_msgs/Header.h>
58 #include <jsk_topic_tools/connection_based_nodelet.h>
59 
60 namespace jsk_pcl_ros_utils
61 {
62 
63  class StaticPolygonArrayPublisher:
64  public jsk_topic_tools::ConnectionBasedNodelet
65  {
66  public:
68  sensor_msgs::PointCloud2,
69  jsk_recognition_msgs::Int32Stamped > SyncPolicy;
71 
72  protected:
75  jsk_recognition_msgs::PolygonArray polygons_;
76  jsk_recognition_msgs::ModelCoefficientsArray coefficients_;
78  bool use_periodic_;
79  bool use_message_;
80  bool use_trigger_;
81  double periodic_rate_; // in Hz
82  std::vector<std::string> frame_ids_;
87  virtual void onInit();
88  virtual void inputCallback(const sensor_msgs::PointCloud2::ConstPtr& msg);
89  virtual void timerCallback(const ros::TimerEvent& event);
90  virtual void publishPolygon(const ros::Time& stamp);
91  virtual bool readPolygonArray(const std::string& param);
92  virtual double getXMLDoubleValue(XmlRpc::XmlRpcValue val);
93  virtual PCLModelCoefficientMsg polygonToModelCoefficients(const geometry_msgs::PolygonStamped& polygon);
94  virtual void triggerCallback(const sensor_msgs::PointCloud2::ConstPtr& input,
95  const jsk_recognition_msgs::Int32Stamped::ConstPtr& trigger);
96  virtual void subscribe();
97  virtual void unsubscribe();
98  private:
99  };
100 
101 }
102 
103 #endif
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::~StaticPolygonArrayPublisher
virtual ~StaticPolygonArrayPublisher()
Definition: static_polygon_array_publisher_nodelet.cpp:132
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::polygons_
jsk_recognition_msgs::PolygonArray polygons_
Definition: static_polygon_array_publisher.h:139
ros::Publisher
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::sub_trigger_
message_filters::Subscriber< jsk_recognition_msgs::Int32Stamped > sub_trigger_
Definition: static_polygon_array_publisher.h:149
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::unsubscribe
virtual void unsubscribe()
Definition: static_polygon_array_publisher_nodelet.cpp:160
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::inputCallback
virtual void inputCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: static_polygon_array_publisher_nodelet.cpp:273
boost::shared_ptr
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::getXMLDoubleValue
virtual double getXMLDoubleValue(XmlRpc::XmlRpcValue val)
Definition: static_polygon_array_publisher_nodelet.cpp:261
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::coefficients_pub_
ros::Publisher coefficients_pub_
Definition: static_polygon_array_publisher.h:137
ros.h
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::triggerCallback
virtual void triggerCallback(const sensor_msgs::PointCloud2::ConstPtr &input, const jsk_recognition_msgs::Int32Stamped::ConstPtr &trigger)
Definition: static_polygon_array_publisher_nodelet.cpp:171
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: static_polygon_array_publisher.h:148
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::coefficients_
jsk_recognition_msgs::ModelCoefficientsArray coefficients_
Definition: static_polygon_array_publisher.h:140
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::sub_
ros::Subscriber sub_
Definition: static_polygon_array_publisher.h:138
time_synchronizer.h
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::polygon_pub_
ros::Publisher polygon_pub_
Definition: static_polygon_array_publisher.h:137
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::onInit
virtual void onInit()
Definition: static_polygon_array_publisher_nodelet.cpp:74
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::timer_
ros::Timer timer_
Definition: static_polygon_array_publisher.h:147
message_filters::Subscriber< sensor_msgs::PointCloud2 >
pcl_nodelet.h
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::timerCallback
virtual void timerCallback(const ros::TimerEvent &event)
Definition: static_polygon_array_publisher_nodelet.cpp:278
message_filters::sync_policies::ApproximateTime
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::readPolygonArray
virtual bool readPolygonArray(const std::string &param)
Definition: static_polygon_array_publisher_nodelet.cpp:208
PCLModelCoefficientMsg
pcl::ModelCoefficients PCLModelCoefficientMsg
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::periodic_timer_
ros::Timer periodic_timer_
Definition: static_polygon_array_publisher.h:141
subscriber.h
sample_camera_info_and_pointcloud_publisher.stamp
stamp
Definition: sample_camera_info_and_pointcloud_publisher.py:13
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::use_message_
bool use_message_
Definition: static_polygon_array_publisher.h:143
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::subscribe
virtual void subscribe()
Definition: static_polygon_array_publisher_nodelet.cpp:143
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::publishPolygon
virtual void publishPolygon(const ros::Time &stamp)
Definition: static_polygon_array_publisher_nodelet.cpp:283
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::use_trigger_
bool use_trigger_
Definition: static_polygon_array_publisher.h:144
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::frame_ids_
std::vector< std::string > frame_ids_
Definition: static_polygon_array_publisher.h:146
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::polygonToModelCoefficients
virtual PCLModelCoefficientMsg polygonToModelCoefficients(const geometry_msgs::PolygonStamped &polygon)
Definition: static_polygon_array_publisher_nodelet.cpp:178
ros::TimerEvent
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::SyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::Int32Stamped > SyncPolicy
Definition: static_polygon_array_publisher.h:133
pcl_conversion_util.h
shape_shifter.h
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: static_polygon_array_publisher.h:150
ros::Time
names.h
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::use_periodic_
bool use_periodic_
Definition: static_polygon_array_publisher.h:142
nodelet.h
synchronizer.h
approximate_time.h
ros::Timer
jsk_pcl_ros_utils::StaticPolygonArrayPublisher::periodic_rate_
double periodic_rate_
Definition: static_polygon_array_publisher.h:145
XmlRpc::XmlRpcValue
ros::Subscriber


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43