Skip to content

Commit

Permalink
Cherry picked commits to make galactic release build (#667)
Browse files Browse the repository at this point in the history
* 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 <jacob@openrobotics.org>

* 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 <jacob@openrobotics.org>

Co-authored-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
SteveMacenski and jacobperron committed May 24, 2021
1 parent 06ea65b commit d7b870f
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 52 deletions.
2 changes: 2 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ find_package(diagnostic_msgs REQUIRED)
find_package(diagnostic_updater REQUIRED)
find_package(geographic_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(message_filters REQUIRED)
find_package(nav_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(sensor_msgs REQUIRED)
Expand Down Expand Up @@ -107,6 +108,7 @@ ament_target_dependencies(
diagnostic_updater
geographic_msgs
geometry_msgs
message_filters
nav_msgs
rclcpp
sensor_msgs
Expand Down
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
<depend>diagnostic_msgs</depend>
<depend>diagnostic_updater</depend>
<depend>geographiclib</depend>
<depend>message_filters</depend>
<depend>nav_msgs</depend>
<build_depend>rclcpp</build_depend>
<build_depend>rmw_implementation</build_depend>
Expand Down
65 changes: 13 additions & 52 deletions src/ros_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -819,10 +819,7 @@ void RosFilter<T>::loadParams()
// 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 &) {
}
this->declare_parameter<std::string>("tf_prefix");
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_);
Expand Down Expand Up @@ -890,10 +887,7 @@ void RosFilter<T>::loadParams()
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 &) {
}
this->declare_parameter<std::vector<bool>>("control_config");
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 <<
Expand All @@ -909,10 +903,7 @@ void RosFilter<T>::loadParams()
use_control_ = false;
}

try {
this->declare_parameter<std::vector<double>>("acceleration_limits");
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
}
this->declare_parameter<std::vector<double>>("acceleration_limits");
if (this->get_parameter("acceleration_limits", acceleration_limits)) {
if (acceleration_limits.size() != TWIST_SIZE) {
std::cerr << "Acceleration configuration must be of size " << TWIST_SIZE <<
Expand All @@ -928,10 +919,7 @@ void RosFilter<T>::loadParams()
acceleration_limits.resize(TWIST_SIZE, 1.0);
}

try {
this->declare_parameter<std::vector<double>>("acceleration_gains");
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
}
this->declare_parameter<std::vector<double>>("acceleration_gains");
if (this->get_parameter("acceleration_gains", acceleration_gains)) {
const int size = acceleration_gains.size();
if (size != TWIST_SIZE) {
Expand All @@ -945,10 +933,7 @@ void RosFilter<T>::loadParams()
}
}

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

try {
this->declare_parameter<std::vector<double>>("deceleration_gains");
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
}
this->declare_parameter<std::vector<double>>("deceleration_gains");
if (this->get_parameter("deceleration_gains", deceleration_gains)) {
const int size = deceleration_gains.size();
if (size != TWIST_SIZE) {
Expand Down Expand Up @@ -999,10 +981,7 @@ void RosFilter<T>::loadParams()
dynamic_process_noise_covariance);

std::vector<double> initial_state;
try {
this->declare_parameter<std::vector<double>>("initial_state");
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
}
this->declare_parameter<std::vector<double>>("initial_state");
if (this->get_parameter("initial_state", initial_state)) {
if (initial_state.size() != STATE_SIZE) {
std::cerr << "Initial state must be of size " << STATE_SIZE <<
Expand Down Expand Up @@ -1091,10 +1070,7 @@ void RosFilter<T>::loadParams()
ss << "odom" << topic_ind++;
std::string odom_topic_name = ss.str();
std::string odom_topic;
try {
this->declare_parameter<std::string>(odom_topic_name);
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
}
this->declare_parameter<std::string>(odom_topic_name);

rclcpp::Parameter parameter;
if (this->get_parameter(odom_topic_name, parameter)) {
Expand Down Expand Up @@ -1244,10 +1220,7 @@ void RosFilter<T>::loadParams()
ss << "pose" << topic_ind++;
std::string pose_topic_name = ss.str();
std::string pose_topic;
try {
this->declare_parameter<std::string>(pose_topic_name);
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
}
this->declare_parameter<std::string>(pose_topic_name);

rclcpp::Parameter parameter;
if (this->get_parameter(pose_topic_name, parameter)) {
Expand Down Expand Up @@ -1364,10 +1337,7 @@ void RosFilter<T>::loadParams()
ss << "twist" << topic_ind++;
std::string twist_topic_name = ss.str();
std::string twist_topic;
try {
this->declare_parameter<std::string>(twist_topic_name);
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
}
this->declare_parameter<std::string>(twist_topic_name);

rclcpp::Parameter parameter;
if (this->get_parameter(twist_topic_name, parameter)) {
Expand Down Expand Up @@ -1448,10 +1418,7 @@ void RosFilter<T>::loadParams()
ss << "imu" << topic_ind++;
std::string imu_topic_name = ss.str();
std::string imu_topic;
try {
this->declare_parameter<std::string>(imu_topic_name);
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
}
this->declare_parameter<std::string>(imu_topic_name);

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

try {
this->declare_parameter<std::vector<double>>("process_noise_covariance");
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
}
this->declare_parameter<std::vector<double>>("process_noise_covariance");
if (this->get_parameter(
"process_noise_covariance",
process_noise_covar_flat))
Expand All @@ -1790,10 +1754,7 @@ void RosFilter<T>::loadParams()
initial_estimate_error_covariance.setZero();
std::vector<double> estimate_error_covar_flat;

try {
this->declare_parameter<std::vector<double>>("initial_estimate_covariance");
} catch (const rclcpp::exceptions::NoParameterOverrideProvided &) {
}
this->declare_parameter<std::vector<double>>("initial_estimate_covariance");
if (this->get_parameter(
"initial_estimate_covariance",
estimate_error_covar_flat))
Expand Down

0 comments on commit d7b870f

Please sign in to comment.