Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
18 changes: 9 additions & 9 deletions nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ amcl:
sigma_hit: 0.2
tf_broadcast: true
transform_tolerance: 1.0
service_introspection_mode: "disabled"
introspection_mode: "disabled"
update_min_a: 0.2
update_min_d: 0.25
z_hit: 0.5
Expand All @@ -48,7 +48,7 @@ bt_navigator:
filter_duration: 0.3
default_server_timeout: 20
wait_for_service_timeout: 1000
service_introspection_mode: "disabled"
introspection_mode: "disabled"
navigators: ["navigate_to_pose", "navigate_through_poses"]
navigate_to_pose:
plugin: "nav2_bt_navigator::NavigateToPoseNavigator"
Expand Down Expand Up @@ -265,7 +265,7 @@ local_costmap:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True
always_send_full_costmap: True
service_introspection_mode: "disabled"
introspection_mode: "disabled"

global_costmap:
global_costmap:
Expand Down Expand Up @@ -318,15 +318,15 @@ global_costmap:
cost_scaling_factor: 3.0
inflation_radius: 0.7
always_send_full_costmap: True
service_introspection_mode: "disabled"
introspection_mode: "disabled"

# The yaml_filename does not need to be specified since it going to be set by defaults in launch.
# If you'd rather set it in the yaml, remove the default "map" value in the launch file(s).
# file & provide full path to map below. If CLI map configuration or launch default is provided, that will be used.
map_server:
ros__parameters:
# yaml_filename: ""
service_introspection_mode: "disabled"
introspection_mode: "disabled"

keepout_filter_mask_server:
ros__parameters:
Expand Down Expand Up @@ -360,14 +360,14 @@ map_saver:
free_thresh_default: 0.25
occupied_thresh_default: 0.65
map_subscribe_transient_local: True
service_introspection_mode: "disabled"
introspection_mode: "disabled"

planner_server:
ros__parameters:
expected_planner_frequency: 20.0
planner_plugins: ["GridBased"]
costmap_update_timeout: 1.0
service_introspection_mode: "disabled"
introspection_mode: "disabled"
GridBased:
plugin: "nav2_navfn_planner::NavfnPlanner"
tolerance: 0.5
Expand Down Expand Up @@ -432,7 +432,7 @@ waypoint_follower:
ros__parameters:
loop_rate: 20
stop_on_failure: false
service_introspection_mode: "disabled"
introspection_mode: "disabled"
waypoint_task_executor_plugin: "wait_at_waypoint"
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
Expand Down Expand Up @@ -519,7 +519,7 @@ docking_server:
base_frame: "base_link"
fixed_frame: "odom"
dock_prestaging_tolerance: 0.5
service_introspection_mode: "disabled"
introspection_mode: "disabled"

# Types of docks
dock_plugins: ["simple_charging_dock"]
Expand Down
12 changes: 6 additions & 6 deletions nav2_ros_common/include/nav2_ros_common/node_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -358,15 +358,15 @@ inline void setIntrospectionMode(
{
#if RCLCPP_VERSION_GTE(29, 0, 0)
rcl_service_introspection_state_t introspection_state = RCL_SERVICE_INTROSPECTION_OFF;
if (!node_parameters_interface->has_parameter("service_introspection_mode")) {
if (!node_parameters_interface->has_parameter("introspection_mode")) {
node_parameters_interface->declare_parameter(
"service_introspection_mode", rclcpp::ParameterValue("disabled"));
"introspection_mode", rclcpp::ParameterValue("disabled"));
}
std::string service_introspection_mode =
node_parameters_interface->get_parameter("service_introspection_mode").as_string();
if (service_introspection_mode == "metadata") {
std::string introspection_mode =
node_parameters_interface->get_parameter("introspection_mode").as_string();
if (introspection_mode == "metadata") {
introspection_state = RCL_SERVICE_INTROSPECTION_METADATA;
} else if (service_introspection_mode == "contents") {
} else if (introspection_mode == "contents") {
introspection_state = RCL_SERVICE_INTROSPECTION_CONTENTS;
}

Expand Down
2 changes: 1 addition & 1 deletion nav2_ros_common/test/test_service_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ TEST(ServiceClient, can_ServiceClient_use_passed_in_node)
};
for(const auto & mode : introspection_modes) {
auto node = rclcpp::Node::make_shared("test_node" + mode);
node->declare_parameter("service_introspection_mode", mode);
node->declare_parameter("introspection_mode", mode);
TestServiceClient t("bar", node, true);
ASSERT_EQ(t.name(), "test_node" + mode);
}
Expand Down
2 changes: 1 addition & 1 deletion nav2_ros_common/test/test_service_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ TEST(ServiceServer, can_handle_all_introspection_modes)
int a = 0;
auto node = rclcpp::Node::make_shared("test_node_" + mode);

node->declare_parameter("service_introspection_mode", mode);
node->declare_parameter("introspection_mode", mode);

auto callback = [&a](const std::shared_ptr<rmw_request_id_t>,
const std::shared_ptr<std_srvs::srv::Empty::Request>,
Expand Down
2 changes: 1 addition & 1 deletion nav2_smac_planner/src/smac_planner_2d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ void SmacPlanner2D::configure(
// Note that we need to declare it here to prevent the parameter from being declared in the
// dynamic reconfigure callback
nav2::declare_parameter_if_not_declared(
node, "service_introspection_mode", rclcpp::ParameterValue("disabled"));
node, "introspection_mode", rclcpp::ParameterValue("disabled"));

_motion_model = MotionModel::TWOD;

Expand Down
2 changes: 1 addition & 1 deletion nav2_smac_planner/src/smac_planner_hybrid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,7 @@ void SmacPlannerHybrid::configure(
// Note that we need to declare it here to prevent the parameter from being declared in the
// dynamic reconfigure callback
nav2::declare_parameter_if_not_declared(
node, "service_introspection_mode", rclcpp::ParameterValue("disabled"));
node, "introspection_mode", rclcpp::ParameterValue("disabled"));

std::string goal_heading_type;
nav2::declare_parameter_if_not_declared(
Expand Down
Loading