22 #include "pcl_thread.h"
24 #include <core/threading/mutex_locker.h>
26 #include <sensor_msgs/PointCloud2.h>
37 :
Thread(
"RosPointCloudThread",
Thread::OPMODE_WAITFORWAKEUP),
53 cfg_ros_research_ival_ =
config->
get_float(
"/ros/pcl/ros-search-interval");
55 fawkes_pointcloud_search();
57 ros_pointcloud_search();
58 ros_pointcloud_last_searched_.
stamp();
64 for (
const std::string &item : ros_pointcloud_available_) {
67 for (
const auto &item : ros_pointcloud_available_ref_) {
70 for (std::pair<std::string, ros::Subscriber> item : ros_pointcloud_subs_) {
71 item.second.shutdown();
83 >= cfg_ros_research_ival_) {
84 ros_pointcloud_last_searched_ = now;
85 ros_pointcloud_search();
86 ros_pointcloud_check_for_listener_in_fawkes();
91 fawkes_pointcloud_publish_to_ros();
96 RosPointCloudThread::ros_pointcloud_search()
98 std::list<std::string> ros_pointclouds_new;
101 ros::master::V_TopicInfo ros_topics;
102 if (!ros::master::getTopics(ros_topics)) {
108 for (
const ros::master::TopicInfo &info : ros_topics) {
110 if (0 == info.datatype.compare(
"sensor_msgs/PointCloud2")) {
112 bool topic_not_from_fawkes =
true;
113 for (
const auto &fawkes_cloud : fawkes_pubs_) {
114 if (0 == info.name.compare(fawkes_cloud.second.pub.getTopic())) {
115 topic_not_from_fawkes =
false;
118 if (topic_not_from_fawkes) {
119 ros_pointclouds_new.push_back(info.name);
125 std::list<std::string> items_to_remove;
126 for (
const std::string &item_old : ros_pointcloud_available_) {
128 for (std::string item_new : ros_pointclouds_new) {
129 if (0 == item_old.compare(item_new)) {
135 items_to_remove.push_back(item_old);
138 for (
const std::string &item : items_to_remove) {
139 logger->
log_info(
name(),
"Pointcloud %s is not available from ROS anymore", item.c_str());
140 ros_pointcloud_available_.remove(item);
144 for (
const std::string &ros_topic : ros_pointclouds_new) {
146 for (
const std::string &in_list : ros_pointcloud_available_) {
147 if (0 == ros_topic.compare(in_list)) {
153 logger->
log_info(
name(),
"Pointcloud %s is now available from ROS", ros_topic.c_str());
154 ros_pointcloud_available_.push_back(ros_topic);
155 ros_pointcloud_subs_[ros_topic] =
rosnode->subscribe<sensor_msgs::PointCloud2>(
158 boost::bind(&RosPointCloudThread::ros_pointcloud_on_data_msg,
this, _1, ros_topic));
164 RosPointCloudThread::ros_pointcloud_check_for_listener_in_fawkes()
166 for (
const auto &item : ros_pointcloud_available_ref_) {
167 unsigned int use_count = 0;
168 if (item.second->is_pointtype<pcl::PointXYZ>()) {
172 }
else if (item.second->is_pointtype<pcl::PointXYZRGB>()) {
176 }
else if (item.second->is_pointtype<pcl::PointXYZI>()) {
187 std::map<std::string, ros::Subscriber>::iterator element =
188 ros_pointcloud_subs_.find(item.first);
189 if (element != ros_pointcloud_subs_.end()) {
190 element->second.shutdown();
191 ros_pointcloud_subs_.erase(item.first);
194 ros_pointcloud_subs_[item.first] =
rosnode->subscribe<sensor_msgs::PointCloud2>(
197 boost::bind(&RosPointCloudThread::ros_pointcloud_on_data_msg,
this, _1, item.first));
203 RosPointCloudThread::fawkes_pointcloud_search()
207 std::vector<std::string>::iterator p;
208 for (p = pcls.begin(); p != pcls.end(); ++p) {
209 std::string topic_name = std::string(
"fawkes_pcls/") + *p;
210 std::string::size_type pos = 0;
211 while ((pos = topic_name.find(
"-", pos)) != std::string::npos) {
212 topic_name.replace(pos, 1,
"_");
216 pi.pub =
rosnode->advertise<sensor_msgs::PointCloud2>(topic_name, 1);
218 logger->
log_info(
name(),
"Publishing point cloud %s at %s", p->c_str(), topic_name.c_str());
220 std::string frame_id;
221 unsigned int width, height;
224 adapter_->
get_info(*p, width, height, frame_id, is_dense, fieldinfo);
225 pi.msg.header.frame_id = frame_id;
226 pi.msg.width = width;
227 pi.msg.height = height;
228 pi.msg.is_dense = is_dense;
229 pi.msg.fields.clear();
230 pi.msg.fields.resize(fieldinfo.size());
231 for (
unsigned int i = 0; i < fieldinfo.size(); ++i) {
232 pi.msg.fields[i].name = fieldinfo[i].name;
233 pi.msg.fields[i].offset = fieldinfo[i].offset;
234 pi.msg.fields[i].datatype = fieldinfo[i].datatype;
235 pi.msg.fields[i].count = fieldinfo[i].count;
238 fawkes_pubs_[*p] = pi;
243 RosPointCloudThread::fawkes_pointcloud_publish_to_ros()
245 std::map<std::string, PublisherInfo>::iterator p;
246 for (p = fawkes_pubs_.begin(); p != fawkes_pubs_.end(); ++p) {
247 PublisherInfo &pi = p->second;
249 unsigned int width, height;
251 size_t point_size, num_points;
254 std::string frame_id;
256 p->first, frame_id, width, height, time, &point_data, point_size, num_points);
258 if (pi.last_sent != time) {
261 size_t data_size = point_size * num_points;
262 pi.msg.data.resize(data_size);
263 memcpy(&pi.msg.data[0], point_data, data_size);
265 pi.msg.width = width;
266 pi.msg.height = height;
267 pi.msg.header.frame_id = frame_id;
268 pi.msg.header.stamp.sec = time.
get_sec();
269 pi.msg.header.stamp.nsec = time.
get_nsec();
270 pi.msg.point_step = point_size;
271 pi.msg.row_step = point_size * pi.msg.width;
273 pi.pub.publish(pi.msg);
279 adapter_->
close(p->first);
286 RosPointCloudThread::ros_pointcloud_on_data_msg(
const sensor_msgs::PointCloud2ConstPtr &msg,
287 const std::string & topic_name)
291 bool r =
false, i =
false;
292 for (
const sensor_msgs::PointField &field : msg->fields) {
294 if (0 == field.name.compare(
"r")) {
297 if (0 == field.name.compare(
"i")) {
302 logger->
log_info(
name(),
"Adding %s with type XYZ ROS -> FAWKES", topic_name.c_str());
303 add_pointcloud<pcl::PointXYZ>(msg, topic_name);
304 }
else if (r && !i) {
305 logger->
log_info(
name(),
"Adding %s with type XYZRGB ROS -> FAWKES", topic_name.c_str());
306 add_pointcloud<pcl::PointXYZRGB>(msg, topic_name);
307 }
else if (!r && i) {
308 logger->
log_info(
name(),
"Adding %s with type XYRI ROS -> FAWKES", topic_name.c_str());
309 add_pointcloud<pcl::PointXYZI>(msg, topic_name);
312 add_pointcloud<pcl::PointXYZ>(msg, topic_name);
319 update_pointcloud<pcl::PointXYZ>(msg, topic_name);
321 update_pointcloud<pcl::PointXYZRGB>(msg, topic_name);
323 update_pointcloud<pcl::PointXYZI>(msg, topic_name);
328 ros_pointcloud_check_for_listener_in_fawkes();
Point cloud adapter class.
void get_data(const std::string &id, std::string &frame_id, unsigned int &width, unsigned int &height, fawkes::Time &time, void **data_ptr, size_t &point_size, size_t &num_points)
Get current data of point cloud.
void close(const std::string &id)
Close an adapter.
void get_info(const std::string &id, unsigned int &width, unsigned int &height, std::string &frame_id, bool &is_dense, V_PointFieldInfo &pfi)
Get info about point cloud.
std::vector< PointFieldInfo > V_PointFieldInfo
Vector of PointFieldInfo.
virtual void loop()
Code to execute in the thread.
virtual void finalize()
Finalize the thread.
RosPointCloudThread()
Constructor.
virtual void init()
Initialize the thread.
virtual ~RosPointCloudThread()
Destructor.
Thread aspect to use blocked timing.
Configuration * config
This is the Configuration member used to access the configuration.
virtual float get_float(const char *path)=0
Get value from configuration which is of type float.
virtual void log_error(const char *component, const char *format,...)=0
Log error message.
virtual void log_info(const char *component, const char *format,...)=0
Log informational message.
Logger * logger
This is the Logger member used to access the logger.
PointCloudManager * pcl_manager
Manager to distribute and access point clouds.
void remove_pointcloud(const char *id)
Remove the point cloud.
std::vector< std::string > get_pointcloud_list() const
Get list of point cloud IDs.
const pcl_utils::StorageAdapter * get_storage_adapter(const char *id)
Get a storage adapter.
bool exists_pointcloud(const char *id)
Check if point cloud exists.
LockPtr< ros::NodeHandle > rosnode
Central ROS node handle.
Thread class encapsulation of pthreads.
const char * name() const
Get name of thread.
A class for handling time.
Time & stamp()
Set this time to the current time.
const timeval * get_timeval() const
Obtain the timeval where the time is stored.
long get_nsec() const
Get nanoseconds.
long get_sec() const
Get seconds.
Adapter class for PCL point types.
bool is_pointtype() const
Check if storage adapter is for specified point type.
Fawkes library namespace.
double time_diff_sec(const timeval &a, const timeval &b)
Calculate time difference of two time structs.