tf2_compass_msgs.h
Go to the documentation of this file.
1 #pragma once
2 
3 // SPDX-License-Identifier: BSD-3-Clause
4 // SPDX-FileCopyrightText: Czech Technical University in Prague
5 
12 #include <string>
13 
14 #include <compass_msgs/Azimuth.h>
15 #include <geometry_msgs/TransformStamped.h>
16 #include <ros/time.h>
17 #include <tf2/convert.h>
18 
19 namespace tf2
20 {
21 template<> const ros::Time& getTimestamp(const compass_msgs::Azimuth& t);
22 template<> const std::string& getFrameId(const compass_msgs::Azimuth& t);
23 
24 compass_msgs::Azimuth toMsg(const compass_msgs::Azimuth& in);
25 void fromMsg(const compass_msgs::Azimuth& msg, compass_msgs::Azimuth& out);
26 
27 template<>
28 void doTransform(
29  const compass_msgs::Azimuth& t_in, compass_msgs::Azimuth& t_out, const geometry_msgs::TransformStamped& transform);
30 }
tf2::getTimestamp
const ros::Time & getTimestamp(const T &t)
tf2::fromMsg
void fromMsg(const A &, B &b)
time.h
ros::Time
tf2::doTransform
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
tf2::getFrameId
const std::string & getFrameId(const T &t)
tf2
tf2::toMsg
B toMsg(const A &a)
convert.h


compass_conversions
Author(s): Martin Pecka
autogenerated on Mon Dec 23 2024 04:03:21