@@ -73,72 +73,87 @@ void Calibration::correctAxis(const size_t link_index)
7373 // the kinematic structure gets destroyed, which has to be corrected:
7474 // - With setting d to 0, both the start and end points of the passive segment move along the
7575 // rotational axis of the start segment. Instead, the end point of the passive segment has to
76- // move along the rotational axis of the next segment. This creates a change in a and and theta, if
76+ // move along the rotational axis of the next segment. This creates a change in a and theta, if
7777 // the two rotational axes are not parallel.
7878 //
7979 // - The length of moving along the next segment's rotational axis is calculated by intersecting
8080 // the rotational axis with the XY-plane of the first segment.
81+ //
82+ auto & d_theta_segment = chain_[2 * link_index];
83+ auto & a_alpha_segment = chain_[2 * link_index + 1 ];
84+
85+ auto & d = d_theta_segment (2 , 3 );
86+ auto & a = a_alpha_segment (0 , 3 );
8187
82- if (chain_[ 2 * link_index]( 2 , 3 ) == 0.0 ) {
88+ if (d == 0.0 ) {
8389 // Nothing to do here.
8490 return ;
8591 }
8692
87- Eigen::Matrix4d fk_current = Eigen::Matrix4d::Identity ();
88- Eigen::Vector3d current_passive = Eigen::Vector3d::Zero ();
93+ // Start of the next joint's d_theta segment relative to the joint before the current one
94+ Eigen::Matrix4d next_joint_root = Eigen::Matrix4d::Identity ();
95+ next_joint_root *= d_theta_segment * a_alpha_segment;
8996
90- Eigen::Matrix4d fk_next_passive = Eigen::Matrix4d::Identity ();
91- fk_next_passive *= chain_[link_index * 2 ] * chain_[link_index * 2 + 1 ];
92- Eigen::Vector3d eigen_passive = fk_next_passive.topRightCorner (3 , 1 );
97+ Eigen::Vector3d next_root_position = next_joint_root.topRightCorner (3 , 1 );
9398
94- Eigen::Vector3d eigen_next = (fk_next_passive * chain_[(link_index + 1 ) * 2 ]).topRightCorner (3 , 1 );
99+ const auto & next_d_theta_segment = chain_[(link_index + 1 ) * 2 ];
100+ Eigen::Vector3d next_d_theta_end = (next_joint_root * next_d_theta_segment).topRightCorner (3 , 1 );
95101
96102 // Construct a representation of the next segment's rotational axis
97- Eigen::ParametrizedLine<double , 3 > next_line ;
98- next_line = Eigen::ParametrizedLine<double , 3 >::Through (eigen_passive, eigen_next );
103+ Eigen::ParametrizedLine<double , 3 > next_rotation_axis ;
104+ next_rotation_axis = Eigen::ParametrizedLine<double , 3 >::Through (next_root_position, next_d_theta_end );
99105
100- RCLCPP_DEBUG_STREAM (rclcpp::get_logger (" ur_calibration" ), " next_line:" << std::endl
101- << " Base:" << std::endl
102- << next_line.origin () << std::endl
103- << " Direction:" << std::endl
104- << next_line.direction ());
106+ RCLCPP_DEBUG_STREAM (rclcpp::get_logger (" ur_calibration" ), " next rotation axis:" << std::endl
107+ << " Base:" << std::endl
108+ << next_rotation_axis.origin ()
109+ << std::endl
110+ << " Direction:" << std::endl
111+ << next_rotation_axis.direction ());
105112
106113 // XY-Plane of first segment's start
107- Eigen::Hyperplane<double , 3 > plane (fk_current.topLeftCorner (3 , 3 ) * Eigen::Vector3d (0 , 0 , 1 ), current_passive);
108-
109- // Intersect the rotation axis with the XY-Plane. We use both notations, the length and
110- // intersection point, as we will need both. The intersection_param is the length moving along the
111- // plane (change in the next segment's d param), while the intersection point will be used for
112- // calculating the new angle theta.
113- double intersection_param = next_line.intersectionParameter (plane);
114- Eigen::Vector3d intersection = next_line.intersectionPoint (plane) - current_passive;
115- double new_theta = std::atan (intersection.y () / intersection.x ());
114+ Eigen::Hyperplane<double , 3 > plane (Eigen::Vector3d (0 , 0 , 1 ), Eigen::Vector3d::Zero ());
115+
116+ // Intersect the rotation axis of the next joint with the XY-Plane.
117+ // * The intersection_param is the length moving along the rotation axis until intersecting the plane.
118+ // * The intersection point will be used for calculating the new angle theta.
119+ double intersection_param = next_rotation_axis.intersectionParameter (plane);
120+ Eigen::Vector3d intersection_point = next_rotation_axis.intersectionPoint (plane);
121+
122+ // A non-zero a parameter will result in an intersection point at (a, 0) even without any
123+ // additional rotations. This effect has to be subtracted from the resulting theta value.
124+ double subtraction_angle = 0.0 ;
125+ if (std::abs (a) > 0 ) {
126+ // This is pi
127+ subtraction_angle = atan (1 ) * 4 ;
128+ }
129+ double new_theta = std::atan2 (intersection_point.y (), intersection_point.x ()) - subtraction_angle;
116130 // Upper and lower arm segments on URs all have negative length due to dh params
117- double new_length = -1 * intersection.norm ();
118- RCLCPP_DEBUG_STREAM (rclcpp::get_logger (" ur_calibration" ), " Wrist line intersecting at " << std::endl << intersection);
131+ double new_link_length = -1 * intersection_point.norm ();
132+ RCLCPP_DEBUG_STREAM (rclcpp::get_logger (" ur_calibration" ), " Next joint's rotation axis intersecting at "
133+ << std::endl
134+ << intersection_point);
119135 RCLCPP_DEBUG_STREAM (rclcpp::get_logger (" ur_calibration" ), " Angle is " << new_theta);
120- RCLCPP_DEBUG_STREAM (rclcpp::get_logger (" ur_calibration" ), " Length is " << new_length );
136+ RCLCPP_DEBUG_STREAM (rclcpp::get_logger (" ur_calibration" ), " Length is " << new_link_length );
121137 RCLCPP_DEBUG_STREAM (rclcpp::get_logger (" ur_calibration" ), " Intersection param is " << intersection_param);
122138
123139 // as we move the passive segment towards the first segment, we have to move away the next segment
124140 // again, to keep the same kinematic structure.
125- double sign_dir = next_line .direction ().z () > 0 ? 1.0 : -1.0 ;
141+ double sign_dir = next_rotation_axis .direction ().z () > 0 ? 1.0 : -1.0 ;
126142 double distance_correction = intersection_param * sign_dir;
127143
128144 // Set d parameter of the first segment to 0 and theta to the calculated new angle
129145 // Correct arm segment length and angle
130- chain_[2 * link_index](2 , 3 ) = 0.0 ;
131- chain_[2 * link_index].topLeftCorner (3 , 3 ) =
132- Eigen::AngleAxisd (new_theta, Eigen::Vector3d::UnitZ ()).toRotationMatrix ();
146+ d = 0.0 ;
147+ d_theta_segment.topLeftCorner (3 , 3 ) = Eigen::AngleAxisd (new_theta, Eigen::Vector3d::UnitZ ()).toRotationMatrix ();
133148
134149 // Correct arm segment length and angle
135- chain_[ 2 * link_index + 1 ]( 0 , 3 ) = new_length ;
136- chain_[ 2 * link_index + 1 ] .topLeftCorner (3 , 3 ) =
150+ a = new_link_length ;
151+ a_alpha_segment .topLeftCorner (3 , 3 ) =
137152 Eigen::AngleAxisd (robot_parameters_.segments_ [link_index].theta_ - new_theta, Eigen::Vector3d::UnitZ ())
138153 .toRotationMatrix () *
139154 Eigen::AngleAxisd (robot_parameters_.segments_ [link_index].alpha_ , Eigen::Vector3d::UnitX ()).toRotationMatrix ();
140155
141- // Correct next joint
156+ // Correct next joint's d parameter
142157 chain_[2 * link_index + 2 ](2 , 3 ) -= distance_correction;
143158}
144159
0 commit comments