Go to the documentation of this file.
32 #include "sensor_msgs/LaserScan.h"
60 sensor_msgs::LaserScan
msg_;
86 std::string tf_message_filter_target_frame;
128 ROS_WARN(
"Use of '~filter_chain' parameter in scan_to_scan_filter_chain has been deprecated. Please replace with '~scan_filter_chain'.");
132 void callback(
const sensor_msgs::LaserScan::ConstPtr& msg_in)
140 ROS_ERROR_THROTTLE(1,
"Filtering the scan from time %i.%i failed.", msg_in->header.stamp.sec, msg_in->header.stamp.nsec);
149 std::unique_ptr<ScanToScanFilterChain> chain_;
160 int main(
int argc,
char **argv)
162 ros::init(argc, argv,
"scan_to_scan_filter_chain");
#define ROS_ERROR_THROTTLE(period,...)
filters::FilterChain< sensor_msgs::LaserScan > filter_chain_
ros::NodeHandle & getNodeHandle() const
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::NodeHandle private_nh_
void setTolerance(const ros::Duration &tolerance)
bool getParam(const std::string &key, bool &b) const
double tf_filter_tolerance_
int main(int argc, char **argv)
ros::NodeHandle & getPrivateNodeHandle() const
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
bool configure(std::string param_name, ros::NodeHandle node=ros::NodeHandle())
ros::Timer deprecation_timer_
bool using_filter_chain_deprecated_
bool update(const T &data_in, T &data_out)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
ros::Publisher output_pub_
bool hasParam(const std::string &key) const
ScanToScanFilterChain(const ros::NodeHandle &nh={}, const ros::NodeHandle &pnh={"~"})
Connection registerCallback(const boost::function< void(P)> &callback)
void deprecation_warn(const ros::TimerEvent &e)
tf::MessageFilter< sensor_msgs::LaserScan > * tf_filter_
void setTargetFrame(const std::string &target_frame)
message_filters::Subscriber< sensor_msgs::LaserScan > scan_sub_
sensor_msgs::LaserScan msg_
T param(const std::string ¶m_name, const T &default_val) const
tf::TransformListener * tf_
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
void callback(const sensor_msgs::LaserScan::ConstPtr &msg_in)
geometry_msgs::TransformStamped t
laser_filters
Author(s): Tully Foote
autogenerated on Mon Apr 3 2023 02:51:57