42 dynamic_reconfigure::Server<depthimage_to_laserscan::DepthConfig>::CallbackType
f;
57 const sensor_msgs::CameraInfoConstPtr& info_msg){
60 sensor_msgs::LaserScanPtr scan_msg =
dtl_.
convert_msg(depth_msg, info_msg);
63 catch (std::runtime_error& e)
81 ROS_DEBUG(
"Unsubscribing from depth topic.");
image_transport::ImageTransport it_
Subscribes to synchronized Image CameraInfo pairs.
sensor_msgs::LaserScanPtr convert_msg(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
void publish(const boost::shared_ptr< M > &message) const
boost::mutex connect_mutex_
Prevents the connectCb and disconnectCb from being called until everything is initialized.
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, const CameraSubscriber::Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
image_transport::CameraSubscriber sub_
Subscriber for image_transport.
dynamic_reconfigure::Server< depthimage_to_laserscan::DepthConfig > srv_
Dynamic reconfigure server.
void set_output_frame(const std::string output_frame_id)
void depthCb(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
#define ROS_ERROR_THROTTLE(rate,...)
void set_scan_height(const int scan_height)
ros::NodeHandle pnh_
Private nodehandle used to generate the transport hints in the connectCb.
ros::Publisher pub_
Publisher for output LaserScan messages.
void connectCb(const ros::SingleSubscriberPublisher &pub)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint32_t getNumSubscribers() const
void set_scan_time(const float scan_time)
void disconnectCb(const ros::SingleSubscriberPublisher &pub)
void set_range_limits(const float range_min, const float range_max)
~DepthImageToLaserScanROS()
depthimage_to_laserscan::DepthImageToLaserScan dtl_
Instance of the DepthImageToLaserScan conversion class.
DepthImageToLaserScanROS(ros::NodeHandle &n, ros::NodeHandle &pnh)
void reconfigureCb(depthimage_to_laserscan::DepthConfig &config, uint32_t level)