|
ROS Serial C client library
|
Structure to hold information about a nodehandle. More...
#include <ros_types.h>

Data Fields | |
| rosPublisher_t *(* | advertise )(rosMessageHandle_t *messagehandle, char *topic, uint16_t buffer_size) |
| Advertises a topic to nodehandle. | |
| rosSubscriber_t *(* | subscribe )(rosMessageHandle_t *messagehandle, char *topic, uint16_t buffer_size, void(*callback)(void *message)) |
| Subscribes a topic to a nodehandle. | |
| struct rosSpinner * | spinner |
| rosInterface_t * | interface |
| rosPublisher_t * | publishers [MAX_PUBLISHERS] |
| rosSubscriber_t * | subscribers [MAX_SUBSCRIBERS] |
| uint8_t | publisher_count |
| uint8_t | subscriber_count |
| rosReturnCode_t | ok |
| rosReturnCode_t | configured |
Structure to hold information about a nodehandle.
| rosPublisher_t*(* advertise)(rosMessageHandle_t *messagehandle, char *topic, uint16_t buffer_size) |
Advertises a topic to nodehandle.
| mh | Pointer to messagehandle |
| topic | Topic name |
| buffer_size | Buffer size |
Example Usage:
// init ROS rosInit(NULL); // get pointer to a nodehandle rosNodeHandle_t* nh = rosNodeHandle("my_nodehandle_interface_id"); // create message MyMessage_t my_message = rosCreateMyMessage_t(nh); // advertise message rosPublisher_t* my_message_pub = nh->advertise(&my_message.mh, "MyMessage", 512); // publish message my_message_pub->publish(&my_message);
indicates if topics are already negotiated
device interface
indicates if nodehandle is still alive
| uint8_t publisher_count |
number of publishers
| rosPublisher_t* publishers[MAX_PUBLISHERS] |
array of publishers
| struct rosSpinner* spinner |
nodehandle spinner
| rosSubscriber_t*(* subscribe)(rosMessageHandle_t *messagehandle, char *topic, uint16_t buffer_size, void(*callback)(void *message)) |
Subscribes a topic to a nodehandle.
| mh | Pointer to messagehandle |
| topic | Topic name |
| buffer_size | Buffer size |
Example Usage:
Subscribers callback function:
void myMessageCallback(void *message) { // cast message MyMessage_t *my_message = message; // Do something here. }
Program code:
// init ROS rosInit(NULL); // get pointer to a nodehandle rosNodeHandle_t* nh = rosNodeHandle("my_nodehandle_interface_id"); // create message MyMessage_t my_message = rosCreateMyMessage_t(nh); // advertise message rosSubscriber_t* my_message_sub = nh->subscribe(&my_message.mh, "MyMessage", 512, myMessageCallback); // spin ROS continously to process callbacks rosSpin();
| uint8_t subscriber_count |
number of subscribers
| rosSubscriber_t* subscribers[MAX_SUBSCRIBERS] |
array of subscribers