diff --git a/talos_bringup/config/talos_full_hardware.yaml b/talos_bringup/config/talos_full_hardware.yaml index ea930250916303beb321b3481d33bbef75218577..4e6505013212b3badbcaa1c4acdadd9c2725e7ac 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 5ceb621a333965f627129fdaeb500e146fbdbba3..966902a2332e74442347560ea17a1622d3e09657 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>