40 ConnectionBasedNodelet::onInit();
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 bba.boxes[i].pose.position.x +=
offset_x_;
94 bba.boxes[i].pose.position.y +=
offset_y_;
95 bba.boxes[i].pose.position.z +=
offset_z_;
96 bba.boxes[i].dimensions.x *=
scale_x_;
97 bba.boxes[i].dimensions.y *=
scale_y_;
98 bba.boxes[i].dimensions.z *=
scale_z_;
99 bba.boxes[i].pose.orientation.x +=
q_.x();
100 bba.boxes[i].pose.orientation.y +=
q_.y();
101 bba.boxes[i].pose.orientation.z +=
q_.z();
102 bba.boxes[i].pose.orientation.w +=
q_.w();
jsk_pcl_ros::RearrangeBoundingBoxConfig Config
void configCallback(Config &config, uint32_t level)
void publish(const boost::shared_ptr< M > &message) const
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::RearrangeBoundingBox, nodelet::Nodelet)
ros::Subscriber sub_bounding_box_array_
ros::Publisher pub_bouding_box_array_
void setEuler(const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll)
virtual void unsubscribe()
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void rearrangeBoundingBoxCallback(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box_array)