37 #ifndef JSK_PCL_ROS_POINTCLOUD_LOCALIZATION 38 #define JSK_PCL_ROS_POINTCLOUD_LOCALIZATION 43 #include <std_srvs/Empty.h> 44 #include <sensor_msgs/PointCloud2.h> 45 #include <geometry_msgs/PoseStamped.h> 46 #include <pcl/point_cloud.h> 47 #include <pcl/point_types.h> 48 #include <jsk_recognition_msgs/UpdateOffset.h> 68 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
75 std_srvs::Empty::Request&
req,
76 std_srvs::Empty::Response&
res);
103 jsk_recognition_msgs::UpdateOffset::Request& req,
104 jsk_recognition_msgs::UpdateOffset::Response& res);
107 pcl::PointCloud<pcl::PointNormal>::Ptr in_cloud,
108 pcl::PointCloud<pcl::PointNormal>& out_cloud);
std::string sensor_frame_
bool clip_unseen_pointcloud_
tf::Transform localize_transform_
ros::Publisher pub_cloud_
virtual void cloudCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
callback function of ~input topic.
tf::TransformListener * tf_listener_
ros::ServiceServer localization_srv_
virtual void applyDownsampling(pcl::PointCloud< pcl::PointNormal >::Ptr in_cloud, pcl::PointCloud< pcl::PointNormal > &out_cloud)
pcl::PointCloud< pcl::PointNormal >::Ptr all_cloud_
ros::ServiceServer update_offset_srv_
sensor_msgs::PointCloud2::ConstPtr latest_cloud_
virtual bool localizationRequest(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
callback function of ~localize service.
bool use_normal_
Resolution of voxel grid.
std::string global_frame_
Publishes tf transformation of global_frame_ -> odom_frame_.
virtual void unsubscribe()
virtual void cloudTimerCallback(const ros::TimerEvent &event)
cloud periodic timer callback
boost::mutex mutex
global mutex.
std::string initialize_tf_
tf::TransformBroadcaster tf_broadcast_
virtual bool isFirstTime()
return true if it is the first time to localize
virtual bool updateOffsetCallback(jsk_recognition_msgs::UpdateOffset::Request &req, jsk_recognition_msgs::UpdateOffset::Response &res)
callback function for ~update_offset service
virtual void tfTimerCallback(const ros::TimerEvent &event)
tf periodic timer callback