Commande.cfg runs :-)
This commit is contained in:
parent
0b4782098c
commit
772c09a0e5
3 changed files with 13 additions and 28 deletions
|
@ -1,7 +1,7 @@
|
||||||
cmake_minimum_required(VERSION 2.8.3)
|
cmake_minimum_required(VERSION 2.8.3)
|
||||||
project(hand_control)
|
project(hand_control)
|
||||||
|
|
||||||
find_package(catkin REQUIRED COMPONENTS
|
find_package(catkin REQUIRED COMPONENTS
|
||||||
pcl_ros
|
pcl_ros
|
||||||
pcl_msgs
|
pcl_msgs
|
||||||
roscpp
|
roscpp
|
||||||
|
@ -11,6 +11,7 @@ project(hand_control)
|
||||||
ardrone_autonomy
|
ardrone_autonomy
|
||||||
dynamic_reconfigure
|
dynamic_reconfigure
|
||||||
)
|
)
|
||||||
|
|
||||||
find_package(
|
find_package(
|
||||||
PkgConfig REQUIRED
|
PkgConfig REQUIRED
|
||||||
)
|
)
|
||||||
|
@ -59,11 +60,14 @@ target_link_libraries(commande-new-1d ${catkin_LIBRARIES})
|
||||||
target_link_libraries(commande-abs ${catkin_LIBRARIES})
|
target_link_libraries(commande-abs ${catkin_LIBRARIES})
|
||||||
|
|
||||||
#add dynamic reconfigure api
|
#add dynamic reconfigure api
|
||||||
generate_dynamic_reconfigure_options(
|
generate_dynamic_reconfigure_options(
|
||||||
cfg/Filtre.cfg
|
cfg/Filtre.cfg
|
||||||
cfg/Commande.cfg
|
cfg/Commande.cfg
|
||||||
)
|
)
|
||||||
|
|
||||||
add_dependencies(filtre ${PROJECT_NAME}_gencfg)
|
add_dependencies(filtre ${PROJECT_NAME}_gencfg)
|
||||||
catkin_package(
|
add_dependencies(commande-abs ${PROJECT_NAME}_gencfg)
|
||||||
|
|
||||||
|
catkin_package(
|
||||||
CATKIN_DEPENDS message_runtime
|
CATKIN_DEPENDS message_runtime
|
||||||
)
|
)
|
||||||
|
|
|
@ -1,14 +1,7 @@
|
||||||
#!usr/bin/env python
|
#!/usr/bin/env python
|
||||||
|
|
||||||
PACKAGE = "hand_control"
|
PACKAGE = "hand_control"
|
||||||
|
|
||||||
from dynamic_reconfigure.parameter_generator_catkin import *
|
from dynamic_reconfigure.parameter_generator_catkin import *
|
||||||
|
|
||||||
gen = ParameterGenerator()
|
gen = ParameterGenerator()
|
||||||
|
|
||||||
#gen.add("int_param", int_t, 0, "An Integer parameter", 50, 0, 100)
|
|
||||||
|
|
||||||
#"commande" node
|
|
||||||
gen.add("max_curvature", double_t, 0, "Maximum curvature of the estimated plane", 0.5, 0., 1.)
|
gen.add("max_curvature", double_t, 0, "Maximum curvature of the estimated plane", 0.5, 0., 1.)
|
||||||
gen.add("x_minimal_deviation", double_t, 0, "Absolute horizontal movement detection treshold", 0.05, 0.)
|
gen.add("x_minimal_deviation", double_t, 0, "Absolute horizontal movement detection treshold", 0.05, 0.)
|
||||||
gen.add("y_minimal_deviation", double_t, 0, "Absolute lateral movement detection treshold", 0.05, 0.)
|
gen.add("y_minimal_deviation", double_t, 0, "Absolute lateral movement detection treshold", 0.05, 0.)
|
||||||
|
@ -17,6 +10,4 @@ gen.add("neutral_alt", double_t, 0, "Reference altitude for vertical movement co
|
||||||
gen.add("min_points_number", int_t, 0, "Minimal number of plane points needed for a valid estimation", 3000, 0)
|
gen.add("min_points_number", int_t, 0, "Minimal number of plane points needed for a valid estimation", 3000, 0)
|
||||||
gen.add("up_fact", double_t, 0, "Upward command amplification factor", 1.5, 1)
|
gen.add("up_fact", double_t, 0, "Upward command amplification factor", 1.5, 1)
|
||||||
gen.add("theta_minimal_deviation", double_t, 0, "Absolute angular movement detection treshold", 15., 0., 180.)
|
gen.add("theta_minimal_deviation", double_t, 0, "Absolute angular movement detection treshold", 15., 0., 180.)
|
||||||
|
|
||||||
|
|
||||||
exit(gen.generate(PACKAGE, "hand_control", "Commande"))
|
exit(gen.generate(PACKAGE, "hand_control", "Commande"))
|
||||||
|
|
|
@ -1,13 +1,7 @@
|
||||||
#!/usr/bin/env python
|
#!/usr/bin/env python
|
||||||
PACKAGE = "hand_control"
|
PACKAGE = "hand_control"
|
||||||
|
|
||||||
from dynamic_reconfigure.parameter_generator_catkin import *
|
from dynamic_reconfigure.parameter_generator_catkin import *
|
||||||
|
|
||||||
gen = ParameterGenerator()
|
gen = ParameterGenerator()
|
||||||
|
|
||||||
#gen.add("int_param", int_t, 0, "An Integer parameter", 50, 0, 100)
|
|
||||||
|
|
||||||
# "filtre" node
|
|
||||||
gen.add("z_max", double_t, 0, "The maximal altitude of the hand", 50., 0.)
|
gen.add("z_max", double_t, 0, "The maximal altitude of the hand", 50., 0.)
|
||||||
gen.add("hue", double_t, 0, "The color hue of the hand", 0., 0., 360.)
|
gen.add("hue", double_t, 0, "The color hue of the hand", 0., 0., 360.)
|
||||||
gen.add("delta_hue", double_t, 0, "The tolerance of the hue filter", 20., 0., 180.)
|
gen.add("delta_hue", double_t, 0, "The tolerance of the hue filter", 20., 0., 180.)
|
||||||
|
@ -15,8 +9,4 @@ gen.add("sat_min", double_t, 0, "The minimum color saturation of the hand", 0.1,
|
||||||
gen.add("sat_max", double_t, 0, "The maximum color saturation of the hand", 1., 0., 1.)
|
gen.add("sat_max", double_t, 0, "The maximum color saturation of the hand", 1., 0., 1.)
|
||||||
gen.add("val_min", double_t, 0, "The minimum color value of the hand", 0.1, 0., 1.)
|
gen.add("val_min", double_t, 0, "The minimum color value of the hand", 0.1, 0., 1.)
|
||||||
gen.add("val_max", double_t, 0, "The maximum color value of the hand", 1., 0., 1.)
|
gen.add("val_max", double_t, 0, "The maximum color value of the hand", 1., 0., 1.)
|
||||||
|
|
||||||
|
|
||||||
#gen.add("bool_param", bool_t, 0, "A Boolean parameter", True)
|
|
||||||
|
|
||||||
exit(gen.generate(PACKAGE, "hand_control", "Filtre"))
|
exit(gen.generate(PACKAGE, "hand_control", "Filtre"))
|
||||||
|
|
Loading…
Reference in a new issue