Public Types | Public Member Functions | Static Public Member Functions | Private Types | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
rtt_roscomm::RosPublishActivity Class Reference

#include <rtt_rostopic_ros_publish_activity.hpp>

Inheritance diagram for rtt_roscomm::RosPublishActivity:
Inheritance graph
[legend]

Public Types

typedef boost::shared_ptr< RosPublishActivityshared_ptr
 
- Public Types inherited from RTT::base::ActivityInterface
typedef boost::shared_ptr< ActivityInterfaceshared_ptr
 

Public Member Functions

void addPublisher (RosPublisher *pub)
 
void removePublisher (RosPublisher *pub)
 
 ~RosPublishActivity ()
 
- Public Member Functions inherited from RTT::Activity
 Activity (base::RunnableInterface *r=0, const std::string &name="Activity")
 
 Activity (int priority, base::RunnableInterface *r=0, const std::string &name="Activity")
 
 Activity (int scheduler, int priority, base::RunnableInterface *r=0, const std::string &name="Activity")
 
 Activity (int scheduler, int priority, Seconds period, base::RunnableInterface *r=0, const std::string &name="Activity")
 
 Activity (int priority, Seconds period, base::RunnableInterface *r=0, const std::string &name="Activity")
 
 Activity (int scheduler, int priority, Seconds period, unsigned cpu_affinity, base::RunnableInterface *r=0, const std::string &name="Activity")
 
virtual bool breakLoop ()
 
virtual bool execute ()
 
virtual void finalize ()
 
virtual unsigned getCpuAffinity () const
 
virtual Seconds getPeriod () const
 
virtual bool initialize ()
 
virtual bool isActive () const
 
virtual bool isPeriodic () const
 
virtual bool isRunning () const
 
virtual bool setCpuAffinity (unsigned cpu)
 
virtual bool setPeriod (Seconds period)
 
void setWaitPeriodPolicy (int p)
 
virtual bool start ()
 
virtual void step ()
 
virtual bool stop ()
 
virtual os::ThreadInterfacethread ()
 
virtual bool timeout ()
 
virtual bool trigger ()
 
virtual void work (base::RunnableInterface::WorkReason reason)
 
virtual ~Activity ()
 
- Public Member Functions inherited from RTT::base::ActivityInterface
 ActivityInterface ()
 
 ActivityInterface (RunnableInterface *run)
 
virtual RunnableInterfacegetRunner () const
 
virtual bool run (RunnableInterface *r)
 
virtual ~ActivityInterface ()
 
- Public Member Functions inherited from RTT::os::Thread
virtual int getMaxOverrun () const
 
virtual const char * getName () const
 
void getPeriod (secs &s, nsecs &ns) const
 
virtual nsecs getPeriodNS () const
 
virtual unsigned int getPid () const
 
virtual int getPriority () const
 
virtual int getScheduler () const
 
Seconds getStopTimeout () const
 
virtual RTOS_TASKgetTask ()
 
virtual const RTOS_TASKgetTask () const
 
virtual void setMaxOverrun (int m)
 
bool setPeriod (Seconds s)
 
bool setPeriod (TIME_SPEC p)
 
bool setPeriod (secs s, nsecs ns)
 
virtual bool setPriority (int priority)
 
virtual bool setScheduler (int sched_type)
 
void setStopTimeout (Seconds s)
 
 Thread (int scheduler, int priority, double period, unsigned cpu_affinity, const std::string &name)
 
virtual void yield ()
 
virtual ~Thread ()
 
- Public Member Functions inherited from RTT::os::ThreadInterface
bool isSelf () const
 
 ThreadInterface ()
 
unsigned int threadNumber () const
 
virtual ~ThreadInterface ()
 

Static Public Member Functions

static shared_ptr Instance ()
 
- Static Public Member Functions inherited from RTT::os::Thread
static void setLockTimeoutNoPeriod (double timeout_in_s)
 
static void setLockTimeoutPeriodFactor (double factor)
 
static void setStackSize (unsigned int ssize)
 

Private Types

typedef Publishers::iterator iterator
 
typedef std::set< RosPublisher * > Publishers
 
typedef boost::weak_ptr< RosPublishActivityweak_ptr
 

Private Member Functions

void loop ()
 
 RosPublishActivity (const std::string &name)
 

Private Attributes

Publishers publishers
 
RTT::os::Mutex publishers_lock
 

Static Private Attributes

static weak_ptr ros_pub_act
 This pointer may not be refcounted since it would prevent cleanup. More...
 

Additional Inherited Members

- Protected Member Functions inherited from RTT::base::ActivityInterface
void disableRun (RunnableInterface *caller)
 
- Protected Member Functions inherited from RTT::os::Thread
void emergencyStop ()
 
void terminate ()
 
- Protected Attributes inherited from RTT::Activity
os::Condition msg_cond
 
os::Mutex msg_lock
 
bool mstopRequested
 
bool mtimeout
 
int mwaitpolicy
 
double update_period
 
- Protected Attributes inherited from RTT::base::ActivityInterface
RunnableInterfacerunner
 
- Protected Attributes inherited from RTT::os::Thread
bool active
 
MutexRecursive breaker
 
bool inloop
 
int maxOverRun
 
int msched_type
 
NANO_TIME period
 
bool prepareForExit
 
RTOS_TASK rtos_task
 
bool running
 
rt_sem_t sem
 
double stopTimeout
 
- Protected Attributes inherited from RTT::os::ThreadInterface
int threadnb
 
- Static Protected Attributes inherited from RTT::os::Thread
static unsigned int default_stack_size
 
static double lock_timeout_no_period_in_s
 
static double lock_timeout_period_factor
 

Detailed Description

A process wide thread that handles all publishing of ROS topics of the current process. There is no strong reason why only one publisher should exist, in later implementations, one publisher thread per channel may exist as well. See the usage recommendations for Instance()

Definition at line 66 of file rtt_rostopic_ros_publish_activity.hpp.

Member Typedef Documentation

typedef Publishers::iterator rtt_roscomm::RosPublishActivity::iterator
private

Definition at line 79 of file rtt_rostopic_ros_publish_activity.hpp.

A set keeping track of all publishers in the current process. It must be guarded by the mutex since insertion/removal happens concurrently.

Definition at line 78 of file rtt_rostopic_ros_publish_activity.hpp.

Definition at line 69 of file rtt_rostopic_ros_publish_activity.hpp.

Definition at line 71 of file rtt_rostopic_ros_publish_activity.hpp.

Constructor & Destructor Documentation

rtt_roscomm::RosPublishActivity::RosPublishActivity ( const std::string &  name)
private

Definition at line 38 of file rtt_rostopic_ros_publish_activity.cpp.

rtt_roscomm::RosPublishActivity::~RosPublishActivity ( )

Definition at line 72 of file rtt_rostopic_ros_publish_activity.cpp.

Member Function Documentation

void rtt_roscomm::RosPublishActivity::addPublisher ( RosPublisher pub)

Definition at line 62 of file rtt_rostopic_ros_publish_activity.cpp.

RosPublishActivity::shared_ptr rtt_roscomm::RosPublishActivity::Instance ( )
static

Returns the single instance of the RosPublisher. This function is not thread-safe when it creates the RosPublisher object. Therefor, it is advised to cache the object which Intance() returns such that, in the unlikely event that two publishers exist, you consistently keep using the same instance, which is fine then.

Definition at line 52 of file rtt_rostopic_ros_publish_activity.cpp.

void rtt_roscomm::RosPublishActivity::loop ( )
privatevirtual

Reimplemented from RTT::Activity.

Definition at line 45 of file rtt_rostopic_ros_publish_activity.cpp.

void rtt_roscomm::RosPublishActivity::removePublisher ( RosPublisher pub)

Definition at line 67 of file rtt_rostopic_ros_publish_activity.cpp.

Member Data Documentation

Publishers rtt_roscomm::RosPublishActivity::publishers
private

Definition at line 80 of file rtt_rostopic_ros_publish_activity.hpp.

RTT::os::Mutex rtt_roscomm::RosPublishActivity::publishers_lock
private

Definition at line 81 of file rtt_rostopic_ros_publish_activity.hpp.

RosPublishActivity::weak_ptr rtt_roscomm::RosPublishActivity::ros_pub_act
staticprivate

This pointer may not be refcounted since it would prevent cleanup.

Definition at line 73 of file rtt_rostopic_ros_publish_activity.hpp.


The documentation for this class was generated from the following files:


rtt_roscomm
Author(s): Ruben Smits, Jonathan Bohren
autogenerated on Sat Jun 8 2019 18:05:17