Skip to content

Commit c36999b

Browse files
authored
Fixed errors due to missing header link. (#432)
Signed-off-by: Shivam Pandey <[email protected]>
1 parent ae30f0b commit c36999b

File tree

1 file changed

+4
-0
lines changed

1 file changed

+4
-0
lines changed

tf2/include/tf2/impl/utils.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,8 +15,12 @@
1515
#ifndef TF2__IMPL__UTILS_H_
1616
#define TF2__IMPL__UTILS_H_
1717

18+
#include <tf2/convert.h>
1819
#include <tf2/transform_datatypes.h>
1920
#include <tf2/LinearMath/Quaternion.h>
21+
#include <geometry_msgs/msg/quaternion.hpp>
22+
#include <geometry_msgs/msg/quaternion_stamped.hpp>
23+
2024

2125
namespace tf2
2226
{

0 commit comments

Comments
 (0)