@@ -29,31 +29,74 @@ OdometryHelper::~OdometryHelper() {}
29
29
void OdometryHelper::odometryCallback (const nav_msgs::Odometry::ConstPtr& msg)
30
30
{
31
31
std::lock_guard<std::mutex> lock (data_mutex_);
32
- odometry_ = *msg;
32
+
33
+ if (!odometry_)
34
+ {
35
+ odometry_ = std::unique_ptr<nav_msgs::Odometry>(new nav_msgs::Odometry ());
36
+ }
37
+
38
+ *odometry_ = *msg;
39
+ }
40
+
41
+ bool OdometryHelper::initialized ()
42
+ {
43
+ std::lock_guard<std::mutex> lock (data_mutex_);
44
+ if (odometry_)
45
+ {
46
+ return true ;
47
+ }
48
+
49
+ return false ;
33
50
}
34
51
35
- nav_msgs::Odometry OdometryHelper::odometry ()
52
+ std::shared_ptr< nav_msgs::Odometry> OdometryHelper::odometry ()
36
53
{
54
+ if (!initialized ())
55
+ {
56
+ return std::shared_ptr<nav_msgs::Odometry>();
57
+ }
58
+
37
59
std::lock_guard<std::mutex> lock (data_mutex_);
38
- nav_msgs::Odometry msg = odometry_;
60
+ std::shared_ptr< nav_msgs::Odometry> msg = std::make_shared<nav_msgs::Odometry>(* odometry_) ;
39
61
return msg;
40
62
}
41
63
42
- void OdometryHelper::position (Eigen::Vector3f& position) {
64
+ bool OdometryHelper::position (Eigen::Vector3f& position) {
65
+ if (!initialized ())
66
+ {
67
+ return false ;
68
+ }
69
+
43
70
std::lock_guard<std::mutex> lock (data_mutex_);
44
- position << odometry_.pose .pose .position .x , odometry_.pose .pose .position .y , odometry_.pose .pose .position .z ;
71
+ position << odometry_->pose .pose .position .x , odometry_->pose .pose .position .y , odometry_->pose .pose .position .z ;
72
+
73
+ return true ;
45
74
}
46
75
47
- void OdometryHelper::yaw (float & angle) {
76
+ bool OdometryHelper::yaw (float & angle) {
77
+ if (!initialized ())
78
+ {
79
+ return false ;
80
+ }
81
+
48
82
std::lock_guard<std::mutex> lock (data_mutex_);
49
- angle = tf::getYaw (odometry_.pose .pose .orientation );
83
+ angle = tf::getYaw (odometry_->pose .pose .orientation );
84
+
85
+ return true ;
50
86
}
51
87
52
- void OdometryHelper::velocities (std::pair<float , float >& mobile_twist_velocities)
88
+ bool OdometryHelper::velocities (std::pair<float , float >& mobile_twist_velocities)
53
89
{
90
+ if (!initialized ())
91
+ {
92
+ return false ;
93
+ }
94
+
54
95
std::lock_guard<std::mutex> lock (data_mutex_);
55
- mobile_twist_velocities.first = odometry_.twist .twist .linear .x ;
56
- mobile_twist_velocities.second = odometry_.twist .twist .angular .z ;
96
+ mobile_twist_velocities.first = odometry_->twist .twist .linear .x ;
97
+ mobile_twist_velocities.second = odometry_->twist .twist .angular .z ;
98
+
99
+ return true ;
57
100
}
58
101
59
102
/* ****************************************************************************
0 commit comments