Skip to content

Commit 0c3357a

Browse files
committed
Working on M frame methods for curvilinear mobilizer.
1 parent bf578b2 commit 0c3357a

File tree

2 files changed

+94
-43
lines changed

2 files changed

+94
-43
lines changed

common/trajectories/piecewise_constant_curvature_trajectory.cc

Lines changed: 90 additions & 39 deletions
Original file line numberDiff line numberDiff line change
@@ -45,29 +45,52 @@ 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 {
5858
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();
6060
const T& rho_i = segment_turning_rates_[this->get_segment_index(w)];
6161

6262
multibody::SpatialVelocity<T> spatial_velocity;
6363
// From Frenet–Serret analysis and the class doc for
6464
// 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;
6768

6869
// 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);
7194

7295
return spatial_velocity;
7396
}
@@ -77,28 +100,56 @@ multibody::SpatialAcceleration<T>
77100
PiecewiseConstantCurvatureTrajectory<T>::CalcSpatialAcceleration(
78101
const T& s, const T& s_dot, const T& s_ddot) const {
79102
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();
81104
const T& rho_i = segment_turning_rates_[this->get_segment_index(w)];
82105

83106
// The spatial acceleration is the time derivative of the spatial velocity.
84107
// We compute the acceleration by applying the chain rule to the formulas
85108
// in CalcSpatialVelocity.
86109
multibody::SpatialAcceleration<T> spatial_acceleration;
87110

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².
91114
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);
93144

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
95146
// 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].
99151
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);
102153
return spatial_acceleration;
103154
}
104155

@@ -123,23 +174,23 @@ template <typename T>
123174
math::RigidTransform<T>
124175
PiecewiseConstantCurvatureTrajectory<T>::CalcRelativePoseInSegment(
125176
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();
127178
// Calculate rotation angle.
128179
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);
130181
if (rho_i == T(0)) {
131182
// Case 1: zero curvature (straight line)
132183
//
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
134185
// t̂_Fi⋅Δs.
135-
p_FioFo_Fi(kCurveTangentIndex) = ds;
186+
p_MioMo_Mi(kCurveTangentIndex) = ds;
136187
} else {
137188
// Case 2: non-zero curvature (circular arc)
138189
//
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.
141192
//
142-
// Fiy
193+
// Miy
143194
//
144195
// C o x
145196
// │\ x
@@ -148,31 +199,31 @@ PiecewiseConstantCurvatureTrajectory<T>::CalcRelativePoseInSegment(
148199
// │ \ x
149200
// │ \ x
150201
// │ \ xx
151-
//p_Fo ox
202+
//p_Mo ox
152203
// │ xxx
153-
// └xxx───────────────→ Fix
154-
// p_Fio
204+
// └xxx───────────────→ Mix
205+
// p_Mio
155206
//
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
158209
// along the arc is θ = ρᵢ⋅Δs, with the sign of ρᵢ handling the
159210
// 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;
162213
}
163-
return math::RigidTransform<T>(R_FiF, p_FioFo_Fi);
214+
return math::RigidTransform<T>(R_MiM, p_MioMo_Mi);
164215
}
165216

166217
template <typename T>
167218
math::RigidTransform<T>
168219
PiecewiseConstantCurvatureTrajectory<T>::MakeInitialPose(
169220
const Vector3<T>& initial_curve_tangent, const Vector3<T>& plane_normal,
170221
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(),
174225
plane_normal.normalized());
175-
return math::RigidTransform<T>(R_WF, initial_position);
226+
return math::RigidTransform<T>(R_AM, initial_position);
176227
}
177228

178229
template <typename T>
@@ -195,9 +246,9 @@ PiecewiseConstantCurvatureTrajectory<T>::MakeSegmentStartPoses(
195246
segment_start_poses.push_back(initial_pose);
196247

197248
for (size_t i = 0; i < (num_segments - 1); i++) {
198-
math::RigidTransform<T> X_FiFip1 =
249+
math::RigidTransform<T> X_MiMip1 =
199250
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);
201252
}
202253

203254
return segment_start_poses;

common/trajectories/piecewise_constant_curvature_trajectory.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -96,17 +96,17 @@ class PiecewiseConstantCurvatureTrajectory final
9696
the same reference frame A.
9797
9898
The `initial_curve_tangent` t̂₀ and the `plane_normal` p̂, along with the
99-
inital curve's normal n̂₀ = p̂ × t̂₀, define the initial orientation R_AM₀ of
99+
initial curve's normal n̂₀ = p̂ × t̂₀, define the initial orientation R_AM₀ of
100100
frame M at s = 0.
101101
102102
@param breaks A vector of n break values sᵢ between segments. The parent
103103
class, PiecewiseTrajectory, enforces that the breaks increase by at least
104104
PiecewiseTrajectory::kEpsilonTime.
105105
@param turning_rates A vector of n-1 turning rates ρᵢ for each segment.
106106
@param initial_curve_tangent The initial tangent of the curve expressed in
107-
the parent frame, t̂_A(s₀).
107+
the parent frame, t̂_A(s₀) = Mx_A(s₀).
108108
@param plane_normal The normal axis of the 2D plane in which the curve
109-
lies, expressed in the parent frame, p̂_A.
109+
lies, expressed in the parent frame, p̂_A = Mz_A (constant).
110110
@param initial_position The initial position of the curve expressed in
111111
the parent frame, p_AoMo_A(s₀).
112112
@param periodicity_tolerance Tolerance used to determine if the resulting
@@ -234,7 +234,7 @@ class PiecewiseConstantCurvatureTrajectory final
234234
multibody::SpatialAcceleration<T> CalcSpatialAcceleration(
235235
const T& s, const T& s_dot, const T& s_ddot) const;
236236

237-
/** Computes the spatial acceleration A_AM_A(s,ṡ,s̈) of frame M measured in
237+
/** Computes the spatial acceleration A_AM_M(s,ṡ,s̈) of frame M measured in
238238
frame A but expressed in frame M.
239239
240240
See CalcSpatialAcceleration() for details. Note that when expressed in frame

0 commit comments

Comments
 (0)