EEROS  1.0.0.0
API for the EEROS Real-Time Robotics Framework
RosPublisherDoubleArray.hpp
Go to the documentation of this file.
1 #ifndef ORG_EEROS_CONTROL_ROSPUBLISHER_DOUBLEARRAY_HPP
2 #define ORG_EEROS_CONTROL_ROSPUBLISHER_DOUBLEARRAY_HPP
3 
5 #include <eeros/math/Matrix.hpp>
6 #include <std_msgs/Float64MultiArray.h>
7 
8 namespace eeros {
9  namespace control {
10 
11  template < typename SigInType >
12  class RosPublisherDoubleArray : public RosPublisher<std_msgs::Float64MultiArray::Type, SigInType> {
13  typedef std_msgs::Float64MultiArray::Type TRosMsg;
14  public:
15  RosPublisherDoubleArray(const std::string& topic, const uint32_t queueSize=1000) :
16  RosPublisher<TRosMsg, SigInType>(topic, queueSize) { }
17 
18  void setRosMsg(TRosMsg& msg) {
19  if (this->in.isConnected()) {
20  auto val = this->in.getSignal().getValue();
21  auto valTmpDouble = val.getColVector(0);
22  msg.data = valTmpDouble;
23  }
24  }
25  };
26  };
27 };
28 
29 #endif // ORG_EEROS_CONTROL_ROSPUBLISHER_DOUBLEARRAY_HPP
void setRosMsg(TRosMsg &msg)
Definition: RosPublisherDoubleArray.hpp:18
RosPublisherDoubleArray(const std::string &topic, const uint32_t queueSize=1000)
Definition: RosPublisherDoubleArray.hpp:15
virtual T getValue() const
Definition: Signal.hpp:49
virtual bool isConnected() const
Definition: Input.hpp:34
Definition: Config.hpp:14
Type
Definition: HALFeatures.hpp:14
Definition: RosPublisher.hpp:13
virtual Signal< T > & getSignal()
Definition: Input.hpp:38
std_msgs::Float64MultiArray::Type msg
Definition: RosPublisher.hpp:37
const std::string & topic
Definition: RosPublisher.hpp:35
Input< SigInType > in
Definition: Block1i.hpp:21
Definition: RosPublisherDoubleArray.hpp:12