Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include "jsk_pcl_ros/rearrange_bounding_box.h"
00036
00037 namespace jsk_pcl_ros
00038 {
00039 void RearrangeBoundingBox::onInit () {
00040 ConnectionBasedNodelet::onInit();
00041
00042 pnh_->param("offset_x", offset_x_, 0.0);
00043 pnh_->param("offset_y", offset_y_, 0.0);
00044 pnh_->param("offset_z", offset_z_, 0.0);
00045 pnh_->param("scale_x", scale_x_, 1.0);
00046 pnh_->param("scale_y", scale_y_, 1.0);
00047 pnh_->param("scale_z", scale_z_, 1.0);
00048 pnh_->param("rotate_x", rotate_x_, 0.0);
00049 pnh_->param("rotate_y", rotate_y_, 0.0);
00050 pnh_->param("rotate_z", rotate_z_, 0.0);
00051 q_ = tf2::Quaternion();
00052 q_.setEuler(rotate_y_, rotate_x_, rotate_z_);
00053
00054 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00055 dynamic_reconfigure::Server<Config>::CallbackType f =
00056 boost::bind(&RearrangeBoundingBox::configCallback, this, _1, _2);
00057 srv_->setCallback (f);
00058
00059 pub_bouding_box_array_ = advertise<jsk_recognition_msgs::BoundingBoxArray>(*pnh_, "output", 1);
00060 onInitPostProcess();
00061 }
00062
00063 void RearrangeBoundingBox::configCallback(Config &config, uint32_t level) {
00064 boost::mutex::scoped_lock lock(mutex_);
00065 offset_x_ = config.offset_x;
00066 offset_y_ = config.offset_y;
00067 offset_z_ = config.offset_z;
00068 scale_x_ = config.scale_x;
00069 scale_y_ = config.scale_y;
00070 scale_z_ = config.scale_z;
00071 rotate_x_ = config.rotate_x;
00072 rotate_y_ = config.rotate_y;
00073 rotate_z_ = config.rotate_z;
00074 q_ = tf2::Quaternion();
00075 q_.setEuler(rotate_y_, rotate_x_, rotate_z_);
00076 }
00077
00078 void RearrangeBoundingBox::subscribe() {
00079 sub_bounding_box_array_ = pnh_->subscribe("input", 1,
00080 &RearrangeBoundingBox::rearrangeBoundingBoxCallback, this);
00081 }
00082
00083 void RearrangeBoundingBox::unsubscribe() {
00084 sub_bounding_box_array_.shutdown();
00085 }
00086
00087 void RearrangeBoundingBox::rearrangeBoundingBoxCallback(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array) {
00088 boost::mutex::scoped_lock lock(mutex_);
00089 jsk_recognition_msgs::BoundingBoxArray bba;
00090 bba.header = box_array->header;
00091 bba.boxes = box_array->boxes;
00092 for(size_t i = 0; i < box_array->boxes.size(); ++i) {
00093 bba.boxes[i].pose.position.x += offset_x_;
00094 bba.boxes[i].pose.position.y += offset_y_;
00095 bba.boxes[i].pose.position.z += offset_z_;
00096 bba.boxes[i].dimensions.x *= scale_x_;
00097 bba.boxes[i].dimensions.y *= scale_y_;
00098 bba.boxes[i].dimensions.z *= scale_z_;
00099 bba.boxes[i].pose.orientation.x += q_.x();
00100 bba.boxes[i].pose.orientation.y += q_.y();
00101 bba.boxes[i].pose.orientation.z += q_.z();
00102 bba.boxes[i].pose.orientation.w += q_.w();
00103 }
00104 pub_bouding_box_array_.publish(bba);
00105 }
00106 }
00107
00108 #include <pluginlib/class_list_macros.h>
00109 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::RearrangeBoundingBox, nodelet::Nodelet);