rearrange_bounding_box_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016, 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  *********************************************************************/
36 
37 namespace jsk_pcl_ros
38 {
40  ConnectionBasedNodelet::onInit();
41 
42  pnh_->param("offset_x", offset_x_, 0.0);
43  pnh_->param("offset_y", offset_y_, 0.0);
44  pnh_->param("offset_z", offset_z_, 0.0);
45  pnh_->param("scale_x", scale_x_, 1.0);
46  pnh_->param("scale_y", scale_y_, 1.0);
47  pnh_->param("scale_z", scale_z_, 1.0);
48  pnh_->param("rotate_x", rotate_x_, 0.0);
49  pnh_->param("rotate_y", rotate_y_, 0.0);
50  pnh_->param("rotate_z", rotate_z_, 0.0);
51  q_ = tf2::Quaternion();
53 
54  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
55  dynamic_reconfigure::Server<Config>::CallbackType f =
56  boost::bind(&RearrangeBoundingBox::configCallback, this, _1, _2);
57  srv_->setCallback (f);
58 
59  pub_bouding_box_array_ = advertise<jsk_recognition_msgs::BoundingBoxArray>(*pnh_, "output", 1);
60  onInitPostProcess();
61  }
62 
63  void RearrangeBoundingBox::configCallback(Config &config, uint32_t level) {
64  boost::mutex::scoped_lock lock(mutex_);
65  offset_x_ = config.offset_x;
66  offset_y_ = config.offset_y;
67  offset_z_ = config.offset_z;
68  scale_x_ = config.scale_x;
69  scale_y_ = config.scale_y;
70  scale_z_ = config.scale_z;
71  rotate_x_ = config.rotate_x;
72  rotate_y_ = config.rotate_y;
73  rotate_z_ = config.rotate_z;
74  q_ = tf2::Quaternion();
76  }
77 
79  sub_bounding_box_array_ = pnh_->subscribe("input", 1,
81  }
82 
85  }
86 
87  void RearrangeBoundingBox::rearrangeBoundingBoxCallback(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array) {
88  boost::mutex::scoped_lock lock(mutex_);
89  jsk_recognition_msgs::BoundingBoxArray bba;
90  bba.header = box_array->header;
91  bba.boxes = box_array->boxes;
92  for(size_t i = 0; i < box_array->boxes.size(); ++i) {
93  geometry_msgs::Quaternion q_base_ = bba.boxes[i].pose.orientation;
94  bba.boxes[i].pose.position.x += offset_x_;
95  bba.boxes[i].pose.position.y += offset_y_;
96  bba.boxes[i].pose.position.z += offset_z_;
97  bba.boxes[i].dimensions.x *= scale_x_;
98  bba.boxes[i].dimensions.y *= scale_y_;
99  bba.boxes[i].dimensions.z *= scale_z_;
100  bba.boxes[i].pose.orientation.x =
101  q_base_.x * q_.w() + q_base_.y * q_.z() - q_base_.z * q_.y() + q_base_.w * q_.x();
102  bba.boxes[i].pose.orientation.y =
103  - q_base_.x * q_.z() + q_base_.y * q_.w() + q_base_.z * q_.x() + q_base_.w * q_.y();
104  bba.boxes[i].pose.orientation.z =
105  q_base_.x * q_.y() - q_base_.y * q_.x() + q_base_.z * q_.w() + q_base_.w * q_.z();
106  bba.boxes[i].pose.orientation.w =
107  - q_base_.x * q_.x() - q_base_.y * q_.y() - q_base_.z * q_.z() + q_base_.w * q_.w();
108  }
110  }
111 }
112 
jsk_pcl_ros::RearrangeBoundingBox::scale_x_
double scale_x_
Definition: rearrange_bounding_box.h:141
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
jsk_pcl_ros::RearrangeBoundingBox::configCallback
void configCallback(Config &config, uint32_t level)
Definition: rearrange_bounding_box_nodelet.cpp:95
jsk_pcl_ros::RearrangeBoundingBox::scale_z_
double scale_z_
Definition: rearrange_bounding_box.h:143
i
int i
jsk_pcl_ros::RearrangeBoundingBox::q_
tf2::Quaternion q_
Definition: rearrange_bounding_box.h:153
rearrange_bounding_box.h
jsk_pcl_ros::RearrangeBoundingBox::pub_bouding_box_array_
ros::Publisher pub_bouding_box_array_
Definition: rearrange_bounding_box.h:138
ros::Subscriber::shutdown
void shutdown()
jsk_pcl_ros::RearrangeBoundingBox::mutex_
boost::mutex mutex_
Definition: rearrange_bounding_box.h:139
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
class_list_macros.h
jsk_pcl_ros::RearrangeBoundingBox::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: rearrange_bounding_box.h:131
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::RearrangeBoundingBox::rotate_x_
double rotate_x_
Definition: rearrange_bounding_box.h:149
jsk_pcl_ros::RearrangeBoundingBox::sub_bounding_box_array_
ros::Subscriber sub_bounding_box_array_
Definition: rearrange_bounding_box.h:137
jsk_pcl_ros::RearrangeBoundingBox::scale_y_
double scale_y_
Definition: rearrange_bounding_box.h:142
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::RearrangeBoundingBox, nodelet::Nodelet)
jsk_pcl_ros::RearrangeBoundingBox::subscribe
virtual void subscribe()
Definition: rearrange_bounding_box_nodelet.cpp:110
jsk_pcl_ros::RearrangeBoundingBox::offset_y_
double offset_y_
Definition: rearrange_bounding_box.h:146
nodelet::Nodelet
tf2::Quaternion::setEuler
void setEuler(const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll)
dump_depth_error.f
f
Definition: dump_depth_error.py:39
jsk_pcl_ros::RearrangeBoundingBox::onInit
virtual void onInit()
Definition: rearrange_bounding_box_nodelet.cpp:71
jsk_pcl_ros::RearrangeBoundingBox::offset_x_
double offset_x_
Definition: rearrange_bounding_box.h:145
jsk_pcl_ros::RearrangeBoundingBox
Definition: rearrange_bounding_box.h:81
tf2::Quaternion
jsk_pcl_ros::RearrangeBoundingBox::rotate_y_
double rotate_y_
Definition: rearrange_bounding_box.h:150
jsk_pcl_ros::RearrangeBoundingBox::rotate_z_
double rotate_z_
Definition: rearrange_bounding_box.h:151
jsk_pcl_ros::RearrangeBoundingBox::rearrangeBoundingBoxCallback
virtual void rearrangeBoundingBoxCallback(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box_array)
Definition: rearrange_bounding_box_nodelet.cpp:119
config
config
jsk_pcl_ros::RearrangeBoundingBox::unsubscribe
virtual void unsubscribe()
Definition: rearrange_bounding_box_nodelet.cpp:115
jsk_pcl_ros::RearrangeBoundingBox::offset_z_
double offset_z_
Definition: rearrange_bounding_box.h:147


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45