Skip to content

Commit d736c0d

Browse files
mini-1235SakshayMahna
authored andcommitted
Rename service_introspection_mode to introspection_mode (ros-navigation#5321)
Signed-off-by: Maurice <[email protected]>
1 parent 0dc23e3 commit d736c0d

File tree

6 files changed

+19
-19
lines changed

6 files changed

+19
-19
lines changed

nav2_bringup/params/nav2_params.yaml

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ amcl:
3030
sigma_hit: 0.2
3131
tf_broadcast: true
3232
transform_tolerance: 1.0
33-
service_introspection_mode: "disabled"
33+
introspection_mode: "disabled"
3434
update_min_a: 0.2
3535
update_min_d: 0.25
3636
z_hit: 0.5
@@ -48,7 +48,7 @@ bt_navigator:
4848
filter_duration: 0.3
4949
default_server_timeout: 20
5050
wait_for_service_timeout: 1000
51-
service_introspection_mode: "disabled"
51+
introspection_mode: "disabled"
5252
navigators: ["navigate_to_pose", "navigate_through_poses"]
5353
navigate_to_pose:
5454
plugin: "nav2_bt_navigator::NavigateToPoseNavigator"
@@ -265,7 +265,7 @@ local_costmap:
265265
plugin: "nav2_costmap_2d::StaticLayer"
266266
map_subscribe_transient_local: True
267267
always_send_full_costmap: True
268-
service_introspection_mode: "disabled"
268+
introspection_mode: "disabled"
269269

270270
global_costmap:
271271
global_costmap:
@@ -318,15 +318,15 @@ global_costmap:
318318
cost_scaling_factor: 3.0
319319
inflation_radius: 0.7
320320
always_send_full_costmap: True
321-
service_introspection_mode: "disabled"
321+
introspection_mode: "disabled"
322322

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

331331
keepout_filter_mask_server:
332332
ros__parameters:
@@ -360,14 +360,14 @@ map_saver:
360360
free_thresh_default: 0.25
361361
occupied_thresh_default: 0.65
362362
map_subscribe_transient_local: True
363-
service_introspection_mode: "disabled"
363+
introspection_mode: "disabled"
364364

365365
planner_server:
366366
ros__parameters:
367367
expected_planner_frequency: 20.0
368368
planner_plugins: ["GridBased"]
369369
costmap_update_timeout: 1.0
370-
service_introspection_mode: "disabled"
370+
introspection_mode: "disabled"
371371
GridBased:
372372
plugin: "nav2_navfn_planner::NavfnPlanner"
373373
tolerance: 0.5
@@ -432,7 +432,7 @@ waypoint_follower:
432432
ros__parameters:
433433
loop_rate: 20
434434
stop_on_failure: false
435-
service_introspection_mode: "disabled"
435+
introspection_mode: "disabled"
436436
waypoint_task_executor_plugin: "wait_at_waypoint"
437437
wait_at_waypoint:
438438
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
@@ -519,7 +519,7 @@ docking_server:
519519
base_frame: "base_link"
520520
fixed_frame: "odom"
521521
dock_prestaging_tolerance: 0.5
522-
service_introspection_mode: "disabled"
522+
introspection_mode: "disabled"
523523

524524
# Types of docks
525525
dock_plugins: ["simple_charging_dock"]

nav2_ros_common/include/nav2_ros_common/node_utils.hpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -358,15 +358,15 @@ inline void setIntrospectionMode(
358358
{
359359
#if RCLCPP_VERSION_GTE(29, 0, 0)
360360
rcl_service_introspection_state_t introspection_state = RCL_SERVICE_INTROSPECTION_OFF;
361-
if (!node_parameters_interface->has_parameter("service_introspection_mode")) {
361+
if (!node_parameters_interface->has_parameter("introspection_mode")) {
362362
node_parameters_interface->declare_parameter(
363-
"service_introspection_mode", rclcpp::ParameterValue("disabled"));
363+
"introspection_mode", rclcpp::ParameterValue("disabled"));
364364
}
365-
std::string service_introspection_mode =
366-
node_parameters_interface->get_parameter("service_introspection_mode").as_string();
367-
if (service_introspection_mode == "metadata") {
365+
std::string introspection_mode =
366+
node_parameters_interface->get_parameter("introspection_mode").as_string();
367+
if (introspection_mode == "metadata") {
368368
introspection_state = RCL_SERVICE_INTROSPECTION_METADATA;
369-
} else if (service_introspection_mode == "contents") {
369+
} else if (introspection_mode == "contents") {
370370
introspection_state = RCL_SERVICE_INTROSPECTION_CONTENTS;
371371
}
372372

nav2_ros_common/test/test_service_client.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@ TEST(ServiceClient, can_ServiceClient_use_passed_in_node)
5151
};
5252
for(const auto & mode : introspection_modes) {
5353
auto node = rclcpp::Node::make_shared("test_node" + mode);
54-
node->declare_parameter("service_introspection_mode", mode);
54+
node->declare_parameter("introspection_mode", mode);
5555
TestServiceClient t("bar", node, true);
5656
ASSERT_EQ(t.name(), "test_node" + mode);
5757
}

nav2_ros_common/test/test_service_server.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ TEST(ServiceServer, can_handle_all_introspection_modes)
5252
int a = 0;
5353
auto node = rclcpp::Node::make_shared("test_node_" + mode);
5454

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

5757
auto callback = [&a](const std::shared_ptr<rmw_request_id_t>,
5858
const std::shared_ptr<std_srvs::srv::Empty::Request>,

nav2_smac_planner/src/smac_planner_2d.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -96,7 +96,7 @@ void SmacPlanner2D::configure(
9696
// Note that we need to declare it here to prevent the parameter from being declared in the
9797
// dynamic reconfigure callback
9898
nav2::declare_parameter_if_not_declared(
99-
node, "service_introspection_mode", rclcpp::ParameterValue("disabled"));
99+
node, "introspection_mode", rclcpp::ParameterValue("disabled"));
100100

101101
_motion_model = MotionModel::TWOD;
102102

nav2_smac_planner/src/smac_planner_hybrid.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -169,7 +169,7 @@ void SmacPlannerHybrid::configure(
169169
// Note that we need to declare it here to prevent the parameter from being declared in the
170170
// dynamic reconfigure callback
171171
nav2::declare_parameter_if_not_declared(
172-
node, "service_introspection_mode", rclcpp::ParameterValue("disabled"));
172+
node, "introspection_mode", rclcpp::ParameterValue("disabled"));
173173

174174
std::string goal_heading_type;
175175
nav2::declare_parameter_if_not_declared(

0 commit comments

Comments
 (0)