Skip to content

Commit

Permalink
Update Ros2ControlSystem.cpp: correct acceleration
Browse files Browse the repository at this point in the history
  • Loading branch information
onionsflying authored Dec 27, 2024
1 parent be9c9ce commit 3d7dc08
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion webots_ros2_control/src/Ros2ControlSystem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,7 +153,7 @@ namespace webots_ros2_control {
const double velocity = std::isnan(joint.position) ? NAN : (position - joint.position) / deltaTime;

if (!std::isnan(joint.velocity))
joint.acceleration = (joint.velocity - velocity) / deltaTime;
joint.acceleration = (velocity - joint.velocity) / deltaTime;
joint.velocity = velocity;
joint.position = position;
}
Expand Down

0 comments on commit 3d7dc08

Please sign in to comment.