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 #ifndef BEAMPUBLISHER_HPP_
00037 #define BEAMPUBLISHER_HPP_
00038 #include <labust/navigation/NavQuestMessages.hpp>
00039 #include <labust/tools/conversions.hpp>
00040 
00041 #include <geometry_msgs/TwistStamped.h>
00042 #include <std_msgs/Float32MultiArray.h>
00043 #include <ros/ros.h>
00044 
00045 namespace labust
00046 {
00047         namespace navigation
00048         {
00052                 template<std::size_t N>
00053                 struct BeamPublisher
00054                 {
00055                         typedef boost::shared_ptr<BeamPublisher<N> > Ptr;
00056                         BeamPublisher(ros::NodeHandle nh, const std::string& topic)
00057                         {
00058                                 pub = nh.advertise<std_msgs::Float32MultiArray>(topic,1);
00059                         }
00060 
00061                         void operator()(const float vec[N], int quality=50)
00062                         {
00063                                 std_msgs::Float32MultiArrayPtr array(
00064                                                 new std_msgs::Float32MultiArray());
00065                                 
00066                                 float cond_vec[N];
00067                                 for (int i=0; i<3;++i) cond_vec[i]=vec[i]/1000;
00068                                 array->data.assign(&cond_vec[0],&cond_vec[N]);
00069                                 
00070                                 pub.publish(array);
00071                         }
00072 
00073                         ros::Publisher pub;
00074                 };
00075 
00079                 struct TwistPublisher
00080                 {
00081                         typedef boost::shared_ptr<TwistPublisher> Ptr;
00082                         TwistPublisher(ros::NodeHandle nh, const std::string& topic,
00083                                         const std::string& frame_id):
00084                                                 frame_id(frame_id)
00085                         {
00086                                 pub = nh.advertise<geometry_msgs::TwistStamped>(topic,1);
00087                         }
00088 
00089                         void operator()(const float vec[3])
00090                         {
00091                                 geometry_msgs::TwistStamped::Ptr twist(
00092                                                 new geometry_msgs::TwistStamped());
00093                                 twist->header.stamp=ros::Time();
00094                                 twist->header.frame_id=frame_id;
00095                                 
00096                                 float cond_vec[3];
00097                                 for (int i=0; i<3;++i) cond_vec[i]=vec[i]/1000;
00098                                 labust::tools::vectorToPoint(cond_vec,twist->twist.linear);
00099                                 pub.publish(twist);
00100                         }
00101 
00102                         std::string frame_id;
00103                         ros::Publisher pub;
00104                 };
00105         }
00106 }
00107 
00108 
00109 #endif