X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=config%2Fwt_node.cfg;h=fe8798cde3fd980c4bdfaf0f96dc84cb6107398b;hp=725c56519a73e35f89b248f0e0fa1ce020594eb2;hb=6c223bf6af2bfcff0279d0c56a32ce2e5e7d9e04;hpb=dfa22bff12a5c6e0685b3e79e681ccc1d0bd1fa1 diff --git a/config/wt_node.cfg b/config/wt_node.cfg index 725c565..fe8798c 100755 --- a/config/wt_node.cfg +++ b/config/wt_node.cfg @@ -6,7 +6,8 @@ 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.04, 4) -gen.add("odom_covar_xy", double_t, 0, "Odometry covariance: translation", 1e-2, 1e-6, 1) +gen.add("range_sensor_fov", double_t, 0, "Range sensor field of view (deg)", 30, 1, 90) +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)