S Morita / mbed-mros2

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

Branch:
test_assortment_of_msgs
Revision:
6:de187e431bef
Parent:
5:26a68a8ff5fa
--- a/include/templates.hpp	Mon Mar 14 23:06:52 2022 +0900
+++ b/include/templates.hpp	Mon Mar 14 23:12:20 2022 +0900
@@ -89,7 +89,7 @@
 template void mros2::Subscriber::callback_handler<geometry_msgs::msg::Twist>(void *callee, const rtps::ReaderCacheChange &cacheChange);
 
 #include "geometry_msgs/msg/pose.hpp"
+template mros2::Publisher mros2::Node::create_publisher<geometry_msgs::msg::Pose>(std::string topic_name, int qos);
+template void mros2::Publisher::publish( geometry_msgs::msg::Pose &msg);
 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(geometry_msgs::msg::Pose*));
 template void mros2::Subscriber::callback_handler<geometry_msgs::msg::Pose>(void *callee, const rtps::ReaderCacheChange &cacheChange);
-template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(geometry_msgs::msg::Pose*));
-template void mros2::Subscriber::callback_handler<geometry_msgs::msg::Pose>(void *callee, const rtps::ReaderCacheChange &cacheChange);