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>    70 void HSVtoRGB( 
float *r, 
float *g, 
float *b, 
float h, 
float s, 
float v )
    83         q = v * ( 1 - s * f );
    84         t = v * ( 1 - s * ( 1 - f ) );
   128         std::map<int, rtabmap::Transform> poses;
   129         std::multimap<int, rtabmap::Link> links;
   130         std::map<int, rtabmap::Signature> signatures;
   134         for(std::map<int, rtabmap::Signature>::iterator iter=signatures.begin(); iter!=signatures.end(); ++iter)
   136                 int id = iter->first;
   151                         if(data.type() == CV_64FC1 && data.rows == 1 && data.cols == 2)
   154                                 int level = data.at<
double>(0);
   155                                 double stamp = data.at<
double>(1);
   156                                 wifiLevels.insert(std::make_pair(stamp, level));
   158                         else if(!data.empty())
   160                                 ROS_ERROR(
"Wrong user data format for wifi signal.");
   167         std::map<double, int> nodeStamps;
   170                 std::map<int, rtabmap::Transform>::const_iterator jter = poses.find(iter->second);
   171                 if(jter != poses.end())
   173                         nodeStamps.insert(*iter);
   179                 ROS_WARN(
"No wifi signal detected yet in user data of map data");
   186         pcl::PointCloud<pcl::PointXYZRGB>::Ptr assembledWifiSignals(
new pcl::PointCloud<pcl::PointXYZRGB>);
   189         for(std::map<double, int>::iterator iter=
wifiLevels.begin(); iter!=
wifiLevels.end(); ++iter, ++id)
   191                 if(min == 0.0
f || min > iter->second)
   195                 if(
max == 0.0
f || max < iter->second)
   206         for(std::map<double, int>::iterator iter=
wifiLevels.begin(); iter!=
wifiLevels.end(); ++iter, ++id)
   209                 double stampWifi = iter->first;
   210                 std::map<double, int>::iterator previousNode = nodeStamps.lower_bound(stampWifi); 
   211                 if(previousNode!=nodeStamps.end() && previousNode->first > stampWifi && previousNode != nodeStamps.begin())
   215                 std::map<double, int>::iterator nextNode = nodeStamps.upper_bound(stampWifi); 
   217                 if(previousNode != nodeStamps.end() &&
   218                    nextNode != nodeStamps.end() &&
   219                    previousNode->second != nextNode->second &&
   224                         double stampA = previousNode->first;
   225                         double stampB = nextNode->first;
   226                         UASSERT(stampWifi>=stampA && stampWifi <=stampB);
   229                         double ratio = (stampWifi-stampA)/(stampB-stampA);
   237                         pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
   244                                 pcl::PointXYZRGB anchor;
   248                                 cloud->push_back(anchor);
   255                                 for(
int i=0; i<10; ++i)
   260                                         pt.z = float(i+1)*0.02f;
   274                                                 pt.r = pt.g = pt.b = 100;
   276                                         cloud->push_back(pt);
   278                                 pcl::PointXYZRGB anchor;
   280                                 cloud->push_back(anchor);
   285                         if(assembledWifiSignals->size() == 0)
   287                                 *assembledWifiSignals = *cloud;
   291                                 *assembledWifiSignals += *cloud;
   296         if(assembledWifiSignals->size())
   298                 sensor_msgs::PointCloud2 cloudMsg;
   300                 cloudMsg.header = mapDataMsg->header;
   301                 wifiSignalCloudPub.
publish(cloudMsg);
   305 int main(
int argc, 
char** argv)
   307         ros::init(argc, argv, 
"wifi_signal_sub");
   317         wifiSignalCloudPub = nh.
advertise<sensor_msgs::PointCloud2>(
"wifi_signals", 1);
 
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
void HSVtoRGB(float *r, float *g, float *b, float h, float s, float v)
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)
geometry_msgs::TransformStamped t
#define UASSERT(condition)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
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)
GLM_FUNC_DECL genType floor(genType const &x)
const EnvSensors & envSensors() const
std::map< double, int > nodeStamps_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool uContains(const std::list< V > &list, const V &value)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
SensorData & sensorData()
const cv::Mat & userDataCompressed() const
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
const double & stamp() const
int main(int argc, char **argv)
ros::Publisher wifiSignalCloudPub
const double & value() const
void uncompressDataConst(cv::Mat *imageRaw, cv::Mat *depthOrRightRaw, LaserScan *laserScanRaw=0, cv::Mat *userDataRaw=0, cv::Mat *groundCellsRaw=0, cv::Mat *obstacleCellsRaw=0, cv::Mat *emptyCellsRaw=0) const