include
slam_toolbox
get_pose_helper.hpp
Go to the documentation of this file.
1
/*
2
* snap_utils
3
* Copyright (c) 2019, Samsung Research America
4
*
5
* THE WORK (AS DEFINED BELOW) IS PROVIDED UNDER THE TERMS OF THIS CREATIVE
6
* COMMONS PUBLIC LICENSE ("CCPL" OR "LICENSE"). THE WORK IS PROTECTED BY
7
* COPYRIGHT AND/OR OTHER APPLICABLE LAW. ANY USE OF THE WORK OTHER THAN AS
8
* AUTHORIZED UNDER THIS LICENSE OR COPYRIGHT LAW IS PROHIBITED.
9
*
10
* BY EXERCISING ANY RIGHTS TO THE WORK PROVIDED HERE, YOU ACCEPT AND AGREE TO
11
* BE BOUND BY THE TERMS OF THIS LICENSE. THE LICENSOR GRANTS YOU THE RIGHTS
12
* CONTAINED HERE IN CONSIDERATION OF YOUR ACCEPTANCE OF SUCH TERMS AND
13
* CONDITIONS.
14
*
15
*/
16
17
/* Author: Steven Macenski */
18
19
#ifndef SLAM_TOOLBOX_POSE_UTILS_H_
20
#define SLAM_TOOLBOX_POSE_UTILS_H_
21
22
#include <geometry_msgs/PoseWithCovarianceStamped.h>
23
#include "
slam_toolbox/toolbox_types.hpp
"
24
#include "
karto_sdk/Mapper.h
"
25
26
namespace
pose_utils
27
{
28
29
// helper to get the robots position
30
class
GetPoseHelper
31
{
32
public
:
33
GetPoseHelper
(
tf2_ros::Buffer
*
tf
,
34
const
std::string& base_frame,
35
const
std::string& odom_frame)
36
:
tf_
(
tf
),
base_frame_
(base_frame),
odom_frame_
(odom_frame)
37
{
38
};
39
40
bool
getOdomPose
(
karto::Pose2
& karto_pose,
const
ros::Time
& t)
41
{
42
geometry_msgs::TransformStamped base_ident, odom_pose;
43
base_ident.header.stamp =
t
;
44
base_ident.header.frame_id =
base_frame_
;
45
base_ident.transform.rotation.w = 1.0;
46
47
try
48
{
49
odom_pose =
tf_
->
transform
(base_ident,
odom_frame_
);
50
}
51
catch
(
tf2::TransformException
e)
52
{
53
ROS_WARN
(
"Failed to compute odom pose, skipping scan (%s)"
, e.what());
54
return
false
;
55
}
56
57
const
double
yaw =
tf2::getYaw
(odom_pose.transform.rotation);
58
karto_pose =
karto::Pose2
(odom_pose.transform.translation.x,
59
odom_pose.transform.translation.y, yaw);
60
61
return
true
;
62
};
63
64
private
:
65
tf2_ros::Buffer
*
tf_
;
66
std::string
base_frame_
,
odom_frame_
;
67
};
68
69
}
// end namespace
70
71
#endif //SLAM_TOOLBOX_POSE_UTILS_H_
tf2::getYaw
double getYaw(const A &a)
pose_utils::GetPoseHelper
Definition:
get_pose_helper.hpp:30
ROS_WARN
#define ROS_WARN(...)
tf2_ros::Buffer
pose_utils::GetPoseHelper::GetPoseHelper
GetPoseHelper(tf2_ros::Buffer *tf, const std::string &base_frame, const std::string &odom_frame)
Definition:
get_pose_helper.hpp:33
toolbox_types.hpp
pose_utils::GetPoseHelper::odom_frame_
std::string odom_frame_
Definition:
get_pose_helper.hpp:66
tf2_ros::BufferInterface::transform
B & transform(const A &in, B &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
ros::Time
pose_utils::GetPoseHelper::getOdomPose
bool getOdomPose(karto::Pose2 &karto_pose, const ros::Time &t)
Definition:
get_pose_helper.hpp:40
pose_utils::GetPoseHelper::base_frame_
std::string base_frame_
Definition:
get_pose_helper.hpp:66
tf
Mapper.h
karto::Pose2
Definition:
Karto.h:2046
pose_utils
Definition:
get_pose_helper.hpp:26
tf2::TransformException
t
geometry_msgs::TransformStamped t
pose_utils::GetPoseHelper::tf_
tf2_ros::Buffer * tf_
Definition:
get_pose_helper.hpp:62
slam_toolbox
Author(s): Steve Macenski
autogenerated on Thu Jan 11 2024 03:37:55