40     ConnectionBasedNodelet::onInit();
 
   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);
 
   54     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
 
   55     dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
   57     srv_->setCallback (
f);
 
   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;
 
  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();