#include <subscriber.h>
Public Member Functions | |
mxArray * | getConnectionHeader () const |
mxArray * | getNumPublishers () const |
mxArray * | getReceiptTime () const |
mxArray * | getTopic () const |
mxArray * | poll (int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[]) |
bool | subscribe (int nrhs, const mxArray *prhs[]) |
Subscriber () | |
Subscriber (int nrhs, const mxArray *prhs[]) | |
~Subscriber () | |
Private Types | |
typedef ros::MessageEvent< void > | MessageEvent |
Private Member Functions | |
void | callback (const MessageEvent &event) |
MessagePtr | introspect (const VoidConstPtr &msg) |
Private Attributes | |
ros::CallbackQueue | callback_queue_ |
MessagePtr | introspection_ |
boost::shared_ptr< MessageEvent > | last_event_ |
boost::shared_ptr< MessageEvent > | new_event_ |
ros::NodeHandle | node_handle_ |
ros::SubscribeOptions | options_ |
ros::WallDuration | timeout_ |
Friends | |
class | SubscriptionCallbackHelper |
Definition at line 44 of file subscriber.h.
typedef ros::MessageEvent<void> rosmatlab::Subscriber::MessageEvent [private] |
Definition at line 63 of file subscriber.h.
Reimplemented from ros::Subscriber.
Definition at line 57 of file subscriber.cpp.
rosmatlab::Subscriber::Subscriber | ( | int | nrhs, |
const mxArray * | prhs[] | ||
) |
Definition at line 64 of file subscriber.cpp.
Reimplemented from ros::Subscriber.
Definition at line 73 of file subscriber.cpp.
void rosmatlab::Subscriber::callback | ( | const MessageEvent & | event | ) | [private] |
Definition at line 167 of file subscriber.cpp.
mxArray * rosmatlab::Subscriber::getConnectionHeader | ( | ) | const |
Definition at line 131 of file subscriber.cpp.
mxArray * rosmatlab::Subscriber::getNumPublishers | ( | ) | const |
Reimplemented from ros::Subscriber.
Definition at line 157 of file subscriber.cpp.
mxArray * rosmatlab::Subscriber::getReceiptTime | ( | ) | const |
Definition at line 144 of file subscriber.cpp.
mxArray * rosmatlab::Subscriber::getTopic | ( | ) | const |
Reimplemented from ros::Subscriber.
Definition at line 152 of file subscriber.cpp.
MessagePtr rosmatlab::Subscriber::introspect | ( | const VoidConstPtr & | msg | ) | [private] |
Definition at line 162 of file subscriber.cpp.
mxArray * rosmatlab::Subscriber::poll | ( | int | nlhs, |
mxArray * | plhs[], | ||
int | nrhs, | ||
const mxArray * | prhs[] | ||
) |
Definition at line 114 of file subscriber.cpp.
bool rosmatlab::Subscriber::subscribe | ( | int | nrhs, |
const mxArray * | prhs[] | ||
) |
Definition at line 77 of file subscriber.cpp.
friend class SubscriptionCallbackHelper [friend] |
Definition at line 62 of file subscriber.h.
Definition at line 70 of file subscriber.h.
Definition at line 73 of file subscriber.h.
boost::shared_ptr<MessageEvent> rosmatlab::Subscriber::last_event_ [private] |
Definition at line 75 of file subscriber.h.
boost::shared_ptr<MessageEvent> rosmatlab::Subscriber::new_event_ [private] |
Definition at line 74 of file subscriber.h.
Definition at line 68 of file subscriber.h.
Definition at line 69 of file subscriber.h.
Definition at line 71 of file subscriber.h.