diff --git a/nav2_behavior_tree/plugins/action/back_up_action.cpp b/nav2_behavior_tree/plugins/action/back_up_action.cpp index 7987db4f32..070cc4a88e 100644 --- a/nav2_behavior_tree/plugins/action/back_up_action.cpp +++ b/nav2_behavior_tree/plugins/action/back_up_action.cpp @@ -36,7 +36,7 @@ void nav2_behavior_tree::BackUpAction::initialize() getInput("backup_speed", speed); double time_allowance; getInput("time_allowance", time_allowance); - double disable_collision_checks; + bool disable_collision_checks; getInput("disable_collision_checks", disable_collision_checks); // Populate the input message diff --git a/nav2_behavior_tree/plugins/action/drive_on_heading_action.cpp b/nav2_behavior_tree/plugins/action/drive_on_heading_action.cpp index 53e0efca85..c5fa780a4c 100644 --- a/nav2_behavior_tree/plugins/action/drive_on_heading_action.cpp +++ b/nav2_behavior_tree/plugins/action/drive_on_heading_action.cpp @@ -37,7 +37,7 @@ void DriveOnHeadingAction::initialize() getInput("speed", speed); double time_allowance; getInput("time_allowance", time_allowance); - double disable_collision_checks; + bool disable_collision_checks; getInput("disable_collision_checks", disable_collision_checks); // Populate the input message