29 #include <ros/publisher.h> 31 #include <sys/socket.h> 32 #include <linux/wireless.h> 33 #include <sys/ioctl.h> 36 #include <rtabmap_ros/UserData.h> 57 else if(quality >= 100)
60 return (quality / 2) - 100;
63 int main(
int argc,
char** argv)
70 std::string
interface = "wlan0";
72 std::string
frameId =
"base_link";
74 pnh.
param(
"interface", interface, interface);
75 pnh.
param(
"rate", rateHz, rateHz);
76 pnh.
param(
"frame_id", frameId, frameId);
91 if((sockfd = socket(AF_INET, SOCK_DGRAM, 0)) == -1) {
92 ROS_ERROR(
"Could not create simple datagram socket");
97 struct iw_statistics stats;
99 strncpy(req.ifr_name, interface.c_str(), IFNAMSIZ);
102 req.u.data.pointer = (caddr_t) &stats;
103 req.u.data.length =
sizeof(stats);
105 req.u.data.flags = 1;
108 if(ioctl(sockfd, SIOCGIWSTATS, &req) == -1)
111 ROS_ERROR(
"Invalid interface (\"%s\"). Tip: Try with sudo!", interface.c_str());
113 else if(((iw_statistics *)req.u.data.pointer)->qual.updated & IW_QUAL_DBM)
116 dBm = ((iw_statistics *)req.u.data.pointer)->qual.level - 256;
120 ROS_ERROR(
"Could not get signal level.");
130 cv::Mat
data(1, 2, CV_64FC1);
131 data.at<
double>(0) =
double(dBm);
136 data.at<
double>(1) = stamp.
toSec();
138 rtabmap_ros::UserData dataMsg;
139 dataMsg.header.frame_id =
frameId;
140 dataMsg.header.stamp =
stamp;
142 wifiPub.
publish<rtabmap_ros::UserData>(dataMsg);
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int quality2dBm(int quality)
void userDataToROS(const cv::Mat &data, rtabmap_ros::UserData &dataMsg, bool compress)
ROSCPP_DECL void spinOnce()