From df379a49a18a830795db9d3d374a68559eb2aef9 Mon Sep 17 00:00:00 2001 From: Luca <luca.marchionni@pal-robotics.com> Date: Sat, 12 Nov 2016 14:05:15 +0100 Subject: [PATCH] Fix imu tf and frame --- talos_bringup/config/talos_full_hardware.yaml | 2 +- talos_description/urdf/torso/torso.urdf.xacro | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/talos_bringup/config/talos_full_hardware.yaml b/talos_bringup/config/talos_full_hardware.yaml index ea93025..4e65050 100644 --- a/talos_bringup/config/talos_full_hardware.yaml +++ b/talos_bringup/config/talos_full_hardware.yaml @@ -52,7 +52,7 @@ force_torque: imu: base_imu: - frame: base_link + frame: imu_link raw_data: orientation_port: orientation_base linear_acceleration_port: linear_acceleration_base diff --git a/talos_description/urdf/torso/torso.urdf.xacro b/talos_description/urdf/torso/torso.urdf.xacro index 5ceb621..966902a 100644 --- a/talos_description/urdf/torso/torso.urdf.xacro +++ b/talos_description/urdf/torso/torso.urdf.xacro @@ -138,7 +138,7 @@ </joint> <xacro:talos_imu name="imu" parent="${name}_2_link" update_rate="100.0"> - <origin xyz="0.04925 0 0.078" rpy="${180.0*deg_to_rad} 0 ${-90.0*deg_to_rad}"/> + <origin xyz="0.04925 0 0.078" rpy="${180.0*deg_to_rad} 0 ${90.0*deg_to_rad}"/> </xacro:talos_imu> -- GitLab