#include "velo2cam_utils.h"#include <ros/ros.h>#include <ros/package.h>#include <sensor_msgs/PointCloud2.h>#include <sensor_msgs/CameraInfo.h>#include <pcl/point_cloud.h>#include <pcl_conversions/pcl_conversions.h>#include <pcl/common/transforms.h>#include <opencv2/opencv.hpp>#include <cv_bridge/cv_bridge.h>#include <image_transport/image_transport.h>#include <tf/tf.h>#include <tf/transform_listener.h>#include <pcl_ros/transforms.h>#include <image_geometry/pinhole_camera_model.h>
Go to the source code of this file.
Classes | |
| struct | COLOUR |
Macros | |
| #define | PCL_NO_PRECOMPILE |
Functions | |
| template<class T > | |
| bool | between (T min, T test, T max) |
| template<typename Type_in , typename Type_out > | |
| float | calc (float &val, const float &psi, int row, int col, const cv::Mat &in, cv::Mat &out) |
| void | checkExtrinics (const sensor_msgs::CameraInfoConstPtr &cinfo_msg) |
| const std::string | currentDateTime () |
| template<typename ImageT > | |
| void | edge_max (cv::Mat &in, cv::Mat &out) |
| void | edges_pointcloud (pcl::PointCloud< Velodyne::Point >::Ptr pc) |
| template<typename ImageT > | |
| void | get_diff (int col, int row, int col_c, int row_c, int &result, cv::Mat &in) |
| COLOUR | GetColour (double v, double vmin, double vmax) |
| template<typename Type_in , typename Type_out > | |
| void | inverse_distance_transformation (cv::Mat &in, cv::Mat &out, float alpha=0.333333333, float psi=0.98) |
| void | laser_callback (const sensor_msgs::PointCloud2::ConstPtr &velo_cloud) |
| int | main (int argc, char **argv) |
| template<typename ImageT > | |
| int | max_diff_neighbors (int row_c, int col_c, cv::Mat &in) |
| template<typename Type_in , typename Type_out > | |
| void | neighbors_x_neg (cv::Mat &in, cv::Mat &out, float psi, float alpha) |
| template<typename Type_in , typename Type_out > | |
| void | neighbors_x_pos (cv::Mat &in, cv::Mat &out, float psi, float alpha) |
| template<typename Type_in , typename Type_out > | |
| void | neighbors_y_neg (cv::Mat &in, cv::Mat &out, float psi, float alpha) |
| template<typename Type_in , typename Type_out > | |
| void | neighbors_y_pos (cv::Mat &in, cv::Mat &out, float psi, float alpha) |
| void | stereo_callback (const sensor_msgs::ImageConstPtr &image_msg) |
| void | transformAsMatrix (const tf::Transform &bt, Eigen::Matrix4f &out_mat) |
Variables | |
| bool | cameraReceived |
| ros::Publisher | cloud_pub |
| pcl::PointCloud< Velodyne::Point >::Ptr | edges_cloud |
| cv::Mat | img_out |
| bool | laserReceived |
| bool | listen_to_tf_ |
| bool | save_to_file_ |
| std::ofstream | savefile |
| std::string | source_frame |
| int | step_ |
| std::string | target_frame |
| #define PCL_NO_PRECOMPILE |
Definition at line 54 of file levinson.cpp.
|
inline |
Definition at line 129 of file levinson.cpp.
|
inline |
Definition at line 180 of file levinson.cpp.
| void checkExtrinics | ( | const sensor_msgs::CameraInfoConstPtr & | cinfo_msg | ) |
Definition at line 303 of file levinson.cpp.
| const std::string currentDateTime | ( | ) |
Definition at line 525 of file levinson.cpp.
|
inline |
Definition at line 163 of file levinson.cpp.
| void edges_pointcloud | ( | pcl::PointCloud< Velodyne::Point >::Ptr | pc | ) |
Definition at line 113 of file levinson.cpp.
|
inline |
Definition at line 136 of file levinson.cpp.
| COLOUR GetColour | ( | double | v, |
| double | vmin, | ||
| double | vmax | ||
| ) |
Definition at line 85 of file levinson.cpp.
| void inverse_distance_transformation | ( | cv::Mat & | in, |
| cv::Mat & | out, | ||
| float | alpha = 0.333333333, |
||
| float | psi = 0.98 |
||
| ) |
Definition at line 261 of file levinson.cpp.
| void laser_callback | ( | const sensor_msgs::PointCloud2::ConstPtr & | velo_cloud | ) |
Definition at line 472 of file levinson.cpp.
| int main | ( | int | argc, |
| char ** | argv | ||
| ) |
Definition at line 538 of file levinson.cpp.
|
inline |
Definition at line 145 of file levinson.cpp.
|
inline |
Definition at line 216 of file levinson.cpp.
|
inline |
Definition at line 202 of file levinson.cpp.
|
inline |
Definition at line 246 of file levinson.cpp.
|
inline |
Definition at line 231 of file levinson.cpp.
| void stereo_callback | ( | const sensor_msgs::ImageConstPtr & | image_msg | ) |
Definition at line 502 of file levinson.cpp.
| void transformAsMatrix | ( | const tf::Transform & | bt, |
| Eigen::Matrix4f & | out_mat | ||
| ) |
Definition at line 286 of file levinson.cpp.
| bool cameraReceived |
Definition at line 72 of file levinson.cpp.
| ros::Publisher cloud_pub |
Definition at line 74 of file levinson.cpp.
| pcl::PointCloud<Velodyne::Point>::Ptr edges_cloud |
Definition at line 73 of file levinson.cpp.
| cv::Mat img_out |
Definition at line 75 of file levinson.cpp.
| bool laserReceived |
Definition at line 72 of file levinson.cpp.
| bool listen_to_tf_ |
Definition at line 77 of file levinson.cpp.
| bool save_to_file_ |
Definition at line 77 of file levinson.cpp.
| std::ofstream savefile |
Definition at line 79 of file levinson.cpp.
| std::string source_frame |
Definition at line 76 of file levinson.cpp.
| int step_ |
Definition at line 78 of file levinson.cpp.
| std::string target_frame |
Definition at line 76 of file levinson.cpp.