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
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049 #ifndef _ROS_MSG_TRANSPORTER_HPP_
00050 #define _ROS_MSG_TRANSPORTER_HPP_
00051
00052 #include <rtt/types/TypeTransporter.hpp>
00053 #include <rtt/Port.hpp>
00054 #include <rtt/TaskContext.hpp>
00055 #include <rtt/internal/ConnFactory.hpp>
00056 #include <ros/ros.h>
00057
00058
00059 #include "ros_publish_activity.hpp"
00060
00061 namespace ros_integration {
00062
00063 using namespace RTT;
00068 template<typename T>
00069 class RosPubChannelElement: public base::ChannelElement<T>,public RosPublisher
00070 {
00071 char hostname[1024];
00072 std::string topicname;
00073 ros::NodeHandle ros_node;
00074 ros::Publisher ros_pub;
00076 RosPublishActivity::shared_ptr act;
00077
00078 public:
00079
00090 RosPubChannelElement(base::PortInterface* port,const ConnPolicy& policy)
00091 {
00092 if ( policy.name_id.empty() ){
00093 std::stringstream namestr;
00094 gethostname(hostname, sizeof(hostname));
00095
00096 namestr << hostname<<'/' << port->getInterface()->getOwner()->getName()
00097 << '/' << port->getName() << '/'<<this << '/' << getpid();
00098 policy.name_id = namestr.str();
00099 }
00100 topicname=policy.name_id;
00101 Logger::In in(topicname);
00102 log(Debug)<<"Creating ROS publisher for port "<<port->getInterface()->getOwner()->getName()<<"."<<port->getName()<<" on topic "<<policy.name_id<<endlog();
00103
00104 ros_pub = ros_node.advertise<T>(policy.name_id, policy.size);
00105 act = RosPublishActivity::Instance();
00106 act->addPublisher( this );
00107 }
00108
00109 ~RosPubChannelElement() {
00110 Logger::In in(topicname);
00111 log(Debug)<<"Destroying RosPubChannelElement"<<endlog();
00112 act->removePublisher( this );
00113 }
00114
00120 virtual bool inputReady() {
00121 return true;
00122 }
00123
00131 virtual bool data_sample(typename base::ChannelElement<T>::param_t sample)
00132 {
00133 return true;
00134 }
00135
00141 bool signal(){
00142
00143
00144 return act->requestPublish(this);
00145 }
00146
00147 void publish(){
00148 typename base::ChannelElement<T>::value_t sample;
00149
00150 typename base::ChannelElement<T>::shared_ptr input = this->getInput();
00151 while( input && (input->read(sample,true) == NewData) )
00152 ros_pub.publish(sample);
00153 }
00154
00155 };
00156
00157 template<typename T>
00158 class RosSubChannelElement: public base::ChannelElement<T>
00159 {
00160 ros::NodeHandle ros_node;
00161 ros::Subscriber ros_sub;
00162 bool newdata,init;
00163 base::DataObjectLockFree<T> m_msg;
00164
00165 public:
00175 RosSubChannelElement(base::PortInterface* port, const ConnPolicy& policy):
00176 newdata(false),init(false)
00177 {
00178 log(Debug)<<"Creating ROS subscriber for port "<<port->getInterface()->getOwner()->getName()<<"."<<port->getName()<<" on topic "<<policy.name_id<<endlog();
00179 ros_sub=ros_node.subscribe(policy.name_id,policy.size,&RosSubChannelElement::newData,this);
00180 this->ref();
00181 }
00182
00183 ~RosSubChannelElement() {
00184 }
00185
00186 virtual bool inputReady() {
00187 return true;
00188 }
00194 void newData(const T& msg){
00195 m_msg.Set(msg);
00196 newdata=true;
00197 init=true;
00198 this->signal();
00199 }
00200
00208 FlowStatus read(typename base::ChannelElement<T>::reference_t sample, bool copy_old_data)
00209 {
00210 if(!init)
00211 return NoData;
00212
00213 if(newdata){
00214 newdata=false;
00215 sample=m_msg.Get();
00216 return NewData;
00217 }
00218 else
00219 if(copy_old_data)
00220 sample=m_msg.Get();
00221 return OldData;
00222 }
00223 };
00224
00225 template <class T>
00226 class RosMsgTransporter : public RTT::types::TypeTransporter{
00227 virtual base::ChannelElementBase::shared_ptr createStream (base::PortInterface *port, const ConnPolicy &policy, bool is_sender) const{
00228 if(is_sender){
00229 base::ChannelElementBase* buf = internal::ConnFactory::buildDataStorage<T>(policy);
00230 base::ChannelElementBase::shared_ptr tmp = base::ChannelElementBase::shared_ptr(new RosPubChannelElement<T>(port,policy));
00231 buf->setOutput(tmp);
00232 return buf;
00233 }
00234 else
00235 return new RosSubChannelElement<T>(port,policy);
00236
00237 }
00238 };
00239 }
00240 #endif