mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
code formatting
This commit is contained in:
@@ -137,7 +137,7 @@ void Calibration::correctAxis(const size_t link_index)
|
|||||||
// Correct next joint
|
// Correct next joint
|
||||||
// ROS_INFO_STREAM("Second Next old:\n" << chain_[2 * link_index + 2]);
|
// ROS_INFO_STREAM("Second Next old:\n" << chain_[2 * link_index + 2]);
|
||||||
chain_[2 * link_index + 2](2, 3) -= distance_correction;
|
chain_[2 * link_index + 2](2, 3) -= distance_correction;
|
||||||
robot_parameters_corrected_.segments_[link_index+1].d_ -= distance_correction;
|
robot_parameters_corrected_.segments_[link_index + 1].d_ -= distance_correction;
|
||||||
// ROS_INFO_STREAM("Second Next new:\n" << chain_[2 * link_index + 2]);
|
// ROS_INFO_STREAM("Second Next new:\n" << chain_[2 * link_index + 2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user