Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <ros/ros.h>
00039 #include <stdlib.h>
00040 #include <stdio.h>
00041 #include <unistd.h>
00042 #include <vector>
00043 #include <string>
00044 #include <signal.h>
00045 #include <boost/thread/mutex.hpp>
00046 #include <boost/thread/thread.hpp>
00047 #include <tf/transform_listener.h>
00048 #include <tf/message_filter.h>
00049 #include <message_filters/subscriber.h>
00050 #include <tf/transform_broadcaster.h>
00051 #include <lse_sensor_msgs/Nostril.h>
00052 #include <pp_explorer/ForeignNostril.h>
00053 #include "wifi_comm/wifi_comm_lib.h"
00054
00055 using namespace wifi_comm;
00056
00057 class PPExplorerComm
00058 {
00059 public:
00060 PPExplorerComm();
00061 ~PPExplorerComm();
00062
00063 private:
00064 WiFiComm * comm;
00065 ros::NodeHandle n_;
00066
00068 message_filters::Subscriber<lse_sensor_msgs::Nostril> nose_sub_;
00070 tf::TransformListener tf_;
00071 tf::MessageFilter<lse_sensor_msgs::Nostril> * tf_filter_;
00072
00073 tf::TransformBroadcaster broadcaster_;
00074
00075 ros::Publisher foreign_nose_pub_;
00076 ros::Subscriber foreign_nose_sub_;
00077
00078 ros::Publisher nose_pub_;
00079
00080 void localNoseCallback(const boost::shared_ptr<const lse_sensor_msgs::Nostril>& msg);
00081 void othersNoseCallback(const pp_explorer::ForeignNostril::ConstPtr& msg);
00082 void robotJoinedNetwork(char * ip);
00083 };
00084
00085 PPExplorerComm::PPExplorerComm() : n_()
00086 {
00087 comm = new WiFiComm(boost::bind(&PPExplorerComm::robotJoinedNetwork, this, _1));
00088
00089 nose_sub_.subscribe(n_, "/nose", 10);
00090 tf_filter_ = new tf::MessageFilter<lse_sensor_msgs::Nostril>(nose_sub_, tf_, "/map", 50);
00091 tf_filter_->registerCallback( boost::bind(&PPExplorerComm::localNoseCallback, this, _1) );
00092
00093 foreign_nose_pub_ = n_.advertise<pp_explorer::ForeignNostril>("/my_nose", 10);
00094 foreign_nose_sub_ = n_.subscribe("/others_nose", 50, &PPExplorerComm::othersNoseCallback, this);
00095
00096 nose_pub_ = n_.advertise<lse_sensor_msgs::Nostril>("/nose", 10);
00097 }
00098
00099 PPExplorerComm::~PPExplorerComm()
00100 {
00101 delete comm;
00102 }
00103
00104 void PPExplorerComm::localNoseCallback(const boost::shared_ptr<const lse_sensor_msgs::Nostril>& msg)
00105 {
00106 if(msg->header.frame_id.compare("dummy") != 0) return;
00107
00108 geometry_msgs::PoseStamped nose;
00109 nose.header.frame_id = msg->header.frame_id;
00110 nose.header.stamp = msg->header.stamp;
00111 nose.pose.position.x = 0.0;
00112 nose.pose.position.y = 0.0;
00113 nose.pose.position.z = 0.0;
00114
00115 geometry_msgs::PoseStamped pp_pose;
00116 try
00117 {
00118
00119 tf_.transformPose("/map", nose, pp_pose);
00120 }
00121 catch(tf::TransformException &ex)
00122 {
00123 ROS_ERROR("PPExplorerComm -- Error: %s", ex.what());
00124 return;
00125 }
00126
00127 pp_explorer::ForeignNostril my_nose_msg;
00128 my_nose_msg.nostril = *msg;
00129 my_nose_msg.pose = pp_pose;
00130
00131 foreign_nose_pub_.publish(my_nose_msg);
00132 }
00133
00134 void PPExplorerComm::othersNoseCallback(const pp_explorer::ForeignNostril::ConstPtr& msg)
00135 {
00136 lse_sensor_msgs::Nostril nose_msg = msg->nostril;
00137 nose_msg.header.stamp = ros::Time::now();
00138
00139 nose_pub_.publish(nose_msg);
00140
00141 broadcaster_.sendTransform(tf::StampedTransform(tf::Transform(tf::Quaternion(msg->pose.pose.orientation.x, msg->pose.pose.orientation.y, msg->pose.pose.orientation.z, msg->pose.pose.orientation.w), tf::Vector3(msg->pose.pose.position.x, msg->pose.pose.position.y, msg->pose.pose.position.z)), ros::Time::now(), msg->pose.header.frame_id.c_str()
00142
00143 , msg->nostril.header.frame_id.c_str()));
00144 }
00145
00146 void PPExplorerComm::robotJoinedNetwork(char * ip)
00147 {
00148
00149 comm->openForeignRelay(ip, "/my_nose", "/others_nose");
00150 }
00151
00152
00153 int main( int argc, char** argv )
00154 {
00155 ros::init(argc, argv, "pp_explorer_comm");
00156
00157 PPExplorerComm myComm;
00158
00159 ros::spin();
00160
00161 return 0;
00162 }
00163
00164
00165