39 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
40 #include <tf2_sensor_msgs/tf2_sensor_msgs.h>
41 #include <sensor_msgs/point_cloud2_iterator.h>
48 ObservationBuffer::ObservationBuffer(
string topic_name,
double observation_keep_time,
double expected_update_rate,
49 double min_obstacle_height,
double max_obstacle_height,
double obstacle_range,
50 double raytrace_range, tf2_ros::Buffer& tf2_buffer,
string global_frame,
51 string sensor_frame,
double tf_tolerance) :
52 tf2_buffer_(tf2_buffer), observation_keep_time_(observation_keep_time), expected_update_rate_(expected_update_rate),
53 last_updated_(ros::Time::now()), global_frame_(global_frame), sensor_frame_(sensor_frame), topic_name_(topic_name),
54 min_obstacle_height_(min_obstacle_height), max_obstacle_height_(max_obstacle_height),
55 obstacle_range_(obstacle_range), raytrace_range_(raytrace_range), tf_tolerance_(tf_tolerance)
65 ros::Time transform_time = ros::Time::now();
68 geometry_msgs::TransformStamped transformStamped;
71 ROS_ERROR(
"Transform between %s and %s with tolerance %.2f failed: %s.", new_global_frame.
c_str(),
83 geometry_msgs::PointStamped origin;
85 origin.header.stamp = transform_time;
89 tf2_buffer_.transform(origin, origin, new_global_frame);
95 catch (TransformException& ex)
97 ROS_ERROR(
"TF Error attempting to transform an observation from %s to %s: %s",
global_frame_.
c_str(),
98 new_global_frame.
c_str(), ex.what());
110 geometry_msgs::PointStamped global_origin;
121 geometry_msgs::PointStamped local_origin;
122 local_origin.header.stamp = cloud.header.stamp;
123 local_origin.header.frame_id = origin_frame;
124 local_origin.point.x = 0;
125 local_origin.point.y = 0;
126 local_origin.point.z = 0;
134 sensor_msgs::PointCloud2 global_frame_cloud;
138 global_frame_cloud.header.stamp = cloud.header.stamp;
141 sensor_msgs::PointCloud2& observation_cloud = *(
observation_list_.front().cloud_);
142 observation_cloud.height = global_frame_cloud.height;
143 observation_cloud.width = global_frame_cloud.width;
144 observation_cloud.fields = global_frame_cloud.fields;
145 observation_cloud.is_bigendian = global_frame_cloud.is_bigendian;
146 observation_cloud.point_step = global_frame_cloud.point_step;
147 observation_cloud.row_step = global_frame_cloud.row_step;
148 observation_cloud.is_dense = global_frame_cloud.is_dense;
150 unsigned int cloud_size = global_frame_cloud.height*global_frame_cloud.width;
151 sensor_msgs::PointCloud2Modifier modifier(observation_cloud);
152 modifier.resize(cloud_size);
153 unsigned int point_count = 0;
156 sensor_msgs::PointCloud2Iterator<float> iter_z(global_frame_cloud,
"z");
159 for (; iter_global != iter_global_end; ++iter_z, iter_global += global_frame_cloud.point_step)
164 std::copy(iter_global, iter_global + global_frame_cloud.point_step, iter_obs);
165 iter_obs += global_frame_cloud.point_step;
171 modifier.
resize(point_count);
172 observation_cloud.header.stamp = cloud.header.stamp;
173 observation_cloud.header.frame_id = global_frame_cloud.header.frame_id;
175 catch (TransformException& ex)
179 ROS_ERROR(
"TF Exception that should never happen for sensor frame: %s, cloud frame: %s, %s",
sensor_frame_.
c_str(),
180 cloud.header.frame_id.c_str(), ex.what());
240 "The %s observation buffer has not been updated for %.2f seconds, and it should be updated every %.2f seconds.",