Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Parameter dumping utility #902

Merged
merged 6 commits into from
Aug 9, 2019
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
136 changes: 100 additions & 36 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,42 +59,106 @@ AmclNode::AmclNode()
{
RCLCPP_INFO(get_logger(), "Creating");

declare_parameter("alpha1", rclcpp::ParameterValue(0.2));
declare_parameter("alpha2", rclcpp::ParameterValue(0.2));
declare_parameter("alpha3", rclcpp::ParameterValue(0.2));
declare_parameter("alpha4", rclcpp::ParameterValue(0.2));
declare_parameter("alpha5", rclcpp::ParameterValue(0.2));
declare_parameter("base_frame_id", rclcpp::ParameterValue(std::string("base_footprint")));
declare_parameter("beam_skip_distance", rclcpp::ParameterValue(0.5));
declare_parameter("beam_skip_error_threshold", rclcpp::ParameterValue(0.9));
declare_parameter("beam_skip_threshold", rclcpp::ParameterValue(0.3));
declare_parameter("do_beamskip", rclcpp::ParameterValue(false));
declare_parameter("global_frame_id", rclcpp::ParameterValue(std::string("map")));
declare_parameter("lambda_short", rclcpp::ParameterValue(0.1));
declare_parameter("laser_likelihood_max_dist", rclcpp::ParameterValue(2.0));
declare_parameter("laser_max_range", rclcpp::ParameterValue(100.0));
declare_parameter("laser_min_range", rclcpp::ParameterValue(-1.0));
declare_parameter("laser_model_type", rclcpp::ParameterValue(std::string("likelihood_field")));
declare_parameter("max_beams", rclcpp::ParameterValue(60));
declare_parameter("max_particles", rclcpp::ParameterValue(2000));
declare_parameter("min_particles", rclcpp::ParameterValue(500));
declare_parameter("odom_frame_id", rclcpp::ParameterValue(std::string("odom")));
declare_parameter("pf_err", rclcpp::ParameterValue(0.05));
declare_parameter("pf_z", rclcpp::ParameterValue(0.99));
declare_parameter("recovery_alpha_fast", rclcpp::ParameterValue(0.0));
declare_parameter("recovery_alpha_slow", rclcpp::ParameterValue(0.0));
declare_parameter("resample_interval", rclcpp::ParameterValue(1));
declare_parameter("robot_model_type", rclcpp::ParameterValue(std::string("differential")));
declare_parameter("save_pose_rate", rclcpp::ParameterValue(0.5));
declare_parameter("sigma_hit", rclcpp::ParameterValue(0.2));
declare_parameter("tf_broadcast", rclcpp::ParameterValue(true));
declare_parameter("transform_tolerance", rclcpp::ParameterValue(1.0));
declare_parameter("update_min_a", rclcpp::ParameterValue(0.2));
declare_parameter("update_min_d", rclcpp::ParameterValue(0.25));
declare_parameter("z_hit", rclcpp::ParameterValue(0.5));
declare_parameter("z_max", rclcpp::ParameterValue(0.05));
declare_parameter("z_rand", rclcpp::ParameterValue(0.5));
declare_parameter("z_short", rclcpp::ParameterValue(0.05));
add_parameter("alpha1", rclcpp::ParameterValue(0.2),
"This is the alpha1 parameter", "These are additional constraints for alpha1");

add_parameter("alpha2", rclcpp::ParameterValue(0.2),
"This is the alpha2 parameter", "These are additional constraints for alpha2");

add_parameter("alpha3", rclcpp::ParameterValue(0.2),
"This is the alpha3 parameter", "These are additional constraints for alpha3");

add_parameter("alpha4", rclcpp::ParameterValue(0.2),
"This is the alpha4 parameter", "These are additional constraints for alpha4");

add_parameter("alpha5", rclcpp::ParameterValue(0.2),
"This is the alpha5 parameter", "These are additional constraints for alpha5");

add_parameter("base_frame_id", rclcpp::ParameterValue(std::string("base_footprint")),
"Which frame to use for the robot base");

add_parameter("beam_skip_distance", rclcpp::ParameterValue(0.5));
add_parameter("beam_skip_error_threshold", rclcpp::ParameterValue(0.9));
add_parameter("beam_skip_threshold", rclcpp::ParameterValue(0.3));
add_parameter("do_beamskip", rclcpp::ParameterValue(false));

add_parameter("global_frame_id", rclcpp::ParameterValue(std::string("map")),
"The name of the coordinate frame published by the localization system");

add_parameter("lambda_short", rclcpp::ParameterValue(0.1),
"Exponential decay parameter for z_short part of model");

add_parameter("laser_likelihood_max_dist", rclcpp::ParameterValue(2.0),
"Maximum distance to do obstacle inflation on map, for use in likelihood_field model");

add_parameter("laser_max_range", rclcpp::ParameterValue(100.0),
"Maximum scan range to be considered",
"-1.0 will cause the laser's reported maximum range to be used");

add_parameter("laser_min_range", rclcpp::ParameterValue(-1.0),
"Minimum scan range to be considered",
"-1.0 will cause the laser's reported minimum range to be used");

add_parameter("laser_model_type", rclcpp::ParameterValue(std::string("likelihood_field")),
"Which model to use, either beam, likelihood_field, or likelihood_field_prob",
"Ssame as likelihood_field but incorporates the beamskip feature, if enabled");

add_parameter("max_beams", rclcpp::ParameterValue(60),
"How many evenly-spaced beams in each scan to be used when updating the filter");

add_parameter("max_particles", rclcpp::ParameterValue(2000),
"Minimum allowed number of particles");

add_parameter("min_particles", rclcpp::ParameterValue(500),
"Maximum allowed number of particles");

add_parameter("odom_frame_id", rclcpp::ParameterValue(std::string("odom")),
"Which frame to use for odometry");

add_parameter("pf_err", rclcpp::ParameterValue(0.05));
add_parameter("pf_z", rclcpp::ParameterValue(0.99));

add_parameter("recovery_alpha_fast", rclcpp::ParameterValue(0.0),
"Exponential decay rate for the fast average weight filter, used in deciding when to recover "
"by adding random poses",
"A good value might be 0.1");

add_parameter("recovery_alpha_slow", rclcpp::ParameterValue(0.0),
"Exponential decay rate for the slow average weight filter, used in deciding when to recover "
"by adding random poses",
"A good value might be 0.001");

add_parameter("resample_interval", rclcpp::ParameterValue(1),
"Number of filter updates required before resampling");

add_parameter("robot_model_type", rclcpp::ParameterValue(std::string("differential")));

add_parameter("save_pose_rate", rclcpp::ParameterValue(0.5),
"Maximum rate (Hz) at which to store the last estimated pose and covariance to the parameter "
"server, in the variables ~initial_pose_* and ~initial_cov_*. This saved pose will be used "
"on subsequent runs to initialize the filter",
"-1.0 to disable");

add_parameter("sigma_hit", rclcpp::ParameterValue(0.2));

add_parameter("tf_broadcast", rclcpp::ParameterValue(true),
"Set this to false to prevent amcl from publishing the transform between the global frame and "
"the odometry frame");

add_parameter("transform_tolerance", rclcpp::ParameterValue(1.0),
"Time with which to post-date the transform that is published, to indicate that this transform "
"is valid into the future");

add_parameter("update_min_a", rclcpp::ParameterValue(0.2),
"Rotational movement required before performing a filter update");

add_parameter("update_min_d", rclcpp::ParameterValue(0.25),
"Translational movement required before performing a filter update");

add_parameter("z_hit", rclcpp::ParameterValue(0.5));
add_parameter("z_max", rclcpp::ParameterValue(0.05));
add_parameter("z_rand", rclcpp::ParameterValue(0.5));
add_parameter("z_short", rclcpp::ParameterValue(0.05));
}

AmclNode::~AmclNode()
Expand Down
67 changes: 67 additions & 0 deletions nav2_util/include/nav2_util/lifecycle_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,73 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
virtual ~LifecycleNode();

typedef struct {
double from_value;
double to_value;
double step;
} floating_point_range;

typedef struct {
int from_value;
int to_value;
int step;
} integer_range;

// Declare a parameter that has no integer or floating point range constraints
void add_parameter(const std::string & name, const rclcpp::ParameterValue & default_value,
const std::string & description = "", const std::string & additional_constraints = "",
bool read_only = false)
{
auto descriptor = rcl_interfaces::msg::ParameterDescriptor();

descriptor.name = name;
descriptor.description = description;
descriptor.additional_constraints = additional_constraints;
descriptor.read_only = read_only;

declare_parameter(descriptor.name, default_value, descriptor);
}

// Declare a parameter that has a floating point range constraint
void add_parameter(const std::string & name, const rclcpp::ParameterValue & default_value,
const floating_point_range fp_range,
const std::string & description = "", const std::string & additional_constraints = "",
bool read_only = false)
{
auto descriptor = rcl_interfaces::msg::ParameterDescriptor();

descriptor.name = name;
descriptor.description = description;
descriptor.additional_constraints = additional_constraints;
descriptor.read_only = read_only;
descriptor.floating_point_range.resize(1);
descriptor.floating_point_range[0].from_value = fp_range.from_value;
descriptor.floating_point_range[0].to_value = fp_range.to_value;
descriptor.floating_point_range[0].step = fp_range.step;

declare_parameter(descriptor.name, default_value, descriptor);
}

// Declare a parameter that has an integer range constraint
void add_parameter(const std::string & name, const rclcpp::ParameterValue & default_value,
const integer_range int_range,
const std::string & description = "", const std::string & additional_constraints = "",
bool read_only = false)
{
auto descriptor = rcl_interfaces::msg::ParameterDescriptor();

descriptor.name = name;
descriptor.description = description;
descriptor.additional_constraints = additional_constraints;
descriptor.read_only = read_only;
descriptor.integer_range.resize(1);
descriptor.integer_range[0].from_value = int_range.from_value;
descriptor.integer_range[0].to_value = int_range.to_value;
descriptor.integer_range[0].step = int_range.step;

declare_parameter(descriptor.name, default_value, descriptor);
}

protected:
// Whether or not to create a local rclcpp::Node which can be used for ROS2 classes that don't
// yet support lifecycle nodes
Expand Down
10 changes: 10 additions & 0 deletions nav2_util/src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -29,9 +29,19 @@ add_executable(lifecycle_bringup
)
target_link_libraries(lifecycle_bringup ${library_name})

find_package(Boost REQUIRED COMPONENTS program_options)

add_executable(dump_params dump_params.cpp)
ament_target_dependencies(dump_params rclcpp)

target_include_directories(dump_params PUBLIC ${Boost_INCLUDE_DIRS})

target_link_libraries(dump_params ${Boost_PROGRAM_OPTIONS_LIBRARY})

install(TARGETS
${library_name}
lifecycle_bringup
dump_params
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
Expand Down
Loading