Skip to content
Snippets Groups Projects
Commit 76a0efd5 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Merge branch 'development' into 'master'

Updated the axel distance and wheel distance values to make them closer to the real values.

See merge request !2
parents e6ea7e22 dcd56e9b
No related branches found
No related tags found
1 merge request!2Updated the axel distance and wheel distance values to make them closer to the real values.
......@@ -43,8 +43,8 @@ gen.add("odom_frame", str_t, 0, "Name of the odometry fram
gen.add("robot_frame", str_t, 0, "Name of the robot frame", "base_footprint")
gen.add("encoder_ticks", int_t, 0, "Number of encoder ticks per revolution", 60, 1, 1000)
gen.add("wheel_diameter", double_t, 0, "Diameter of the wheel in meters", 0.108, 0.01,1000)
gen.add("wheel_distance", double_t, 0, "Distance between wheels in meters", 0.261, 0.01,1000)
gen.add("axel_distance", double_t, 0, "Distance betweena axels in meters", 0.3662, 0.01,1.0)
gen.add("wheel_distance", double_t, 0, "Distance between wheels in meters", 0.265, 0.01,1000)
gen.add("axel_distance", double_t, 0, "Distance betweena axels in meters", 0.36, 0.01,1.0)
gen.add("enable_filter", bool_t, 0, "Enable the low pass filter for the encoder data", True)
gen.add("filter_coeff", double_t, 0, "Coefficient for the first order low pass filter", 0.3, 0.01,1.0)
gen.add("speed_deadband", double_t, 0, "Minimum valid speed command", 0.1, 0.1, 1.0)
......
......@@ -3,8 +3,8 @@ odom_frame: "car1/odom"
robot_frame: "car1/base_footprint"
encoder_ticks: 30
wheel_diameter: 0.100
wheel_distance: 0.261
axel_distance: 0.3662
wheel_distance: 0.265
axel_distance: 0.36
enable_filter: True
filter_coeff: 0.3
speed_deadband: 0.1
......
......@@ -3,8 +3,8 @@ odom_frame: "car2/odom"
robot_frame: "car2/base_footprint"
encoder_ticks: 30
wheel_diameter: 0.100
wheel_distance: 0.261
axel_distance: 0.3662
wheel_distance: 0.265
axel_distance: 0.36
enable_filter: True
filter_coeff: 0.3
speed_deadband: 0.1
......
......@@ -3,8 +3,8 @@ odom_frame: "model_car/odom"
robot_frame: "model_car/base_footprint"
encoder_ticks: 30
wheel_diameter: 0.100
wheel_distance: 0.261
axel_distance: 0.3662
wheel_distance: 0.265
axel_distance: 0.36
enable_filter: True
filter_coeff: 0.3
speed_deadband: 0.1
......
......@@ -3,8 +3,8 @@ odom_frame: "model_car/odom"
robot_frame: "model_car/base_footprint"
encoder_ticks: 30
wheel_diameter: 0.100
wheel_distance: 0.261
axel_distance: 0.3662
wheel_distance: 0.265
axel_distance: 0.36
enable_filter: True
filter_coeff: 0.3
speed_deadband: 0.1
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment