rect_to_roi.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, 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 
37 #include <boost/assign.hpp>
38 #include <jsk_topic_tools/log_utils.h>
39 
40 namespace jsk_perception
41 {
42  void RectToROI::onInit()
43  {
44  DiagnosticNodelet::onInit();
45  pub_ = advertise<sensor_msgs::CameraInfo>(*pnh_, "output", 1);
46  onInitPostProcess();
47  }
48 
50  {
51  sub_rect_ = pnh_->subscribe(
52  "input", 1, &RectToROI::rectCallback, this);
53  sub_info_ = pnh_->subscribe(
54  "input/camera_info", 1, &RectToROI::infoCallback, this);
55  ros::V_string names = boost::assign::list_of("~input")("~input/camera_info");
56  jsk_topic_tools::warnNoRemap(names);
57  }
58 
60  {
63  }
64 
66  const sensor_msgs::CameraInfo::ConstPtr& info_msg)
67  {
68  boost::mutex::scoped_lock lock(mutex_);
70  }
71 
73  const geometry_msgs::PolygonStamped::ConstPtr& rect_msg)
74  {
75  boost::mutex::scoped_lock lock(mutex_);
76  if (latest_camera_info_) {
77  sensor_msgs::CameraInfo roi(*latest_camera_info_);
78  geometry_msgs::Point32 P0 = rect_msg->polygon.points[0];
79  geometry_msgs::Point32 P1 = rect_msg->polygon.points[1];
80  double min_x = std::max(std::min(P0.x, P1.x), 0.0f);
81  double max_x = std::max(P0.x, P1.x);
82  double min_y = std::max(std::min(P0.y, P1.y), 0.0f);
83  double max_y = std::max(P0.y, P1.y);
84  double width = std::min(max_x - min_x, latest_camera_info_->width - min_x);
85  double height = std::min(max_y - min_y, latest_camera_info_->height - min_y);
86  roi.roi.x_offset = (int)min_x;
87  roi.roi.y_offset = (int)min_y;
88  roi.roi.height = height;
89  roi.roi.width = width;
90  pub_.publish(roi);
91  }
92  else {
93  NODELET_ERROR("camera info is not yet available");
94  }
95  }
96 }
97 
jsk_perception::RectToROI::sub_rect_
ros::Subscriber sub_rect_
Definition: rect_to_roi.h:124
jsk_perception::RectToROI::pub_
ros::Publisher pub_
Definition: rect_to_roi.h:126
NODELET_ERROR
#define NODELET_ERROR(...)
jsk_perception::RectToROI::rectCallback
virtual void rectCallback(const geometry_msgs::PolygonStamped::ConstPtr &rect_msg)
Definition: rect_to_roi.cpp:104
ssd_train_dataset.int
int
Definition: ssd_train_dataset.py:175
jsk_perception::RectToROI::onInit
virtual void onInit()
Definition: rect_to_roi.cpp:74
ros::Subscriber::shutdown
void shutdown()
jsk_perception::RectToROI::mutex_
boost::mutex mutex_
Definition: rect_to_roi.h:123
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
class_list_macros.h
jsk_perception
Definition: add_mask_image.h:48
jsk_perception::RectToROI
Definition: rect_to_roi.h:78
jsk_perception::RectToROI::sub_info_
ros::Subscriber sub_info_
Definition: rect_to_roi.h:125
lock
mutex_t * lock
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_perception::RectToROI, nodelet::Nodelet)
width
width
jsk_perception::RectToROI::latest_camera_info_
sensor_msgs::CameraInfo::ConstPtr latest_camera_info_
Definition: rect_to_roi.h:127
nodelet::Nodelet
rect_to_roi.h
jsk_perception::RectToROI::unsubscribe
virtual void unsubscribe()
Definition: rect_to_roi.cpp:91
jsk_perception::RectToROI::subscribe
virtual void subscribe()
Definition: rect_to_roi.cpp:81
ros::V_string
std::vector< std::string > V_string
height
height
jsk_perception::RectToROI::infoCallback
virtual void infoCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg)
Definition: rect_to_roi.cpp:97
info_msg
info_msg


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:17