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
1 change: 1 addition & 0 deletions doc/parameters/param_list.md
Original file line number Diff line number Diff line change
Expand Up @@ -547,6 +547,7 @@ When `recovery_plugins` parameter is not overridden, the following default plugi
| z_rand | 0.5 | Mixture weight for z_rand part of model, sum of all used z weight must be 1. Beam uses all 4, likelihood model uses z_hit and z_rand. |
| z_short | 0.05 | Mixture weight for z_short part of model, sum of all used z weight must be 1. Beam uses all 4, likelihood model uses z_hit and z_rand. |
| always_reset_initial_pose | false | Requires that AMCL is provided an initial pose either via topic or initial_pose* parameter (with parameter set_initial_pose: true) when reset. Otherwise, by default AMCL will use the last known pose to initialize |
| scan_topic | scan | Topic to subscribe to in order to receive the laser scan for localization |

---

Expand Down
2 changes: 1 addition & 1 deletion nav2_amcl/include/nav2_amcl/amcl_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -167,7 +167,6 @@ class AmclNode : public nav2_util::LifecycleNode

// Laser scan related
void initLaserScan();
const char * scan_topic_{"scan"};
nav2_amcl::Laser * createLaserObject();
int scan_error_count_{0};
std::vector<nav2_amcl::Laser *> lasers_;
Expand Down Expand Up @@ -250,6 +249,7 @@ class AmclNode : public nav2_util::LifecycleNode
double z_max_;
double z_short_;
double z_rand_;
std::string scan_topic_{"scan"};
};

} // namespace nav2_amcl
Expand Down
5 changes: 5 additions & 0 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -213,6 +213,10 @@ AmclNode::AmclNode()
"Requires that AMCL is provided an initial pose either via topic or initial_pose* parameter "
"(with parameter set_initial_pose: true) when reset. Otherwise, by default AMCL will use the"
"last known pose to initialize");

add_parameter(
"scan_topic", rclcpp::ParameterValue("scan"),
"Topic to subscribe to in order to receive the laser scan for localization");
}

AmclNode::~AmclNode()
Expand Down Expand Up @@ -1098,6 +1102,7 @@ AmclNode::initParameters()
get_parameter("z_short", z_short_);
get_parameter("first_map_only_", first_map_only_);
get_parameter("always_reset_initial_pose", always_reset_initial_pose_);
get_parameter("scan_topic", scan_topic_);

save_pose_period_ = tf2::durationFromSec(1.0 / save_pose_rate);
transform_tolerance_ = tf2::durationFromSec(tmp_tol);
Expand Down
1 change: 1 addition & 0 deletions nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ amcl:
z_max: 0.05
z_rand: 0.5
z_short: 0.05
scan_topic: scan

amcl_map_client:
ros__parameters:
Expand Down
1 change: 1 addition & 0 deletions nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ amcl:
z_max: 0.05
z_rand: 0.5
z_short: 0.05
scan_topic: scan

amcl_map_client:
ros__parameters:
Expand Down
1 change: 1 addition & 0 deletions nav2_bringup/bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ amcl:
z_max: 0.05
z_rand: 0.5
z_short: 0.05
scan_topic: scan

amcl_map_client:
ros__parameters:
Expand Down