-
Notifications
You must be signed in to change notification settings - Fork 218
/
CLaserOdometry2DNode.cpp
268 lines (231 loc) · 9.03 KB
/
CLaserOdometry2DNode.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
/** ****************************************************************************************
* This node presents a fast and precise method to estimate the planar motion of a lidar
* from consecutive range scans. It is very useful for the estimation of the robot odometry from
* 2D laser range measurements.
* This module is developed for mobile robots with innacurate or inexistent built-in odometry.
* It allows the estimation of a precise odometry with low computational cost.
* For more information, please refer to:
*
* Planar Odometry from a Radial Laser Scanner. A Range Flow-based Approach. ICRA'16.
* Available at: http://mapir.uma.es/papersrepo/2016/2016_Jaimez_ICRA_RF2O.pdf
*
* Maintainer: Javier G. Monroy
* MAPIR group: https://mapir.isa.uma.es
*
* Modifications: Jeremie Deray & (see contributons on github)
******************************************************************************************** */
#include "rf2o_laser_odometry/CLaserOdometry2DNode.hpp"
using namespace rf2o;
CLaserOdometry2DNode::CLaserOdometry2DNode(): Node("CLaserOdometry2DNode")
{
RCLCPP_INFO(get_logger(), "Initializing RF2O node...");
// Read Parameters
//----------------
this->declare_parameter<std::string>("laser_scan_topic", "/scan");
this->get_parameter("laser_scan_topic", laser_scan_topic);
this->declare_parameter<std::string>("odom_topic", "/odom_rf2o");
this->get_parameter("odom_topic", odom_topic);
this->declare_parameter<std::string>("base_frame_id", "base_link");
this->get_parameter("base_frame_id", base_frame_id);
this->declare_parameter<std::string>("odom_frame_id", "odom");
this->get_parameter("odom_frame_id", odom_frame_id);
this->declare_parameter<bool>("publish_tf", true);
this->get_parameter("publish_tf", publish_tf);
this->declare_parameter<std::string>("init_pose_from_topic", "/base_pose_ground_truth");
this->get_parameter("init_pose_from_topic", init_pose_from_topic);
this->declare_parameter<double>("freq", 10.0);
this->get_parameter("freq", freq);
// Init Publishers and Subscribers
//---------------------------------
buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*buffer_);
odom_broadcaster = std::make_unique<tf2_ros::TransformBroadcaster>(this);
odom_pub = this->create_publisher<nav_msgs::msg::Odometry>(odom_topic, 5);
laser_sub = this->create_subscription<sensor_msgs::msg::LaserScan>(laser_scan_topic,rclcpp::QoS(rclcpp::KeepLast(1)).best_effort().durability_volatile(),
std::bind(&CLaserOdometry2DNode::LaserCallBack, this, std::placeholders::_1));
// Initialize pose
if (init_pose_from_topic != "")
{
initPose_sub = this->create_subscription<nav_msgs::msg::Odometry>(init_pose_from_topic,rclcpp::QoS(rclcpp::KeepLast(1)).best_effort().durability_volatile(),
std::bind(&CLaserOdometry2DNode::initPoseCallBack, this, std::placeholders::_1));
GT_pose_initialized = false;
}
else
{
// init to 0
GT_pose_initialized = true;
initial_robot_pose.pose.pose.position.x = 0;
initial_robot_pose.pose.pose.position.y = 0;
initial_robot_pose.pose.pose.position.z = 0;
initial_robot_pose.pose.pose.orientation.w = 0;
initial_robot_pose.pose.pose.orientation.x = 0;
initial_robot_pose.pose.pose.orientation.y = 0;
initial_robot_pose.pose.pose.orientation.z = 0;
}
// Init variables
rf2o_ref.module_initialized = false;
rf2o_ref.first_laser_scan = true;
}
/**
* Keeps the last scan from the 2D lidar to be latter processed
* On the first laser scan, the node is initialized.
*/
void CLaserOdometry2DNode::LaserCallBack(const sensor_msgs::msg::LaserScan::SharedPtr new_scan)
{
if (GT_pose_initialized)
{
// Keep in memory the last received laser_scan
last_scan = *new_scan;
rf2o_ref.current_scan_time = last_scan.header.stamp;
if (rf2o_ref.first_laser_scan == false)
{
// copy laser range data to rf2o internal variable
for (unsigned int i = 0; i < rf2o_ref.width; i++)
rf2o_ref.range_wf(i) = new_scan->ranges[i];
// inform of new scan available
new_scan_available = true;
}
else
{
// Initialize module on first scan (from laser params)
setLaserPoseFromTf();
rf2o_ref.init(last_scan, initial_robot_pose.pose.pose);
rf2o_ref.first_laser_scan = false;
}
}
}
/**
* Gets the laser pose with respect the base_link (through TF)
* This allow estimation of the odometry with respect to the robot base reference system.
*/
bool CLaserOdometry2DNode::setLaserPoseFromTf()
{
bool retrieved = false;
geometry_msgs::msg::TransformStamped tf_laser;
try
{
tf_laser = buffer_->lookupTransform(base_frame_id, last_scan.header.frame_id, tf2::TimePointZero);
retrieved = true;
}
catch (tf2::TransformException &ex)
{
RCLCPP_ERROR(get_logger(), "%s",ex.what());
retrieved = false;
}
// Keep this transform as Eigen Matrix3d
tf2::Transform transform;
tf2::convert(tf_laser.transform, transform);
const tf2::Matrix3x3 &basis = transform.getBasis();
Eigen::Matrix3d R;
for(int r = 0; r < 3; r++)
for(int c = 0; c < 3; c++)
R(r,c) = basis[r][c];
Pose3d laser_tf(R);
const tf2::Vector3 &t = transform.getOrigin();
laser_tf.translation()(0) = t[0];
laser_tf.translation()(1) = t[1];
laser_tf.translation()(2) = t[2];
// Sets this transform in rf2o
rf2o_ref.setLaserPose(laser_tf);
return retrieved;
}
bool CLaserOdometry2DNode::scan_available()
{
return new_scan_available;
}
/**
* Process the last scans to estimate the current odometry
*/
void CLaserOdometry2DNode::process()
{
// Do only run when a new scan is ready
if( rf2o_ref.is_initialized() && scan_available() )
{
// Process odometry estimation
rf2o_ref.odometryCalculation(last_scan);
// Publish odometry over ROS2 (tf/topic)
publish();
// Do not run on the same data!
new_scan_available = false;
}
else
{
// This is a warning. We depend on laser scans, so no meaning running faster than scan freq.
RCLCPP_WARN(get_logger(), "Waiting for laser_scans....");
}
}
/**
* This function is used to initialize the robot pose before estimating its odometry.
* By default the odometry will start from pose_0, but when comparing different methods
* it may be necessary to start from a different pose.
*/
void CLaserOdometry2DNode::initPoseCallBack(const nav_msgs::msg::Odometry::SharedPtr new_initPose)
{
// Initialize module on first GT pose. Else do Nothing!
if (!GT_pose_initialized)
{
initial_robot_pose = *new_initPose;
GT_pose_initialized = true;
}
}
/**
* Publish current odocmetry estimation over ROS
* According to the node parameters it will publish over tf and/or especified topic
*/
void CLaserOdometry2DNode::publish()
{
// 1. publish odom as a topic (no harm!)
RCLCPP_DEBUG(get_logger(), "Publishing odom over topic:[%s]", odom_topic.c_str());
tf2::Quaternion tf_quaternion;
tf_quaternion.setRPY(0.0, 0.0, rf2o::getYaw(rf2o_ref.robot_pose_.rotation()));
geometry_msgs::msg::Quaternion quaternion = tf2::toMsg(tf_quaternion);
// compose odom msg
nav_msgs::msg::Odometry odom;
odom.header.stamp = rf2o_ref.last_odom_time; // the time of the last scan used!
odom.header.frame_id = odom_frame_id;
//set the position
odom.pose.pose.position.x = rf2o_ref.robot_pose_.translation()(0);
odom.pose.pose.position.y = rf2o_ref.robot_pose_.translation()(1);
odom.pose.pose.position.z = 0.0;
odom.pose.pose.orientation = quaternion;
//set the velocity
odom.child_frame_id = base_frame_id;
odom.twist.twist.linear.x = rf2o_ref.lin_speed; //linear speed
odom.twist.twist.linear.y = 0.0;
odom.twist.twist.angular.z = rf2o_ref.ang_speed; //angular speed
//publish the message
odom_pub->publish(odom);
// 2. publish over tf? (one one node should publish this transform!)
if (publish_tf)
{
RCLCPP_DEBUG(get_logger(), "Publishing TF: [base_link] to [odom]");
geometry_msgs::msg::TransformStamped odom_trans;
odom_trans.header.stamp = rf2o_ref.last_odom_time; // the time of the last scan used!
odom_trans.header.frame_id = odom_frame_id;
odom_trans.child_frame_id = base_frame_id;
odom_trans.transform.translation.x = rf2o_ref.robot_pose_.translation()(0);
odom_trans.transform.translation.y = rf2o_ref.robot_pose_.translation()(1);
odom_trans.transform.translation.z = 0.0;
odom_trans.transform.rotation = quaternion;
//send the transform
odom_broadcaster->sendTransform(odom_trans);
}
}
} /* namespace rf2o */
//-----------------------------------------------------------------------------------
// MAIN
//-----------------------------------------------------------------------------------
int main(int argc, char** argv)
{
rclcpp::init(argc, argv);
auto myLaserOdomNode = std::make_shared<rf2o::CLaserOdometry2DNode>();
// set desired loop rate
rclcpp::Rate rate(myLaserOdomNode->freq);
// Loop
while (rclcpp::ok()){
rclcpp::spin_some(myLaserOdomNode);
myLaserOdomNode->process();
rate.sleep();
}
return 0;
}