Namespaces | Functions
pcl_ros_util.h File Reference
#include <ros/ros.h>
#include <std_msgs/Header.h>
#include <pcl_msgs/PointIndices.h>
#include <jsk_recognition_msgs/BoundingBox.h>
#include <pcl/PointIndices.h>
#include <pcl/filters/crop_box.h>
#include <sensor_msgs/PointCloud2.h>
#include "jsk_recognition_utils/pcl_conversion_util.h"
Include dependency graph for pcl_ros_util.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 jsk_recognition_utils
 

Functions

template<typename PointT >
void jsk_recognition_utils::cropPointCloud (const typename pcl::PointCloud< PointT >::Ptr &cloud, const jsk_recognition_msgs::BoundingBox &bbox_msg, std::vector< int > *indices, bool extract_removed_indices=false)
 Crop point cloud with jsk_recognition_msgs/BoundingBox. More...
 
bool jsk_recognition_utils::hasField (const std::string &field_name, const sensor_msgs::PointCloud2 &msg)
 check if sensor_msgs/PointCloud2 message has the specified field. More...
 
bool jsk_recognition_utils::isSameFrameId (const std::string &a, const std::string &b)
 Return true if a and b are the same frame_id. More...
 
bool jsk_recognition_utils::isSameFrameId (const std_msgs::Header &a, const std_msgs::Header &b)
 Return true if a and b have the same frame_id. More...
 
template<class T1 , class T2 >
bool jsk_recognition_utils::isSameFrameId (const T1 &a, const T2 &b)
 Return true if a and b have the same frame_id. More...
 
void jsk_recognition_utils::publishPointIndices (ros::Publisher &pub, const pcl::PointIndices &indices, const std_msgs::Header &header)
 Convert pcl::PointIndices to pcl_msgs::PointIndices and publish it with overriding header. More...
 


jsk_recognition_utils
Author(s):
autogenerated on Mon May 3 2021 03:03:03