#include <pcdfilter_pa_node.h>
Public Member Functions | |
cPcdFilterPaNode () | |
default constructor More... | |
~cPcdFilterPaNode () | |
default destructor More... | |
Public Member Functions inherited from cPcdFilterPaRos | |
sensor_msgs::PointCloud2Ptr | applyMasktoCloud (const sensor_msgs::PointCloud2ConstPtr cloud, const std::vector< bool > mask) const |
sensor_msgs::PointCloud2Ptr | convertCloud (const sensor_msgs::PointCloudConstPtr &msg) const |
converts the given pointcloud to newer format More... | |
sensor_msgs::PointCloud2Ptr | convertCloud (const sensor_msgs::LaserScanConstPtr &msg) const |
converts the given laserscan to a pointcloud More... | |
const cv::Mat | convertCloudToOpencv (const sensor_msgs::PointCloud2ConstPtr &msg, const bool force_copy=false) const |
cPcdFilterPaRos () | |
default constructor More... | |
bool | filterCloud (const sensor_msgs::PointCloud2ConstPtr &msg, sensor_msgs::PointCloud2Ptr &result) |
filters the given pointcloud More... | |
bool | filterCloud (sensor_msgs::PointCloud2Ptr &result) |
filters the buffered pointcloud More... | |
bool | updateTf (const tf::TransformListener &tf_listener, const std::string base_frame, const ros::Time time=ros::Time::now()) |
bool | updateTf (const tf::TransformListener &tf_listener) |
~cPcdFilterPaRos () | |
default destructor More... | |
Public Member Functions inherited from cPcdFilterPa | |
cPcdFilterPa () | |
default constructor More... | |
std::vector< int > | pointcloudFilter (const cv::Mat &pointcloud, std::vector< bool > &mask) const |
~cPcdFilterPa () | |
default destructor More... | |
Protected Member Functions | |
void | addFilters (const std::vector< std::string > &new_filters) |
function for adding several filters and giving feedback More... | |
bool | addFiltersCallbackSrv (pcdfilter_pa::PcdFilterPaFilter::Request &req, pcdfilter_pa::PcdFilterPaFilter::Response &res) |
callback function for adding additional filters More... | |
bool | changeFiltersCallbackSrv (pcdfilter_pa::PcdFilterPaFilter::Request &req, pcdfilter_pa::PcdFilterPaFilter::Response &res) |
callback function for changing filters More... | |
bool | disableCallbackSrv (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
callback function for disabling filter node More... | |
bool | enableCallbackSrv (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
callback function for enabling filter node More... | |
bool | filterCallbackSrv (pcdfilter_pa::PcdFilterPaCloud::Request &req, pcdfilter_pa::PcdFilterPaCloud::Response &res) |
callback function for filtering via service More... | |
void | setCloudCallbackSub (const sensor_msgs::PointCloud2ConstPtr &msg) |
callback function for receiving a pointcloud More... | |
void | setCloudLaserCallbackSub (const sensor_msgs::LaserScanConstPtr &msg) |
callback function for receiving a laserscan More... | |
void | setCloudOldCallbackSub (const sensor_msgs::PointCloudConstPtr &msg) |
callback function for receiving a pointcloud (old format) More... | |
Protected Attributes | |
ros::NodeHandle | nh_ |
node handler for topic subscription and advertising More... | |
cPcdFilterPaNodeParameter | nodeparams_ |
ros specific variables, which will be read from Parameterserver More... | |
ros::Publisher | pub_pcd_ |
publisher for filtered pointcloud More... | |
ros::ServiceServer | ser_add_filters_ |
service for adding additional filters More... | |
ros::ServiceServer | ser_change_filters_ |
service for changing filters More... | |
ros::ServiceServer | ser_disable_ |
service for disabling node More... | |
ros::ServiceServer | ser_enable_ |
service for enabling node More... | |
ros::ServiceServer | ser_filter_ |
service for filtering More... | |
ros::Subscriber | sub_laser_ |
subscriber for a laserscan More... | |
ros::Subscriber | sub_pcd_ |
subscriber for a pointcloud More... | |
ros::Subscriber | sub_pcd_old_ |
subscriber for a pointcloud (old format) More... | |
tf::TransformListener | tf_listener_ |
for getting all necessary tfs More... | |
Private Member Functions | |
void | disable (void) |
function for deactivating this node (disabling inputs) More... | |
void | enable (void) |
function for activating this node (enabling inputs) More... | |
Additional Inherited Members | |
Public Attributes inherited from cPcdFilterPaRos | |
cPcdFilterPaRosFilters | filters_ |
object for filter handling More... | |
cPcdFilterPaRosThrottle | input_throttle_ |
object for input throttling - e.g. only every 5th pointcloud More... | |
sensor_msgs::PointCloud2ConstPtr | pcd_buffered_msg_ |
cv::Mat | pcd_buffered_points_ |
cPcdFilterPaRosParameter | rosparams_ |
ros specific parameter More... | |
Public Attributes inherited from cPcdFilterPa | |
cPcdFilterPaParameter | params_ |
specific parameter More... | |
Definition at line 73 of file pcdfilter_pa_node.h.
cPcdFilterPaNode::cPcdFilterPaNode | ( | ) |
default constructor
Definition at line 68 of file pcdfilter_pa_node.cpp.
cPcdFilterPaNode::~cPcdFilterPaNode | ( | ) |
default destructor
Definition at line 136 of file pcdfilter_pa_node.cpp.
|
protected |
function for adding several filters and giving feedback
Definition at line 236 of file pcdfilter_pa_node.cpp.
|
protected |
callback function for adding additional filters
Definition at line 186 of file pcdfilter_pa_node.cpp.
|
protected |
callback function for changing filters
Definition at line 251 of file pcdfilter_pa_node.cpp.
|
private |
function for deactivating this node (disabling inputs)
Definition at line 307 of file pcdfilter_pa_node.cpp.
|
protected |
callback function for disabling filter node
Definition at line 272 of file pcdfilter_pa_node.cpp.
|
private |
function for activating this node (enabling inputs)
Definition at line 280 of file pcdfilter_pa_node.cpp.
|
protected |
callback function for enabling filter node
Definition at line 264 of file pcdfilter_pa_node.cpp.
|
protected |
callback function for filtering via service
Definition at line 206 of file pcdfilter_pa_node.cpp.
|
protected |
callback function for receiving a pointcloud
Definition at line 140 of file pcdfilter_pa_node.cpp.
|
protected |
callback function for receiving a laserscan
Definition at line 179 of file pcdfilter_pa_node.cpp.
|
protected |
callback function for receiving a pointcloud (old format)
Definition at line 172 of file pcdfilter_pa_node.cpp.
|
protected |
node handler for topic subscription and advertising
Definition at line 86 of file pcdfilter_pa_node.h.
|
protected |
ros specific variables, which will be read from Parameterserver
Definition at line 83 of file pcdfilter_pa_node.h.
|
protected |
publisher for filtered pointcloud
Definition at line 99 of file pcdfilter_pa_node.h.
|
protected |
service for adding additional filters
Definition at line 105 of file pcdfilter_pa_node.h.
|
protected |
service for changing filters
Definition at line 107 of file pcdfilter_pa_node.h.
|
protected |
service for disabling node
Definition at line 112 of file pcdfilter_pa_node.h.
|
protected |
service for enabling node
Definition at line 110 of file pcdfilter_pa_node.h.
|
protected |
service for filtering
Definition at line 102 of file pcdfilter_pa_node.h.
|
protected |
subscriber for a laserscan
Definition at line 96 of file pcdfilter_pa_node.h.
|
protected |
subscriber for a pointcloud
Definition at line 92 of file pcdfilter_pa_node.h.
|
protected |
subscriber for a pointcloud (old format)
Definition at line 94 of file pcdfilter_pa_node.h.
|
protected |
for getting all necessary tfs
Definition at line 89 of file pcdfilter_pa_node.h.