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:
4:19c9ef779c65
Parent:
3:aaf6422e0be9
Child:
5:26a68a8ff5fa
--- a/include/templates.hpp	Mon Mar 14 22:54:22 2022 +0900
+++ b/include/templates.hpp	Mon Mar 14 23:01:09 2022 +0900
@@ -1,26 +1,26 @@
 #include "std_msgs/msg/u_int8.hpp"
 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::UInt8*));
 template void mros2::Subscriber::callback_handler<std_msgs::msg::UInt8>(void *callee, const rtps::ReaderCacheChange &cacheChange);
-template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Uint8>(std::string topic_name, int qos);
-template void mros2::Publisher::publish(std_msgs::msg::Uint8 &msg);
+template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::UInt8>(std::string topic_name, int qos);
+template void mros2::Publisher::publish(std_msgs::msg::UInt8 &msg);
 
 #include "std_msgs/msg/u_int16.hpp"
 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::UInt16*));
 template void mros2::Subscriber::callback_handler<std_msgs::msg::UInt16>(void *callee, const rtps::ReaderCacheChange &cacheChange);
-template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Uint16>(std::string topic_name, int qos);
-template void mros2::Publisher::publish(std_msgs::msg::Uint16 &msg);
+template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::UInt16>(std::string topic_name, int qos);
+template void mros2::Publisher::publish(std_msgs::msg::UInt16 &msg);
 
 #include "std_msgs/msg/u_int32.hpp"
 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::UInt32*));
 template void mros2::Subscriber::callback_handler<std_msgs::msg::UInt32>(void *callee, const rtps::ReaderCacheChange &cacheChange);
-template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Uint32>(std::string topic_name, int qos);
-template void mros2::Publisher::publish(std_msgs::msg::Uint32 &msg);
+template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::UInt32>(std::string topic_name, int qos);
+template void mros2::Publisher::publish(std_msgs::msg::UInt32 &msg);
 
 #include "std_msgs/msg/u_int64.hpp"
 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::UInt64*));
 template void mros2::Subscriber::callback_handler<std_msgs::msg::UInt64>(void *callee, const rtps::ReaderCacheChange &cacheChange);
-template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Uint64>(std::string topic_name, int qos);
-template void mros2::Publisher::publish(std_msgs::msg::Uint64 &msg);
+template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::UInt64>(std::string topic_name, int qos);
+template void mros2::Publisher::publish(std_msgs::msg::UInt64 &msg);
 
 #include "std_msgs/msg/int8.hpp"
 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Int8*));