Skip to content
Snippets Groups Projects
Unverified Commit 0a9477e2 authored by Michael Equi's avatar Michael Equi Committed by GitHub
Browse files

Added parameters to configure amcl laser scan topic (#1870)

* Added parameters to configure amcl topic

* changed parameter to scan_topic and added to all the configuration files

* added scan_topic amcl param to docs

* Satisfied linter
parent 4e1c18db
No related branches found
No related tags found
No related merge requests found
......@@ -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 |
---
......
......@@ -167,7 +167,6 @@ protected:
// 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_;
......@@ -250,6 +249,7 @@ protected:
double z_max_;
double z_short_;
double z_rand_;
std::string scan_topic_{"scan"};
};
} // namespace nav2_amcl
......
......@@ -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()
......@@ -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);
......
......@@ -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:
......
......@@ -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:
......
......@@ -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:
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment