28 boost::optional<velodyne_pointcloud::Calibration>
calibration =
data_->setup(private_nh);
51 data_->scansPerPacket()));
57 node.
advertise<sensor_msgs::PointCloud2>(
"velodyne_points", 10);
59 srv_ = boost::make_shared <dynamic_reconfigure::Server<velodyne_pointcloud::
60 CloudNodeConfig> > (private_nh);
61 dynamic_reconfigure::Server<velodyne_pointcloud::CloudNodeConfig>::
64 srv_->setCallback (f);
90 data_->setParameters(config.min_range, config.max_range, config.view_direction,
113 data_->scansPerPacket()));
132 for (
size_t i = 0; i < scanMsg->packets.size(); ++i)
boost::shared_ptr< diagnostic_updater::TopicDiagnostic > diag_topic_
boost::shared_ptr< velodyne_rawdata::DataContainerBase > container_ptr_
boost::mutex reconfigure_mtx_
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
double max_range
maximum range to publish
void setHardwareID(const std::string &hwid)
std::string target_frame
target frame
void callback(velodyne_pointcloud::CloudNodeConfig &config, uint32_t level)
void processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg)
Callback for raw scan messages.
bool organize_cloud
enable/disable organized cloud structure
uint16_t num_lasers
number of lasers
double min_range
minimum range to publish
Convert(ros::NodeHandle node, ros::NodeHandle private_nh)
Constructor.
diagnostic_updater::Updater diagnostics_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_DEBUG_STREAM(args)
uint32_t getNumSubscribers() const
#define ROS_INFO_STREAM(args)
boost::shared_ptr< velodyne_rawdata::RawData > data_
std::string fixed_frame
fixed frame
#define ROS_ERROR_STREAM(args)
ros::Subscriber velodyne_scan_
boost::shared_ptr< dynamic_reconfigure::Server< velodyne_pointcloud::CloudNodeConfig > > srv_