46 #ifndef __PCD_FILTER_PA_NODE_H 47 #define __PCD_FILTER_PA_NODE_H 52 #include "pcdfilter_pa/PcdFilterPaFilter.h" 53 #include "pcdfilter_pa/PcdFilterPaCloud.h" 58 #include <sensor_msgs/PointCloud2.h> 59 #include <sensor_msgs/PointCloud.h> 60 #include <sensor_msgs/LaserScan.h> 61 #include <std_srvs/Empty.h> 70 int main(
int argc,
char **argv);
123 pcdfilter_pa::PcdFilterPaCloud::Request &req,
124 pcdfilter_pa::PcdFilterPaCloud::Response &res);
128 pcdfilter_pa::PcdFilterPaFilter::Request &req,
129 pcdfilter_pa::PcdFilterPaFilter::Response &res);
132 pcdfilter_pa::PcdFilterPaFilter::Request &req,
133 pcdfilter_pa::PcdFilterPaFilter::Response &res);
137 std_srvs::Empty::Response &res);
140 std_srvs::Empty::Response &res);
143 void addFilters(
const std::vector<std::string> &new_filters);
152 #endif // __PCD_FILTER_PA_NODE_H void addFilters(const std::vector< std::string > &new_filters)
function for adding several filters and giving feedback
void disable(void)
function for deactivating this node (disabling inputs)
ros::ServiceServer ser_add_filters_
service for adding additional filters
ros::ServiceServer ser_filter_
service for filtering
bool enableCallbackSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
callback function for enabling filter node
tf::TransformListener tf_listener_
for getting all necessary tfs
ros::Subscriber sub_pcd_old_
subscriber for a pointcloud (old format)
int main(int argc, char **argv)
bool changeFiltersCallbackSrv(pcdfilter_pa::PcdFilterPaFilter::Request &req, pcdfilter_pa::PcdFilterPaFilter::Response &res)
callback function for changing filters
ros::ServiceServer ser_enable_
service for enabling node
bool addFiltersCallbackSrv(pcdfilter_pa::PcdFilterPaFilter::Request &req, pcdfilter_pa::PcdFilterPaFilter::Response &res)
callback function for adding additional filters
cPcdFilterPaNode()
default constructor
void enable(void)
function for activating this node (enabling inputs)
ros::Subscriber sub_laser_
subscriber for a laserscan
ros::Subscriber sub_pcd_
subscriber for a pointcloud
void setCloudLaserCallbackSub(const sensor_msgs::LaserScanConstPtr &msg)
callback function for receiving a laserscan
~cPcdFilterPaNode()
default destructor
ros::NodeHandle nh_
node handler for topic subscription and advertising
cPcdFilterPaNodeParameter nodeparams_
ros specific variables, which will be read from Parameterserver
bool disableCallbackSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
callback function for disabling filter node
void setCloudCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for receiving a pointcloud
ros::Publisher pub_pcd_
publisher for filtered pointcloud
bool filterCallbackSrv(pcdfilter_pa::PcdFilterPaCloud::Request &req, pcdfilter_pa::PcdFilterPaCloud::Response &res)
callback function for filtering via service
ros::ServiceServer ser_change_filters_
service for changing filters
ros::ServiceServer ser_disable_
service for disabling node
void setCloudOldCallbackSub(const sensor_msgs::PointCloudConstPtr &msg)
callback function for receiving a pointcloud (old format)