Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependents: mbed-os-example-mros2 example-mbed-mros2-sub-pose example-mbed-mros2-pub-twist example-mbed-mros2-mturtle-teleop
Diff: include/templates.hpp
- Revision:
- 7:c80f65422d99
- Parent:
- 6:de187e431bef
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/include/templates.hpp Sat Mar 19 09:23:37 2022 +0900 @@ -0,0 +1,95 @@ +#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); + +#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); + +#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); + +#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); + +#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*)); +template void mros2::Subscriber::callback_handler<std_msgs::msg::Int8>(void *callee, const rtps::ReaderCacheChange &cacheChange); +template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Int8>(std::string topic_name, int qos); +template void mros2::Publisher::publish(std_msgs::msg::Int8 &msg); + +#include "std_msgs/msg/int16.hpp" +template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Int16*)); +template void mros2::Subscriber::callback_handler<std_msgs::msg::Int16>(void *callee, const rtps::ReaderCacheChange &cacheChange); +template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Int16>(std::string topic_name, int qos); +template void mros2::Publisher::publish(std_msgs::msg::Int16 &msg); + +#include "std_msgs/msg/int32.hpp" +template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Int32*)); +template void mros2::Subscriber::callback_handler<std_msgs::msg::Int32>(void *callee, const rtps::ReaderCacheChange &cacheChange); +template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Int32>(std::string topic_name, int qos); +template void mros2::Publisher::publish(std_msgs::msg::Int32 &msg); + +#include "std_msgs/msg/int64.hpp" +template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Int64*)); +template void mros2::Subscriber::callback_handler<std_msgs::msg::Int64>(void *callee, const rtps::ReaderCacheChange &cacheChange); +template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Int64>(std::string topic_name, int qos); +template void mros2::Publisher::publish(std_msgs::msg::Int64 &msg); + +#include "std_msgs/msg/float32.hpp" +template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Float32*)); +template void mros2::Subscriber::callback_handler<std_msgs::msg::Float32>(void *callee, const rtps::ReaderCacheChange &cacheChange); +template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Float32>(std::string topic_name, int qos); +template void mros2::Publisher::publish(std_msgs::msg::Float32 &msg); + +#include "std_msgs/msg/float64.hpp" +template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Float64*)); +template void mros2::Subscriber::callback_handler<std_msgs::msg::Float64>(void *callee, const rtps::ReaderCacheChange &cacheChange); +template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Float64>(std::string topic_name, int qos); +template void mros2::Publisher::publish(std_msgs::msg::Float64 &msg); + +#include "std_msgs/msg/char.hpp" +template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Char>(std::string topic_name, int qos); +template void mros2::Publisher::publish(std_msgs::msg::Char &msg); +template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Char*)); +template void mros2::Subscriber::callback_handler<std_msgs::msg::Char>(void *callee, const rtps::ReaderCacheChange &cacheChange); + +#include "std_msgs/msg/bool.hpp" +template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Bool>(std::string topic_name, int qos); +template void mros2::Publisher::publish(std_msgs::msg::Bool &msg); +template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Bool*)); +template void mros2::Subscriber::callback_handler<std_msgs::msg::Bool>(void *callee, const rtps::ReaderCacheChange &cacheChange); + +#include "std_msgs/msg/byte.hpp" +template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::Byte>(std::string topic_name, int qos); +template void mros2::Publisher::publish(std_msgs::msg::Byte &msg); +template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::Byte*)); +template void mros2::Subscriber::callback_handler<std_msgs::msg::Byte>(void *callee, const rtps::ReaderCacheChange &cacheChange); + +#include "std_msgs/msg/string.hpp" +template mros2::Publisher mros2::Node::create_publisher<std_msgs::msg::String>(std::string topic_name, int qos); +template void mros2::Publisher::publish(std_msgs::msg::String &msg); +template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(std_msgs::msg::String*)); +template void mros2::Subscriber::callback_handler<std_msgs::msg::String>(void *callee, const rtps::ReaderCacheChange &cacheChange); + +#include "geometry_msgs/msg/twist.hpp" +template mros2::Publisher mros2::Node::create_publisher<geometry_msgs::msg::Twist>(std::string topic_name, int qos); +template void mros2::Publisher::publish( geometry_msgs::msg::Twist &msg); +template mros2::Subscriber mros2::Node::create_subscription(std::string topic_name, int qos, void (*fp)(geometry_msgs::msg::Twist*)); +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);