45 return sqrt(pow(ray.x, 2.0) + pow(ray.y, 2.0) + pow(ray.z, 2.0));
49 double dot_product = ray1.x*ray2.x + ray1.y*ray2.y + ray1.z*ray2.z;
52 return acos(dot_product / (magnitude1 * magnitude2));
57 bool new_finite = std::isfinite(new_value);
58 bool old_finite = std::isfinite(old_value);
61 if(!new_finite && !old_finite){
62 if(!std::isnan(new_value)){
69 bool range_check = range_min <= new_value && new_value <= range_max;
79 bool shorter_check = new_value < old_value;
84 const sensor_msgs::CameraInfoConstPtr& info_msg){
93 cv::Point2d raw_pixel_right(depth_msg->width-1,
cam_model_.
cy());
105 sensor_msgs::LaserScanPtr scan_msg(
new sensor_msgs::LaserScan());
106 scan_msg->header = depth_msg->header;
110 scan_msg->angle_min = angle_min;
111 scan_msg->angle_max = angle_max;
112 scan_msg->angle_increment = (scan_msg->angle_max - scan_msg->angle_min) / (depth_msg->width - 1);
113 scan_msg->time_increment = 0.0;
120 std::stringstream ss;
121 ss <<
"scan_height ( " <<
scan_height_ <<
" pixels) is too large for the image height.";
122 throw std::runtime_error(ss.str());
126 uint32_t ranges_size = depth_msg->width;
127 scan_msg->ranges.assign(ranges_size, std::numeric_limits<float>::quiet_NaN());
139 std::stringstream ss;
140 ss <<
"Depth image has unsupported encoding: " << depth_msg->encoding;
141 throw std::runtime_error(ss.str());
sensor_msgs::LaserScanPtr convert_msg(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
cv::Point3d projectPixelTo3dRay(const cv::Point2d &uv_rect) const
void set_output_frame(const std::string output_frame_id)
image_geometry::PinholeCameraModel cam_model_
image_geometry helper class for managing sensor_msgs/CameraInfo messages.
double angle_between_rays(const cv::Point3d &ray1, const cv::Point3d &ray2) const
bool use_point(const float new_value, const float old_value, const float range_min, const float range_max) const
float scan_time_
Stores the time between scans.
void set_scan_height(const int scan_height)
float range_min_
Stores the current minimum range to use.
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
const std::string TYPE_32FC1
float range_max_
Stores the current maximum range to use.
const std::string TYPE_16UC1
int scan_height_
Number of pixel rows to use when producing a laserscan from an area.
cv::Point2d rectifyPoint(const cv::Point2d &uv_raw) const
void set_scan_time(const float scan_time)
double magnitude_of_ray(const cv::Point3d &ray) const
void set_range_limits(const float range_min, const float range_max)
std::string output_frame_id_
Output frame_id for each laserscan. This is likely NOT the camera's frame_id.