diff --git a/VirtualRobot/Dynamics/dynamics.cpp b/VirtualRobot/Dynamics/dynamics.cpp
index fe3d4abcda48606174b466cfb5dae28dfc988165..ebbe3aa51bf6fa86d3298483a87139a83cfdc50f 100644
--- a/VirtualRobot/Dynamics/dynamics.cpp
+++ b/VirtualRobot/Dynamics/dynamics.cpp
@@ -372,7 +372,7 @@ void Dynamics::toRBDL(boost::shared_ptr<RigidBodyDynamics::Model> model, RobotNo
 
     cout << "****** spatial_translation: " << spatial_translation.transpose() << endl;
 
-    SpatialTransform spatial_transform = SpatialTransform(spatial_rotation, spatial_translation);
+    SpatialTransform spatial_transform = SpatialTransform(spatial_rotation.transpose(), spatial_translation);
 
     // last, joint
     Joint joint = Joint(JointTypeFixed);