@@ -45,29 +45,52 @@ math::RigidTransform<T> PiecewiseConstantCurvatureTrajectory<T>::CalcPose(
45
45
const T& s) const {
46
46
const T w = maybe_wrap (s);
47
47
int segment_index = this ->get_segment_index (w);
48
- const math::RigidTransform<T> X_FiF =
48
+ const math::RigidTransform<T> X_MiM =
49
49
CalcRelativePoseInSegment (segment_turning_rates_[segment_index],
50
50
w - this ->start_time (segment_index));
51
- return segment_start_poses_[segment_index] * X_FiF;
51
+ return segment_start_poses_[segment_index] * X_MiM; // = X_AM
52
52
}
53
53
54
54
template <typename T>
55
55
multibody::SpatialVelocity<T>
56
56
PiecewiseConstantCurvatureTrajectory<T>::CalcSpatialVelocity(
57
57
const T& s, const T& s_dot) const {
58
58
const T w = maybe_wrap (s);
59
- const math::RotationMatrix<T> R_AF = CalcPose (w).rotation ();
59
+ const math::RotationMatrix<T> R_AM = CalcPose (w).rotation ();
60
60
const T& rho_i = segment_turning_rates_[this ->get_segment_index (w)];
61
61
62
62
multibody::SpatialVelocity<T> spatial_velocity;
63
63
// From Frenet–Serret analysis and the class doc for
64
64
// PiecewiseConstantCurvatureTrajectory, the rotational velocity is equal to
65
- // the Darboux vector times the tangential velocity: ρ⋅Fz⋅ds/dt.
66
- spatial_velocity.rotational () = rho_i * R_AF.col (kPlaneNormalIndex ) * s_dot;
65
+ // the Darboux vector (plane normal p̂ (= Mz)) times the tangential velocity:
66
+ // ρ⋅Mz⋅ds/dt.
67
+ spatial_velocity.rotational () = rho_i * R_AM.col (kPlaneNormalIndex ) * s_dot;
67
68
68
69
// The translational velocity is equal to the tangent direction times the
69
- // tangential velocity: dr(s)/dt = t̂(s)⋅ds/dt = Fx(s)⋅ds/dt.
70
- spatial_velocity.translational () = R_AF.col (kCurveTangentIndex ) * s_dot;
70
+ // tangential velocity: dr(s)/dt = t̂(s)⋅ds/dt = Mx(s)⋅ds/dt.
71
+ spatial_velocity.translational () = R_AM.col (kCurveTangentIndex ) * s_dot;
72
+
73
+ return spatial_velocity;
74
+ }
75
+
76
+ template <typename T>
77
+ multibody::SpatialVelocity<T>
78
+ PiecewiseConstantCurvatureTrajectory<T>::CalcSpatialVelocityInM(
79
+ const T& s, const T& s_dot) const {
80
+ const T w = maybe_wrap (s);
81
+ const T& rho_i = segment_turning_rates_[this ->get_segment_index (w)];
82
+
83
+ multibody::SpatialVelocity<T> spatial_velocity;
84
+ // From Frenet–Serret analysis and the class doc for
85
+ // PiecewiseConstantCurvatureTrajectory, the rotational velocity is equal to
86
+ // the Darboux vector (plane normal p̂ (= Mz)) times the tangential velocity:
87
+ // ρ⋅Mz⋅ds/dt. But Mz expressed in M is just [0 0 1].
88
+ spatial_velocity.rotational () = Vector3<T>(0 , 0 , rho_i * s_dot);
89
+
90
+ // The translational velocity is equal to the tangent direction times the
91
+ // tangential velocity: dr(s)/dt = t̂(s)⋅ds/dt = Mx(s)⋅ds/dt. But Mx
92
+ // expressed in M is just [1 0 0].
93
+ spatial_velocity.translational () = Vector3<T>(s_dot, 0 , 0 );
71
94
72
95
return spatial_velocity;
73
96
}
@@ -77,28 +100,56 @@ multibody::SpatialAcceleration<T>
77
100
PiecewiseConstantCurvatureTrajectory<T>::CalcSpatialAcceleration(
78
101
const T& s, const T& s_dot, const T& s_ddot) const {
79
102
const T w = maybe_wrap (s);
80
- const math::RotationMatrix<T> R_AF = CalcPose (w).rotation ();
103
+ const math::RotationMatrix<T> R_AM = CalcPose (w).rotation ();
81
104
const T& rho_i = segment_turning_rates_[this ->get_segment_index (w)];
82
105
83
106
// The spatial acceleration is the time derivative of the spatial velocity.
84
107
// We compute the acceleration by applying the chain rule to the formulas
85
108
// in CalcSpatialVelocity.
86
109
multibody::SpatialAcceleration<T> spatial_acceleration;
87
110
88
- // The angular velocity is ρᵢ⋅Fz ⋅ds/dt. As Fz and ρᵢ are constant
89
- // everywhere except the breaks, the angular acceleration is then equal to
90
- // ρᵢ⋅Fz ⋅d²s/dt².
111
+ // The angular velocity is ρᵢ⋅Mz ⋅ds/dt. As Mz is constant everywhere, and ρᵢ
112
+ // constant everywhere except the breaks, the angular acceleration is then
113
+ // equal to ρᵢ⋅Mz ⋅d²s/dt².
91
114
spatial_acceleration.rotational () =
92
- rho_i * R_AF.col (kPlaneNormalIndex ) * s_ddot;
115
+ rho_i * R_AM.col (kPlaneNormalIndex ) * s_ddot;
116
+
117
+ // The translational velocity is dr(s)/dt = Mx(s)⋅ds/dt. Thus by product and
118
+ // chain rule, the translational acceleration is:
119
+ // a(s) = d²r(s)/ds² = dMx(s)/ds⋅(ds/dt)² + Mx⋅d²s/dt².
120
+ // From the class doc, we know dMx/ds = ρᵢ⋅My.
121
+ // Thus the translational acceleration is a(s) = ρᵢ⋅My⋅(ds/dt)² + Mx⋅d²s/dt².
122
+ spatial_acceleration.translational () =
123
+ rho_i * R_AM.col (kCurveNormalIndex ) * s_dot * s_dot +
124
+ R_AM.col (kCurveTangentIndex ) * s_ddot;
125
+ return spatial_acceleration;
126
+ }
127
+
128
+ template <typename T>
129
+ multibody::SpatialAcceleration<T>
130
+ PiecewiseConstantCurvatureTrajectory<T>::CalcSpatialAccelerationInM(
131
+ const T& s, const T& s_dot, const T& s_ddot) const {
132
+ const T w = maybe_wrap (s);
133
+ const T& rho_i = segment_turning_rates_[this ->get_segment_index (w)];
134
+
135
+ // The spatial acceleration is the time derivative of the spatial velocity.
136
+ // We compute the acceleration by applying the chain rule to the formulas
137
+ // in CalcSpatialVelocity.
138
+ multibody::SpatialAcceleration<T> spatial_acceleration;
139
+
140
+ // The angular velocity is ρᵢ⋅Mz⋅ds/dt. As Mz is constant everywyere, and ρᵢ
141
+ // constant everywhere except the breaks, the angular acceleration is then
142
+ // equal to ρᵢ⋅Mz⋅d²s/dt². But Mz expressed in M is just [0 0 1].
143
+ spatial_acceleration.rotational () = Vector3<T>(0 , 0 , rho_i * s_ddot);
93
144
94
- // The translational velocity is dr(s)/dt = Fx (s)⋅ds/dt. Thus by product and
145
+ // The translational velocity is dr(s)/dt = Mx (s)⋅ds/dt. Thus by product and
95
146
// chain rule, the translational acceleration is:
96
- // a(s) = d²r(s)/ds² = dFx(s)/ds⋅(ds/dt)² + Fx⋅d²s/dt².
97
- // From the class doc, we know dFx/ds = ρᵢ⋅Fy.
98
- // Thus the translational acceleration is a(s) = ρᵢ⋅Fy⋅(ds/dt)² + Fx⋅d²s/dt².
147
+ // a(s) = d²r(s)/ds² = dMx(s)/ds⋅(ds/dt)² + Mx⋅d²s/dt².
148
+ // From the class doc, we know dMx/ds = ρᵢ⋅My.
149
+ // Thus the translational acceleration is a(s) = ρᵢ⋅My⋅(ds/dt)² + Mx⋅d²s/dt².
150
+ // Expressed in M, Mx=[1 0 0] and My=[0 1 0].
99
151
spatial_acceleration.translational () =
100
- rho_i * R_AF.col (kCurveNormalIndex ) * s_dot * s_dot +
101
- R_AF.col (kCurveTangentIndex ) * s_ddot;
152
+ Vector3<T>(s_ddot, rho_i * s_dot * s_dot, 0 );
102
153
return spatial_acceleration;
103
154
}
104
155
@@ -123,23 +174,23 @@ template <typename T>
123
174
math::RigidTransform<T>
124
175
PiecewiseConstantCurvatureTrajectory<T>::CalcRelativePoseInSegment(
125
176
const T& rho_i, const T& ds) {
126
- Vector3<T> p_FioFo_Fi = Vector3<T>::Zero ();
177
+ Vector3<T> p_MioMo_Mi = Vector3<T>::Zero ();
127
178
// Calculate rotation angle.
128
179
const T theta = ds * rho_i;
129
- math::RotationMatrix<T> R_FiF = math::RotationMatrix<T>::MakeZRotation (theta);
180
+ math::RotationMatrix<T> R_MiM = math::RotationMatrix<T>::MakeZRotation (theta);
130
181
if (rho_i == T (0 )) {
131
182
// Case 1: zero curvature (straight line)
132
183
//
133
- // The tangent axis is constant, thus the displacement p_FioFo_Fi is just
184
+ // The tangent axis is constant, thus the displacement p_MioMo_Mi is just
134
185
// t̂_Fi⋅Δs.
135
- p_FioFo_Fi (kCurveTangentIndex ) = ds;
186
+ p_MioMo_Mi (kCurveTangentIndex ) = ds;
136
187
} else {
137
188
// Case 2: non-zero curvature (circular arc)
138
189
//
139
- // The entire trajectory lies in a plane with normal Fiz , and thus
140
- // the arc is embedded in the Fix-Fiy plane.
190
+ // The entire trajectory lies in a plane with normal Miz , and thus
191
+ // the arc is embedded in the Mix-Miy plane.
141
192
//
142
- // Fiy
193
+ // Miy
143
194
// ↑
144
195
// C o x
145
196
// │\ x
@@ -148,31 +199,31 @@ PiecewiseConstantCurvatureTrajectory<T>::CalcRelativePoseInSegment(
148
199
// │ \ x
149
200
// │ \ x
150
201
// │ \ xx
151
- // │ p_Fo ox
202
+ // │ p_Mo ox
152
203
// │ xxx
153
- // └xxx───────────────→ Fix
154
- // p_Fio
204
+ // └xxx───────────────→ Mix
205
+ // p_Mio
155
206
//
156
- // The circular arc's centerpoint C is located at p_FioC = (1/ρᵢ)⋅Fiy ,
157
- // with initial direction Fix and radius abs(1/ρᵢ). Thus the angle traveled
207
+ // The circular arc's centerpoint C is located at p_MioC = (1/ρᵢ)⋅Miy ,
208
+ // with initial direction Mix and radius abs(1/ρᵢ). Thus the angle traveled
158
209
// along the arc is θ = ρᵢ⋅Δs, with the sign of ρᵢ handling the
159
210
// clockwise/counterclockwise direction. The ρᵢ > 0 case is shown above.
160
- p_FioFo_Fi (kCurveNormalIndex ) = (T (1 ) - cos (theta)) / rho_i;
161
- p_FioFo_Fi (kCurveTangentIndex ) = sin (theta) / rho_i;
211
+ p_MioMo_Mi (kCurveNormalIndex ) = (T (1 ) - cos (theta)) / rho_i;
212
+ p_MioMo_Mi (kCurveTangentIndex ) = sin (theta) / rho_i;
162
213
}
163
- return math::RigidTransform<T>(R_FiF, p_FioFo_Fi );
214
+ return math::RigidTransform<T>(R_MiM, p_MioMo_Mi );
164
215
}
165
216
166
217
template <typename T>
167
218
math::RigidTransform<T>
168
219
PiecewiseConstantCurvatureTrajectory<T>::MakeInitialPose(
169
220
const Vector3<T>& initial_curve_tangent, const Vector3<T>& plane_normal,
170
221
const Vector3<T>& initial_position) {
171
- const Vector3<T> initial_Fy_A = plane_normal.cross (initial_curve_tangent);
172
- const auto R_WF = math::RotationMatrix<T>::MakeFromOrthonormalColumns (
173
- initial_curve_tangent.normalized (), initial_Fy_A .normalized (),
222
+ const Vector3<T> initial_My_A = plane_normal.cross (initial_curve_tangent);
223
+ const auto R_AM = math::RotationMatrix<T>::MakeFromOrthonormalColumns (
224
+ initial_curve_tangent.normalized (), initial_My_A .normalized (),
174
225
plane_normal.normalized ());
175
- return math::RigidTransform<T>(R_WF , initial_position);
226
+ return math::RigidTransform<T>(R_AM , initial_position);
176
227
}
177
228
178
229
template <typename T>
@@ -195,9 +246,9 @@ PiecewiseConstantCurvatureTrajectory<T>::MakeSegmentStartPoses(
195
246
segment_start_poses.push_back (initial_pose);
196
247
197
248
for (size_t i = 0 ; i < (num_segments - 1 ); i++) {
198
- math::RigidTransform<T> X_FiFip1 =
249
+ math::RigidTransform<T> X_MiMip1 =
199
250
CalcRelativePoseInSegment (turning_rates[i], segment_durations[i]);
200
- segment_start_poses.push_back (segment_start_poses.back () * X_FiFip1 );
251
+ segment_start_poses.push_back (segment_start_poses.back () * X_MiMip1 );
201
252
}
202
253
203
254
return segment_start_poses;
0 commit comments