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
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 #include "RosLib.hpp"
00061
00062 namespace ros_integration {
00063
00064 using namespace RTT;
00069 template<typename T>
00070 class RosPubChannelElement: public base::ChannelElement<T>,public RosPublisher
00071 {
00072 char hostname[1024];
00073 std::string topicname;
00074 ros::NodeHandle ros_node;
00075 ros::Publisher ros_pub;
00077 RosPublishActivity::shared_ptr act;
00078
00079 typename base::ChannelElement<T>::value_t sample;
00080
00081 public:
00082
00093 RosPubChannelElement(base::PortInterface* port,const ConnPolicy& policy)
00094 {
00095 if ( policy.name_id.empty() ){
00096 std::stringstream namestr;
00097 gethostname(hostname, sizeof(hostname));
00098
00099 if (port->getInterface() && port->getInterface()->getOwner()) {
00100 namestr << hostname<<'/' << port->getInterface()->getOwner()->getName()
00101 << '/' << port->getName() << '/'<<this << '/' << getpid();
00102 } else {
00103 namestr << hostname<<'/' << port->getName() << '/'<<this << '/' << getpid();
00104 }
00105 policy.name_id = namestr.str();
00106 }
00107 topicname=policy.name_id;
00108 Logger::In in(topicname);
00109
00110 if (port->getInterface() && port->getInterface()->getOwner()) {
00111 log(Debug)<<"Creating ROS publisher for port "<<port->getInterface()->getOwner()->getName()<<"."<<port->getName()<<" on topic "<<policy.name_id<<endlog();
00112 } else {
00113 log(Debug)<<"Creating ROS publisher for port "<<port->getName()<<" on topic "<<policy.name_id<<endlog();
00114 }
00115
00116 ros_pub = ros_node.advertise<T>(policy.name_id, policy.size > 0 ? policy.size : 1, policy.init);
00117 act = RosPublishActivity::Instance();
00118 act->addPublisher( this );
00119 }
00120
00121 ~RosPubChannelElement() {
00122 Logger::In in(topicname);
00123 log(Debug)<<"Destroying RosPubChannelElement"<<endlog();
00124 act->removePublisher( this );
00125 }
00126
00132 virtual bool inputReady() {
00133 return true;
00134 }
00135
00143 virtual bool data_sample(typename base::ChannelElement<T>::param_t sample)
00144 {
00145 this->sample = sample;
00146 return true;
00147 }
00148
00154 bool signal(){
00155
00156
00157 return act->trigger();
00158 }
00159
00160 void publish(){
00161
00162 typename base::ChannelElement<T>::shared_ptr input = this->getInput();
00163 while( input && (input->read(sample,false) == NewData) )
00164 write(sample);
00165 }
00166
00167 bool write(typename base::ChannelElement<T>::param_t sample)
00168 {
00169 ros_pub.publish(sample);
00170 return true;
00171 }
00172
00173 };
00174
00175 template<typename T>
00176 class RosSubChannelElement: public base::ChannelElement<T>
00177 {
00178 ros::NodeHandle ros_node;
00179 ros::Subscriber ros_sub;
00180
00181 public:
00191 RosSubChannelElement(base::PortInterface* port, const ConnPolicy& policy)
00192 {
00193 if (port->getInterface() && port->getInterface()->getOwner()) {
00194 log(Debug)<<"Creating ROS subscriber for port "<<port->getInterface()->getOwner()->getName()<<"."<<port->getName()<<" on topic "<<policy.name_id<<endlog();
00195 } else {
00196 log(Debug)<<"Creating ROS subscriber for port "<<port->getName()<<" on topic "<<policy.name_id<<endlog();
00197 }
00198 ros_sub=ros_node.subscribe(policy.name_id,policy.size,&RosSubChannelElement::newData,this);
00199 this->ref();
00200 }
00201
00202 ~RosSubChannelElement() {
00203 }
00204
00205 virtual bool inputReady() {
00206 return true;
00207 }
00213 void newData(const T& msg){
00214 typename base::ChannelElement<T>::shared_ptr output = this->getOutput();
00215 if (output)
00216 output->write(msg);
00217 }
00218 };
00219
00220 template <class T>
00221 class RosMsgTransporter : public RTT::types::TypeTransporter{
00222 virtual base::ChannelElementBase::shared_ptr createStream (base::PortInterface *port, const ConnPolicy &policy, bool is_sender) const{
00223 base::ChannelElementBase::shared_ptr buf = internal::ConnFactory::buildDataStorage<T>(policy);
00224 base::ChannelElementBase::shared_ptr tmp;
00225 if(is_sender){
00226 tmp = base::ChannelElementBase::shared_ptr(new RosPubChannelElement<T>(port,policy));
00227 if (policy.type == ORO_ROS_CONNPOLICY_TYPE_UNBUFFERED){
00228 log(Debug) << "Creating unbuffered publisher connection for port " << port->getName() << ". This may not be real-time safe!" << endlog();
00229 return tmp;
00230 }
00231 if (!buf) return base::ChannelElementBase::shared_ptr();
00232 buf->setOutput(tmp);
00233 return buf;
00234 }
00235 else {
00236 if (!buf) return base::ChannelElementBase::shared_ptr();
00237 tmp = new RosSubChannelElement<T>(port,policy);
00238 tmp->setOutput(buf);
00239 return tmp;
00240 }
00241 }
00242 };
00243 }
00244 #endif