Skip to content

Commit 3a8bfa1

Browse files
committed
Adds M-frame methods for curvilinear mobilizer.
1 parent acf4541 commit 3a8bfa1

8 files changed

+360
-152
lines changed

common/trajectories/piecewise_constant_curvature_trajectory.cc

Lines changed: 63 additions & 48 deletions
Original file line numberDiff line numberDiff line change
@@ -45,61 +45,75 @@ math::RigidTransform<T> PiecewiseConstantCurvatureTrajectory<T>::CalcPose(
4545
const T& s) const {
4646
const T w = maybe_wrap(s);
4747
int segment_index = this->get_segment_index(w);
48-
const math::RigidTransform<T> X_FiF =
48+
const math::RigidTransform<T> X_MiM =
4949
CalcRelativePoseInSegment(segment_turning_rates_[segment_index],
5050
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
5252
}
5353

5454
template <typename T>
5555
multibody::SpatialVelocity<T>
5656
PiecewiseConstantCurvatureTrajectory<T>::CalcSpatialVelocity(
5757
const T& s, const T& s_dot) const {
58-
const T w = maybe_wrap(s);
59-
const math::RotationMatrix<T> R_AF = CalcPose(w).rotation();
60-
const T& rho_i = segment_turning_rates_[this->get_segment_index(w)];
58+
const math::RotationMatrix<T> R_AM = CalcPose(s).rotation();
59+
return R_AM * CalcSpatialVelocityInM(s, s_dot); // V_AM_A
60+
}
61+
62+
template <typename T>
63+
multibody::SpatialVelocity<T>
64+
PiecewiseConstantCurvatureTrajectory<T>::CalcSpatialVelocityInM(
65+
const T& s, const T& s_dot) const {
66+
const T& rho_i = curvature(s);
6167

6268
multibody::SpatialVelocity<T> spatial_velocity;
6369
// From Frenet–Serret analysis and the class doc for
6470
// 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;
71+
// the Darboux vector (plane normal p̂ (= Mz)) times the tangential velocity:
72+
// ρ⋅Mz⋅ds/dt. But Mz expressed in M is just [0 0 1].
73+
spatial_velocity.rotational() = Vector3<T>(0, 0, rho_i * s_dot);
6774

6875
// 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;
76+
// tangential velocity: dr(s)/dt = t̂(s)⋅ds/dt = Mx(s)⋅ds/dt. But Mx
77+
// expressed in M is just [1 0 0].
78+
spatial_velocity.translational() = Vector3<T>(s_dot, 0, 0);
7179

72-
return spatial_velocity;
80+
return spatial_velocity; // V_AM_M
7381
}
7482

7583
template <typename T>
7684
multibody::SpatialAcceleration<T>
7785
PiecewiseConstantCurvatureTrajectory<T>::CalcSpatialAcceleration(
7886
const T& s, const T& s_dot, const T& s_ddot) const {
79-
const T w = maybe_wrap(s);
80-
const math::RotationMatrix<T> R_AF = CalcPose(w).rotation();
81-
const T& rho_i = segment_turning_rates_[this->get_segment_index(w)];
87+
const math::RotationMatrix<T> R_AM = CalcPose(s).rotation();
88+
return R_AM * CalcSpatialAccelerationInM(s, s_dot, s_ddot);
89+
}
90+
91+
template <typename T>
92+
multibody::SpatialAcceleration<T>
93+
PiecewiseConstantCurvatureTrajectory<T>::CalcSpatialAccelerationInM(
94+
const T& s, const T& s_dot, const T& s_ddot) const {
95+
const T& rho_i = curvature(s);
8296

8397
// The spatial acceleration is the time derivative of the spatial velocity.
8498
// We compute the acceleration by applying the chain rule to the formulas
8599
// in CalcSpatialVelocity.
86100
multibody::SpatialAcceleration<T> spatial_acceleration;
87101

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².
91-
spatial_acceleration.rotational() =
92-
rho_i * R_AF.col(kPlaneNormalIndex) * s_ddot;
102+
// The angular velocity is ρᵢ⋅Mz⋅ds/dt. As Mz is constant everywyere, and ρᵢ
103+
// constant everywhere except the breaks, the angular acceleration is then
104+
// equal to ρᵢ⋅Mz⋅d²s/dt². But Mz expressed in M is just [0 0 1].
105+
spatial_acceleration.rotational() = Vector3<T>(0, 0, rho_i * s_ddot);
93106

94-
// The translational velocity is dr(s)/dt = Fx(s)⋅ds/dt. Thus by product and
107+
// The translational velocity is dr(s)/dt = Mx(s)⋅ds/dt. Thus by product and
95108
// 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².
109+
// a(s) = d²r(s)/ds² = dMx(s)/ds⋅(ds/dt)² + Mx⋅d²s/dt².
110+
// From the class doc, we know dMx/ds = ρᵢ⋅My.
111+
// Thus the translational acceleration is a(s) = ρᵢ⋅My⋅(ds/dt)² + Mx⋅d²s/dt².
112+
// But expressed in M, Mx=[1 0 0] and My=[0 1 0].
99113
spatial_acceleration.translational() =
100-
rho_i * R_AF.col(kCurveNormalIndex) * s_dot * s_dot +
101-
R_AF.col(kCurveTangentIndex) * s_ddot;
102-
return spatial_acceleration;
114+
Vector3<T>(s_ddot, rho_i * s_dot * s_dot, 0);
115+
116+
return spatial_acceleration; // A_AM_M
103117
}
104118

105119
template <typename T>
@@ -123,23 +137,23 @@ template <typename T>
123137
math::RigidTransform<T>
124138
PiecewiseConstantCurvatureTrajectory<T>::CalcRelativePoseInSegment(
125139
const T& rho_i, const T& ds) {
126-
Vector3<T> p_FioFo_Fi = Vector3<T>::Zero();
140+
Vector3<T> p_MioMo_Mi = Vector3<T>::Zero();
127141
// Calculate rotation angle.
128142
const T theta = ds * rho_i;
129-
math::RotationMatrix<T> R_FiF = math::RotationMatrix<T>::MakeZRotation(theta);
143+
math::RotationMatrix<T> R_MiM = math::RotationMatrix<T>::MakeZRotation(theta);
130144
if (rho_i == T(0)) {
131145
// Case 1: zero curvature (straight line)
132146
//
133-
// The tangent axis is constant, thus the displacement p_FioFo_Fi is just
147+
// The tangent axis is constant, thus the displacement p_MioMo_Mi is just
134148
// t̂_Fi⋅Δs.
135-
p_FioFo_Fi(kCurveTangentIndex) = ds;
149+
p_MioMo_Mi(kCurveTangentIndex) = ds;
136150
} else {
137151
// Case 2: non-zero curvature (circular arc)
138152
//
139-
// The entire trajectory lies in a plane with normal Fiz, and thus
140-
// the arc is embedded in the Fix-Fiy plane.
153+
// The entire trajectory lies in a plane with normal Miz, and thus
154+
// the arc is embedded in the Mix-Miy plane.
141155
//
142-
// Fiy
156+
// Miy
143157
//
144158
// C o x
145159
// │\ x
@@ -148,31 +162,31 @@ PiecewiseConstantCurvatureTrajectory<T>::CalcRelativePoseInSegment(
148162
// │ \ x
149163
// │ \ x
150164
// │ \ xx
151-
//p_Fo ox
165+
//p_Mo ox
152166
// │ xxx
153-
// └xxx───────────────→ Fix
154-
// p_Fio
167+
// └xxx───────────────→ Mix
168+
// p_Mio
155169
//
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
170+
// The circular arc's centerpoint C is located at p_MioC = (1/ρᵢ)⋅Miy,
171+
// with initial direction Mix and radius abs(1/ρᵢ). Thus the angle traveled
158172
// along the arc is θ = ρᵢ⋅Δs, with the sign of ρᵢ handling the
159173
// 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;
174+
p_MioMo_Mi(kCurveNormalIndex) = (T(1) - cos(theta)) / rho_i;
175+
p_MioMo_Mi(kCurveTangentIndex) = sin(theta) / rho_i;
162176
}
163-
return math::RigidTransform<T>(R_FiF, p_FioFo_Fi);
177+
return math::RigidTransform<T>(R_MiM, p_MioMo_Mi);
164178
}
165179

166180
template <typename T>
167181
math::RigidTransform<T>
168182
PiecewiseConstantCurvatureTrajectory<T>::MakeInitialPose(
169183
const Vector3<T>& initial_curve_tangent, const Vector3<T>& plane_normal,
170184
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(),
185+
const Vector3<T> initial_My_A = plane_normal.cross(initial_curve_tangent);
186+
const auto R_AM = math::RotationMatrix<T>::MakeFromOrthonormalColumns(
187+
initial_curve_tangent.normalized(), initial_My_A.normalized(),
174188
plane_normal.normalized());
175-
return math::RigidTransform<T>(R_WF, initial_position);
189+
return math::RigidTransform<T>(R_AM, initial_position); // X_AM
176190
}
177191

178192
template <typename T>
@@ -192,12 +206,13 @@ PiecewiseConstantCurvatureTrajectory<T>::MakeSegmentStartPoses(
192206
// Build frames for the start of each segment.
193207
std::vector<math::RigidTransform<T>> segment_start_poses;
194208
segment_start_poses.reserve(num_segments);
195-
segment_start_poses.push_back(initial_pose);
209+
segment_start_poses.push_back(initial_pose); // X_AM(0)
196210

197-
for (size_t i = 0; i < (num_segments - 1); i++) {
198-
math::RigidTransform<T> X_FiFip1 =
211+
for (size_t i = 0; i < (num_segments - 1); ++i) {
212+
math::RigidTransform<T> X_MiMip1 =
199213
CalcRelativePoseInSegment(turning_rates[i], segment_durations[i]);
200-
segment_start_poses.push_back(segment_start_poses.back() * X_FiFip1);
214+
// X_AM(i+1)
215+
segment_start_poses.push_back(segment_start_poses.back() * X_MiMip1);
201216
}
202217

203218
return segment_start_poses;

0 commit comments

Comments
 (0)