From: Erik Andresen Date: Mon, 27 Jul 2020 17:21:03 +0000 (+0200) Subject: Fix naming of dynamic reconfigure files X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=commitdiff_plain;h=255212530a5073e1ebd97f7b8c168c4b1535fb8e Fix naming of dynamic reconfigure files --- diff --git a/CMakeLists.txt b/CMakeLists.txt index 689434c..be7eeab 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -71,8 +71,8 @@ rosruby_setup() rosruby_generate_messages(fiducial_msgs) generate_dynamic_reconfigure_options( - config/path_following.cfg - config/wt_node.cfg + config/PathFollowing.cfg + config/WildThumper.cfg ) ################################### @@ -100,6 +100,7 @@ catkin_package( ## Your package locations should be listed before other locations include_directories( ${catkin_INCLUDE_DIRS} + /opt/ros/tinkerforge/c_bindings/source ) ## Declare a cpp library diff --git a/config/PathFollowing.cfg b/config/PathFollowing.cfg new file mode 100755 index 0000000..901b0bf --- /dev/null +++ b/config/PathFollowing.cfg @@ -0,0 +1,14 @@ +#!/usr/bin/env python + +from dynamic_reconfigure.parameter_generator_catkin import * + +gen = ParameterGenerator() + +gen.add("binary_threshold", int_t, 0, "Binary Threshold", 192, 0, 255) +gen.add("ht_min_points", int_t, 0, "HT Min Points", 30, 0, 1000) +gen.add("roi_y", int_t, 0, "ROI Y (cm)", 70, 0, 1000) +gen.add("road_distance_cm", double_t, 0, "Road distance (cm)", 15, 0, 1000) +gen.add("lad_cm", double_t, 0, "Look ahead distance (cm)", 60, 0, 1000) +gen.add("speed_m_s", double_t, 0, "Speed m/s", 0, 0, 1) + +exit(gen.generate("wild_thumper", "path_following", "PathFollowing")) diff --git a/config/WildThumper.cfg b/config/WildThumper.cfg new file mode 100755 index 0000000..08d089f --- /dev/null +++ b/config/WildThumper.cfg @@ -0,0 +1,17 @@ +#!/usr/bin/env python + +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.04, 4) +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) +gen.add("rollover_protect_pwm", double_t, 0, "Pitch rollover protection speed (pwm)", 255, 0, 255) +gen.add("stay_docked", bool_t, 0, "Try to stay dock again after an undocking event", True) + +exit(gen.generate("wild_thumper", "wild_thumper", "WildThumper")) diff --git a/config/path_following.cfg b/config/path_following.cfg deleted file mode 100755 index 901b0bf..0000000 --- a/config/path_following.cfg +++ /dev/null @@ -1,14 +0,0 @@ -#!/usr/bin/env python - -from dynamic_reconfigure.parameter_generator_catkin import * - -gen = ParameterGenerator() - -gen.add("binary_threshold", int_t, 0, "Binary Threshold", 192, 0, 255) -gen.add("ht_min_points", int_t, 0, "HT Min Points", 30, 0, 1000) -gen.add("roi_y", int_t, 0, "ROI Y (cm)", 70, 0, 1000) -gen.add("road_distance_cm", double_t, 0, "Road distance (cm)", 15, 0, 1000) -gen.add("lad_cm", double_t, 0, "Look ahead distance (cm)", 60, 0, 1000) -gen.add("speed_m_s", double_t, 0, "Speed m/s", 0, 0, 1) - -exit(gen.generate("wild_thumper", "path_following", "PathFollowing")) diff --git a/config/wt_node.cfg b/config/wt_node.cfg deleted file mode 100755 index 08d089f..0000000 --- a/config/wt_node.cfg +++ /dev/null @@ -1,17 +0,0 @@ -#!/usr/bin/env python - -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.04, 4) -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) -gen.add("rollover_protect_pwm", double_t, 0, "Pitch rollover protection speed (pwm)", 255, 0, 255) -gen.add("stay_docked", bool_t, 0, "Try to stay dock again after an undocking event", True) - -exit(gen.generate("wild_thumper", "wild_thumper", "WildThumper"))