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 #include <ros/ros.h>
00038 #include <plumesim/ReadPlumeSim.h>
00039 #include <lse_sensor_msgs/Nostril.h>
00040 #include <nav_msgs/Odometry.h>
00041 #include <cstdlib>
00042
00043 using namespace plumesim;
00044
00045 nav_msgs::Odometry my_odom;
00046
00047 void odomCallback(const nav_msgs::OdometryConstPtr& msg)
00048 {
00049 my_odom.pose.pose.position.x = msg->pose.pose.position.x;
00050 my_odom.pose.pose.position.y = msg->pose.pose.position.y;
00051 my_odom.pose.pose.position.z = msg->pose.pose.position.z;
00052 }
00053
00054 int main(int argc, char **argv)
00055 {
00056 ros::init(argc, argv, "virtual_nose_node");
00057
00058 ROS_INFO("VirtualNose for ROS v0.2");
00059
00060 ros::NodeHandle n;
00061 ros::NodeHandle pn("~");
00062
00063 std::string frame_id;
00064 pn.param<std::string>("frame_id", frame_id, "base_link");
00065
00066 std::string plumesim_name;
00067 pn.param<std::string>("plumesim_name", plumesim_name, "plumesim/read_plumesim");
00068
00069 ros::Subscriber odom_sub = n.subscribe("odom", 10, odomCallback);
00070
00071 ros::Publisher nose_pub = n.advertise<lse_sensor_msgs::Nostril>("/nose", 10);
00072
00073 ros::ServiceClient client = n.serviceClient<plumesim::ReadPlumeSim>(plumesim_name.c_str());
00074
00075 ros::Rate r(10);
00076 while(ros::ok())
00077 {
00078 plumesim::ReadPlumeSim srv;
00079 srv.request.odom.pose.pose.position.x = my_odom.pose.pose.position.x;
00080 srv.request.odom.pose.pose.position.y = my_odom.pose.pose.position.y;
00081 srv.request.odom.pose.pose.position.z = my_odom.pose.pose.position.z;
00082
00083 if(client.call(srv))
00084 {
00085 lse_sensor_msgs::Nostril nose_msg;
00086
00087 nose_msg.reading = srv.response.nostril.reading*3300.00/100.0;
00088 nose_msg.header.stamp = ros::Time::now();
00089 nose_msg.header.frame_id = frame_id;
00090 nose_msg.min_reading = 0.0;
00091 nose_msg.max_reading = 3300.0;
00092 nose_msg.sensor_model = "Virtual Nose";
00093
00094 nose_pub.publish(nose_msg);
00095 }
00096 else
00097 {
00098 ROS_ERROR("Virtual Nose -- Failed to get a reading from PlumeSim.");
00099 }
00100 ros::spinOnce();
00101 r.sleep();
00102 }
00103
00104 return(0);
00105 }