32 #include "sensor_msgs/LaserScan.h" 53 sensor_msgs::LaserScan
msg_;
61 scan_sub_(nh_,
"scan_in", 50),
62 tf_filter_(scan_sub_, tf_,
"base_link", 50),
63 filter_chain_(
"sensor_msgs::LaserScan")
73 output_pub_ = nh_.
advertise<sensor_msgs::LaserScan>(
"output", 1000);
80 ROS_WARN(
"'generic_laser_filter_node' has been deprecated. Please switch to 'scan_to_scan_filter_chain'.");
84 void callback(
const sensor_msgs::LaserScan::ConstPtr& msg_in)
87 filter_chain_.
update (*msg_in, msg_);
94 int main(
int argc,
char **argv)
96 ros::init(argc, argv,
"scan_filter_node");
filters::FilterChain< sensor_msgs::LaserScan > filter_chain_
GenericLaserScanFilterNode()
ros::Timer deprecation_timer_
void publish(const boost::shared_ptr< M > &message) const
tf::TransformListener tf_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
sensor_msgs::LaserScan msg_
ROSCPP_DECL void spin(Spinner &spinner)
void deprecation_warn(const ros::TimerEvent &e)
ros::Publisher output_pub_
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool update(const T &data_in, T &data_out)
message_filters::Subscriber< sensor_msgs::LaserScan > scan_sub_
bool configure(std::string param_name, ros::NodeHandle node=ros::NodeHandle())
void callback(const sensor_msgs::LaserScan::ConstPtr &msg_in)
void setTolerance(const ros::Duration &tolerance)
tf::MessageFilter< sensor_msgs::LaserScan > tf_filter_
int main(int argc, char **argv)
Connection registerCallback(const C &callback)