35 #define BOOST_PARAMETER_MAX_ARITY 7 42 #include <pcl/common/transforms.h> 49 DiagnosticNodelet::onInit();
51 "output/config", 1,
true);
52 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
53 typename dynamic_reconfigure::Server<Config>::CallbackType
f =
55 srv_->setCallback (f);
59 pnh_->param(
"projected_center_frame_id",
65 pub_ = advertise<sensor_msgs::Image>(*
pnh_,
"output", 1);
86 std_msgs::Header msg_header(msg->header);
87 pcl::PointCloud<pcl::PointXYZ> transformed_cloud;
95 msg->header.stamp, ros_fixed_to_center);
104 Eigen::Affine3d fixed_to_center = (Eigen::Translation3d(pos[0], pos[1], 0) *
105 Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ()));
112 msg->header.stamp, ros_msg_to_fixed);
118 Eigen::Affine3d msg_to_fixed;
121 pcl::PointCloud<pcl::PointXYZ> from_msg_cloud;
123 pcl::transformPointCloud(from_msg_cloud, transformed_cloud, (msg_to_fixed * fixed_to_center).
inverse());
129 tf_fixed_to_center.
stamp_ = msg_header.stamp;
138 height_map = cv::Scalar::all(- FLT_MAX);
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)) {
154 max_height =
std::max(max_height, p.z);
155 min_height =
std::min(min_height, p.z);
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;
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_;
HeightmapConverterConfig Config
double min(const OneDataStat &d)
wrapper function for min method for boost::function
bool use_projected_center_
#define NODELET_ERROR(...)
tf::TransformListener * tf_
ros::Publisher pub_config_
void publish(const boost::shared_ptr< M > &message) const
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
void transformEigenToTF(Eigen::Affine3f &eigen, tf::Transform &t)
double max(const OneDataStat &d)
wrapper function for max method for boost::function
virtual void unsubscribe()
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
double duration_transform_timeout_
tf::TransformBroadcaster tf_broadcaster_
std::string center_frame_id_
cv::Point toIndex(const pcl::PointXYZ &p) const
std::string fixed_frame_id_
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
std::string projected_center_frame_id_
virtual void convert(const sensor_msgs::PointCloud2::ConstPtr &msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::HeightmapConverter, nodelet::Nodelet)
virtual void configCallback(Config &config, uint32_t level)
static tf::TransformListener * getInstance()
const std::string TYPE_32FC2
double initial_probability_
sensor_msgs::ImagePtr toImageMsg() const