S Morita / mbed-mros2

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

Committer:
smoritaemb
Date:
Mon Mar 14 23:01:09 2022 +0900
Branch:
test_assortment_of_msgs
Revision:
4:19c9ef779c65
Parent:
3:aaf6422e0be9
Child:
5:26a68a8ff5fa
Fixed trivial typo(Uint => UInt) in templates.hpp.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
smoritaemb 3:aaf6422e0be9 1 #include "std_msgs/msg/u_int8.hpp"
smoritaemb 3:aaf6422e0be9 2 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::UInt8*));
smoritaemb 3:aaf6422e0be9 3 template void mros2::Subscriber::callback_handler<std_msgs::msg::UInt8>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 4:19c9ef779c65 4 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::UInt8>(std::string topic_name, int qos);
smoritaemb 4:19c9ef779c65 5 template void mros2::Publisher::publish(std_msgs::msg::UInt8 &msg);
smoritaemb 3:aaf6422e0be9 6
smoritaemb 3:aaf6422e0be9 7 #include "std_msgs/msg/u_int16.hpp"
smoritaemb 3:aaf6422e0be9 8 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::UInt16*));
smoritaemb 3:aaf6422e0be9 9 template void mros2::Subscriber::callback_handler<std_msgs::msg::UInt16>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 4:19c9ef779c65 10 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::UInt16>(std::string topic_name, int qos);
smoritaemb 4:19c9ef779c65 11 template void mros2::Publisher::publish(std_msgs::msg::UInt16 &msg);
smoritaemb 3:aaf6422e0be9 12
smoritaemb 3:aaf6422e0be9 13 #include "std_msgs/msg/u_int32.hpp"
smoritaemb 3:aaf6422e0be9 14 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::UInt32*));
smoritaemb 3:aaf6422e0be9 15 template void mros2::Subscriber::callback_handler<std_msgs::msg::UInt32>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 4:19c9ef779c65 16 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::UInt32>(std::string topic_name, int qos);
smoritaemb 4:19c9ef779c65 17 template void mros2::Publisher::publish(std_msgs::msg::UInt32 &msg);
smoritaemb 3:aaf6422e0be9 18
smoritaemb 3:aaf6422e0be9 19 #include "std_msgs/msg/u_int64.hpp"
smoritaemb 3:aaf6422e0be9 20 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::UInt64*));
smoritaemb 3:aaf6422e0be9 21 template void mros2::Subscriber::callback_handler<std_msgs::msg::UInt64>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 4:19c9ef779c65 22 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::UInt64>(std::string topic_name, int qos);
smoritaemb 4:19c9ef779c65 23 template void mros2::Publisher::publish(std_msgs::msg::UInt64 &msg);
smoritaemb 3:aaf6422e0be9 24
smoritaemb 3:aaf6422e0be9 25 #include "std_msgs/msg/int8.hpp"
smoritaemb 3:aaf6422e0be9 26 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Int8*));
smoritaemb 3:aaf6422e0be9 27 template void mros2::Subscriber::callback_handler<std_msgs::msg::Int8>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 3:aaf6422e0be9 28 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Int8>(std::string topic_name, int qos);
smoritaemb 3:aaf6422e0be9 29 template void mros2::Publisher::publish(std_msgs::msg::Int8 &msg);
smoritaemb 3:aaf6422e0be9 30
smoritaemb 3:aaf6422e0be9 31 #include "std_msgs/msg/int16.hpp"
smoritaemb 3:aaf6422e0be9 32 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Int16*));
smoritaemb 3:aaf6422e0be9 33 template void mros2::Subscriber::callback_handler<std_msgs::msg::Int16>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 3:aaf6422e0be9 34 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Int16>(std::string topic_name, int qos);
smoritaemb 3:aaf6422e0be9 35 template void mros2::Publisher::publish(std_msgs::msg::Int16 &msg);
smoritaemb 3:aaf6422e0be9 36
smoritaemb 3:aaf6422e0be9 37 #include "std_msgs/msg/int32.hpp"
smoritaemb 3:aaf6422e0be9 38 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Int32*));
smoritaemb 3:aaf6422e0be9 39 template void mros2::Subscriber::callback_handler<std_msgs::msg::Int32>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 3:aaf6422e0be9 40 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Int32>(std::string topic_name, int qos);
smoritaemb 3:aaf6422e0be9 41 template void mros2::Publisher::publish(std_msgs::msg::Int32 &msg);
smoritaemb 3:aaf6422e0be9 42
smoritaemb 3:aaf6422e0be9 43 #include "std_msgs/msg/int64.hpp"
smoritaemb 3:aaf6422e0be9 44 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Int64*));
smoritaemb 3:aaf6422e0be9 45 template void mros2::Subscriber::callback_handler<std_msgs::msg::Int64>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 3:aaf6422e0be9 46 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Int64>(std::string topic_name, int qos);
smoritaemb 3:aaf6422e0be9 47 template void mros2::Publisher::publish(std_msgs::msg::Int64 &msg);
smoritaemb 3:aaf6422e0be9 48
smoritaemb 3:aaf6422e0be9 49 #include "std_msgs/msg/float32.hpp"
smoritaemb 3:aaf6422e0be9 50 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Float32*));
smoritaemb 3:aaf6422e0be9 51 template void mros2::Subscriber::callback_handler<std_msgs::msg::Float32>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 3:aaf6422e0be9 52 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Float32>(std::string topic_name, int qos);
smoritaemb 3:aaf6422e0be9 53 template void mros2::Publisher::publish(std_msgs::msg::Float32 &msg);
smoritaemb 3:aaf6422e0be9 54
smoritaemb 3:aaf6422e0be9 55 #include "std_msgs/msg/float64.hpp"
smoritaemb 3:aaf6422e0be9 56 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Float64*));
smoritaemb 3:aaf6422e0be9 57 template void mros2::Subscriber::callback_handler<std_msgs::msg::Float64>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 3:aaf6422e0be9 58 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Float64>(std::string topic_name, int qos);
smoritaemb 3:aaf6422e0be9 59 template void mros2::Publisher::publish(std_msgs::msg::Float64 &msg);
smoritaemb 3:aaf6422e0be9 60
smoritaemb 3:aaf6422e0be9 61 #include "std_msgs/msg/char.hpp"
smoritaemb 3:aaf6422e0be9 62 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Char>(std::string topic_name, int qos);
smoritaemb 3:aaf6422e0be9 63 template void mros2::Publisher::publish(std_msgs::msg::Char &msg);
smoritaemb 3:aaf6422e0be9 64 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Char*));
smoritaemb 3:aaf6422e0be9 65 template void mros2::Subscriber::callback_handler<std_msgs::msg::Char>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 3:aaf6422e0be9 66
smoritaemb 3:aaf6422e0be9 67 #include "std_msgs/msg/bool.hpp"
smoritaemb 3:aaf6422e0be9 68 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Bool>(std::string topic_name, int qos);
smoritaemb 3:aaf6422e0be9 69 template void mros2::Publisher::publish(std_msgs::msg::Bool &msg);
smoritaemb 3:aaf6422e0be9 70 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Bool*));
smoritaemb 3:aaf6422e0be9 71 template void mros2::Subscriber::callback_handler<std_msgs::msg::Bool>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 3:aaf6422e0be9 72
smoritaemb 3:aaf6422e0be9 73 #include "std_msgs/msg/byte.hpp"
smoritaemb 3:aaf6422e0be9 74 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Byte>(std::string topic_name, int qos);
smoritaemb 3:aaf6422e0be9 75 template void mros2::Publisher::publish(std_msgs::msg::Byte &msg);
smoritaemb 3:aaf6422e0be9 76 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Byte*));
smoritaemb 3:aaf6422e0be9 77 template void mros2::Subscriber::callback_handler<std_msgs::msg::Byte>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 3:aaf6422e0be9 78
smoritaemb 3:aaf6422e0be9 79 #include "std_msgs/msg/string.hpp"
smoritaemb 3:aaf6422e0be9 80 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::String>(std::string topic_name, int qos);
smoritaemb 3:aaf6422e0be9 81 template void mros2::Publisher::publish(std_msgs::msg::String &msg);
smoritaemb 3:aaf6422e0be9 82 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::String*));
smoritaemb 3:aaf6422e0be9 83 template void mros2::Subscriber::callback_handler<std_msgs::msg::String>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 3:aaf6422e0be9 84
smoritaemb 3:aaf6422e0be9 85 #include "geometry_msgs/msg/twist.hpp"
smoritaemb 3:aaf6422e0be9 86 template mros2::Publisher mros2::Node::create_publisher<geometry_msgs::msg::Twist>(std::string topic_name, int qos);
smoritaemb 3:aaf6422e0be9 87 template void mros2::Publisher::publish(geometry_msgs::msg::Twist &msg);
smoritaemb 3:aaf6422e0be9 88 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Twist*));
smoritaemb 3:aaf6422e0be9 89 template void mros2::Subscriber::callback_handler<std_msgs::msg::Twist>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 3:aaf6422e0be9 90
smoritaemb 3:aaf6422e0be9 91 #include "geometry_msgs/msg/pose.hpp"
smoritaemb 3:aaf6422e0be9 92 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(geometry_msgs::msg::Pose*));
smoritaemb 3:aaf6422e0be9 93 template void mros2::Subscriber::callback_handler<geometry_msgs::msg::Pose>(void *callee, const rtps::ReaderCacheChange &cacheChange);
smoritaemb 3:aaf6422e0be9 94 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Pose*));
smoritaemb 3:aaf6422e0be9 95 template void mros2::Subscriber::callback_handler<std_msgs::msg::Pose>(void *callee, const rtps::ReaderCacheChange &cacheChange);