Skip to content

Commit d7b870f

Browse files
Cherry picked commits to make galactic release build (#667)
* Add missing message_filters dependency (#666) Headers from message_filters are included here: https://github.com/cra-ros-pkg/robot_localization/blob/67098c2341b5d1ccbcceb8eede60e79db74814a6/include/robot_localization/ros_robot_localization_listener.h\#L41-L42 Signed-off-by: Jacob Perron <[email protected]> * Remove try-catch blocks around declare_parameter (#663) Try-catches were added in #631 due to a new rclcpp feature enforcing static parameter. The behavior was later patched for this particular use-case in ros2/rclcpp#1673, so now we can avoid having to try-catch. Signed-off-by: Jacob Perron <[email protected]> Co-authored-by: Jacob Perron <[email protected]>
1 parent 06ea65b commit d7b870f

File tree

3 files changed

+16
-52
lines changed

3 files changed

+16
-52
lines changed

CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@ find_package(diagnostic_msgs REQUIRED)
2020
find_package(diagnostic_updater REQUIRED)
2121
find_package(geographic_msgs REQUIRED)
2222
find_package(geometry_msgs REQUIRED)
23+
find_package(message_filters REQUIRED)
2324
find_package(nav_msgs REQUIRED)
2425
find_package(rosidl_default_generators REQUIRED)
2526
find_package(sensor_msgs REQUIRED)
@@ -107,6 +108,7 @@ ament_target_dependencies(
107108
diagnostic_updater
108109
geographic_msgs
109110
geometry_msgs
111+
message_filters
110112
nav_msgs
111113
rclcpp
112114
sensor_msgs

package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@
2626
<depend>diagnostic_msgs</depend>
2727
<depend>diagnostic_updater</depend>
2828
<depend>geographiclib</depend>
29+
<depend>message_filters</depend>
2930
<depend>nav_msgs</depend>
3031
<build_depend>rclcpp</build_depend>
3132
<build_depend>rmw_implementation</build_depend>

src/ros_filter.cpp

Lines changed: 13 additions & 52 deletions
Original file line numberDiff line numberDiff line change
@@ -819,10 +819,7 @@ void RosFilter<T>::loadParams()
819819
// Try to resolve tf_prefix
820820
std::string tf_prefix = "";
821821
std::string tf_prefix_path = "";
822-
try {
823-
this->declare_parameter<std::string>("tf_prefix");
824-
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
825-
}
822+
this->declare_parameter<std::string>("tf_prefix");
826823
if (this->get_parameter("tf_prefix", tf_prefix_path)) {
827824
// Append the tf prefix in a tf2-friendly manner
828825
filter_utilities::appendPrefix(tf_prefix, map_frame_id_);
@@ -890,10 +887,7 @@ void RosFilter<T>::loadParams()
890887
control_timeout = this->declare_parameter("control_timeout", 0.0);
891888

892889
if (use_control_) {
893-
try {
894-
this->declare_parameter<std::vector<bool>>("control_config");
895-
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
896-
}
890+
this->declare_parameter<std::vector<bool>>("control_config");
897891
if (this->get_parameter("control_config", control_update_vector)) {
898892
if (control_update_vector.size() != TWIST_SIZE) {
899893
std::cerr << "Control configuration must be of size " << TWIST_SIZE <<
@@ -909,10 +903,7 @@ void RosFilter<T>::loadParams()
909903
use_control_ = false;
910904
}
911905

912-
try {
913-
this->declare_parameter<std::vector<double>>("acceleration_limits");
914-
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
915-
}
906+
this->declare_parameter<std::vector<double>>("acceleration_limits");
916907
if (this->get_parameter("acceleration_limits", acceleration_limits)) {
917908
if (acceleration_limits.size() != TWIST_SIZE) {
918909
std::cerr << "Acceleration configuration must be of size " << TWIST_SIZE <<
@@ -928,10 +919,7 @@ void RosFilter<T>::loadParams()
928919
acceleration_limits.resize(TWIST_SIZE, 1.0);
929920
}
930921

931-
try {
932-
this->declare_parameter<std::vector<double>>("acceleration_gains");
933-
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
934-
}
922+
this->declare_parameter<std::vector<double>>("acceleration_gains");
935923
if (this->get_parameter("acceleration_gains", acceleration_gains)) {
936924
const int size = acceleration_gains.size();
937925
if (size != TWIST_SIZE) {
@@ -945,10 +933,7 @@ void RosFilter<T>::loadParams()
945933
}
946934
}
947935

948-
try {
949-
this->declare_parameter<std::vector<double>>("deceleration_limits");
950-
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
951-
}
936+
this->declare_parameter<std::vector<double>>("deceleration_limits");
952937
if (this->get_parameter("deceleration_limits", deceleration_limits)) {
953938
if (deceleration_limits.size() != TWIST_SIZE) {
954939
std::cerr << "Deceleration configuration must be of size " << TWIST_SIZE <<
@@ -964,10 +949,7 @@ void RosFilter<T>::loadParams()
964949
deceleration_limits = acceleration_limits;
965950
}
966951

967-
try {
968-
this->declare_parameter<std::vector<double>>("deceleration_gains");
969-
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
970-
}
952+
this->declare_parameter<std::vector<double>>("deceleration_gains");
971953
if (this->get_parameter("deceleration_gains", deceleration_gains)) {
972954
const int size = deceleration_gains.size();
973955
if (size != TWIST_SIZE) {
@@ -999,10 +981,7 @@ void RosFilter<T>::loadParams()
999981
dynamic_process_noise_covariance);
1000982

1001983
std::vector<double> initial_state;
1002-
try {
1003-
this->declare_parameter<std::vector<double>>("initial_state");
1004-
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
1005-
}
984+
this->declare_parameter<std::vector<double>>("initial_state");
1006985
if (this->get_parameter("initial_state", initial_state)) {
1007986
if (initial_state.size() != STATE_SIZE) {
1008987
std::cerr << "Initial state must be of size " << STATE_SIZE <<
@@ -1091,10 +1070,7 @@ void RosFilter<T>::loadParams()
10911070
ss << "odom" << topic_ind++;
10921071
std::string odom_topic_name = ss.str();
10931072
std::string odom_topic;
1094-
try {
1095-
this->declare_parameter<std::string>(odom_topic_name);
1096-
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
1097-
}
1073+
this->declare_parameter<std::string>(odom_topic_name);
10981074

10991075
rclcpp::Parameter parameter;
11001076
if (this->get_parameter(odom_topic_name, parameter)) {
@@ -1244,10 +1220,7 @@ void RosFilter<T>::loadParams()
12441220
ss << "pose" << topic_ind++;
12451221
std::string pose_topic_name = ss.str();
12461222
std::string pose_topic;
1247-
try {
1248-
this->declare_parameter<std::string>(pose_topic_name);
1249-
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
1250-
}
1223+
this->declare_parameter<std::string>(pose_topic_name);
12511224

12521225
rclcpp::Parameter parameter;
12531226
if (this->get_parameter(pose_topic_name, parameter)) {
@@ -1364,10 +1337,7 @@ void RosFilter<T>::loadParams()
13641337
ss << "twist" << topic_ind++;
13651338
std::string twist_topic_name = ss.str();
13661339
std::string twist_topic;
1367-
try {
1368-
this->declare_parameter<std::string>(twist_topic_name);
1369-
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
1370-
}
1340+
this->declare_parameter<std::string>(twist_topic_name);
13711341

13721342
rclcpp::Parameter parameter;
13731343
if (this->get_parameter(twist_topic_name, parameter)) {
@@ -1448,10 +1418,7 @@ void RosFilter<T>::loadParams()
14481418
ss << "imu" << topic_ind++;
14491419
std::string imu_topic_name = ss.str();
14501420
std::string imu_topic;
1451-
try {
1452-
this->declare_parameter<std::string>(imu_topic_name);
1453-
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
1454-
}
1421+
this->declare_parameter<std::string>(imu_topic_name);
14551422

14561423
rclcpp::Parameter parameter;
14571424
if (this->get_parameter(imu_topic_name, parameter)) {
@@ -1760,10 +1727,7 @@ void RosFilter<T>::loadParams()
17601727
process_noise_covariance.setZero();
17611728
std::vector<double> process_noise_covar_flat;
17621729

1763-
try {
1764-
this->declare_parameter<std::vector<double>>("process_noise_covariance");
1765-
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
1766-
}
1730+
this->declare_parameter<std::vector<double>>("process_noise_covariance");
17671731
if (this->get_parameter(
17681732
"process_noise_covariance",
17691733
process_noise_covar_flat))
@@ -1790,10 +1754,7 @@ void RosFilter<T>::loadParams()
17901754
initial_estimate_error_covariance.setZero();
17911755
std::vector<double> estimate_error_covar_flat;
17921756

1793-
try {
1794-
this->declare_parameter<std::vector<double>>("initial_estimate_covariance");
1795-
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
1796-
}
1757+
this->declare_parameter<std::vector<double>>("initial_estimate_covariance");
17971758
if (this->get_parameter(
17981759
"initial_estimate_covariance",
17991760
estimate_error_covar_flat))

0 commit comments

Comments
 (0)