git commit -m "first commit for v2"
This commit is contained in:
18
Devices/Packages/ros_kinematics/cfg/DiffDriveParameters.cfg
Executable file
18
Devices/Packages/ros_kinematics/cfg/DiffDriveParameters.cfg
Executable file
@@ -0,0 +1,18 @@
|
||||
#!/usr/bin/env python
|
||||
|
||||
PACKAGE = 'ros_kinematics'
|
||||
|
||||
from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, bool_t, double_t
|
||||
|
||||
gen = ParameterGenerator()
|
||||
|
||||
# Kinematic parameters related
|
||||
gen.add("left_wheel_radius_multiplier", double_t, 0, "Left wheel radius multiplier.", 1.0, 0.5, 1.5)
|
||||
gen.add("right_wheel_radius_multiplier", double_t, 0, "Right wheel radius multiplier.", 1.0, 0.5, 1.5)
|
||||
gen.add("wheel_separation_multiplier", double_t, 0, "Wheel separation multiplier.", 1.0, 0.5, 1.5)
|
||||
|
||||
# Publication related
|
||||
gen.add("publish_rate", double_t, 0, "Publish rate of odom.", 50.0, 0.0, 2000.0)
|
||||
gen.add("enable_odom_tf", bool_t, 0, "Publish odom frame to tf.", False)
|
||||
|
||||
exit(gen.generate(PACKAGE, "ros_kinematics", "DiffDriveParameters"))
|
||||
11
Devices/Packages/ros_kinematics/cfg/SteerDriveParameters.cfg
Executable file
11
Devices/Packages/ros_kinematics/cfg/SteerDriveParameters.cfg
Executable file
@@ -0,0 +1,11 @@
|
||||
#!/usr/bin/env python
|
||||
from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, double_t
|
||||
|
||||
gen = ParameterGenerator()
|
||||
|
||||
gen.add('odomEncSteeringAngleOffset', double_t, 0, 'Góc bẻ lái động cơ lái được offset so với gốc origin ', 1.757546557, 0.0, 6.283185)
|
||||
gen.add('steering_fix_wheel_distance_x', double_t, 0, 'Khoảng cách tâm O quay quanh trục Z động cơ Steer theo trục X', 1.3268, 0.0, 5.0)
|
||||
gen.add('steering_fix_wheel_distance_y', double_t, 0, 'Khoảng cách tâm O quay quanh trục Z động cơ Steer theo trục X', 0.0, 0.0, 5.0)
|
||||
gen.add('wheelAcceleration', double_t, 0, 'Gia tốc bánh kéo', 0.0, 0.0, 3.0)
|
||||
|
||||
exit(gen.generate('ros_kinematics', 'ros_kinematics', 'SteerDriveParameters'))
|
||||
Reference in New Issue
Block a user