diff --git a/individual_params/config/default/ftd_sensor_kit/sensor_kit_calibration.yaml b/individual_params/config/default/ftd_sensor_kit/sensor_kit_calibration.yaml index ad3eb08..b54d9c9 100644 --- a/individual_params/config/default/ftd_sensor_kit/sensor_kit_calibration.yaml +++ b/individual_params/config/default/ftd_sensor_kit/sensor_kit_calibration.yaml @@ -7,20 +7,20 @@ sensor_kit_base_link: pitch: 0.0 yaw: 0.0 ydlidar_front_base_link: # Okinawa testbed 20240702 - x: 0.29 + x: 0.25 y: -0.14 - z: -0.73 - roll: -3.14159 + z: -0.7 + roll: -3.14159 pitch: 0.0 - yaw: -1.5708 -# ydlidar_front_base_link: # Okinawa testbed planned + yaw: -1.5708 +# ydlidar_front_base_link: # Okinawa testbed planned # x: 0.22 # y: 0.0 # z: -0.50 # roll: 0.0 # pitch: 0.0 # yaw: 1.5708 - ydlidar_rear_base_link: # Okinawa testbed planned + ydlidar_rear_base_link: # Okinawa testbed planned x: -1.06 y: 0.0 z: -0.57 @@ -28,9 +28,9 @@ sensor_kit_base_link: pitch: 0.0 yaw: 0.0 tamagawa/imu_link: # Okinawa testbed center - x: -0.5 + x: -0.05 y: 0.0 - z: -0.50 + z: -0.45 roll: 0.0 pitch: 0.0 - yaw: 0.0 + yaw: 1.5708 diff --git a/individual_params/config/default/ftd_sensor_kit/sensors_calibration.yaml b/individual_params/config/default/ftd_sensor_kit/sensors_calibration.yaml index ab6dea5..5349277 100644 --- a/individual_params/config/default/ftd_sensor_kit/sensors_calibration.yaml +++ b/individual_params/config/default/ftd_sensor_kit/sensors_calibration.yaml @@ -1,8 +1,8 @@ base_link: sensor_kit_base_link: - x: 1.01 + x: 1.15 y: 0.0 - z: 0.93 + z: 0.9 roll: 0.0 pitch: 0.0 yaw: 0.0