S Morita / mbed-mros2

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

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers templates.hpp Source File

templates.hpp

00001 #include "std_msgs/msg/u_int8.hpp"
00002 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::UInt8*));
00003 template void mros2::Subscriber::callback_handler<std_msgs::msg::UInt8>(void *callee, const rtps::ReaderCacheChange &cacheChange);
00004 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::UInt8>(std::string topic_name, int qos);
00005 template void mros2::Publisher::publish(std_msgs::msg::UInt8 &msg);
00006 
00007 #include "std_msgs/msg/u_int16.hpp"
00008 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::UInt16*));
00009 template void mros2::Subscriber::callback_handler<std_msgs::msg::UInt16>(void *callee, const rtps::ReaderCacheChange &cacheChange);
00010 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::UInt16>(std::string topic_name, int qos);
00011 template void mros2::Publisher::publish(std_msgs::msg::UInt16 &msg);
00012 
00013 #include "std_msgs/msg/u_int32.hpp"
00014 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::UInt32*));
00015 template void mros2::Subscriber::callback_handler<std_msgs::msg::UInt32>(void *callee, const rtps::ReaderCacheChange &cacheChange);
00016 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::UInt32>(std::string topic_name, int qos);
00017 template void mros2::Publisher::publish(std_msgs::msg::UInt32 &msg);
00018 
00019 #include "std_msgs/msg/u_int64.hpp"
00020 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::UInt64*));
00021 template void mros2::Subscriber::callback_handler<std_msgs::msg::UInt64>(void *callee, const rtps::ReaderCacheChange &cacheChange);
00022 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::UInt64>(std::string topic_name, int qos);
00023 template void mros2::Publisher::publish(std_msgs::msg::UInt64 &msg);
00024 
00025 #include "std_msgs/msg/int8.hpp"
00026 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Int8*));
00027 template void mros2::Subscriber::callback_handler<std_msgs::msg::Int8>(void *callee, const rtps::ReaderCacheChange &cacheChange);
00028 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Int8>(std::string topic_name, int qos);
00029 template void mros2::Publisher::publish(std_msgs::msg::Int8 &msg);
00030 
00031 #include "std_msgs/msg/int16.hpp"
00032 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Int16*));
00033 template void mros2::Subscriber::callback_handler<std_msgs::msg::Int16>(void *callee, const rtps::ReaderCacheChange &cacheChange);
00034 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Int16>(std::string topic_name, int qos);
00035 template void mros2::Publisher::publish(std_msgs::msg::Int16 &msg);
00036 
00037 #include "std_msgs/msg/int32.hpp"
00038 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Int32*));
00039 template void mros2::Subscriber::callback_handler<std_msgs::msg::Int32>(void *callee, const rtps::ReaderCacheChange &cacheChange);
00040 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Int32>(std::string topic_name, int qos);
00041 template void mros2::Publisher::publish(std_msgs::msg::Int32 &msg);
00042 
00043 #include "std_msgs/msg/int64.hpp"
00044 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Int64*));
00045 template void mros2::Subscriber::callback_handler<std_msgs::msg::Int64>(void *callee, const rtps::ReaderCacheChange &cacheChange);
00046 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Int64>(std::string topic_name, int qos);
00047 template void mros2::Publisher::publish(std_msgs::msg::Int64 &msg);
00048 
00049 #include "std_msgs/msg/float32.hpp"
00050 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Float32*));
00051 template void mros2::Subscriber::callback_handler<std_msgs::msg::Float32>(void *callee, const rtps::ReaderCacheChange &cacheChange);
00052 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Float32>(std::string topic_name, int qos);
00053 template void mros2::Publisher::publish(std_msgs::msg::Float32 &msg);
00054 
00055 #include "std_msgs/msg/float64.hpp"
00056 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Float64*));
00057 template void mros2::Subscriber::callback_handler<std_msgs::msg::Float64>(void *callee, const rtps::ReaderCacheChange &cacheChange);
00058 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Float64>(std::string topic_name, int qos);
00059 template void mros2::Publisher::publish(std_msgs::msg::Float64 &msg);
00060 
00061 #include "std_msgs/msg/char.hpp"
00062 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Char>(std::string topic_name, int qos);
00063 template void mros2::Publisher::publish(std_msgs::msg::Char &msg);
00064 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Char*));
00065 template void mros2::Subscriber::callback_handler<std_msgs::msg::Char>(void *callee, const rtps::ReaderCacheChange &cacheChange);
00066 
00067 #include "std_msgs/msg/bool.hpp"
00068 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Bool>(std::string topic_name, int qos);
00069 template void mros2::Publisher::publish(std_msgs::msg::Bool &msg);
00070 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Bool*));
00071 template void mros2::Subscriber::callback_handler<std_msgs::msg::Bool>(void *callee, const rtps::ReaderCacheChange &cacheChange);
00072 
00073 #include "std_msgs/msg/byte.hpp"
00074 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Byte>(std::string topic_name, int qos);
00075 template void mros2::Publisher::publish(std_msgs::msg::Byte &msg);
00076 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Byte*));
00077 template void mros2::Subscriber::callback_handler<std_msgs::msg::Byte>(void *callee, const rtps::ReaderCacheChange &cacheChange);
00078 
00079 #include "std_msgs/msg/string.hpp"
00080 template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::String>(std::string topic_name, int qos);
00081 template void mros2::Publisher::publish(std_msgs::msg::String &msg);
00082 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::String*));
00083 template void mros2::Subscriber::callback_handler<std_msgs::msg::String>(void *callee, const rtps::ReaderCacheChange &cacheChange);
00084 
00085 #include "geometry_msgs/msg/twist.hpp"
00086 template mros2::Publisher mros2::Node::create_publisher<geometry_msgs::msg::Twist>(std::string topic_name, int qos);
00087 template void mros2::Publisher::publish( geometry_msgs::msg::Twist &msg);
00088 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(geometry_msgs::msg::Twist*));
00089 template void mros2::Subscriber::callback_handler<geometry_msgs::msg::Twist>(void *callee, const rtps::ReaderCacheChange &cacheChange);
00090 
00091 #include "geometry_msgs/msg/pose.hpp"
00092 template mros2::Publisher mros2::Node::create_publisher<geometry_msgs::msg::Pose>(std::string topic_name, int qos);
00093 template void mros2::Publisher::publish( geometry_msgs::msg::Pose &msg);
00094 template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(geometry_msgs::msg::Pose*));
00095 template void mros2::Subscriber::callback_handler<geometry_msgs::msg::Pose>(void *callee, const rtps::ReaderCacheChange &cacheChange);