16 #include <std_msgs/Float32.h>
17 #include <std_msgs/Float64.h>
18 #include <std_msgs/String.h>
19 #include <std_msgs/Int8.h>
20 #include <std_msgs/Int64.h>
21 #include <std_msgs/Bool.h>
22 #include <nav_msgs/Odometry.h>
23 #include <tf2/LinearMath/Quaternion.h>
24 #include <tf/transform_broadcaster.h>
25 #include <geometry_msgs/Pose.h>
26 #include <geometry_msgs/Twist.h>
47 void operator()(std_msgs::Float64ConstPtr msg,
double* value)
49 *value = msg.get()->data;
59 *value = msg.get()->data;
68 void operator()(std_msgs::StringConstPtr msg, std::string* value)
70 *value = msg.get()->data;
72 void operator()(std_msgs::StringConstPtr msg, std::string& value)
74 value = msg.get()->data;
76 void operator()(
const std_msgs::String& msg_string, std::string& std_string)
78 std_string = msg_string.data;
87 void operator()(std_msgs::Int64ConstPtr msg, int64_t* value)
89 *value = msg.get()->data;
91 void operator()(std_msgs::Int64ConstPtr msg, int64_t& value)
93 value = msg.get()->data;
95 void operator()(
const std_msgs::Int64& msg, int64_t& std)
Definition: areaofeffectconverter.h:20
Definition: stdconverter.h:39
std_msgs::String operator()(std::string value)
Definition: stdconverter.h:62
std_msgs::Float64 operator()(double value)
Definition: stdconverter.h:41
void operator()(const std_msgs::Int64 &msg, int64_t &std)
Definition: stdconverter.h:95
void operator()(std_msgs::StringConstPtr msg, std::string *value)
Definition: stdconverter.h:68
std_msgs::Int64 operator()(int64_t value)
Definition: stdconverter.h:81
void operator()(std_msgs::Int64ConstPtr msg, int64_t *value)
Definition: stdconverter.h:87
void operator()(std_msgs::Float64ConstPtr msg, double *value)
Definition: stdconverter.h:47
void operator()(const std_msgs::String &msg_string, std::string &std_string)
Definition: stdconverter.h:76
void operator()(std_msgs::BoolConstPtr msg, bool *value)
Definition: stdconverter.h:57
void operator()(std_msgs::Int64ConstPtr msg, int64_t &value)
Definition: stdconverter.h:91
void operator()(std_msgs::StringConstPtr msg, std::string &value)
Definition: stdconverter.h:72
std_msgs::Bool operator()(bool value)
Definition: stdconverter.h:51