Porting mros2 as an Mbed library.

Dependents:   mbed-os-example-mros2 example-mbed-mros2-sub-pose example-mbed-mros2-pub-twist example-mbed-mros2-mturtle-teleop

Committer:
smoritaemb
Date:
Thu Dec 30 21:06:29 2021 +0900
Revision:
0:580aba13d1a1
Child:
2:159877d749c2
Updated to catch up to mros2 v2.3

Who changed what in which revision?

UserRevisionLine numberNew contents of line
smoritaemb 0:580aba13d1a1 1 #include "mros2.h"
smoritaemb 0:580aba13d1a1 2 #include "mros2_user_config.h"
smoritaemb 0:580aba13d1a1 3
smoritaemb 0:580aba13d1a1 4 #include <rtps/rtps.h>
smoritaemb 0:580aba13d1a1 5
smoritaemb 0:580aba13d1a1 6 #ifdef __MBED__
smoritaemb 0:580aba13d1a1 7 #include "mbed.h"
smoritaemb 0:580aba13d1a1 8 #else /* __MBED__ */
smoritaemb 0:580aba13d1a1 9 #include "cmsis_os.h"
smoritaemb 0:580aba13d1a1 10 #endif /* __MBED__ */
smoritaemb 0:580aba13d1a1 11
smoritaemb 0:580aba13d1a1 12 #include "std_msgs/msg/bool.hpp"
smoritaemb 0:580aba13d1a1 13 #include "std_msgs/msg/byte.hpp"
smoritaemb 0:580aba13d1a1 14 #include "std_msgs/msg/char.hpp"
smoritaemb 0:580aba13d1a1 15 #include "std_msgs/msg/float32.hpp"
smoritaemb 0:580aba13d1a1 16 #include "std_msgs/msg/float64.hpp"
smoritaemb 0:580aba13d1a1 17 #include "std_msgs/msg/int8.hpp"
smoritaemb 0:580aba13d1a1 18 #include "std_msgs/msg/int16.hpp"
smoritaemb 0:580aba13d1a1 19 #include "std_msgs/msg/int32.hpp"
smoritaemb 0:580aba13d1a1 20 #include "std_msgs/msg/int64.hpp"
smoritaemb 0:580aba13d1a1 21 #include "std_msgs/msg/string.hpp"
smoritaemb 0:580aba13d1a1 22 #include "std_msgs/msg/u_int8.hpp"
smoritaemb 0:580aba13d1a1 23 #include "std_msgs/msg/u_int16.hpp"
smoritaemb 0:580aba13d1a1 24 #include "std_msgs/msg/u_int32.hpp"
smoritaemb 0:580aba13d1a1 25 #include "std_msgs/msg/u_int64.hpp"
smoritaemb 0:580aba13d1a1 26
smoritaemb 0:580aba13d1a1 27 #include "TEST.hpp"
smoritaemb 0:580aba13d1a1 28
smoritaemb 0:580aba13d1a1 29
smoritaemb 0:580aba13d1a1 30 namespace mros2
smoritaemb 0:580aba13d1a1 31 {
smoritaemb 0:580aba13d1a1 32
smoritaemb 0:580aba13d1a1 33 rtps::Domain *domain_ptr = NULL;
smoritaemb 0:580aba13d1a1 34 rtps::Participant *part_ptr = NULL; //TODO: detele this
smoritaemb 0:580aba13d1a1 35 rtps::Writer *pub_ptr = NULL;
smoritaemb 0:580aba13d1a1 36
smoritaemb 0:580aba13d1a1 37 #define SUB_MSG_SIZE 4 // addr size
smoritaemb 0:580aba13d1a1 38 osMessageQueueId_t subscriber_msg_gueue_id;
smoritaemb 0:580aba13d1a1 39
smoritaemb 0:580aba13d1a1 40 bool completeNodeInit = false;
smoritaemb 0:580aba13d1a1 41 uint8_t endpointId = 0;
smoritaemb 0:580aba13d1a1 42 uint32_t subCbArray[10];
smoritaemb 0:580aba13d1a1 43
smoritaemb 0:580aba13d1a1 44 uint8_t buf[100];
smoritaemb 0:580aba13d1a1 45 uint8_t buf_index = 4;
smoritaemb 0:580aba13d1a1 46
smoritaemb 0:580aba13d1a1 47 /* Callback function to set the boolean to true upon a match */
smoritaemb 0:580aba13d1a1 48 void setTrue(void* args)
smoritaemb 0:580aba13d1a1 49 {
smoritaemb 0:580aba13d1a1 50 *static_cast<volatile bool*>(args) = true;
smoritaemb 0:580aba13d1a1 51 }
smoritaemb 0:580aba13d1a1 52
smoritaemb 0:580aba13d1a1 53 bool subMatched = false;
smoritaemb 0:580aba13d1a1 54 bool pubMatched = false;
smoritaemb 0:580aba13d1a1 55
smoritaemb 0:580aba13d1a1 56 void pubMatch(void* args)
smoritaemb 0:580aba13d1a1 57 {
smoritaemb 0:580aba13d1a1 58 MROS2_DEBUG("[MROS2LIB] publisher matched with remote subscriber");
smoritaemb 0:580aba13d1a1 59 }
smoritaemb 0:580aba13d1a1 60
smoritaemb 0:580aba13d1a1 61 void subMatch(void* args)
smoritaemb 0:580aba13d1a1 62 {
smoritaemb 0:580aba13d1a1 63 MROS2_DEBUG("[MROS2LIB] subscriber matched with remote publisher");
smoritaemb 0:580aba13d1a1 64 }
smoritaemb 0:580aba13d1a1 65
smoritaemb 0:580aba13d1a1 66
smoritaemb 0:580aba13d1a1 67 /*
smoritaemb 0:580aba13d1a1 68 * Initialization of mROS 2 environment
smoritaemb 0:580aba13d1a1 69 */
smoritaemb 0:580aba13d1a1 70 #ifdef __MBED__
smoritaemb 0:580aba13d1a1 71 Thread *mros2_init_thread;
smoritaemb 0:580aba13d1a1 72 #endif /* __MBED__ */
smoritaemb 0:580aba13d1a1 73 void init(int argc, char * argv[])
smoritaemb 0:580aba13d1a1 74 {
smoritaemb 0:580aba13d1a1 75 buf[0] = 0;
smoritaemb 0:580aba13d1a1 76 buf[1] = 1;
smoritaemb 0:580aba13d1a1 77 buf[2] = 0;
smoritaemb 0:580aba13d1a1 78 buf[3] = 0;
smoritaemb 0:580aba13d1a1 79
smoritaemb 0:580aba13d1a1 80 #ifdef __MBED__
smoritaemb 0:580aba13d1a1 81 mros2_init_thread = new Thread(osPriorityAboveNormal, 2000, nullptr, "mROS2Thread");
smoritaemb 0:580aba13d1a1 82 mros2_init_thread->start(callback(mros2_init, (void *)NULL));
smoritaemb 0:580aba13d1a1 83 #else /* __MBED__ */
smoritaemb 0:580aba13d1a1 84 osThreadAttr_t attributes;
smoritaemb 0:580aba13d1a1 85
smoritaemb 0:580aba13d1a1 86 attributes.name = "mROS2Thread",
smoritaemb 0:580aba13d1a1 87 attributes.stack_size = 1000,
smoritaemb 0:580aba13d1a1 88 attributes.priority = (osPriority_t)24,
smoritaemb 0:580aba13d1a1 89
smoritaemb 0:580aba13d1a1 90 osThreadNew(mros2_init, NULL, (const osThreadAttr_t*)&attributes);
smoritaemb 0:580aba13d1a1 91 #endif /* __MBED__ */
smoritaemb 0:580aba13d1a1 92
smoritaemb 0:580aba13d1a1 93 }
smoritaemb 0:580aba13d1a1 94
smoritaemb 0:580aba13d1a1 95 void mros2_init(void *args)
smoritaemb 0:580aba13d1a1 96 {
smoritaemb 0:580aba13d1a1 97 osStatus_t ret;
smoritaemb 0:580aba13d1a1 98
smoritaemb 0:580aba13d1a1 99 MROS2_DEBUG("[MROS2LIB] mros2_init task start");
smoritaemb 0:580aba13d1a1 100
smoritaemb 0:580aba13d1a1 101 #ifndef __MBED__
smoritaemb 0:580aba13d1a1 102 MX_LWIP_Init();
smoritaemb 0:580aba13d1a1 103 MROS2_DEBUG("[MROS2LIB] Initilizing lwIP complete");
smoritaemb 0:580aba13d1a1 104 #endif /* __MBED__ */
smoritaemb 0:580aba13d1a1 105
smoritaemb 0:580aba13d1a1 106 int sub_msg_count;
smoritaemb 0:580aba13d1a1 107 static rtps::Domain domain;
smoritaemb 0:580aba13d1a1 108 domain_ptr = &domain;
smoritaemb 0:580aba13d1a1 109
smoritaemb 0:580aba13d1a1 110 #ifndef __MBED__
smoritaemb 0:580aba13d1a1 111 sub_msg_count = mros2_get_submsg_count();
smoritaemb 0:580aba13d1a1 112 subscriber_msg_gueue_id = osMessageQueueNew(sub_msg_count, SUB_MSG_SIZE, NULL);
smoritaemb 0:580aba13d1a1 113 if (subscriber_msg_gueue_id == NULL) {
smoritaemb 0:580aba13d1a1 114 MROS2_ERROR("[MROS2LIB] ERROR: mROS2 init failed");
smoritaemb 0:580aba13d1a1 115 return;
smoritaemb 0:580aba13d1a1 116 }
smoritaemb 0:580aba13d1a1 117 #endif /* __MBED__ */
smoritaemb 0:580aba13d1a1 118
smoritaemb 0:580aba13d1a1 119 /* wait until participant(node) is created */
smoritaemb 0:580aba13d1a1 120 while(!completeNodeInit) {
smoritaemb 0:580aba13d1a1 121 osDelay(100);
smoritaemb 0:580aba13d1a1 122 }
smoritaemb 0:580aba13d1a1 123 domain.completeInit();
smoritaemb 0:580aba13d1a1 124 MROS2_DEBUG("[MROS2LIB] Initilizing Domain complete");
smoritaemb 0:580aba13d1a1 125
smoritaemb 0:580aba13d1a1 126 while(!subMatched && !pubMatched) {
smoritaemb 0:580aba13d1a1 127 osDelay(1000);
smoritaemb 0:580aba13d1a1 128 }
smoritaemb 0:580aba13d1a1 129
smoritaemb 0:580aba13d1a1 130 MROS2_DEBUG("[MROS2LIB] mros2_init task end");
smoritaemb 0:580aba13d1a1 131
smoritaemb 0:580aba13d1a1 132 ret = osThreadTerminate(NULL);
smoritaemb 0:580aba13d1a1 133 if (ret != osOK) {
smoritaemb 0:580aba13d1a1 134 MROS2_ERROR("[MROS2LIB] ERROR: mros2_init() task terminate error %d", ret);
smoritaemb 0:580aba13d1a1 135 }
smoritaemb 0:580aba13d1a1 136 }
smoritaemb 0:580aba13d1a1 137
smoritaemb 0:580aba13d1a1 138
smoritaemb 0:580aba13d1a1 139 /*
smoritaemb 0:580aba13d1a1 140 * Node functions
smoritaemb 0:580aba13d1a1 141 */
smoritaemb 0:580aba13d1a1 142 Node Node::create_node(std::string node_name)
smoritaemb 0:580aba13d1a1 143 {
smoritaemb 0:580aba13d1a1 144 MROS2_DEBUG("[MROS2LIB] create_node");
smoritaemb 0:580aba13d1a1 145 MROS2_DEBUG("[MROS2LIB] start creating participant");
smoritaemb 0:580aba13d1a1 146
smoritaemb 0:580aba13d1a1 147 while(domain_ptr == NULL) {
smoritaemb 0:580aba13d1a1 148 osDelay(100);
smoritaemb 0:580aba13d1a1 149 }
smoritaemb 0:580aba13d1a1 150
smoritaemb 0:580aba13d1a1 151 Node node;
smoritaemb 0:580aba13d1a1 152 node.part = domain_ptr->createParticipant();
smoritaemb 0:580aba13d1a1 153 /* TODO: utilize node name */
smoritaemb 0:580aba13d1a1 154 node.node_name = node_name;
smoritaemb 0:580aba13d1a1 155 part_ptr = node.part;
smoritaemb 0:580aba13d1a1 156 if(node.part == nullptr) {
smoritaemb 0:580aba13d1a1 157 MROS2_ERROR("[MROS2LIB] ERROR: create_node() failed");
smoritaemb 0:580aba13d1a1 158 while(true) {}
smoritaemb 0:580aba13d1a1 159 }
smoritaemb 0:580aba13d1a1 160 completeNodeInit = true;
smoritaemb 0:580aba13d1a1 161
smoritaemb 0:580aba13d1a1 162 MROS2_DEBUG("[MROS2LIB] successfully created participant");
smoritaemb 0:580aba13d1a1 163 return node;
smoritaemb 0:580aba13d1a1 164 }
smoritaemb 0:580aba13d1a1 165
smoritaemb 0:580aba13d1a1 166
smoritaemb 0:580aba13d1a1 167 /*
smoritaemb 0:580aba13d1a1 168 * Publisher functions
smoritaemb 0:580aba13d1a1 169 */
smoritaemb 0:580aba13d1a1 170 template <class T>
smoritaemb 0:580aba13d1a1 171 Publisher Node::create_publisher(std::string topic_name, int qos)
smoritaemb 0:580aba13d1a1 172 {
smoritaemb 0:580aba13d1a1 173 rtps::Writer* writer = domain_ptr->createWriter(*part_ptr, ("rt/"+topic_name).c_str(), message_traits::TypeName<T*>().value(), false);
smoritaemb 0:580aba13d1a1 174 if(writer == nullptr) {
smoritaemb 0:580aba13d1a1 175 MROS2_ERROR("[MROS2LIB] ERROR: failed to create writer in create_publisher()");
smoritaemb 0:580aba13d1a1 176 while(true) {}
smoritaemb 0:580aba13d1a1 177 }
smoritaemb 0:580aba13d1a1 178
smoritaemb 0:580aba13d1a1 179 Publisher pub;
smoritaemb 0:580aba13d1a1 180 pub_ptr = writer;
smoritaemb 0:580aba13d1a1 181 pub.topic_name = topic_name;
smoritaemb 0:580aba13d1a1 182
smoritaemb 0:580aba13d1a1 183 /* Register callback to ensure that a publisher is matched to the writer before sending messages */
smoritaemb 0:580aba13d1a1 184 part_ptr->registerOnNewSubscriberMatchedCallback(pubMatch, &subMatched);
smoritaemb 0:580aba13d1a1 185
smoritaemb 0:580aba13d1a1 186 MROS2_DEBUG("[MROS2LIB] create_publisher complete.");
smoritaemb 0:580aba13d1a1 187 return pub;
smoritaemb 0:580aba13d1a1 188 }
smoritaemb 0:580aba13d1a1 189
smoritaemb 0:580aba13d1a1 190 template <class T>
smoritaemb 0:580aba13d1a1 191 void Publisher::publish(T& msg)
smoritaemb 0:580aba13d1a1 192 {
smoritaemb 0:580aba13d1a1 193 msg.copyToBuf(&buf[4]);
smoritaemb 0:580aba13d1a1 194 pub_ptr->newChange(rtps::ChangeKind_t::ALIVE, buf, msg.getTotalSize() + 4);
smoritaemb 0:580aba13d1a1 195 }
smoritaemb 0:580aba13d1a1 196
smoritaemb 0:580aba13d1a1 197
smoritaemb 0:580aba13d1a1 198 /*
smoritaemb 0:580aba13d1a1 199 * Subscriber functions
smoritaemb 0:580aba13d1a1 200 */
smoritaemb 0:580aba13d1a1 201 typedef struct {
smoritaemb 0:580aba13d1a1 202 void (*cb_fp)(intptr_t);
smoritaemb 0:580aba13d1a1 203 intptr_t argp;
smoritaemb 0:580aba13d1a1 204 } SubscribeDataType;
smoritaemb 0:580aba13d1a1 205
smoritaemb 0:580aba13d1a1 206 template <class T>
smoritaemb 0:580aba13d1a1 207 Subscriber Node::create_subscription(std::string topic_name, int qos, void(*fp)(T*))
smoritaemb 0:580aba13d1a1 208 {
smoritaemb 0:580aba13d1a1 209 rtps::Reader* reader = domain_ptr->createReader(*(this->part), ("rt/"+topic_name).c_str(), message_traits::TypeName<T*>().value(), false);
smoritaemb 0:580aba13d1a1 210 if(reader == nullptr) {
smoritaemb 0:580aba13d1a1 211 MROS2_ERROR("[MROS2LIB] ERROR: failed to create reader in create_subscription()");
smoritaemb 0:580aba13d1a1 212 while(true) {}
smoritaemb 0:580aba13d1a1 213 }
smoritaemb 0:580aba13d1a1 214
smoritaemb 0:580aba13d1a1 215 Subscriber sub;
smoritaemb 0:580aba13d1a1 216 sub.topic_name = topic_name;
smoritaemb 0:580aba13d1a1 217 sub.cb_fp = (void (*)(intptr_t))fp;
smoritaemb 0:580aba13d1a1 218
smoritaemb 0:580aba13d1a1 219 SubscribeDataType *data_p;
smoritaemb 0:580aba13d1a1 220 data_p = new SubscribeDataType;
smoritaemb 0:580aba13d1a1 221 data_p->cb_fp = (void (*)(intptr_t))fp;
smoritaemb 0:580aba13d1a1 222 data_p->argp = (intptr_t)NULL;
smoritaemb 0:580aba13d1a1 223 reader->registerCallback(sub.callback_handler<T>, (void *)data_p);
smoritaemb 0:580aba13d1a1 224
smoritaemb 0:580aba13d1a1 225 /* Register callback to ensure that a subscriber is matched to the reader before receiving messages */
smoritaemb 0:580aba13d1a1 226 part_ptr->registerOnNewPublisherMatchedCallback(subMatch, &pubMatched);
smoritaemb 0:580aba13d1a1 227
smoritaemb 0:580aba13d1a1 228 MROS2_DEBUG("[MROS2LIB] create_subscription complete. data memory address=0x%x", data_p);
smoritaemb 0:580aba13d1a1 229 return sub;
smoritaemb 0:580aba13d1a1 230 }
smoritaemb 0:580aba13d1a1 231
smoritaemb 0:580aba13d1a1 232 template <class T>
smoritaemb 0:580aba13d1a1 233 void Subscriber::callback_handler(void *callee, const rtps::ReaderCacheChange &cacheChange)
smoritaemb 0:580aba13d1a1 234 {
smoritaemb 0:580aba13d1a1 235 T msg;
smoritaemb 0:580aba13d1a1 236 msg.copyFromBuf(&cacheChange.getData()[4]);
smoritaemb 0:580aba13d1a1 237
smoritaemb 0:580aba13d1a1 238 SubscribeDataType *sub = (SubscribeDataType *)callee;
smoritaemb 0:580aba13d1a1 239 void (*fp)(intptr_t) = sub->cb_fp;
smoritaemb 0:580aba13d1a1 240 fp((intptr_t)&msg);
smoritaemb 0:580aba13d1a1 241 }
smoritaemb 0:580aba13d1a1 242
smoritaemb 0:580aba13d1a1 243
smoritaemb 0:580aba13d1a1 244 /*
smoritaemb 0:580aba13d1a1 245 * Other utility functions
smoritaemb 0:580aba13d1a1 246 */
smoritaemb 0:580aba13d1a1 247 void spin()
smoritaemb 0:580aba13d1a1 248 {
smoritaemb 0:580aba13d1a1 249 while(true) {
smoritaemb 0:580aba13d1a1 250 #ifndef __MBED__
smoritaemb 0:580aba13d1a1 251 osStatus_t ret;
smoritaemb 0:580aba13d1a1 252 SubscribeDataType* msg;
smoritaemb 0:580aba13d1a1 253 ret = osMessageQueueGet(subscriber_msg_gueue_id, &msg, NULL, osWaitForever);
smoritaemb 0:580aba13d1a1 254 if (ret != osOK) {
smoritaemb 0:580aba13d1a1 255 MROS2_ERROR("[MROS2LIB] ERROR: mROS2 spin() wait error %d", ret);
smoritaemb 0:580aba13d1a1 256 }
smoritaemb 0:580aba13d1a1 257 #else /* __MBED__ */
smoritaemb 0:580aba13d1a1 258 // The queue above seems not to be pushed anywhere. So just sleep.
smoritaemb 0:580aba13d1a1 259 ThisThread::sleep_for(1000);
smoritaemb 0:580aba13d1a1 260 #endif /* __MBED__ */
smoritaemb 0:580aba13d1a1 261 }
smoritaemb 0:580aba13d1a1 262 }
smoritaemb 0:580aba13d1a1 263
smoritaemb 0:580aba13d1a1 264 } /* namespace mros2 */
smoritaemb 0:580aba13d1a1 265
smoritaemb 0:580aba13d1a1 266
smoritaemb 0:580aba13d1a1 267 /*
smoritaemb 0:580aba13d1a1 268 * Declaration for embeddedRTPS participants
smoritaemb 0:580aba13d1a1 269 */
smoritaemb 0:580aba13d1a1 270 void *networkSubDriverPtr;
smoritaemb 0:580aba13d1a1 271 void *networkPubDriverPtr;
smoritaemb 0:580aba13d1a1 272 void (*hbPubFuncPtr)(void *);
smoritaemb 0:580aba13d1a1 273 void (*hbSubFuncPtr)(void *);
smoritaemb 0:580aba13d1a1 274
smoritaemb 0:580aba13d1a1 275 extern "C" void callHbPubFunc(void *arg)
smoritaemb 0:580aba13d1a1 276 {
smoritaemb 0:580aba13d1a1 277 if(hbPubFuncPtr != NULL && networkPubDriverPtr != NULL) {
smoritaemb 0:580aba13d1a1 278 (*hbPubFuncPtr)(networkPubDriverPtr);
smoritaemb 0:580aba13d1a1 279 }
smoritaemb 0:580aba13d1a1 280 }
smoritaemb 0:580aba13d1a1 281 extern "C" void callHbSubFunc(void *arg)
smoritaemb 0:580aba13d1a1 282 {
smoritaemb 0:580aba13d1a1 283 if(hbSubFuncPtr != NULL && networkSubDriverPtr != NULL) {
smoritaemb 0:580aba13d1a1 284 (*hbSubFuncPtr)(networkSubDriverPtr);
smoritaemb 0:580aba13d1a1 285 }
smoritaemb 0:580aba13d1a1 286 }
smoritaemb 0:580aba13d1a1 287
smoritaemb 0:580aba13d1a1 288 void setTrue(void* args)
smoritaemb 0:580aba13d1a1 289 {
smoritaemb 0:580aba13d1a1 290 *static_cast<volatile bool*>(args) = true;
smoritaemb 0:580aba13d1a1 291 }
smoritaemb 0:580aba13d1a1 292
smoritaemb 0:580aba13d1a1 293
smoritaemb 0:580aba13d1a1 294 /*
smoritaemb 0:580aba13d1a1 295 * specialize template functions
smoritaemb 0:580aba13d1a1 296 */
smoritaemb 0:580aba13d1a1 297
smoritaemb 0:580aba13d1a1 298 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Bool>(std::string topic_name, int qos);
smoritaemb 0:580aba13d1a1 299 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Bool*));
smoritaemb 0:580aba13d1a1 300 template void mros2::Publisher::publish(std_msgs::msg::Bool &msg);
smoritaemb 0:580aba13d1a1 301 template void mros2::Subscriber::callback_handler<std_msgs::msg::Bool>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 0:580aba13d1a1 302
smoritaemb 0:580aba13d1a1 303 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Byte>(std::string topic_name, int qos);
smoritaemb 0:580aba13d1a1 304 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Byte*));
smoritaemb 0:580aba13d1a1 305 template void mros2::Publisher::publish(std_msgs::msg::Byte &msg);
smoritaemb 0:580aba13d1a1 306 template void mros2::Subscriber::callback_handler<std_msgs::msg::Byte>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 0:580aba13d1a1 307
smoritaemb 0:580aba13d1a1 308 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Char>(std::string topic_name, int qos);
smoritaemb 0:580aba13d1a1 309 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Char*));
smoritaemb 0:580aba13d1a1 310 template void mros2::Publisher::publish(std_msgs::msg::Char &msg);
smoritaemb 0:580aba13d1a1 311 template void mros2::Subscriber::callback_handler<std_msgs::msg::Char>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 0:580aba13d1a1 312
smoritaemb 0:580aba13d1a1 313 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Float32>(std::string topic_name, int qos);
smoritaemb 0:580aba13d1a1 314 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Float32*));
smoritaemb 0:580aba13d1a1 315 template void mros2::Publisher::publish(std_msgs::msg::Float32 &msg);
smoritaemb 0:580aba13d1a1 316 template void mros2::Subscriber::callback_handler<std_msgs::msg::Float32>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 0:580aba13d1a1 317
smoritaemb 0:580aba13d1a1 318 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Float64>(std::string topic_name, int qos);
smoritaemb 0:580aba13d1a1 319 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Float64*));
smoritaemb 0:580aba13d1a1 320 template void mros2::Publisher::publish(std_msgs::msg::Float64 &msg);
smoritaemb 0:580aba13d1a1 321 template void mros2::Subscriber::callback_handler<std_msgs::msg::Float64>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 0:580aba13d1a1 322
smoritaemb 0:580aba13d1a1 323 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Int8>(std::string topic_name, int qos);
smoritaemb 0:580aba13d1a1 324 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Int8*));
smoritaemb 0:580aba13d1a1 325 template void mros2::Publisher::publish(std_msgs::msg::Int8 &msg);
smoritaemb 0:580aba13d1a1 326 template void mros2::Subscriber::callback_handler<std_msgs::msg::Int8>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 0:580aba13d1a1 327
smoritaemb 0:580aba13d1a1 328 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Int16>(std::string topic_name, int qos);
smoritaemb 0:580aba13d1a1 329 template mros2::Subscriber mros2::Node::create_subscription<std_msgs::msg::Int16>(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Int16*));
smoritaemb 0:580aba13d1a1 330 template void mros2::Publisher::publish(std_msgs::msg::Int16 &msg);
smoritaemb 0:580aba13d1a1 331 template void mros2::Subscriber::callback_handler<std_msgs::msg::Int16>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 0:580aba13d1a1 332
smoritaemb 0:580aba13d1a1 333 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Int32>(std::string topic_name, int qos);
smoritaemb 0:580aba13d1a1 334 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Int32*));
smoritaemb 0:580aba13d1a1 335 template void mros2::Publisher::publish(std_msgs::msg::Int32 &msg);
smoritaemb 0:580aba13d1a1 336 template void mros2::Subscriber::callback_handler<std_msgs::msg::Int32>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 0:580aba13d1a1 337
smoritaemb 0:580aba13d1a1 338 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Int64>(std::string topic_name, int qos);
smoritaemb 0:580aba13d1a1 339 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Int64*));
smoritaemb 0:580aba13d1a1 340 template void mros2::Publisher::publish(std_msgs::msg::Int64 &msg);
smoritaemb 0:580aba13d1a1 341 template void mros2::Subscriber::callback_handler<std_msgs::msg::Int64>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 0:580aba13d1a1 342
smoritaemb 0:580aba13d1a1 343 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::String>(std::string topic_name, int qos);
smoritaemb 0:580aba13d1a1 344 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::String*));
smoritaemb 0:580aba13d1a1 345 template void mros2::Publisher::publish(std_msgs::msg::String &msg);
smoritaemb 0:580aba13d1a1 346 template void mros2::Subscriber::callback_handler<std_msgs::msg::String>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 0:580aba13d1a1 347
smoritaemb 0:580aba13d1a1 348 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::UInt8>(std::string topic_name, int qos);
smoritaemb 0:580aba13d1a1 349 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::UInt8*));
smoritaemb 0:580aba13d1a1 350 template void mros2::Publisher::publish(std_msgs::msg::UInt8 &msg);
smoritaemb 0:580aba13d1a1 351 template void mros2::Subscriber::callback_handler<std_msgs::msg::UInt8>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 0:580aba13d1a1 352
smoritaemb 0:580aba13d1a1 353 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::UInt16>(std::string topic_name, int qos);
smoritaemb 0:580aba13d1a1 354 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::UInt16*));
smoritaemb 0:580aba13d1a1 355 template void mros2::Publisher::publish(std_msgs::msg::UInt16 &msg);
smoritaemb 0:580aba13d1a1 356 template void mros2::Subscriber::callback_handler<std_msgs::msg::UInt16>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 0:580aba13d1a1 357
smoritaemb 0:580aba13d1a1 358 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::UInt32>(std::string topic_name, int qos);
smoritaemb 0:580aba13d1a1 359 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::UInt32*));
smoritaemb 0:580aba13d1a1 360 template void mros2::Publisher::publish(std_msgs::msg::UInt32 &msg);
smoritaemb 0:580aba13d1a1 361 template void mros2::Subscriber::callback_handler<std_msgs::msg::UInt32>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 0:580aba13d1a1 362
smoritaemb 0:580aba13d1a1 363 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::UInt64>(std::string topic_name, int qos);
smoritaemb 0:580aba13d1a1 364 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::UInt64*));
smoritaemb 0:580aba13d1a1 365 template void mros2::Publisher::publish(std_msgs::msg::UInt64 &msg);
smoritaemb 0:580aba13d1a1 366 template void mros2::Subscriber::callback_handler<std_msgs::msg::UInt64>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 0:580aba13d1a1 367
smoritaemb 0:580aba13d1a1 368 /* Work in Progress: for custom message
smoritaemb 0:580aba13d1a1 369 template mros2::Publisher mros2::Node::create_publisher<TEST>(std::string topic_name, int qos);
smoritaemb 0:580aba13d1a1 370 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(TEST*));
smoritaemb 0:580aba13d1a1 371 template void mros2::Publisher::publish(TEST& msg);
smoritaemb 0:580aba13d1a1 372 */