-
Notifications
You must be signed in to change notification settings - Fork 906
/
Copy pathros_filter.cpp
3467 lines (3032 loc) · 133 KB
/
ros_filter.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
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
* Copyright (c) 2014, 2015, 2016 Charles River Analytics, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#include <robot_localization/ekf.hpp>
#include <robot_localization/filter_utilities.hpp>
#include <robot_localization/ros_filter.hpp>
#include <robot_localization/ros_filter_utilities.hpp>
#include <robot_localization/ukf.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <rcl/time.h>
#include <rclcpp/qos.hpp>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/imu.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <algorithm>
#include <limits>
#include <map>
#include <string>
#include <utility>
#include <memory>
#include <vector>
namespace robot_localization
{
using namespace std::chrono_literals;
template<typename T>
RosFilter<T>::RosFilter(const rclcpp::NodeOptions & options)
: Node(options.arguments()[0], options),
print_diagnostics_(true),
publish_acceleration_(false),
publish_transform_(true),
reset_on_time_jump_(false),
smooth_lagged_data_(false),
toggled_on_(true),
two_d_mode_(false),
use_control_(false),
disabled_at_startup_(false),
enabled_(false),
dynamic_diag_error_level_(diagnostic_msgs::msg::DiagnosticStatus::OK),
static_diag_error_level_(diagnostic_msgs::msg::DiagnosticStatus::OK),
frequency_(30.0),
gravitational_acceleration_(9.80665),
history_length_(0ns),
latest_control_(),
last_set_pose_time_(0, 0, RCL_ROS_TIME),
latest_control_time_(0, 0, RCL_ROS_TIME),
tf_timeout_(0ns),
tf_time_offset_(0ns)
{
tf_buffer_ = std::make_unique<tf2_ros::Buffer>(this->get_clock());
tf_listener_ = std::make_unique<tf2_ros::TransformListener>(*tf_buffer_);
state_variable_names_.push_back("X");
state_variable_names_.push_back("Y");
state_variable_names_.push_back("Z");
state_variable_names_.push_back("ROLL");
state_variable_names_.push_back("PITCH");
state_variable_names_.push_back("YAW");
state_variable_names_.push_back("X_VELOCITY");
state_variable_names_.push_back("Y_VELOCITY");
state_variable_names_.push_back("Z_VELOCITY");
state_variable_names_.push_back("ROLL_VELOCITY");
state_variable_names_.push_back("PITCH_VELOCITY");
state_variable_names_.push_back("YAW_VELOCITY");
state_variable_names_.push_back("X_ACCELERATION");
state_variable_names_.push_back("Y_ACCELERATION");
state_variable_names_.push_back("Z_ACCELERATION");
}
template<typename T>
RosFilter<T>::~RosFilter()
{
topic_subs_.clear();
timer_.reset();
set_pose_sub_.reset();
control_sub_.reset();
tf_listener_.reset();
tf_buffer_.reset();
diagnostic_updater_.reset();
world_transform_broadcaster_.reset();
set_pose_service_.reset();
freq_diag_.reset();
accel_pub_.reset();
position_pub_.reset();
}
template<typename T>
void RosFilter<T>::reset()
{
// Get rid of any initial poses (pretend we've never had a measurement)
initial_measurements_.clear();
previous_measurements_.clear();
previous_measurement_covariances_.clear();
clearMeasurementQueue();
filter_state_history_.clear();
measurement_history_.clear();
// Also set the last set pose time, so we ignore all messages
// that occur before it
last_set_pose_time_ = rclcpp::Time(0);
// clear tf buffer to avoid TF_OLD_DATA errors
tf_buffer_->clear();
// clear last message timestamp, so older messages will be accepted
last_message_times_.clear();
// reset filter to uninitialized state
filter_.reset();
// clear all waiting callbacks
// ros::getGlobalCallbackQueue()->clear();
}
template<typename T>
void RosFilter<T>::toggleFilterProcessingCallback(
const std::shared_ptr<rmw_request_id_t>/*request_header*/,
const std::shared_ptr<
robot_localization::srv::ToggleFilterProcessing::Request> req,
const std::shared_ptr<
robot_localization::srv::ToggleFilterProcessing::Response> resp)
{
if (req->on == toggled_on_) {
RCLCPP_WARN(
this->get_logger(),
"Service was called to toggle filter processing but state was already as "
"requested.");
resp->status = false;
} else {
RCLCPP_INFO(
this->get_logger(),
"Toggling filter measurement filtering to %s.", req->on ? "On" : "Off");
toggled_on_ = req->on;
resp->status = true;
}
}
// @todo: Replace with AccelWithCovarianceStamped
template<typename T>
void RosFilter<T>::accelerationCallback(
const sensor_msgs::msg::Imu::SharedPtr msg,
const CallbackData & callback_data,
const std::string & target_frame)
{
// If we've just reset the filter, then we want to ignore any messages
// that arrive with an older timestamp
if (last_set_pose_time_ >= msg->header.stamp) {
return;
}
const std::string & topic_name = callback_data.topic_name_;
RF_DEBUG(
"------ RosFilter<T>::accelerationCallback (" << topic_name <<
") ------\n")
// "Twist message:\n" << *msg);
if (last_message_times_.count(topic_name) == 0) {
last_message_times_.insert(
std::pair<std::string, rclcpp::Time>(topic_name, msg->header.stamp));
}
// Make sure this message is newer than the last one
if (last_message_times_[topic_name] <= msg->header.stamp) {
RF_DEBUG("Update vector for " << topic_name << " is:\n" << topic_name);
Eigen::VectorXd measurement(STATE_SIZE);
Eigen::MatrixXd measurement_covariance(STATE_SIZE, STATE_SIZE);
measurement.setZero();
measurement_covariance.setZero();
// Make sure we're actually updating at least one of these variables
std::vector<bool> update_vector_corrected = callback_data.update_vector_;
// Prepare the twist data for inclusion in the filter
if (prepareAcceleration(
msg, topic_name, target_frame,
update_vector_corrected, measurement,
measurement_covariance))
{
// Store the measurement. Add an "acceleration" suffix so we know what
// kind of measurement we're dealing with when we debug the core filter
// logic.
enqueueMeasurement(
topic_name, measurement, measurement_covariance,
update_vector_corrected,
callback_data.rejection_threshold_, msg->header.stamp);
RF_DEBUG(
"Enqueued new measurement for " << topic_name <<
"_acceleration\n");
} else {
RF_DEBUG(
"Did *not* enqueue measurement for " << topic_name <<
"_acceleration\n");
}
last_message_times_[topic_name] = msg->header.stamp;
RF_DEBUG(
"Last message time for " <<
topic_name << " is now " <<
filter_utilities::toSec(last_message_times_[topic_name]) <<
"\n");
} else {
// else if (reset_on_time_jump_ && rclcpp::Time::isSimTime())
//{
// reset();
//}
std::stringstream stream;
stream << "The " << topic_name << " message has a timestamp before that of "
"the previous message received," << " this message will be ignored. This may"
" indicate a bad timestamp. (message time: " << msg->header.stamp.nanosec <<
")";
addDiagnostic(
diagnostic_msgs::msg::DiagnosticStatus::WARN, topic_name +
"_timestamp", stream.str(), false);
RF_DEBUG(
"Message is too old. Last message time for " <<
topic_name << " is " <<
filter_utilities::toSec(last_message_times_[topic_name]) <<
", current message time is " <<
filter_utilities::toSec(msg->header.stamp) << ".\n");
}
RF_DEBUG(
"\n----- /RosFilter<T>::accelerationCallback (" << topic_name <<
") ------\n");
}
template<typename T>
void RosFilter<T>::controlCallback(
const geometry_msgs::msg::Twist::SharedPtr msg)
{
geometry_msgs::msg::TwistStamped::SharedPtr twist_stamped_ptr =
std::make_shared<geometry_msgs::msg::TwistStamped>();
twist_stamped_ptr->twist = *msg;
twist_stamped_ptr->header.frame_id = base_link_frame_id_;
twist_stamped_ptr->header.stamp = this->now();
controlStampedCallback(twist_stamped_ptr);
}
template<typename T>
void RosFilter<T>::controlStampedCallback(
const geometry_msgs::msg::TwistStamped::SharedPtr msg)
{
if (msg->header.frame_id == base_link_frame_id_ ||
msg->header.frame_id == "")
{
latest_control_(ControlMemberVx) = msg->twist.linear.x;
latest_control_(ControlMemberVy) = msg->twist.linear.y;
latest_control_(ControlMemberVz) = msg->twist.linear.z;
latest_control_(ControlMemberVroll) = msg->twist.angular.x;
latest_control_(ControlMemberVpitch) = msg->twist.angular.y;
latest_control_(ControlMemberVyaw) = msg->twist.angular.z;
latest_control_time_ = msg->header.stamp;
// Update the filter with this control term
filter_.setControl(latest_control_, msg->header.stamp);
} else {
// ROS_WARN_STREAM_THROTTLE(5.0, "Commanded velocities must be given in the
// robot's body frame (" << base_link_frame_id_ << "). Message frame was " <<
// msg->header.frame_id);
std::cerr <<
"Commanded velocities must be given in the robot's body frame (" <<
base_link_frame_id_ << "). Message frame was " <<
msg->header.frame_id << "\n";
}
}
template<typename T>
void RosFilter<T>::enqueueMeasurement(
const std::string & topic_name, const Eigen::VectorXd & measurement,
const Eigen::MatrixXd & measurement_covariance,
const std::vector<bool> & update_vector, const double mahalanobis_thresh,
const rclcpp::Time & time)
{
MeasurementPtr meas = MeasurementPtr(new Measurement());
meas->topic_name_ = topic_name;
meas->measurement_ = measurement;
meas->covariance_ = measurement_covariance;
meas->update_vector_ = update_vector;
meas->time_ = time;
meas->mahalanobis_thresh_ = mahalanobis_thresh;
meas->latest_control_ = latest_control_;
meas->latest_control_time_ = latest_control_time_;
measurement_queue_.push(meas);
}
template<typename T>
void RosFilter<T>::forceTwoD(
Eigen::VectorXd & measurement,
Eigen::MatrixXd & measurement_covariance,
std::vector<bool> & update_vector)
{
measurement(StateMemberZ) = 0.0;
measurement(StateMemberRoll) = 0.0;
measurement(StateMemberPitch) = 0.0;
measurement(StateMemberVz) = 0.0;
measurement(StateMemberVroll) = 0.0;
measurement(StateMemberVpitch) = 0.0;
measurement(StateMemberAz) = 0.0;
measurement_covariance(StateMemberZ, StateMemberZ) = 1e-6;
measurement_covariance(StateMemberRoll, StateMemberRoll) = 1e-6;
measurement_covariance(StateMemberPitch, StateMemberPitch) = 1e-6;
measurement_covariance(StateMemberVz, StateMemberVz) = 1e-6;
measurement_covariance(StateMemberVroll, StateMemberVroll) = 1e-6;
measurement_covariance(StateMemberVpitch, StateMemberVpitch) = 1e-6;
measurement_covariance(StateMemberAz, StateMemberAz) = 1e-6;
update_vector[StateMemberZ] = 1;
update_vector[StateMemberRoll] = 1;
update_vector[StateMemberPitch] = 1;
update_vector[StateMemberVz] = 1;
update_vector[StateMemberVroll] = 1;
update_vector[StateMemberVpitch] = 1;
update_vector[StateMemberAz] = 1;
}
template<typename T>
bool RosFilter<T>::getFilteredOdometryMessage(nav_msgs::msg::Odometry * message)
{
// If the filter has received a measurement at some point...
if (filter_.getInitializedStatus()) {
// Grab our current state and covariance estimates
const Eigen::VectorXd & state = filter_.getState();
const Eigen::MatrixXd & estimate_error_covariance =
filter_.getEstimateErrorCovariance();
// Convert from roll, pitch, and yaw back to quaternion for
// orientation values
tf2::Quaternion quat;
quat.setRPY(
state(StateMemberRoll), state(StateMemberPitch),
state(StateMemberYaw));
// Fill out the message
message->pose.pose.position.x = state(StateMemberX);
message->pose.pose.position.y = state(StateMemberY);
message->pose.pose.position.z = state(StateMemberZ);
message->pose.pose.orientation.x = quat.x();
message->pose.pose.orientation.y = quat.y();
message->pose.pose.orientation.z = quat.z();
message->pose.pose.orientation.w = quat.w();
message->twist.twist.linear.x = state(StateMemberVx);
message->twist.twist.linear.y = state(StateMemberVy);
message->twist.twist.linear.z = state(StateMemberVz);
message->twist.twist.angular.x = state(StateMemberVroll);
message->twist.twist.angular.y = state(StateMemberVpitch);
message->twist.twist.angular.z = state(StateMemberVyaw);
// Our covariance matrix layout doesn't quite match
for (size_t i = 0; i < POSE_SIZE; i++) {
for (size_t j = 0; j < POSE_SIZE; j++) {
message->pose.covariance[POSE_SIZE * i + j] =
estimate_error_covariance(i, j);
}
}
// POSE_SIZE and TWIST_SIZE are currently the same size, but we can spare a
// few cycles to be meticulous and not index a twist covariance array on the
// size of a pose covariance array
for (size_t i = 0; i < TWIST_SIZE; i++) {
for (size_t j = 0; j < TWIST_SIZE; j++) {
message->twist.covariance[TWIST_SIZE * i + j] =
estimate_error_covariance(
i + POSITION_V_OFFSET,
j + POSITION_V_OFFSET);
}
}
message->header.stamp = filter_.getLastMeasurementTime();
message->header.frame_id = world_frame_id_;
message->child_frame_id = base_link_output_frame_id_;
}
return filter_.getInitializedStatus();
}
template<typename T>
bool RosFilter<T>::getFilteredAccelMessage(
geometry_msgs::msg::AccelWithCovarianceStamped * message)
{
// If the filter has received a measurement at some point...
if (filter_.getInitializedStatus()) {
// Grab our current state and covariance estimates
const Eigen::VectorXd & state = filter_.getState();
const Eigen::MatrixXd & estimate_error_covariance =
filter_.getEstimateErrorCovariance();
//! Fill out the accel_msg
message->accel.accel.linear.x = state(StateMemberAx);
message->accel.accel.linear.y = state(StateMemberAy);
message->accel.accel.linear.z = state(StateMemberAz);
// Fill the covariance (only the left-upper matrix since we are not
// estimating the rotational accelerations arround the axes
for (size_t i = 0; i < ACCELERATION_SIZE; i++) {
for (size_t j = 0; j < ACCELERATION_SIZE; j++) {
// We use the POSE_SIZE since the accel cov matrix of ROS is 6x6
message->accel.covariance[POSE_SIZE * i + j] = estimate_error_covariance(
i + POSITION_A_OFFSET, j + POSITION_A_OFFSET);
}
}
// Fill header information
message->header.stamp = rclcpp::Time(filter_.getLastMeasurementTime());
message->header.frame_id = base_link_output_frame_id_;
}
return filter_.getInitializedStatus();
}
template<typename T>
void RosFilter<T>::imuCallback(
const sensor_msgs::msg::Imu::SharedPtr msg,
const std::string & topic_name,
const CallbackData & pose_callback_data,
const CallbackData & twist_callback_data,
const CallbackData & accel_callback_data)
{
RF_DEBUG(
"------ RosFilter<T>::imuCallback (" <<
topic_name << ") ------\n") // << "IMU message:\n" << *msg);
// If we've just reset the filter, then we want to ignore any messages
// that arrive with an older timestamp
if (last_set_pose_time_ >= msg->header.stamp) {
std::stringstream stream;
stream << "The " << topic_name << " message has a timestamp equal to or"
" before the last filter reset, " << "this message will be ignored. This may"
"indicate an empty or bad timestamp. (message time: " << msg->header.stamp.nanosec <<
")";
addDiagnostic(
diagnostic_msgs::msg::DiagnosticStatus::WARN,
topic_name + "_timestamp", stream.str(), false);
RF_DEBUG(
"Received message that preceded the most recent pose reset. "
"Ignoring...");
return;
}
// As with the odometry message, we can separate out the pose- and
// twist-related variables in the IMU message and pass them to the pose and
// twist callbacks (filters)
if (pose_callback_data.update_sum_ > 0) {
// Per the IMU message specification, if the IMU does not provide
// orientation, then its first covariance value should be set to -1, and we
// should ignore that portion of the message. robot_localization allows
// users to explicitly ignore data using its parameters, but we should also
// be compliant with message specs.
if (::fabs(msg->orientation_covariance[0] + 1) < 1e-9) {
RF_DEBUG(
"Received IMU message with -1 as its first covariance value for "
"orientation. "
"Ignoring orientation...");
} else {
// Extract the pose (orientation) data, pass it to its filter
geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr pos_ptr =
std::make_shared<geometry_msgs::msg::PoseWithCovarianceStamped>();
pos_ptr->header = msg->header;
pos_ptr->pose.pose.orientation = msg->orientation;
// Copy the covariance for roll, pitch, and yaw
for (size_t i = 0; i < ORIENTATION_SIZE; i++) {
for (size_t j = 0; j < ORIENTATION_SIZE; j++) {
pos_ptr->pose.covariance[POSE_SIZE * (i + ORIENTATION_SIZE) +
(j + ORIENTATION_SIZE)] =
msg->orientation_covariance[ORIENTATION_SIZE * i + j];
}
}
// IMU data gets handled a bit differently, since the message is ambiguous
// and has only a single frame_id, even though the data in it is reported
// in two different frames. As we assume users will specify a base_link to
// imu transform, we make the target frame base_link_frame_id_ and tell
// the poseCallback that it is working with IMU data. This will cause it
// to apply different logic to the data.
poseCallback(pos_ptr, pose_callback_data, base_link_frame_id_, true);
}
}
if (twist_callback_data.update_sum_ > 0) {
// Ignore rotational velocity if the first covariance value is -1
if (::fabs(msg->angular_velocity_covariance[0] + 1) < 1e-9) {
RF_DEBUG(
"Received IMU message with -1 as its first covariance value for "
"angular "
"velocity. Ignoring angular velocity...");
} else {
// Repeat for velocity
geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr twist_ptr =
std::make_shared<geometry_msgs::msg::TwistWithCovarianceStamped>();
twist_ptr->header = msg->header;
twist_ptr->twist.twist.angular = msg->angular_velocity;
// Copy the covariance
for (size_t i = 0; i < ORIENTATION_SIZE; i++) {
for (size_t j = 0; j < ORIENTATION_SIZE; j++) {
twist_ptr->twist.covariance[TWIST_SIZE * (i + ORIENTATION_SIZE) +
(j + ORIENTATION_SIZE)] =
msg->angular_velocity_covariance[ORIENTATION_SIZE * i + j];
}
}
twistCallback(twist_ptr, twist_callback_data, base_link_frame_id_);
}
}
if (accel_callback_data.update_sum_ > 0) {
// Ignore linear acceleration if the first covariance value is -1
if (::fabs(msg->linear_acceleration_covariance[0] + 1) < 1e-9) {
RF_DEBUG(
"Received IMU message with -1 as its first covariance value for "
"linear "
"acceleration. Ignoring linear acceleration...");
} else {
// Pass the message on
accelerationCallback(msg, accel_callback_data, base_link_frame_id_);
}
}
RF_DEBUG("\n----- /RosFilter<T>::imuCallback (" << topic_name << ") ------\n");
}
template<typename T>
void RosFilter<T>::integrateMeasurements(const rclcpp::Time & current_time)
{
RF_DEBUG(
"------ RosFilter<T>::integrateMeasurements ------\n\n"
"Integration time is " <<
std::setprecision(20) << filter_utilities::toSec(current_time) <<
"\n" <<
measurement_queue_.size() << " measurements in queue.\n");
bool predict_to_current_time = predict_to_current_time_;
// If we have any measurements in the queue, process them
if (!measurement_queue_.empty()) {
// Check if the first measurement we're going to process is older than the
// filter's last measurement. This means we have received an out-of-sequence
// message (one with an old timestamp), and we need to revert both the
// filter state and measurement queue to the first state that preceded the
// time stamp of our first measurement.
const MeasurementPtr & first_measurement = measurement_queue_.top();
int restored_measurement_count = 0;
if (smooth_lagged_data_ &&
first_measurement->time_ < filter_.getLastMeasurementTime())
{
RF_DEBUG(
"Received a measurement that was " <<
filter_utilities::toSec(
filter_.getLastMeasurementTime() -
first_measurement->time_) <<
" seconds in the past. Reverting filter state and "
"measurement queue...");
int original_count = static_cast<int>(measurement_queue_.size());
const rclcpp::Time first_measurement_time = first_measurement->time_;
const std::string first_measurement_topic =
first_measurement->topic_name_;
// revertTo may invalidate first_measurement
if (!revertTo(first_measurement_time - rclcpp::Duration(1ns))) {
RF_DEBUG(
"ERROR: history interval is too small to revert to time " <<
filter_utilities::toSec(first_measurement_time) << "\n");
// ROS_WARN_STREAM_DELAYED_THROTTLE(history_length_,
// "Received old measurement for topic " << first_measurement_topic <<
// ", but history interval is insufficiently sized. "
// "Measurement time is " << std::setprecision(20) <<
// first_measurement_time <<
// ", current time is " << current_time <<
// ", history length is " << history_length_ << ".");
restored_measurement_count = 0;
}
restored_measurement_count =
static_cast<int>(measurement_queue_.size()) - original_count;
}
while (!measurement_queue_.empty() && rclcpp::ok()) {
MeasurementPtr measurement = measurement_queue_.top();
// If we've reached a measurement that has a time later than now, it
// should wait until a future iteration. Since measurements are stored in
// a priority queue, all remaining measurements will be in the future.
if (current_time < measurement->time_) {
break;
}
measurement_queue_.pop();
// When we receive control messages, we call this directly in the control
// callback. However, we also associate a control with each sensor message
// so that we can support lagged smoothing. As we cannot guarantee that
// the new control callback will fire before a new measurement, we should
// only perform this operation if we are processing messages from the
// history. Otherwise, we may get a new measurement, store the "old"
// latest control, then receive a control, call setControl, and then
// overwrite that value with this one (i.e., with the "old" control we
// associated with the measurement).
if (use_control_ && restored_measurement_count > 0) {
filter_.setControl(
measurement->latest_control_,
measurement->latest_control_time_);
restored_measurement_count--;
}
// This will call predict and, if necessary, correct
filter_.processMeasurement(*(measurement.get()));
// Store old states and measurements if we're smoothing
if (smooth_lagged_data_) {
// Invariant still holds: measurementHistoryDeque_.back().time_ <
// measurement_queue_.top().time_
measurement_history_.push_back(measurement);
// We should only save the filter state once per unique timstamp
if (measurement_queue_.empty() ||
measurement_queue_.top()->time_ !=
filter_.getLastMeasurementTime())
{
saveFilterState(filter_);
}
}
}
} else if (filter_.getInitializedStatus()) {
// In the event that we don't get any measurements for a long time,
// we still need to continue to estimate our state. Therefore, we
// should project the state forward here.
rclcpp::Duration last_update_delta =
current_time - filter_.getLastMeasurementTime();
// If we get a large delta, then continuously predict until
if (last_update_delta >= filter_.getSensorTimeout()) {
predict_to_current_time = true;
RF_DEBUG(
"Sensor timeout! Last measurement time was " <<
filter_utilities::toSec(filter_.getLastMeasurementTime()) <<
", current time is " << filter_utilities::toSec(current_time) <<
", delta is " << filter_utilities::toSec(last_update_delta) <<
"\n");
}
} else {
RF_DEBUG("Filter not yet initialized.\n");
}
if (filter_.getInitializedStatus() && predict_to_current_time) {
rclcpp::Duration last_update_delta =
current_time - filter_.getLastMeasurementTime();
filter_.validateDelta(last_update_delta);
filter_.predict(current_time, last_update_delta);
// Update the last measurement time and last update time
filter_.setLastMeasurementTime(
filter_.getLastMeasurementTime() +
last_update_delta);
}
RF_DEBUG("\n----- /RosFilter<T>::integrateMeasurements ------\n");
}
template<typename T>
void RosFilter<T>::loadParams()
{
/* For diagnostic purposes, collect information about how many different
* sources are measuring each absolute pose variable and do not have
* differential integration enabled.
*/
std::map<StateMembers, int> abs_pose_var_counts;
abs_pose_var_counts[StateMemberX] = 0;
abs_pose_var_counts[StateMemberY] = 0;
abs_pose_var_counts[StateMemberZ] = 0;
abs_pose_var_counts[StateMemberRoll] = 0;
abs_pose_var_counts[StateMemberPitch] = 0;
abs_pose_var_counts[StateMemberYaw] = 0;
// Same for twist variables
std::map<StateMembers, int> twist_var_counts;
twist_var_counts[StateMemberVx] = 0;
twist_var_counts[StateMemberVy] = 0;
twist_var_counts[StateMemberVz] = 0;
twist_var_counts[StateMemberVroll] = 0;
twist_var_counts[StateMemberVpitch] = 0;
twist_var_counts[StateMemberVyaw] = 0;
// Determine if we'll be printing diagnostic information
print_diagnostics_ = this->declare_parameter("print_diagnostics", false);
// Check for custom gravitational acceleration value
gravitational_acceleration_ = this->declare_parameter(
"gravitational_acceleration",
gravitational_acceleration_);
// Grab the debug param. If true, the node will produce a LOT of output.
bool debug = this->declare_parameter("debug", false);
std::string debug_out_file = "robot_localization_debug.txt";
if (debug) {
try {
debug_out_file = this->declare_parameter("debug_out_file", debug_out_file);
debug_stream_.open(debug_out_file.c_str());
// Make sure we succeeded
if (debug_stream_.is_open()) {
filter_.setDebug(debug, &debug_stream_);
} else {
std::cerr <<
"RosFilter<T>::loadParams() - unable to create debug output file " <<
debug_out_file << "\n";
}
} catch (const std::exception & e) {
std::cerr <<
"RosFilter<T>::loadParams() - unable to create debug output file" <<
debug_out_file << ". Error was " << e.what() << "\n";
}
}
// These params specify the name of the robot's body frame (typically
// base_link) and odometry frame (typically odom)
map_frame_id_ = this->declare_parameter("map_frame", std::string("map"));
odom_frame_id_ = this->declare_parameter("odom_frame", std::string("odom"));
base_link_frame_id_ = this->declare_parameter(
"base_link_frame",
std::string("base_link"));
base_link_output_frame_id_ = this->declare_parameter(
"base_link_frame_output",
base_link_frame_id_);
/*
* These parameters are designed to enforce compliance with REP-105:
* http://www.ros.org/reps/rep-0105.html
* When fusing absolute position data from sensors such as GPS, the state
* estimate can undergo discrete jumps. According to REP-105, we want three
* coordinate frames: map, odom, and base_link. The map frame can have
* discontinuities, but is the frame with the most accurate position estimate
* for the robot and should not suffer from drift. The odom frame drifts over
* time, but is guaranteed to be continuous and is accurate enough for local
* planning and navigation. The base_link frame is affixed to the robot. The
* intention is that some odometry source broadcasts the odom->base_link
* transform. The localization software should broadcast map->base_link.
* However, tf does not allow multiple parents for a coordinate frame, so
* we must *compute* map->base_link, but then use the existing odom->base_link
* transform to compute *and broadcast* map->odom.
*
* The state estimation nodes in robot_localization therefore have two
* "modes." If your world_frame parameter value matches the odom_frame
* parameter value, then robot_localization will assume someone else is
* broadcasting a transform from odom_frame->base_link_frame, and it will
* compute the map_frame->odom_frame transform. Otherwise, it will simply
* compute the odom_frame->base_link_frame transform.
*
* The default is the latter behavior (broadcast of odom->base_link).
*/
world_frame_id_ = this->declare_parameter("world_frame", odom_frame_id_);
if (map_frame_id_ == odom_frame_id_ ||
odom_frame_id_ == base_link_frame_id_ ||
map_frame_id_ == base_link_frame_id_ ||
odom_frame_id_ == base_link_output_frame_id_ ||
map_frame_id_ == base_link_output_frame_id_)
{
std::cerr <<
"Invalid frame configuration! The values for map_frame, odom_frame, "
"and base_link_frame must be unique. If using a base_link_frame_output "
"values, it must not match the map_frame or odom_frame."
"\n";
}
// Try to resolve tf_prefix
std::string tf_prefix = "";
std::string tf_prefix_path = "";
try {
this->declare_parameter<std::string>("tf_prefix");
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
}
if (this->get_parameter("tf_prefix", tf_prefix_path)) {
// Append the tf prefix in a tf2-friendly manner
filter_utilities::appendPrefix(tf_prefix, map_frame_id_);
filter_utilities::appendPrefix(tf_prefix, odom_frame_id_);
filter_utilities::appendPrefix(tf_prefix, base_link_frame_id_);
filter_utilities::appendPrefix(tf_prefix, base_link_output_frame_id_);
filter_utilities::appendPrefix(tf_prefix, world_frame_id_);
}
// Whether we're publshing the world_frame->base_link_frame transform
publish_transform_ = this->declare_parameter("publish_tf", true);
// Whether we're publishing the acceleration state transform
publish_acceleration_ = this->declare_parameter("publish_acceleration", false);
// Transform future dating
double offset_tmp = this->declare_parameter("transform_time_offset", 0.0);
tf_time_offset_ = rclcpp::Duration::from_seconds(offset_tmp);
// Transform timeout
double timeout_tmp = this->declare_parameter("transform_timeout", 0.0);
tf_timeout_ = rclcpp::Duration::from_seconds(timeout_tmp);
// Update frequency and sensor timeout
frequency_ = this->declare_parameter("frequency", 30.0);
double sensor_timeout = this->declare_parameter("sensor_timeout", 1.0 / frequency_);
filter_.setSensorTimeout(rclcpp::Duration::from_seconds(sensor_timeout));
// Determine if we're in 2D mode
two_d_mode_ = this->declare_parameter("two_d_mode", false);
// Smoothing window size
smooth_lagged_data_ = this->declare_parameter("smooth_lagged_data", false);
double history_length_double = this->declare_parameter("history_length", 0.0);
if (!smooth_lagged_data_ && std::abs(history_length_double) > 0) {
std::cerr << "Filter history interval of " << history_length_double <<
" specified, but smooth_lagged_data is set to false. Lagged "
"data will not be smoothed.";
}
if (smooth_lagged_data_ && history_length_double < 0) {
std::cerr << "Negative history interval of " << history_length_double <<
" specified. Absolute value will be assumed.";
}
history_length_ = rclcpp::Duration::from_seconds(std::abs(history_length_double));
// Whether we reset filter on jump back in time
reset_on_time_jump_ = this->declare_parameter("reset_on_time_jump", false);
// Determine if we're using a control term
double control_timeout = sensor_timeout;
std::vector<bool> control_update_vector;
std::vector<double> acceleration_limits;
std::vector<double> acceleration_gains;
std::vector<double> deceleration_limits;
std::vector<double> deceleration_gains;
use_control_ = this->declare_parameter("use_control", false);
control_timeout = this->declare_parameter("control_timeout", 0.0);
if (use_control_) {
try {
this->declare_parameter<std::vector<bool>>("control_config");
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
}
if (this->get_parameter("control_config", control_update_vector)) {
if (control_update_vector.size() != TWIST_SIZE) {
std::cerr << "Control configuration must be of size " << TWIST_SIZE <<
". Provided config was of "
"size " <<
control_update_vector.size() <<
". No control term will be used.\n";
use_control_ = false;
}
} else {
std::cerr << "use_control is set to true, but control_config is missing. "
"No control term will be used.\n";
use_control_ = false;
}
try {
this->declare_parameter<std::vector<double>>("acceleration_limits");
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
}
if (this->get_parameter("acceleration_limits", acceleration_limits)) {
if (acceleration_limits.size() != TWIST_SIZE) {
std::cerr << "Acceleration configuration must be of size " << TWIST_SIZE <<
". Provided config was of "
"size " <<
acceleration_limits.size() <<
". No control term will be used.\n";
use_control_ = false;
}
} else {
std::cerr << "use_control is set to true, but acceleration_limits is "
"missing. Will use default values.\n";
acceleration_limits.resize(TWIST_SIZE, 1.0);
}
try {
this->declare_parameter<std::vector<double>>("acceleration_gains");
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
}
if (this->get_parameter("acceleration_gains", acceleration_gains)) {
const int size = acceleration_gains.size();
if (size != TWIST_SIZE) {
std::cerr << "Acceleration gain configuration must be of size " <<
TWIST_SIZE << ". Provided config was of size " << size <<
". All gains will be assumed to be 1.\n";
std::fill_n(
acceleration_gains.begin(), std::min(size, TWIST_SIZE),
1.0);
acceleration_gains.resize(TWIST_SIZE, 1.0);
}
}
try {
this->declare_parameter<std::vector<double>>("deceleration_limits");
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
}
if (this->get_parameter("deceleration_limits", deceleration_limits)) {
if (deceleration_limits.size() != TWIST_SIZE) {
std::cerr << "Deceleration configuration must be of size " << TWIST_SIZE <<
". Provided config was of size " <<
deceleration_limits.size() <<
". No control term will be used.\n";
use_control_ = false;
}
} else {
std::cout << "use_control is set to true, but no deceleration_limits "
"specified. Will use acceleration "
"limits.\n";
deceleration_limits = acceleration_limits;
}
try {
this->declare_parameter<std::vector<double>>("deceleration_gains");
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
}
if (this->get_parameter("deceleration_gains", deceleration_gains)) {
const int size = deceleration_gains.size();
if (size != TWIST_SIZE) {
std::cerr << "Deceleration gain configuration must be of size " <<
TWIST_SIZE << ". Provided config was of size " << size <<
". All gains will be assumed to be 1.\n";
std::fill_n(
deceleration_gains.begin(), std::min(size, TWIST_SIZE),
1.0);
deceleration_gains.resize(TWIST_SIZE, 1.0);
}
} else {
std::cout << "use_control is set to true, but no deceleration_gains "
"specified. Will use acceleration "
"gains.\n";
deceleration_gains = acceleration_gains;
}
} else {
control_update_vector.resize(TWIST_SIZE, 0);
acceleration_limits.resize(TWIST_SIZE, 1.0);
acceleration_gains.resize(TWIST_SIZE, 1.0);
deceleration_limits.resize(TWIST_SIZE, 1.0);
deceleration_gains.resize(TWIST_SIZE, 1.0);
}
bool dynamic_process_noise_covariance = this->declare_parameter(
"dynamic_process_noise_covariance", false);
filter_.setUseDynamicProcessNoiseCovariance(
dynamic_process_noise_covariance);
std::vector<double> initial_state;
try {
this->declare_parameter<std::vector<double>>("initial_state");
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
}
if (this->get_parameter("initial_state", initial_state)) {
if (initial_state.size() != STATE_SIZE) {