EEROS  1.0.0.0
API for the EEROS Real-Time Robotics Framework
RosSubscriberDoubleArray.hpp
Go to the documentation of this file.
1 #ifndef ORG_EEROS_CONTROL_ROSSUBSCRIBER_DOUBLEARRAY_HPP
2 #define ORG_EEROS_CONTROL_ROSSUBSCRIBER_DOUBLEARRAY_HPP
3 
5 #include <eeros/core/System.hpp>
6 #include <std_msgs/Float64MultiArray.h>
7 
8 namespace eeros {
9  namespace control {
10 
11  template < typename SigOutType >
12  class RosSubscriberDoubleArray : public RosSubscriber<std_msgs::Float64MultiArray::Type, SigOutType> {
13  typedef std_msgs::Float64MultiArray::Type TRosMsg;
14  public:
15  RosSubscriberDoubleArray(const std::string& topic, const uint32_t queueSize=1000, const bool callNewest=false ) :
16  RosSubscriber<TRosMsg, SigOutType>(topic, queueSize, callNewest){ }
17 
18  void rosCallbackFct(const TRosMsg& msg) {
19  auto time = eeros::System::getTimeNs(); // use system time for timestamp
20  this->out.getSignal().setTimestamp( time );
21  std::vector<double> valTmp(msg.data.begin(), msg.data.end() );
22  val.setCol(0, valTmp);
23  this->out.getSignal().setValue(val);
24  }
25  protected:
26  SigOutType val;
27  };
28  };
29 };
30 
31 #endif // ORG_EEROS_CONTROL_ROSSUBSCRIBER_DOUBLEARRAY_HPP
virtual Signal< T > & getSignal()
Definition: Output.hpp:16
RosSubscriberDoubleArray(const std::string &topic, const uint32_t queueSize=1000, const bool callNewest=false)
Definition: RosSubscriberDoubleArray.hpp:15
Definition: RosSubscriberDoubleArray.hpp:12
Definition: Config.hpp:14
static uint64_t getTimeNs()
Definition: System_POSIX.cpp:41
virtual void setValue(T newValue)
Definition: Signal.hpp:53
Output< SigOutType > out
Definition: Block1o.hpp:23
Type
Definition: HALFeatures.hpp:14
const std::string & topic
Definition: RosSubscriber.hpp:51
virtual void setTimestamp(timestamp_t newTimestamp)
Definition: Signal.hpp:66
Definition: RosSubscriber.hpp:14
void rosCallbackFct(const TRosMsg &msg)
Definition: RosSubscriberDoubleArray.hpp:18
SigOutType val
Definition: RosSubscriberDoubleArray.hpp:26