From 9ab9372a83550bac25f96dde21453d06b331a88c Mon Sep 17 00:00:00 2001
From: Sergi Hernandez Juan <shernand@iri.upc.edu>
Date: Tue, 9 Feb 2021 08:18:29 +0100
Subject: [PATCH] Added the set of configuration files adapted to the adc car.

---
 config/adc_car/basler_camera_sim_config.yaml | 19 +++++++
 config/adc_car/delock_camera_sim_config.yaml | 19 +++++++
 config/adc_car/mpu9250_imu_config.yaml       | 26 +++++++++
 config/adc_car/rear_center_sonar_config.yaml | 10 ++++
 config/adc_car/rear_left_sonar_config.yaml   | 10 ++++
 config/adc_car/rear_right_sonar_config.yaml  | 10 ++++
 config/adc_car/rp_lidar_config.yaml          | 20 +++++++
 config/adc_car/side_left_sonar_config.yaml   | 10 ++++
 config/adc_car/side_right_sonar_config.yaml  | 10 ++++
 config/adc_car_control_params.yaml           | 14 +++++
 config/adc_car_controller_config.yaml        | 57 ++++++++++++++++++++
 config/adc_car_odometry_params.yaml          | 14 +++++
 12 files changed, 219 insertions(+)
 create mode 100644 config/adc_car/basler_camera_sim_config.yaml
 create mode 100644 config/adc_car/delock_camera_sim_config.yaml
 create mode 100644 config/adc_car/mpu9250_imu_config.yaml
 create mode 100644 config/adc_car/rear_center_sonar_config.yaml
 create mode 100644 config/adc_car/rear_left_sonar_config.yaml
 create mode 100644 config/adc_car/rear_right_sonar_config.yaml
 create mode 100644 config/adc_car/rp_lidar_config.yaml
 create mode 100644 config/adc_car/side_left_sonar_config.yaml
 create mode 100644 config/adc_car/side_right_sonar_config.yaml
 create mode 100644 config/adc_car_control_params.yaml
 create mode 100644 config/adc_car_controller_config.yaml
 create mode 100644 config/adc_car_odometry_params.yaml

diff --git a/config/adc_car/basler_camera_sim_config.yaml b/config/adc_car/basler_camera_sim_config.yaml
new file mode 100644
index 0000000..2fbe6d5
--- /dev/null
+++ b/config/adc_car/basler_camera_sim_config.yaml
@@ -0,0 +1,19 @@
+horizontal_fov: 2.25
+width: 1280
+height: 960
+format: 'R8G8B8'
+clip_near: 0.1
+clip_far: 100
+noise_type: 'gaussian'
+noise_mean: 0.0
+noise_stddev: 0.007
+update_rate: 45
+camera_name: 'sensors/basler_camera'
+image_topic: 'image_raw'
+camera_info_topic: 'camera_info'
+hack_baseline: 0.07
+distortion_K1: 0.0
+distortion_K2: 0.0
+distortion_K3: 0.0
+distortion_T1: 0.0
+distortion_T2: 0.0
diff --git a/config/adc_car/delock_camera_sim_config.yaml b/config/adc_car/delock_camera_sim_config.yaml
new file mode 100644
index 0000000..6d7d5fe
--- /dev/null
+++ b/config/adc_car/delock_camera_sim_config.yaml
@@ -0,0 +1,19 @@
+horizontal_fov: 1.4 
+width: 1024
+height: 768
+format: 'R8G8B8'
+clip_near: 0.1
+clip_far: 100
+noise_type: 'gaussian'
+noise_mean: 0.0
+noise_stddev: 0.007
+update_rate: 30
+camera_name: 'sensors/delock_camera'
+image_topic: 'image_raw'
+camera_info_topic: 'camera_info'
+hack_baseline: 0.07
+distortion_K1: 0.0
+distortion_K2: 0.0
+distortion_K3: 0.0
+distortion_T1: 0.0
+distortion_T2: 0.0
diff --git a/config/adc_car/mpu9250_imu_config.yaml b/config/adc_car/mpu9250_imu_config.yaml
new file mode 100644
index 0000000..d95002f
--- /dev/null
+++ b/config/adc_car/mpu9250_imu_config.yaml
@@ -0,0 +1,26 @@
+rate: 100.0
+namespace: 'adc_car'
+tf_prefix: 'adc_car'
+imu_topic: 'sensors/imu'
+accel_offset_x: 0.06
+accel_offset_y: 0.06
+accel_offset_z: 0.08
+accel_drift_x: 0.001
+accel_drift_y: 0.001
+accel_drift_z: 0.001
+accel_noise_x: 0.008
+accel_noise_y: 0.008
+accel_noise_z: 0.008
+rate_offset_x: 5.0
+rate_offset_y: 5.0
+rate_offset_z: 5.0
+rate_drift_x: 0.015
+rate_drift_y: 0.015
+rate_drift_z: 0.015
+rate_noise_x: 0.1
+rate_noise_y: 0.1
+rate_noise_z: 0.1
+heading_offset: 0.0
+heading_drift: 0.0
+heading_noise: 0.0
+
diff --git a/config/adc_car/rear_center_sonar_config.yaml b/config/adc_car/rear_center_sonar_config.yaml
new file mode 100644
index 0000000..c63338f
--- /dev/null
+++ b/config/adc_car/rear_center_sonar_config.yaml
@@ -0,0 +1,10 @@
+rate: 20.0
+visualize: true
+fov: 0.5
+min_range: 0.2
+max_range: 4.0
+resolution: 0.003
+frame_id: 'adc_car/rear_center_ranger1d'
+ranger1d_topic: 'sensors/range/rear_center_sonar'
+type: 'ultrasound'
+noise: 0.01
diff --git a/config/adc_car/rear_left_sonar_config.yaml b/config/adc_car/rear_left_sonar_config.yaml
new file mode 100644
index 0000000..4a17277
--- /dev/null
+++ b/config/adc_car/rear_left_sonar_config.yaml
@@ -0,0 +1,10 @@
+rate: 20.0
+visualize: true
+fov: 0.5
+min_range: 0.2
+max_range: 4.0
+resolution: 0.003
+frame_id: 'adc_car/rear_left_ranger1d'
+ranger1d_topic: 'sensors/range/rear_left_sonar'
+type: 'ultrasound'
+noise: 0.01
diff --git a/config/adc_car/rear_right_sonar_config.yaml b/config/adc_car/rear_right_sonar_config.yaml
new file mode 100644
index 0000000..96a2039
--- /dev/null
+++ b/config/adc_car/rear_right_sonar_config.yaml
@@ -0,0 +1,10 @@
+rate: 20.0
+visualize: true
+fov: 0.5
+min_range: 0.2
+max_range: 4.0
+resolution: 0.003
+frame_id: 'adc_car/rear_right_ranger1d'
+ranger1d_topic: 'sensors/range/rear_right_sonar'
+type: 'ultrasound'
+noise: 0.01
diff --git a/config/adc_car/rp_lidar_config.yaml b/config/adc_car/rp_lidar_config.yaml
new file mode 100644
index 0000000..02c79f3
--- /dev/null
+++ b/config/adc_car/rp_lidar_config.yaml
@@ -0,0 +1,20 @@
+pose_x: 0
+pose_y: 0
+pose_z: 0
+pose_roll: 0
+pose_pitch: 0
+pose_yaw: 0
+visualize: false
+update_rate: 10
+samples: 400
+resolution: 1
+min_angle: -1.5708
+max_angle: 1.5708
+range_min: 0.15
+range_max: 6.0
+range_resolution: 0.05
+noise_type: 'gaussian'
+noise_mean: 0.0
+noise_stddev: 0.01
+topic_name: 'sensors/scan'
+#frame_name: 'scan_frame'
diff --git a/config/adc_car/side_left_sonar_config.yaml b/config/adc_car/side_left_sonar_config.yaml
new file mode 100644
index 0000000..fbcf3c6
--- /dev/null
+++ b/config/adc_car/side_left_sonar_config.yaml
@@ -0,0 +1,10 @@
+rate: 20.0
+visualize: true
+fov: 0.5
+min_range: 0.2
+max_range: 4.0
+resolution: 0.003
+frame_id: 'adc_car/side_left_ranger1d'
+ranger1d_topic: 'sensors/range/side_left_sonar'
+type: 'ultrasound'
+noise: 0.01
diff --git a/config/adc_car/side_right_sonar_config.yaml b/config/adc_car/side_right_sonar_config.yaml
new file mode 100644
index 0000000..c1bb4a1
--- /dev/null
+++ b/config/adc_car/side_right_sonar_config.yaml
@@ -0,0 +1,10 @@
+rate: 20.0
+visualize: true
+fov: 0.5
+min_range: 0.2
+max_range: 4.0
+resolution: 0.003
+frame_id: 'adc_car/side_right_ranger1d'
+ranger1d_topic: 'sensors/range/side_right_sonar'
+type: 'ultrasound'
+noise: 0.01
diff --git a/config/adc_car_control_params.yaml b/config/adc_car_control_params.yaml
new file mode 100644
index 0000000..a97da44
--- /dev/null
+++ b/config/adc_car_control_params.yaml
@@ -0,0 +1,14 @@
+rate: 40
+speed_Kp: 20.0
+speed_Ki: 10.0
+speed_Kd: 0.05
+speed_i_max: 20.0
+watchdog_time: 0.5
+axel_distance: 0.3662
+max_steer_angle: 0.4
+min_steer_angle: -0.4
+max_speed_control: 20.0
+min_speed_control: -20.0
+max_steer_control: 100.0
+min_steer_control: -100.0
+
diff --git a/config/adc_car_controller_config.yaml b/config/adc_car_controller_config.yaml
new file mode 100644
index 0000000..5281aac
--- /dev/null
+++ b/config/adc_car_controller_config.yaml
@@ -0,0 +1,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
diff --git a/config/adc_car_odometry_params.yaml b/config/adc_car_odometry_params.yaml
new file mode 100644
index 0000000..d200601
--- /dev/null
+++ b/config/adc_car_odometry_params.yaml
@@ -0,0 +1,14 @@
+rate: 40
+odom_frame: "adc_car/odom"
+robot_frame: "adc_car/base_footprint"
+encoder_ticks: 60
+wheel_diameter: 0.100
+wheel_distance: 0.216
+axel_distance: 0.3662
+filter_coeff: 0.75
+max_steer_angle: 0.4
+min_steer_angle: -0.4
+max_steer_control: 100.0
+min_steer_control: -100.0
+publish_tf: True
+
-- 
GitLab