31 first_rcfg_call(true),
32 diagnostics_(node, private_nh, node_name)
34 boost::optional<velodyne_pointcloud::Calibration>
calibration =
data_->setup(private_nh);
48 srv_ = boost::make_shared<dynamic_reconfigure::Server<TransformNodeCfg>> (private_nh);
49 dynamic_reconfigure::Server<TransformNodeCfg>::CallbackType
f;
51 srv_->setCallback (
f);
71 velodyne_pointcloud::TransformNodeConfig &config, uint32_t level)
74 data_->setParameters(config.min_range, config.max_range,
75 config.view_direction, config.view_width);
101 data_->scansPerPacket()));
124 if(!
container_ptr->computeTransformToTarget(scanMsg->header.stamp))
131 for (
size_t i = 0; i < scanMsg->packets.size(); ++i)
135 if(!
container_ptr->computeTransformToFixed(scanMsg->packets[i].stamp))