File conversions.hpp
↰ Parent directory (include/proto2ros
)
Definition (include/proto2ros/conversions.hpp
)
Includes
builtin_interfaces/msg/duration.hpp
builtin_interfaces/msg/time.hpp
google/protobuf/any.pb.h
google/protobuf/duration.pb.h
google/protobuf/struct.pb.h
google/protobuf/timestamp.pb.h
google/protobuf/wrappers.pb.h
proto2ros/msg/any.hpp
proto2ros/msg/any_proto.hpp
proto2ros/msg/bytes.hpp
proto2ros/msg/list.hpp
proto2ros/msg/struct.hpp
proto2ros/msg/value.hpp
std_msgs/msg/bool.hpp
std_msgs/msg/float32.hpp
std_msgs/msg/float64.hpp
std_msgs/msg/int32.hpp
std_msgs/msg/int64.hpp
std_msgs/msg/string.hpp
std_msgs/msg/u_int32.hpp
std_msgs/msg/u_int64.hpp
stdexcept
Namespaces
Functions
Template Function proto2ros::conversions::Convert(const T&, proto2ros::msg::AnyProto *)
Function proto2ros::conversions::Convert(const proto2ros::msg::AnyProto&, google::protobuf::Any *)
Function proto2ros::conversions::Convert(const google::protobuf::Any&, proto2ros::msg::AnyProto *)
Function proto2ros::conversions::Convert(const std_msgs::msg::Bool&, google::protobuf::BoolValue *)
Function proto2ros::conversions::Convert(const google::protobuf::BoolValue&, std_msgs::msg::Bool *)
Function proto2ros::conversions::Convert(const proto2ros::msg::Value&, google::protobuf::Value *)
Function proto2ros::conversions::Convert(const google::protobuf::Value&, proto2ros::msg::Value *)
Function proto2ros::conversions::Convert(const proto2ros::msg::List&, google::protobuf::ListValue *)
Function proto2ros::conversions::Convert(const google::protobuf::ListValue&, proto2ros::msg::List *)
Function proto2ros::conversions::Convert(const proto2ros::msg::Struct&, google::protobuf::Struct *)
Function proto2ros::conversions::Convert(const google::protobuf::Struct&, proto2ros::msg::Struct *)
Template Function proto2ros::conversions::Convert(const proto2ros::msg::AnyProto&, T *)