heightmap_converter_nodelet.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 #define BOOST_PARAMETER_MAX_ARITY 7
38 #include <cv_bridge/cv_bridge.h>
40 #include <jsk_topic_tools/color_utils.h>
42 #include <pcl/common/transforms.h>
44 
45 namespace jsk_pcl_ros
46 {
48  {
49  DiagnosticNodelet::onInit();
50  pub_config_ = pnh_->advertise<jsk_recognition_msgs::HeightmapConfig>(
51  "output/config", 1, true);
52  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
53  typename dynamic_reconfigure::Server<Config>::CallbackType f =
54  boost::bind (&HeightmapConverter::configCallback, this, _1, _2);
55  srv_->setCallback (f);
56 
57  pnh_->param("fixed_frame_id", fixed_frame_id_, std::string("map"));
58  pnh_->param("center_frame_id", center_frame_id_, std::string("BODY"));
59  pnh_->param("projected_center_frame_id",
60  projected_center_frame_id_, std::string("BODY_on_map"));
61  pnh_->param("use_projected_center", use_projected_center_, false);
62 
63  pnh_->param("max_queue_size", max_queue_size_, 10);
64  pnh_->param("duration_transform_timeout", duration_transform_timeout_, 1.0);
65  pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
66 
68 
69  onInitPostProcess();
70  }
71 
73  {
74  sub_ = pnh_->subscribe("input", max_queue_size_, &HeightmapConverter::convert, this);
75  }
76 
78  {
79  sub_.shutdown();
80  }
81 
82  void HeightmapConverter::convert(const sensor_msgs::PointCloud2::ConstPtr& msg)
83  {
84  boost::mutex::scoped_lock lock(mutex_);
85  vital_checker_->poke();
86  std_msgs::Header msg_header(msg->header);
87  pcl::PointCloud<pcl::PointXYZ> transformed_cloud;
89  /* convert points */
90  tf::StampedTransform ros_fixed_to_center;
91  try {
95  msg->header.stamp, ros_fixed_to_center);
96  }
97  catch (tf2::TransformException &e) {
98  NODELET_ERROR("Transform error: %s", e.what());
99  return;
100  }
101  double roll, pitch, yaw;
102  tf::Vector3 pos = ros_fixed_to_center.getOrigin();
103  ros_fixed_to_center.getBasis().getRPY(roll, pitch, yaw);
104  Eigen::Affine3d fixed_to_center = (Eigen::Translation3d(pos[0], pos[1], 0) *
105  Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ()));
106 
107  tf::StampedTransform ros_msg_to_fixed;
108  try {
109  tf_->waitForTransform(msg->header.frame_id, fixed_frame_id_,
111  tf_->lookupTransform(msg->header.frame_id, fixed_frame_id_,
112  msg->header.stamp, ros_msg_to_fixed);
113  }
114  catch (tf2::TransformException &e) {
115  NODELET_ERROR("Transform error: %s", e.what());
116  return;
117  }
118  Eigen::Affine3d msg_to_fixed;
119  tf::transformTFToEigen(ros_msg_to_fixed, msg_to_fixed);
120 
121  pcl::PointCloud<pcl::PointXYZ> from_msg_cloud;
122  pcl::fromROSMsg(*msg, from_msg_cloud);
123  pcl::transformPointCloud(from_msg_cloud, transformed_cloud, (msg_to_fixed * fixed_to_center).inverse());
124 
125  tf::StampedTransform tf_fixed_to_center;
126  transformEigenToTF(fixed_to_center, tf_fixed_to_center);
127  tf_fixed_to_center.frame_id_ = fixed_frame_id_;
128  tf_fixed_to_center.child_frame_id_ = projected_center_frame_id_;
129  tf_fixed_to_center.stamp_ = msg_header.stamp;
130  tf_broadcaster_.sendTransform(tf_fixed_to_center);
131 
132  msg_header.frame_id = projected_center_frame_id_;
133  } else {
134  pcl::fromROSMsg(*msg, transformed_cloud);
135  }
136  /* float image */
137  cv::Mat height_map = cv::Mat(resolution_y_, resolution_x_, CV_32FC2);
138  height_map = cv::Scalar::all(- FLT_MAX);
139 
140  float max_height = - FLT_MAX;
141  float min_height = FLT_MAX;
142  for (size_t i = 0; i < transformed_cloud.points.size(); i++) {
143  pcl::PointXYZ p = transformed_cloud.points[i];
144  if (std::isnan(p.x) || std::isnan(p.y) || std::isnan(p.z)) {
145  continue;
146  }
147  if (p.z > max_z_ or p.z < min_z_) {
148  continue;
149  }
150  cv::Point index = toIndex(p);
151  if (index.x >= 0 && index.x < resolution_x_ &&
152  index.y >= 0 && index.y < resolution_y_) {
153  /* Store min/max value for colorization */
154  max_height = std::max(max_height, p.z);
155  min_height = std::min(min_height, p.z);
156  // accept maximum points
157  if (height_map.at<cv::Vec2f>(index.y, index.x)[0] < p.z) {
158  height_map.at<cv::Vec2f>(index.y, index.x)[0] = p.z;
159  height_map.at<cv::Vec2f>(index.y, index.x)[1] = initial_probability_;
160  }
161  }
162  }
163  // Convert to sensor_msgs/Image
164  cv_bridge::CvImage height_map_image(msg_header,
166  height_map);
167  pub_.publish(height_map_image.toImageMsg());
168  }
169 
170  void HeightmapConverter::configCallback(Config &config, uint32_t level)
171  {
172  boost::mutex::scoped_lock lock(mutex_);
173  min_x_ = config.min_x;
174  max_x_ = config.max_x;
175  min_y_ = config.min_y;
176  max_y_ = config.max_y;
177  min_z_ = config.min_z;
178  max_z_ = config.max_z;
179  resolution_x_ = config.resolution_x;
180  resolution_y_ = config.resolution_y;
181  initial_probability_ = config.initial_probability;
182  jsk_recognition_msgs::HeightmapConfig heightmap_config;
183  heightmap_config.min_x = min_x_;
184  heightmap_config.min_y = min_y_;
185  heightmap_config.max_x = max_x_;
186  heightmap_config.max_y = max_y_;
187  pub_config_.publish(heightmap_config);
188  }
189 
190 }
191 
jsk_pcl_ros::HeightmapConverter::center_frame_id_
std::string center_frame_id_
Definition: heightmap_converter.h:160
jsk_pcl_ros::HeightmapConverter::fixed_frame_id_
std::string fixed_frame_id_
Definition: heightmap_converter.h:159
tf::StampedTransform::stamp_
ros::Time stamp_
NODELET_ERROR
#define NODELET_ERROR(...)
jsk_pcl_ros::HeightmapConverter::pub_
ros::Publisher pub_
Definition: heightmap_converter.h:145
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
_2
boost::arg< 2 > _2
tf::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
image_encodings.h
transformEigenToTF
void transformEigenToTF(Eigen::Affine3f &eigen, tf::Transform &t)
i
int i
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
pos
pos
tf::Matrix3x3::getRPY
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
p
p
tf::StampedTransform::child_frame_id_
std::string child_frame_id_
jsk_pcl_ros::HeightmapConverter::onInit
virtual void onInit()
Definition: heightmap_converter_nodelet.cpp:47
jsk_pcl_ros::min
double min(const OneDataStat &d)
wrapper function for min method for boost::function
Definition: one_data_stat.h:126
jsk_pcl_ros::HeightmapConverter::pub_config_
ros::Publisher pub_config_
Definition: heightmap_converter.h:146
jsk_pcl_ros::HeightmapConverter
Definition: heightmap_converter.h:86
inverse
geometry_msgs::Pose inverse(geometry_msgs::Pose pose)
jsk_pcl_ros::HeightmapConverter::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: heightmap_converter.h:148
ros::Subscriber::shutdown
void shutdown()
tf_listener_singleton.h
tf::Transform::getBasis
TFSIMD_FORCE_INLINE Matrix3x3 & getBasis()
tf::StampedTransform
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
tf::StampedTransform::frame_id_
std::string frame_id_
jsk_pcl_ros::HeightmapConverter::tf_broadcaster_
tf::TransformBroadcaster tf_broadcaster_
Definition: heightmap_converter.h:166
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
jsk_pcl_ros::HeightmapConverter::initial_probability_
double initial_probability_
Definition: heightmap_converter.h:163
class_list_macros.h
jsk_pcl_ros::HeightmapConverter::max_x_
double max_x_
Definition: heightmap_converter.h:151
jsk_pcl_ros::HeightmapConverter::projected_center_frame_id_
std::string projected_center_frame_id_
Definition: heightmap_converter.h:161
tf_eigen.h
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::HeightmapConverter::convert
virtual void convert(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: heightmap_converter_nodelet.cpp:82
jsk_pcl_ros::HeightmapConverter::resolution_x_
int resolution_x_
Definition: heightmap_converter.h:156
jsk_pcl_ros::HeightmapConverter::mutex_
boost::mutex mutex_
Definition: heightmap_converter.h:144
tf::transformTFToEigen
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3f &eigen)
jsk_pcl_ros::HeightmapConverter::toIndex
cv::Point toIndex(const pcl::PointXYZ &p) const
Definition: heightmap_converter.h:130
jsk_pcl_ros::HeightmapConverter::sub_
ros::Subscriber sub_
Definition: heightmap_converter.h:147
jsk_pcl_ros::HeightmapConverter::use_projected_center_
bool use_projected_center_
Definition: heightmap_converter.h:162
_1
boost::arg< 1 > _1
tf::Transformer::waitForTransform
bool waitForTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
jsk_pcl_ros::HeightmapConverter::resolution_y_
int resolution_y_
Definition: heightmap_converter.h:157
heightmap_converter.h
jsk_pcl_ros::HeightmapConverter::min_z_
double min_z_
Definition: heightmap_converter.h:154
jsk_pcl_ros::HeightmapConverter::subscribe
virtual void subscribe()
Definition: heightmap_converter_nodelet.cpp:72
jsk_pcl_ros::HeightmapConverter::Config
HeightmapConverterConfig Config
Definition: heightmap_converter.h:122
jsk_pcl_ros::HeightmapConverter::min_x_
double min_x_
Definition: heightmap_converter.h:150
sensor_msgs::image_encodings::TYPE_32FC2
const std::string TYPE_32FC2
jsk_pcl_ros::HeightmapConverter::duration_transform_timeout_
double duration_transform_timeout_
Definition: heightmap_converter.h:149
nodelet::Nodelet
jsk_pcl_ros::HeightmapConverter::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: heightmap_converter_nodelet.cpp:170
cv_bridge.h
dump_depth_error.f
f
Definition: dump_depth_error.py:39
jsk_pcl_ros::HeightmapConverter::min_y_
double min_y_
Definition: heightmap_converter.h:152
cv_bridge::CvImage
index
unsigned int index
jsk_recognition_utils::TfListenerSingleton::getInstance
static tf::TransformListener * getInstance()
tf::Transformer::lookupTransform
void lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, StampedTransform &transform) const
tf2::TransformException
config
config
jsk_pcl_ros::HeightmapConverter::max_z_
double max_z_
Definition: heightmap_converter.h:155
ros::Duration
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
jsk_pcl_ros::HeightmapConverter::max_y_
double max_y_
Definition: heightmap_converter.h:153
tf::Transform::getOrigin
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
jsk_pcl_ros::HeightmapConverter::max_queue_size_
int max_queue_size_
Definition: heightmap_converter.h:158
jsk_pcl_ros::HeightmapConverter::unsubscribe
virtual void unsubscribe()
Definition: heightmap_converter_nodelet.cpp:77
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::HeightmapConverter, nodelet::Nodelet)
jsk_pcl_ros::HeightmapConverter::tf_
tf::TransformListener * tf_
Definition: heightmap_converter.h:165
pcl_conversions.h


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