X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=config%2Fwt_node.cfg;h=aad0d5498c4007d96bb46234abf0021151690c78;hp=598362246fc1ee0586a544ffd9e44523b4824ef1;hb=b301eb19e6487497a8bb946c538a25aa4ee28c1d;hpb=67ce0bb517f49851a8421981b074d472c8dc9624 diff --git a/config/wt_node.cfg b/config/wt_node.cfg index 5983622..aad0d54 100755 --- a/config/wt_node.cfg +++ b/config/wt_node.cfg @@ -5,8 +5,11 @@ from dynamic_reconfigure.parameter_generator_catkin import * gen = ParameterGenerator() gen.add("range_sensor_clip", bool_t, 0, "Clip range sensor values to max range", True) -gen.add("range_sensor_max", double_t, 0, "Range sensor max range", 0.5, 0.4, 6) -gen.add("odom_covar_xy", double_t, 0, "Odometry covariance: translation", 1e-2, 1e-6, 1) -gen.add("odom_covar_angle", double_t, 0, "Odometry covariance: rotation", 0.25, 1e-6, 6.2832) +gen.add("range_sensor_max", double_t, 0, "Range sensor max range", 0.5, 0.04, 4) +gen.add("odom_covar_xy", double_t, 0, "Odometry covariance: translation", 1e-3, 1e-6, 1) +gen.add("odom_covar_angle", double_t, 0, "Odometry covariance: rotation", 1.00, 1e-6, 6.2832) +gen.add("rollover_protect", bool_t, 0, "Enable motor rollover protection on pitch", True) +gen.add("rollover_protect_limit",double_t, 0, "Pitch rollover protection limit (degree)", 45, 0, 90) +gen.add("rollover_protect_pwm", double_t, 0, "Pitch rollover protection speed (pwm)", 255, 0, 255) exit(gen.generate("wild_thumper", "wild_thumper", "WildThumper"))