29 #include <ros/publisher.h> 36 #include <rtabmap_ros/MapData.h> 39 #include <sensor_msgs/PointCloud2.h> 41 #include <pcl/point_cloud.h> 42 #include <pcl/point_types.h> 60 return 2 * (dBm + 100);
71 std::map<int, rtabmap::Transform> poses;
72 std::multimap<int, rtabmap::Link> links;
73 std::map<int, rtabmap::Signature> signatures;
76 std::map<double, int> nodeStamps;
77 for(std::map<int, rtabmap::Signature>::iterator iter=signatures.begin(); iter!=signatures.end(); ++iter)
80 iter->second.sensorData().uncompressDataConst(0 ,0, 0, &data);
82 if(data.type() == CV_64FC1 && data.rows == 1 && data.cols == 2)
85 int level = data.at<
double>(0);
86 double stamp = data.at<
double>(1);
87 wifiLevels.insert(std::make_pair(stamp, level));
89 else if(!data.empty())
91 ROS_ERROR(
"Wrong user data format for wifi signal.");
95 nodeStamps.insert(std::make_pair(iter->second.getStamp(), iter->first));
100 ROS_WARN(
"No wifi signal detected yet in user data of map data");
107 pcl::PointCloud<pcl::PointXYZRGB>::Ptr assembledWifiSignals(
new pcl::PointCloud<pcl::PointXYZRGB>);
109 for(std::map<double, int>::iterator iter=
wifiLevels.begin(); iter!=
wifiLevels.end(); ++iter, ++id)
112 double stampWifi = iter->first;
113 std::map<double, int>::iterator previousNode = nodeStamps.lower_bound(stampWifi);
114 if(previousNode!=nodeStamps.end() && previousNode->first > stampWifi && previousNode != nodeStamps.begin())
118 std::map<double, int>::iterator nextNode = nodeStamps.upper_bound(stampWifi);
120 if(previousNode != nodeStamps.end() &&
121 nextNode != nodeStamps.end() &&
122 previousNode->second != nextNode->second &&
127 double stampA = previousNode->first;
128 double stampB = nextNode->first;
129 UASSERT(stampWifi>=stampA && stampWifi <=stampB);
132 double ratio = (stampWifi-stampA)/(stampB-stampA);
142 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
143 for(
int i=0; i<10; ++i)
148 pt.z = float(i+1)*0.02f;
162 pt.r = pt.g = pt.b = 100;
164 cloud->push_back(pt);
166 pcl::PointXYZRGB anchor(255, 0, 0);
167 cloud->push_back(anchor);
171 if(assembledWifiSignals->size() == 0)
173 *assembledWifiSignals = *cloud;
177 *assembledWifiSignals += *cloud;
182 if(assembledWifiSignals->size())
184 sensor_msgs::PointCloud2 cloudMsg;
186 cloudMsg.header = mapDataMsg->header;
187 wifiSignalCloudPub.
publish(cloudMsg);
191 int main(
int argc,
char** argv)
193 ros::init(argc, argv,
"wifi_signal_sub");
198 std::string
interface = "wlan0";
200 std::string frameId =
"base_link";
202 wifiSignalCloudPub = nh.
advertise<sensor_msgs::PointCloud2>(
"wifi_signals", 1);
void publish(const boost::shared_ptr< M > &message) const
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
std::map< double, int > wifiLevels
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void mapDataCallback(const rtabmap_ros::MapDataConstPtr &mapDataMsg)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
#define UASSERT(condition)
void mapDataFromROS(const rtabmap_ros::MapData &msg, std::map< int, rtabmap::Transform > &poses, std::multimap< int, rtabmap::Link > &links, std::map< int, rtabmap::Signature > &signatures, rtabmap::Transform &mapToOdom)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool uContains(const std::list< V > &list, const V &value)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
int main(int argc, char **argv)
ros::Publisher wifiSignalCloudPub