Skip to content

Commit

Permalink
Fix some warnings on GCC13/Ubuntu 24.04 (ros-navigation#4265)
Browse files Browse the repository at this point in the history
* nav_2d_utils: use get_parameter without default value

the original prototype construct a Parameter from the &parameter
references. Our value is unassigned, which caused a warning.
fix ‘value’ may be used uninitialized warning on gcc13.

Signed-off-by: Chuanhong Guo <gch981213@gmail.com>

* nav2_behaviors: use get_parameter without default value

the two-parameter version of get_parameter constructs a
Parameter from the &parameter references. Our value is
unassigned, which caused a warning.
fix 'may be used uninitialized' warning on gcc13.

Signed-off-by: Chuanhong Guo <gch981213@gmail.com>

* waypoint_follower: use get_parameter without default value

the two-parameter version of get_parameter constructs a
Parameter from the &parameter references. Our value is
unassigned, which caused a warning.
fix 'may be used uninitialized' warning on gcc13.

Signed-off-by: Chuanhong Guo <gch981213@gmail.com>

* nav2_behavior_tree: use get_parameter without default value

the two-parameter version of get_parameter constructs a
Parameter from the &parameter references. Our value is
unassigned, which caused a warning.
fix 'may be used uninitialized' warning on gcc13.

Signed-off-by: Chuanhong Guo <gch981213@gmail.com>

* constrained_smoother: initialize prelast_dir in upsampleAndPopulate

It's technically not needed but GCC can't figure this out and
complains.

Signed-off-by: Chuanhong Guo <gch981213@gmail.com>

* waypoint_follower: fix warns about null pointer dereferencing

gcc13 warns that get_current_goal() may be nullptr and doesn't
allow the assignment of it to poses:
error: potential null pointer dereference [-Werror=null-dereference]

Check the pointer before using it.

Signed-off-by: Chuanhong Guo <gch981213@gmail.com>

* Update nav2_waypoint_follower/src/waypoint_follower.cpp

Signed-off-by: Steve Macenski <stevenmacenski@gmail.com>

---------

Signed-off-by: Chuanhong Guo <gch981213@gmail.com>
Signed-off-by: Steve Macenski <stevenmacenski@gmail.com>
Co-authored-by: Steve Macenski <stevenmacenski@gmail.com>
  • Loading branch information
981213 and SteveMacenski authored Apr 24, 2024
1 parent f856384 commit fbec0fa
Show file tree
Hide file tree
Showing 6 changed files with 15 additions and 12 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -144,8 +144,8 @@ bool BtActionServer<ActionT>::on_configure()
rclcpp::copy_all_parameter_values(node, client_node_);

// set the timeout in seconds for the action server to discard goal handles if not finished
double action_server_result_timeout;
node->get_parameter("action_server_result_timeout", action_server_result_timeout);
double action_server_result_timeout =
node->get_parameter("action_server_result_timeout").as_double();
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);

Expand Down
2 changes: 1 addition & 1 deletion nav2_behaviors/src/behavior_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,8 +147,8 @@ void BehaviorServer::setupResourcesForBehaviorPlugins()
get_parameter("global_costmap_topic", global_costmap_topic);
get_parameter("local_footprint_topic", local_footprint_topic);
get_parameter("global_footprint_topic", global_footprint_topic);
get_parameter("transform_tolerance", transform_tolerance);
get_parameter("robot_base_frame", robot_base_frame);
transform_tolerance = get_parameter("transform_tolerance").as_double();

bool need_local_costmap = false;
bool need_global_costmap = false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -293,7 +293,7 @@ class Smoother
}
int last_i = 0;
int prelast_i = -1;
Eigen::Vector2d prelast_dir;
Eigen::Vector2d prelast_dir = {0, 0};
for (int i = 1; i <= static_cast<int>(path_optim.size()); i++) {
if (i == static_cast<int>(path_optim.size()) || optimized[i]) {
if (prelast_i != -1) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,12 +64,10 @@ param_t searchAndGetParam(
const nav2_util::LifecycleNode::SharedPtr & nh, const std::string & param_name,
const param_t & default_value)
{
param_t value;
nav2_util::declare_parameter_if_not_declared(
nh, param_name,
rclcpp::ParameterValue(default_value));
nh->get_parameter(param_name, value);
return value;
return nh->get_parameter(param_name).get_value<param_t>();
}

} // namespace nav_2d_utils
Expand Down
2 changes: 1 addition & 1 deletion nav2_waypoint_follower/plugins/input_at_waypoint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ void InputAtWaypoint::initialize(
nav2_util::declare_parameter_if_not_declared(
node, plugin_name + ".input_topic",
rclcpp::ParameterValue("input_at_waypoint/input"));
node->get_parameter(plugin_name + ".timeout", timeout);
timeout = node->get_parameter(plugin_name + ".timeout").as_double();
node->get_parameter(plugin_name + ".enabled", is_enabled_);
node->get_parameter(plugin_name + ".input_topic", input_topic);

Expand Down
13 changes: 9 additions & 4 deletions nav2_waypoint_follower/src/waypoint_follower.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,8 +78,7 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & /*state*/)
get_node_waitables_interface(),
"navigate_to_pose", callback_group_);

double action_server_result_timeout;
get_parameter("action_server_result_timeout", action_server_result_timeout);
double action_server_result_timeout = get_parameter("action_server_result_timeout").as_double();
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);

Expand Down Expand Up @@ -187,15 +186,21 @@ std::vector<geometry_msgs::msg::PoseStamped> WaypointFollower::getLatestGoalPose
const T & action_server)
{
std::vector<geometry_msgs::msg::PoseStamped> poses;
const auto current_goal = action_server->get_current_goal();

if (!current_goal) {
RCLCPP_ERROR(get_logger(), "No current action goal found!");
return poses;
}

// compile time static check to decide which block of code to be built
if constexpr (std::is_same<T, std::unique_ptr<ActionServer>>::value) {
// If normal waypoint following callback was called, we build here
poses = action_server->get_current_goal()->poses;
poses = current_goal->poses;
} else {
// If GPS waypoint following callback was called, we build here
poses = convertGPSPosesToMapPoses(
action_server->get_current_goal()->gps_poses);
current_goal->gps_poses);
}
return poses;
}
Expand Down

0 comments on commit fbec0fa

Please sign in to comment.