Skip to content

Commit 10cd9dd

Browse files
authored
Merge pull request #119 from yujinrobot/odom_helper_check
[navi_toolkit] OdometryHelper checks / info if odom is available
2 parents 0fa79d6 + f1b6a8e commit 10cd9dd

File tree

2 files changed

+68
-16
lines changed

2 files changed

+68
-16
lines changed

yocs_navi_toolkit/include/yocs_navi_toolkit/odometry_helper.hpp

Lines changed: 15 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,11 @@ class OdometryHelper
3535
OdometryHelper(const std::string& odometry_topic_name);
3636
virtual ~OdometryHelper();
3737

38+
/**
39+
* @brief Returns if initialised (odometry available)
40+
*/
41+
bool initialized();
42+
3843
/********************
3944
** Setters
4045
********************/
@@ -46,29 +51,33 @@ class OdometryHelper
4651
// convenience getters in various formats.
4752

4853
/**
49-
* @brief 3d position of the robot in eigen format.
54+
* @brief 3d position of the robot in Eigen format.
55+
* @return true if successful (helper got odometry)
5056
*/
51-
void position(Eigen::Vector3f& position);
57+
bool position(Eigen::Vector3f& position);
5258

5359
/**
5460
* @brief Heading angle for mobile robot 2d use cases.
5561
*
5662
* @param angle : in radians
63+
* @return true if successful (helper got odometry)
5764
*/
58-
void yaw(float& angle);
65+
bool yaw(float& angle);
5966

6067
/**
6168
* @brief Mobile robot velocities in a 2d use case.
6269
*
6370
* @param mobile_robot_velocities : linear translational velocity, v and angular rate, w
71+
* @return true if successful (helper got odometry)
6472
*/
65-
void velocities(std::pair<float, float>& mobile_robot_velocities);
66-
nav_msgs::Odometry odometry();
73+
bool velocities(std::pair<float, float>& mobile_robot_velocities);
74+
75+
std::shared_ptr<nav_msgs::Odometry> odometry();
6776

6877
protected:
6978
ros::Subscriber odometry_subscriber_;
7079
std::mutex data_mutex_;
71-
nav_msgs::Odometry odometry_;
80+
std::unique_ptr<nav_msgs::Odometry> odometry_;
7281
};
7382

7483
/*****************************************************************************

yocs_navi_toolkit/src/lib/odometry_helper.cpp

Lines changed: 53 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -29,31 +29,74 @@ OdometryHelper::~OdometryHelper() {}
2929
void OdometryHelper::odometryCallback(const nav_msgs::Odometry::ConstPtr& msg)
3030
{
3131
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;
3350
}
3451

35-
nav_msgs::Odometry OdometryHelper::odometry()
52+
std::shared_ptr<nav_msgs::Odometry> OdometryHelper::odometry()
3653
{
54+
if(!initialized())
55+
{
56+
return std::shared_ptr<nav_msgs::Odometry>();
57+
}
58+
3759
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_);
3961
return msg;
4062
}
4163

42-
void OdometryHelper::position(Eigen::Vector3f& position) {
64+
bool OdometryHelper::position(Eigen::Vector3f& position) {
65+
if(!initialized())
66+
{
67+
return false;
68+
}
69+
4370
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;
4574
}
4675

47-
void OdometryHelper::yaw(float& angle) {
76+
bool OdometryHelper::yaw(float& angle) {
77+
if(!initialized())
78+
{
79+
return false;
80+
}
81+
4882
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;
5086
}
5187

52-
void OdometryHelper::velocities(std::pair<float, float>& mobile_twist_velocities)
88+
bool OdometryHelper::velocities(std::pair<float, float>& mobile_twist_velocities)
5389
{
90+
if(!initialized())
91+
{
92+
return false;
93+
}
94+
5495
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;
57100
}
58101

59102
/*****************************************************************************

0 commit comments

Comments
 (0)