Skip to content

Commit 3c93104

Browse files
mabelzhangayrton04SteveMacenskiokalachev
committed
Port to Dashing: melodic-devel 2.5.1 to 2.6.2 (#526)
* Fixing issue with potential seg fault (cherry picked from commit a426d7d) * adding log statements for nans in the invertable matrix (cherry picked from commit 627ff2a) * redefining error in ros filter for ros logging (cherry picked from commit 327e3fd) * swap validateFilterOutput logic and 1 line (cherry picked from commit b0964de) * Add published accel topic to documentation (cherry picked from commit 8c992fa) * template for toggle service (cherry picked from commit a1ce8fc) * functionize repetative clearing (cherry picked from commit a86fa92) * add service message (cherry picked from commit 3656917) * fix compiler errors * adding service caller information in rosout (cherry picked from commit 8b743cc) * snake -> camel (cherry picked from commit 62c3336) * adding time reset to the toggle off mode to prevent covariance explosion (cherry picked from commit 91ad1c2) * check that filter_ is valid before setting a time (cherry picked from commit abd26ad) * Adding more output for measurement history failures (cherry picked from commit f4e60a9) * Updating comment and output (cherry picked from commit 33f9c89) * Fixing tests (cherry picked from commit c492276) * Fixing CMakeLists (cherry picked from commit 6dbbf3e) * correct CMakeLists merge error; fix warnings; linters * fix RLE/RLL tests Co-authored-by: Tom Moore <[email protected]> Co-authored-by: Steven Macenski <[email protected]> Co-authored-by: Oleg Kalachev <[email protected]>
1 parent 8edc978 commit 3c93104

10 files changed

+209
-58
lines changed

CMakeLists.txt

Lines changed: 20 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -25,14 +25,17 @@ find_package(tf2_eigen REQUIRED)
2525
find_package(tf2_geometry_msgs REQUIRED)
2626
find_package(tf2_ros REQUIRED)
2727
find_package(Eigen3 REQUIRED)
28-
find_package(yaml-cpp REQUIRED)
28+
29+
find_package(PkgConfig REQUIRED)
30+
pkg_check_modules(YAML_CPP yaml-cpp)
2931

3032
set(library_name rl_lib)
3133

3234
rosidl_generate_interfaces(${PROJECT_NAME}
3335
"srv/GetState.srv"
3436
"srv/SetDatum.srv"
3537
"srv/SetPose.srv"
38+
"srv/ToggleFilterProcessing.srv"
3639
DEPENDENCIES
3740
builtin_interfaces
3841
geometry_msgs
@@ -85,7 +88,7 @@ add_executable(
8588
target_link_libraries(
8689
${library_name}
8790
${EIGEN3_LIBRARIES}
88-
yaml-cpp
91+
${YAML_CPP_LIBRARIES}
8992
)
9093

9194
ament_target_dependencies(
@@ -221,17 +224,28 @@ if(BUILD_TESTING)
221224
# target_link_libraries(test_ukf_localization_node_bag3 ${library_name})
222225

223226
#### RLE/RLL TESTS #####
224-
ament_add_gtest(test_robot_localization_estimator
227+
ament_add_gtest_executable(test_robot_localization_estimator
225228
test/test_robot_localization_estimator.cpp)
226229
target_link_libraries(test_robot_localization_estimator ${library_name})
230+
ament_add_test(test_robot_localization_estimator
231+
GENERATE_RESULT_FOR_RETURN_CODE_ZERO
232+
TIMEOUT 100
233+
COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test/test_robot_localization_estimator.launch.py"
234+
WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}"
235+
)
227236

228-
ament_add_gtest(test_ros_robot_localization_listener
237+
ament_add_gtest_executable(test_ros_robot_localization_listener
229238
test/test_ros_robot_localization_listener.cpp)
230239
target_link_libraries(test_ros_robot_localization_listener ${library_name})
231-
232-
ament_add_gtest(test_ros_robot_localization_listener_publisher
240+
ament_add_gtest_executable(test_ros_robot_localization_listener_publisher
233241
test/test_ros_robot_localization_listener_publisher.cpp)
234242
target_link_libraries(test_ros_robot_localization_listener_publisher ${library_name})
243+
ament_add_test(test_ros_robot_localization_listener
244+
GENERATE_RESULT_FOR_RETURN_CODE_ZERO
245+
TIMEOUT 100
246+
COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test/test_ros_robot_localization_listener.launch.py"
247+
WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}"
248+
)
235249

236250
ament_cppcheck(LANGUAGE "c++")
237251
ament_cpplint()

doc/state_estimation_nodes.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -305,6 +305,7 @@ Published Topics
305305
================
306306

307307
* ``odometry/filtered`` (`nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_)
308+
* ``accel/filtered`` (`geometry_msgs/AccelWithCovarianceStamped <http://docs.ros.org/api/geometry_msgs/html/msg/AccelWithCovarianceStamped.html>`_) (if enabled)
308309

309310
Published Transforms
310311
====================

include/robot_localization/robot_localization_estimator.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -211,7 +211,7 @@ class RobotLocalizationEstimator
211211
//!
212212
void interpolate(
213213
const EstimatorState & given_state_1,
214-
const EstimatorState & given_state_2,
214+
const EstimatorState & /*given_state_2*/,
215215
const double requested_time, EstimatorState & state_at_req_time) const;
216216

217217
//!

include/robot_localization/ros_filter.hpp

Lines changed: 38 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@
3434
#define ROBOT_LOCALIZATION__ROS_FILTER_HPP_
3535

3636
#include <robot_localization/srv/set_pose.hpp>
37+
#include <robot_localization/srv/toggle_filter_processing.hpp>
3738

3839
#include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
3940
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
@@ -116,6 +117,19 @@ class RosFilter : public rclcpp::Node
116117
//!
117118
void reset();
118119

120+
//! @brief Service callback to toggle processing measurements for a standby
121+
//! mode but continuing to publish
122+
//! @param[in] request - The state requested, on (True) or off (False)
123+
//! @param[out] response - status if upon success
124+
//! @return boolean true if successful, false if not
125+
//!
126+
void toggleFilterProcessingCallback(
127+
const std::shared_ptr<rmw_request_id_t>/*request_header*/,
128+
const std::shared_ptr<
129+
robot_localization::srv::ToggleFilterProcessing::Request> req,
130+
const std::shared_ptr<
131+
robot_localization::srv::ToggleFilterProcessing::Response> resp);
132+
119133
//! @brief Callback method for receiving all acceleration (IMU) messages
120134
//! @param[in] msg - The ROS IMU message to take in.
121135
//! @param[in] callback_data - Relevant static callback data
@@ -301,6 +315,12 @@ class RosFilter : public rclcpp::Node
301315
const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg,
302316
const CallbackData & callback_data, const std::string & target_frame);
303317

318+
//! @brief Validates filter outputs for NaNs and Infinite values
319+
//! @param[out] message - The standard ROS odometry message to be validated
320+
//! @return true if the filter output is valid, false otherwise
321+
//!
322+
bool validateFilterOutput(const nav_msgs::msg::Odometry & message);
323+
304324
protected:
305325
//! @brief Finds the latest filter state before the given timestamp and makes
306326
//! it the current state again.
@@ -329,6 +349,10 @@ class RosFilter : public rclcpp::Node
329349
//!
330350
void clearExpiredHistory(const rclcpp::Time cutoff_time);
331351

352+
//! @brief Clears measurement queue
353+
//!
354+
void clearMeasurementQueue();
355+
332356
//! @brief Adds a diagnostic message to the accumulating map and updates the
333357
//! error level
334358
//! @param[in] error_level - The error level of the diagnostic
@@ -475,10 +499,9 @@ class RosFilter : public rclcpp::Node
475499
//!
476500
bool smooth_lagged_data_;
477501

478-
//! @brief Service that allows another node to enable the filter. Uses a
479-
//! standard Empty service.
502+
//! @brief Whether the filter should process new measurements or not.
480503
//!
481-
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr enable_filter_srv_;
504+
bool toggled_on_;
482505

483506
//! @brief Whether or not we're in 2D mode
484507
//!
@@ -679,6 +702,13 @@ class RosFilter : public rclcpp::Node
679702
//!
680703
rclcpp::Duration tf_time_offset_;
681704

705+
//! @brief Service that allows another node to toggle on/off filter
706+
//! processing while still publishing.
707+
//! Uses a robot_localization ToggleFilterProcessing service.
708+
//!
709+
rclcpp::Service<robot_localization::srv::ToggleFilterProcessing>::SharedPtr
710+
toggle_filter_processing_srv_;
711+
682712
//! @brief Subscribes to the control input topic
683713
//!
684714
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr control_sub_;
@@ -695,6 +725,11 @@ class RosFilter : public rclcpp::Node
695725
rclcpp::Service<robot_localization::srv::SetPose>::SharedPtr
696726
set_pose_service_;
697727

728+
//! @brief Service that allows another node to enable the filter. Uses a
729+
//! standard Empty service.
730+
//!
731+
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr enable_filter_srv_;
732+
698733
//! @brief Transform buffer for managing coordinate transforms
699734
//!
700735
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;

src/robot_localization_estimator.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -190,7 +190,7 @@ void RobotLocalizationEstimator::extrapolate(
190190

191191
void RobotLocalizationEstimator::interpolate(
192192
const EstimatorState & given_state_1,
193-
const EstimatorState & given_state_2,
193+
const EstimatorState & /*given_state_2*/,
194194
const double requested_time,
195195
EstimatorState & state_at_req_time) const
196196
{

0 commit comments

Comments
 (0)