adc_car_controller_config.yaml 1.52 KB
Newer Older
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
#model_car:
  # Publish all joint states -----------------------------------
  joint_state_controller:
    type: joint_state_controller/JointStateController
    publish_rate: 50  

  car_controller:
    type: iri_model_car_controller/ModelCarController
    steer_left_joint: base_link_2_steer_left_joint
    steer_right_joint: base_link_2_steer_right_joint
    drive_rear_left_joint: base_link_2_rear_left_wheel_joint
    drive_rear_right_joint: base_link_2_rear_right_wheel_joint
    drive_front_left_joint: steer_left_2_front_left_wheel_joint
    drive_front_right_joint: steer_right_2_front_right_wheel_joint
    axel_distance: 0.3662
    wheel_distance: 0.216
    wheel_diameter: 0.100
    encoder_ticks: 60
    encoder_rate: 40
    min_steer_angle: -0.4
    max_steer_angle: 0.4
    min_speed: -1.5
    max_speed: 1.5
    control_topic: /adc_car/control
    encoders_topic: /adc_car/encoders
    
    gains:
      base_link_2_steer_left_joint:
        p: 20.0
        d: 0.0
        i: 0.0
        i_clamp: 1
      base_link_2_steer_right_joint:
        p: 20.0
        d: 0.0
        i: 0.0
        i_clamp: 1
      base_link_2_rear_left_wheel_joint:
        p: 0.5
        d: 0.0
        i: 0.01
        i_clamp: 0.1
      base_link_2_rear_right_wheel_joint:
        p: 0.5
        d: 0.0
        i: 0.01
        i_clamp: 0.1
      steer_left_2_front_left_wheel_joint:
        p: 0.5
        d: 0.0
        i: 0.01
        i_clamp: 0.1
      steer_right_2_front_right_wheel_joint:
        p: 0.5
        d: 0.0
        i: 0.01
        i_clamp: 0.1