30 #include <boost/bind.hpp>
31 #include <boost/chrono.hpp>
32 #include <boost/thread.hpp>
33 #include <boost/thread/lock_guard.hpp>
34 #include <boost/thread/mutex.hpp>
35 #include <boost/asio.hpp>
42 #include <sensor_msgs/PointCloud.h>
43 #include <sensor_msgs/PointCloud2.h>
45 #include <sensor_msgs/MagneticField.h>
46 #include <sensor_msgs/Imu.h>
60 const boost::posix_time::ptime& time_read)
67 if (
cloud_.points.size() == 0)
74 for (
int i = 0; i < index[range_index.
nspots]; i++)
80 geometry_msgs::Point32 point;
81 point.x = points[i].x;
82 point.y = points[i].y;
83 point.z = points[i].z;
84 cloud_.points.push_back(point);
85 cloud_.channels[0].values.push_back(points[i].i);
101 float* data =
reinterpret_cast<float*
>(&
cloud2_.data[0]);
103 for (
int i = 0; i < index[range_index.
nspots]; i++)
109 *(data++) = points[i].x;
110 *(data++) = points[i].y;
111 *(data++) = points[i].z;
112 *(data++) = points[i].i;
125 ROS_INFO(
"Dropping timestamp jump backed cloud");
133 cloud_.channels[0].values.clear();
140 ROS_INFO(
"Dropping timestamp jump backed cloud2");
158 const std::string& message,
159 const boost::posix_time::ptime& time_read)
165 const boost::posix_time::ptime& time_read)
177 std::sort(sorted_timstamp_base.begin(), sorted_timstamp_base.end());
180 timestamp_base_ = sorted_timstamp_base[sorted_timstamp_base.size() / 2];
190 const boost::posix_time::ptime& time_read)
200 imu_.header.stamp = stamp;
201 for (
int i = 0; i < aux_header.
data_count; i++)
203 imu_.orientation_covariance[0] = -1.0;
204 imu_.angular_velocity.x = auxs[i].ang_vel.x;
205 imu_.angular_velocity.y = auxs[i].ang_vel.y;
206 imu_.angular_velocity.z = auxs[i].ang_vel.z;
207 imu_.linear_acceleration.x = auxs[i].lin_acc.x;
208 imu_.linear_acceleration.y = auxs[i].lin_acc.y;
209 imu_.linear_acceleration.z = auxs[i].lin_acc.z;
212 ROS_INFO(
"Dropping timestamp jump backed imu");
225 mag_.header.stamp = stamp;
226 for (
int i = 0; i < aux_header.
data_count; i++)
228 mag_.magnetic_field.x = auxs[i].mag.x;
229 mag_.magnetic_field.y = auxs[i].mag.y;
230 mag_.magnetic_field.z = auxs[i].mag.z;
233 ROS_INFO(
"Dropping timestamp jump backed mag");
277 ROS_WARN(
"'interlace' parameter is deprecated. Use horizontal_interlace instead.");
292 std::string output_cycle;
293 pnh_.
param(
"output_cycle", output_cycle, std::string(
"field"));
295 if (output_cycle.compare(
"frame") == 0)
297 else if (output_cycle.compare(
"field") == 0)
299 else if (output_cycle.compare(
"line") == 0)
303 ROS_ERROR(
"Unknown output_cycle value %s", output_cycle.c_str());
317 sensor_msgs::ChannelFloat32 channel;
318 channel.name = std::string(
"intensity");
319 cloud_.channels.push_back(channel);
326 sensor_msgs::PointField::FLOAT32,
"z", 1, sensor_msgs::PointField::FLOAT32,
327 "intensity", 1, sensor_msgs::PointField::FLOAT32);
371 ROS_DEBUG(
"PointCloud2 output disabled");
383 void cbTimer(
const boost::system::error_code& error)
396 boost::posix_time::milliseconds(500));
403 boost::thread thread(
404 boost::bind(&boost::asio::io_service::run, &
io_));
429 sensor_msgs::MagneticField
mag_;
443 boost::asio::io_service
io_;
469 int main(
int argc,
char** argv)