diff --git a/.github/workflows/docker-action.yml b/.github/workflows/docker-action.yml index cd836b1c..f72bf9ec 100644 --- a/.github/workflows/docker-action.yml +++ b/.github/workflows/docker-action.yml @@ -21,7 +21,7 @@ jobs: fail-fast: false steps: - uses: actions/checkout@v2 - - uses: coq-community/docker-coq-action@v1 + - uses: rocq-community/docker-rocq-action@v1 with: opam_file: 'robot-rocq.opam' custom_image: ${{ matrix.image }} diff --git a/_CoqProject b/_CoqProject index 5c100751..8d0d5664 100644 --- a/_CoqProject +++ b/_CoqProject @@ -17,5 +17,17 @@ scara.v derive_matrix.v differential_kinematics.v extra_trigo.v +ode_common.v +ode_contseg.v +ode.v +lasalle.v +pendulum.v +tilt_mathcomp.v +tilt_analysis.v +tilt_robot.v +tilt_stability.v +tilt_lyapunov.v +tilt_lasalle.v + -R . robot diff --git a/derive_matrix.v b/derive_matrix.v index b73157b5..1c679a73 100644 --- a/derive_matrix.v +++ b/derive_matrix.v @@ -1,27 +1,31 @@ (* coq-robot (c) 2017 AIST and INRIA. License: LGPL-2.1-or-later. *) +From HB Require Import structures. From mathcomp Require Import all_ssreflect ssralg ssrint ssrnum rat. From mathcomp Require Import closed_field polyrcf matrix mxalgebra mxpoly zmodp. From mathcomp Require Import interval_inference. From mathcomp Require Import realalg complex fingroup perm. -From mathcomp Require Import sesquilinear. +From mathcomp Require Import sesquilinear ring. From mathcomp Require Import boolp reals classical_sets. -From mathcomp Require Import topology normedtype landau derive. +From mathcomp Require Import topology normedtype landau derive trigo. From mathcomp Require Import functions. Require Import ssr_ext euclidean rigid skew. -(******************************************************************************) -(* Derivatives of time-varying matrices *) +(**md**************************************************************************) +(* # Derivatives of time-varying matrices *) (* *) -(* derive1mx M(t) == the derivative matrix of M(t) *) -(* ang_vel_mx M == angular velocity matrix of M(t)              *) +(* ``` *) +(* derivable_mx M t v == pointwise derivability of matrices *) +(* ang_vel_mx M == angular velocity matrix of M(t) *) +(* ang_vel M t == angular velocity *) +(* ``` *) (* *) (******************************************************************************) Set Implicit Arguments. Unset Strict Implicit. Unset Printing Implicit Defensive. -Import Order.TTheory GRing.Theory Num.Def Num.Theory. +Import Order.TTheory GRing.Theory Num.Def Num.Theory. Import numFieldNormedType.Exports. Local Open Scope ring_scope. @@ -30,193 +34,420 @@ Lemma mx_lin1N (R : pzRingType) n (M : 'M[R]_n) : mx_lin1 (- M) = -1 \*: mx_lin1 M :> ( _ -> _). Proof. by rewrite funeqE => v /=; rewrite scaleN1r mulmxN. Qed. -Lemma mxE_funeqE (R : realFieldType) (V W : normedModType R) - n m (f : V -> 'I_n -> 'I_m -> W) i j : - (fun x => (\matrix_(i < n, j < m) (f x i j)) i j) = - (fun x => f x i j). -Proof. by rewrite funeqE => ?; rewrite mxE. Qed. - -Section Derive_lemmasVW. -Variables (R : numFieldType) (V W : normedModType R). -Implicit Types f g : V -> W. - -(* TODO: Fixme in MCA *) -Lemma derive_cst (k : W) (x v : V) : 'D_v (cst k) x = 0. -Proof. by rewrite derive_val. Qed. - -End Derive_lemmasVW. - -Lemma derive1_cst {R : numFieldType} (V : normedModType R) (k : V) t : ((cst k)^`() t)%classic = 0. -Proof. by rewrite derive1E derive_cst. Qed. - -Section derive_mx. +Import Order.Def. -Variable (R : realFieldType) (V W : normedModType R). - -Definition derivable_mx m n (M : R -> 'M[W]_(m, n)) t v := - forall i j, derivable (fun x : R^o => (M x) i j) t v. - -Definition derive1mx m n (M : R -> 'M[W]_(m, n)) := fun t => - \matrix_(i < m, j < n) (derive1 (fun x => M x i j) t : W). - -Lemma derive1mxE m n t (f : 'I_m -> 'I_n -> R -> W) : - derive1mx (fun x => \matrix_(i, j) f i j x) t = - \matrix_(i, j) (derive1 (f i j) t : W). +(* NB: added to be able to produce the following instance to be able to use bigop lemmas *) +Lemma nng_max0r {K : realFieldType} : left_id ((0:K)%:nng) (@maxr {nonneg K}). Proof. -rewrite /derive1mx; apply/matrixP => ? ?; rewrite !mxE; congr (derive1 _ t). -rewrite funeqE => ?; by rewrite mxE. +move=> x. +rewrite /max; case: ifPn => //. +rewrite -leNgt => x0. +apply/eqP; rewrite eq_le; apply/andP; split; last first. + exact: x0. +by have : 0 <= x%:nngnum by []. (* NB: this should be automatic *) Qed. -Variables m n : nat. -Implicit Types M N : R -> 'M[W]_(m, n). +(* TODO: backport to MCA *) +HB.instance Definition _ {K : realFieldType} := + Monoid.isComLaw.Build {nonneg K} 0%:nng max maxA maxC nng_max0r. -Lemma derivable_mxD M N t : derivable_mx M t 1 -> derivable_mx N t 1 -> - derivable_mx (fun x => M x + N x) t 1. +Lemma norm_trmx (R : realFieldType) m n (M : 'M[R]_(m, n)) : `|M^T| = `|M|. Proof. -move=> Hf Hg a b. evar (f1 : R -> W). evar (f2 : R -> W). -rewrite (_ : (fun x => _) = f1 + f2); last first. - rewrite funeqE => x; rewrite -[RHS]/(f1 x + f2 x) mxE /f1 /f2; reflexivity. -rewrite {}/f1 {}/f2; exact: derivableD. +rewrite [LHS]mx_normE/=. +under eq_bigr do rewrite mxE. +rewrite -(pair_big xpredT xpredT (fun i j => `|M j i|%:nng))/=. +by rewrite exchange_big//= pair_big. Qed. -Lemma derivable_mxN M t : derivable_mx M t 1 -> - derivable_mx (fun x => - M x) t 1. -Proof. -move=> HM a b. -rewrite (_ : (fun x => _) = (fun x => - (M x a b))); first exact: derivableN. -by rewrite funeqE => ?; rewrite mxE. -Qed. +Section pointwise_derivable. +Context {R : realFieldType} {V W : normedModType R} {m n : nat}. +Implicit Types M : V -> 'M[R]_(m, n). -Lemma derivable_mxB M N t : derivable_mx M t 1 -> derivable_mx N t 1 -> - derivable_mx (fun x => M x - N x) t 1. -Proof. move=> Hf Hg; apply derivable_mxD => //; exact: derivable_mxN. Qed. +Definition derivable_mx M t v := + forall i j, derivable (fun x => M x i j) t v. -Lemma trmx_derivable M t v : - derivable_mx M t v = derivable_mx (fun x => (M x)^T) t v. +Lemma derivable_mxP M t v : derivable_mx M t v <-> derivable M t v. Proof. -rewrite propeqE; split => [H j i|H i j]. -by rewrite (_ : (fun _ => _) = (fun x => M x i j)) // funeqE => z; rewrite mxE. -by rewrite (_ : (fun _ => _) = (fun x => (M x)^T j i)) // funeqE => z; rewrite mxE. -Qed. - -Lemma derivable_mx_row M t i : - derivable_mx M t 1 -> derivable_mx (row i \o M) t 1. +split; rewrite /derivable_mx /derivable. +- move=> H. + apply/cvg_ex => /=. + pose l := \matrix_(i < m, j < n) sval (cid ((cvg_ex _).1 (H i j))). + exists l. + apply/cvgrPdist_le => /= e e0. + near=> x. + rewrite /Num.Def.normr/= mx_normrE. + apply: (bigmax_le _ (ltW e0)) => /= i _. + rewrite !mxE/=. + move: i. + near: x. + apply: filter_forall => /= i. + exact: ((@cvgrPdist_le _ _ _ _ (dnbhs_filter 0) _ _).1 + (svalP (cid ((cvg_ex _).1 (H i.1 i.2)))) _ e0). +- move=> /cvg_ex[/= l Hl] i j. + apply/cvg_ex; exists (l i j). + apply/cvgrPdist_le => /= e e0. + move/cvgrPdist_le : Hl => /(_ _ e0)[/= r r0] H. + near=> x. + apply: le_trans; last first. + apply: (H x). + rewrite /ball_/=. + rewrite sub0r normrN. + near: x. + exact: dnbhs0_lt. + near: x. + exact: nbhs_dnbhs_neq. + rewrite [leRHS]/Num.Def.normr/= mx_normrE. + apply: le_trans; last exact: le_bigmax. + by rewrite /= !mxE. +Unshelve. all: by end_near. Qed. + +Lemma derivable_trmx M t v : + derivable (fun x => (M x)^T) t v = derivable M t v. Proof. -move=> H a b. -by rewrite (_ : (fun _ => _) = (fun x => (M x) i b)) // funeqE => z; rewrite mxE. -Qed. - -Lemma derivable_mx_col M t i : - derivable_mx M t 1 -> derivable_mx (trmx \o col i \o M) t 1. +rewrite propeqE; split; rewrite /derivable/=. +- move=> /cvg_ex[/= l Hl]. + apply/cvg_ex => /=; exists l^T. + apply/cvgrPdist_le => /= e e0. + move/cvgrPdist_le : Hl => /(_ _ e0)[/= r r0 re]. + near=> x. + rewrite [leLHS](_ : _ = + `|l - x^-1 *: ((M (x *: v + t))^T - (M t)^T)|); last first. + rewrite -[RHS]norm_trmx. + rewrite [in RHS]linearD/=. + rewrite [in RHS]linearN/=. + congr (`| _ - _ |). + rewrite [RHS]linearZ/=. + rewrite [in RHS]linearB. + by rewrite /= !trmxK. + apply: re => /=. + rewrite sub0r normrN. + by near: x; exact: dnbhs0_lt. + by near: x; exact: nbhs_dnbhs_neq. +- move=> /cvg_ex[/= l Hl]. + apply/cvg_ex => /=; exists l^T. + apply/cvgrPdist_le => /= e e0. + move/cvgrPdist_le : Hl => /(_ _ e0)[/= r r0 re]. + near=> x. + rewrite [leLHS](_ : _ = `|l - x^-1 *: ((M (x *: v + t)) - (M t))|); last first. + rewrite -[RHS]norm_trmx. + rewrite [in RHS]linearD/=. + rewrite [in RHS]linearN/=. + congr (`| _ - _ |). + rewrite [RHS]linearZ/=. + by rewrite [in RHS]linearB. + apply: re => /=. + rewrite sub0r normrN. + by near: x; exact: dnbhs0_lt. + by near: x; exact: nbhs_dnbhs_neq. +Unshelve. all: by end_near. Qed. + +Lemma derivable_coord (a : V -> 'rV[R]_n) t v (i : 'I_n) : + derivable a t v -> + derivable (fun x : V => (a x)``_i) t v. Proof. -move=> H a b. -by rewrite (_ : (fun _ => _) = (fun x => (M x) b i)) // funeqE => z; rewrite 2!mxE. +move=> /cvg_ex[/= l Hl]. +apply/cvg_ex; exists (l``_i) => /=. +apply/cvgrPdist_le => /= e e0. +move/cvgrPdist_le : Hl => /(_ _ e0) Hl. +apply: filterS Hl => x. +rewrite {1}/Num.Def.normr/= mx_normrE. +move/bigmax_leP => -[_/=] /(_ (ord0, i)). +by rewrite !mxE/=; exact. Qed. -Lemma derivable_mx_cst (P : 'M[W]_(m, n)) t : derivable_mx (cst P) t 1. -Proof. move=> a b; by rewrite (_ : (fun x : R => _) = cst (P a b)). Qed. +End pointwise_derivable. +Section pointwise_derivable_TODO. (* TODO: generalize n/m+1 -> n/m*) +Context {R : realFieldType} {V W : normedModType R} {m n : nat}. +Implicit Types M : V -> 'M[R]_(m.+1, n.+1). -Lemma derive1mx_cst (P : 'M[W]_(m, n)) : derive1mx (cst P) = cst 0. +Lemma derivable_row M t v i : derivable M t v -> derivable (row i \o M) t v. Proof. -rewrite /derive1mx funeqE => t; apply/matrixP => i j; rewrite !mxE. -by rewrite (_ : (fun x : R => _) = cst (P i j)) // derive1_cst. -Qed. - -Lemma derive1mx_tr M t : derive1mx (trmx \o M) t = (derive1mx M t)^T. +rewrite /derivable => /cvg_ex[/= l Hl]. +apply/cvg_ex => /=. +exists (row i l). +apply/cvgrPdist_le => /= e e0. +move/cvgrPdist_le : Hl => /(_ _ e0)[r /= r0 re]. +near=> x. +apply: le_trans; last first. + apply: (re x). + rewrite /ball_ /= sub0r normrN. + by near: x; exact: dnbhs0_lt. + by near: x; exact: nbhs_dnbhs_neq. +rewrite /Num.Def.normr/= !mx_normrE. +apply/bigmax_leP => /=. +split. + exact: le_trans (le_bigmax _ _ (ord0, ord0)). +move=> j _. +rewrite !mxE. +under eq_bigr do rewrite !mxE. +exact: le_trans (le_bigmax _ _ (i, j.2)). +Unshelve. all: by end_near. Qed. + +Lemma derivable_col M t v i : derivable M t v -> derivable (col i \o M) t v. +Proof. +rewrite /derivable => /cvg_ex[/= l Hl]. +apply/cvg_ex => /=. +exists (col i l). +apply/cvgrPdist_le => /= e e0. +move/cvgrPdist_le : Hl => /(_ _ e0)[r /= r0 re]. +near=> x. +apply: le_trans; last first. + apply: (re x). + rewrite /ball_ /= sub0r normrN. + by near: x; exact: dnbhs0_lt. + by near: x; exact: nbhs_dnbhs_neq. +rewrite /Num.Def.normr/= !mx_normrE. +apply/bigmax_leP => /=. +split. + exact: le_trans (le_bigmax _ _ (ord0, ord0)). +move=> j _. +rewrite !mxE. +under eq_bigr do rewrite !mxE. +exact: le_trans (le_bigmax _ _ (j.1, i)). +Unshelve. all: by end_near. Qed. + +Lemma derivable_row3 (a b c : V -> R) t v : + derivable a t v -> derivable b t v -> derivable c t v -> + derivable (fun x => row3 (a x) (b x) (c x)) t v. Proof. +move=> /cvg_ex[/= l Hl] /cvg_ex[/= o Ho] /cvg_ex[/= p Hp]. +apply/cvg_ex; exists (row3 l o p) => /=. +apply/cvgrPdist_le => /= e e0. +move/cvgrPdist_le : Hl => /(_ _ e0)[r/= r0 re]. +move/cvgrPdist_le : Ho => /(_ _ e0)[s/= s0 se]. +move/cvgrPdist_le : Hp => /(_ _ e0)[u/= u0 ue]. +near=> x. +rewrite /Num.Def.normr/= mx_normrE. +apply: bigmax_le. + exact: ltW. +move=> /= [i j] _. +rewrite (ord1 i){i}/=. +rewrite row3N. +rewrite row3D. +rewrite row3Z. +rewrite row3N. +rewrite row3D. +rewrite row3E. +rewrite ![in leLHS]mxE/=. +case: fintype.splitP => [j0|]. + rewrite (ord1 j0) => _. + rewrite !mxE eqxx/= mulr1n. + apply: re. + rewrite /= sub0r normrN. + by near: x; exact: dnbhs0_lt. + by near: x; exact: nbhs_dnbhs_neq. +move=> k j1k. +rewrite !mxE. +case: fintype.splitP => [k0|k0]. + rewrite (ord1 k0) => _. + rewrite !mxE eqxx/= mulr1n. + apply: se. + rewrite /= sub0r normrN. + by near: x; exact: dnbhs0_lt. + by near: x; exact: nbhs_dnbhs_neq. +rewrite (ord1 k0) => _. +rewrite !mxE eqxx/= mulr1n. +apply: ue. + rewrite /= sub0r normrN. + by near: x; exact: dnbhs0_lt. +by near: x; exact: nbhs_dnbhs_neq. +Unshelve. all: by end_near. Qed. + +End pointwise_derivable_TODO. + +Section pointwise_derive. +Local Open Scope classical_set_scope. +Context {R : realFieldType} {V W : normedModType R} . + +Lemma derive_mx {m n : nat} (M : V -> 'M[R]_(m, n)) t v : + derivable M t v -> + 'D_v M t = \matrix_(i < m, j < n) 'D_v (fun t => M t i j) t. +Proof. +move=> /cvg_ex[/= l Hl]; apply/cvg_lim => //=. +apply/cvgrPdist_le => /= e e0. +move/cvgrPdist_le : (Hl) => /(_ (e / 2)). +rewrite divr_gt0// => /(_ isT)[d /= d0 dle]. +near=> x. +rewrite [in leLHS]/Num.Def.normr/= mx_normrE. +apply/(bigmax_le _ (ltW e0)) => -[/= i j] _. +rewrite [in leLHS]mxE/= [X in _ + X]mxE -[X in X - _](subrK (l i j)). +rewrite -(addrA (_ - _)) (le_trans (ler_normD _ _))// (splitr e) lerD//. +- rewrite mxE. + suff : (h^-1 *: (M (h *: v + t) i j - M t i j)) @[h --> 0^'] --> l i j. + move/cvg_lim => /=; rewrite /derive /= => ->//. + by rewrite subrr normr0 divr_ge0// ltW. + apply/cvgrPdist_le => /= r r0. + move/cvgrPdist_le : Hl => /(_ r r0)[/= s s0] sr. + near=> y. + have : `|l - y^-1 *: (M (y *: v + t) - M t)| <= r. + rewrite sr//=; last by near: y; exact: nbhs_dnbhs_neq. + by rewrite sub0r normrN; near: y; exact: dnbhs0_lt. + apply: le_trans. + rewrite [in leRHS]/Num.Def.normr/= mx_normrE. + by under eq_bigr do rewrite !mxE; exact: (le_bigmax _ _ (i, j)). +- rewrite mxE. + have : `|l - x^-1 *: (M (x *: v + t) - M t)| <= e / 2. + apply: dle => //=; last by near: x; exact: nbhs_dnbhs_neq. + by rewrite sub0r normrN; near: x; exact: dnbhs0_lt. + apply: le_trans. + rewrite [in leRHS]/Num.Def.normr/= mx_normrE/=. + under eq_bigr do rewrite !mxE. + apply: le_trans; last exact: le_bigmax. + by rewrite !mxE. +Unshelve. all: by end_near. Qed. + +Lemma derive_trmx {m n : nat} (M : V -> 'M[R]_(m, n)) t v : + derivable M t v -> 'D_v (trmx \o M) t = ('D_v M t)^T. +Proof. +move=> Mt1. +rewrite !derive_mx//=; last by rewrite derivable_trmx. apply/matrixP => i j; rewrite !mxE. -by rewrite (_ : (fun _ => _) = (fun t => M t j i)) // funeqE => ?; rewrite mxE. +by under eq_fun do rewrite mxE. Qed. -Lemma derive1mxD M N t : derivable_mx M t 1 -> derivable_mx N t 1 -> - derive1mx (M + N) t = derive1mx M t + derive1mx N t. +End pointwise_derive. + +Lemma derivable_lsubmx {R : realFieldType} {V : normedModType R} {n1 n2} + (f : V -> 'rV[R]_(n1 + n2)) t v : + derivable f t v -> derivable (fun x => lsubmx (f x)) t v. Proof. -move=> Hf Hg; apply/matrixP => a b; rewrite /derive1mx !mxE. -rewrite (_ : (fun _ => _) = (fun x => M x a b) \+ fun x => N x a b); last first. - by rewrite funeqE => ?; rewrite mxE. -by rewrite derive1E deriveD 2?{1}derive1E. +move=> /= => df1. +apply/derivable_mxP => i j/=. +rewrite (ord1 i). +have /cvg_ex[/= l Hl]:= df1. +apply/cvg_ex => /=; exists (l``_(lshift n2 j)). +apply/cvgrPdist_le => /= e e0. +move/cvgrPdist_le : Hl => /(_ _ e0). +apply: filterS => x. +apply: le_trans. +rewrite [in leRHS]/Num.Def.normr/= mx_normrE. +apply: le_trans; last first. + exact: (le_bigmax _ _ (ord0, lshift n2 j)). +by rewrite !mxE. Qed. -Lemma derive1mxN M t : derivable_mx M t 1 -> derive1mx (- M) t = - derive1mx M t. +Lemma derive_lsubmx {R : realFieldType} {V : normedModType R} {n1 n2} + (f : V -> 'rV[R]_(n1 + n2)) t v : + derivable f t v -> + 'D_v (fun x => lsubmx (f x)) t = @lsubmx _ _ n1 _ ('D_v f t). Proof. -move=> Hf; apply/matrixP => a b. -rewrite !mxE [in RHS]derive1E -deriveN; last by []. -by rewrite -derive1E; f_equal; rewrite funeqE => x; rewrite mxE. +move=> df1; apply/matrixP => i j; rewrite !mxE /=. +rewrite derive_mx ?mxE//=; last exact: derivable_lsubmx. +rewrite derive_mx ?mxE//=; congr ('D_v _ t). +by apply/funext => x; rewrite !mxE. Qed. -Lemma derive1mxB M N t : derivable_mx M t 1 -> derivable_mx N t 1 -> - derive1mx (M - N) t = derive1mx M t - derive1mx N t. +Lemma derivable_rsubmx {R : realFieldType} {V : normedModType R} {n1 n2} + (f : V -> 'rV[R]_(n1 + n2)) t v : + derivable f t v -> derivable (fun x => rsubmx (f x)) t v. Proof. -by move=> Hf Hg; rewrite derive1mxD ?derive1mxN; last by exact: derivable_mxN. +move=> /= => df1. +apply/derivable_mxP => i j/=. +rewrite (ord1 i). +have /cvg_ex[/= r Hr]:= df1. +apply/cvg_ex => /=; exists (r``_(rshift n1 j)). +apply/cvgrPdist_le => /= e e0. +move/cvgrPdist_le : Hr => /(_ _ e0). +apply: filterS => x. +apply: le_trans. +rewrite [in leRHS]/Num.Def.normr/= mx_normrE. +apply: le_trans; last first. + exact: (le_bigmax _ _ (ord0, rshift n1 j)). +by rewrite !mxE. Qed. -End derive_mx. - -Section derive_mx_R. +Lemma derive_rsubmx {R : realFieldType} {V : normedModType R} {n1 n2} + (f : V -> 'rV[R]_(n1 + n2)) t v : + derivable f t v -> + 'D_v (fun x => rsubmx (f x)) t = @rsubmx _ _ n1 _ ('D_v f t). +Proof. +move=> df1; apply/matrixP => i j; rewrite !mxE /=. +rewrite derive_mx ?mxE//=; last exact: derivable_rsubmx. +rewrite derive_mx ?mxE//=; congr ('D_v _ t). +by apply/funext => x; rewrite !mxE. +Qed. -Variables (R : realFieldType) (m n k : nat). +Section derivable_mulmx. +Context {R : realFieldType} {V : normedModType R} {m n k : nat}. -Lemma derivable_mxM (f : R -> 'M[R^o]_(m, k)) (g : R -> 'M[R^o]_(k, n)) t : - derivable_mx f t 1 -> derivable_mx g t 1 -> derivable_mx (fun x => f x *m g x) t 1. +Lemma derivable_mulmx + (f : V -> 'M[R]_(m, k)) (g : V -> 'M[R]_(k, n)) t v : + derivable f t v -> derivable g t v -> derivable (fun x => f x *m g x) t v. Proof. -move=> Hf Hg a b. evar (f1 : 'I_k -> R^o -> R^o). -rewrite (_ : (fun x => _) = (\sum_i f1 i)); last first. +move=> /derivable_mxP Hf /derivable_mxP Hg; apply/derivable_mxP => a b. +evar (f1 : 'I_k -> V -> R). +rewrite (_ : (fun x => _) = \sum_i f1 i); last first. rewrite funeqE => t'; rewrite mxE fct_sumE; apply: eq_bigr => k0 _. - rewrite /f1; reflexivity. + by rewrite /f1; reflexivity. rewrite {}/f1; apply: derivable_sum => k0. -evar (f1 : R^o -> R). evar (f2 : R -> R). +evar (f1 : V -> R). evar (f2 : V -> R). rewrite (_ : (fun t' => _) = f1 * f2); last first. - rewrite funeqE => t'; rewrite -[RHS]/(f1 t' * f2 t') /f1 /f2; reflexivity. -rewrite {}/f1 {}/f2; exact: derivableM. + by rewrite funeqE => t'; rewrite -[RHS]/(f1 t' * f2 t') /f1 /f2; reflexivity. +by rewrite {}/f1 {}/f2; exact: derivableM. Qed. -End derive_mx_R. +End derivable_mulmx. -Section derive_mx_SE. +Section derive_SE. +Context {R : rcfType} {V : normedModType R} (M : V -> 'M[R^o]_4). -Variables (R : rcfType) (M : R -> 'M[R^o]_4). +Lemma derivable_rot_of_hom x v : derivable M x v -> + derivable (@rot_of_hom _ \o M) x v. +Proof. +move=> Mt1. +apply/derivable_mxP => i j; rewrite /rot_of_hom/=. +rewrite (_ : (fun _ => _) = + fun y => (M y) (lshift 1 i) (lshift 1 j)); last first. + by rewrite funeqE => y; rewrite !mxE. +by have /derivable_mxP := Mt1; exact. +Qed. -Lemma derivable_rot_of_hom : (forall t, derivable_mx M t 1) -> - forall x, derivable_mx (@rot_of_hom _ \o M) x 1. +Lemma derivable_trans_of_hom x v : derivable M x v -> + derivable (@trans_of_hom _ \o M) x v. Proof. -move=> H x i j. -rewrite (_ : (fun _ => _) = (fun y => (M y) (lshift 1 i) (lshift 1 j))); last first. - rewrite funeqE => y; by rewrite !mxE. -exact: H. +move=> Mxv; apply/derivable_mxP => i j; rewrite /trans_of_hom/=. +rewrite (_ : (fun _ => _) = + fun y => (M y) (rshift 3 i) (lshift 1 j)); last first. + by rewrite funeqE => y; rewrite !mxE. +by have /derivable_mxP := Mxv; exact. Qed. -Lemma derive1mx_SE : (forall t, M t \in 'SE3[R]) -> - forall t, derive1mx M t = block_mx - (derive1mx (@rot_of_hom R^o \o M) t) 0 - (derive1mx (@trans_of_hom R^o \o M) t) 0. +Lemma derive1mx_SE t v : derivable M t v -> (forall t, M t \in 'SE3[R]) -> + 'D_v M t = block_mx + ('D_v (@rot_of_hom R^o \o M) t) 0 + ('D_v (@trans_of_hom R^o \o M) t) 0. Proof. -move=> MSE t. +move=> Mtv MSE. +rewrite !derive_mx//; [|exact: derivable_trans_of_hom + |exact: derivable_rot_of_hom]. rewrite block_mxEh. -rewrite {1}(_ : M = (fun x => hom (rot_of_hom (M x)) (trans_of_hom (M x)))); last first. - rewrite funeqE => x; by rewrite -(SE3E (MSE x)). +rewrite {1}(_ : M = + fun x => hom (rot_of_hom (M x)) (trans_of_hom (M x))); last first. + by rewrite funeqE => x; rewrite -(SE3E (MSE x)). apply/matrixP => i j. rewrite 2!mxE; case: splitP => [j0 jj0|j0 jj0]. rewrite (_ : j = lshift 1 j0); last exact/val_inj. rewrite mxE; case: splitP => [i1 ii1|i1 ii1]. rewrite (_ : i = lshift 1 i1); last exact/val_inj. - rewrite mxE; congr (derive1 _ t); rewrite funeqE => x. + rewrite mxE; congr ('D_v _ t); rewrite funeqE => x. by rewrite /hom (block_mxEul _ _ _ _ i1 j0). rewrite (_ : i = rshift 3 i1); last exact/val_inj. - rewrite mxE; congr (derive1 _ t); rewrite funeqE => x. + rewrite mxE; congr ('D_v _ t); rewrite funeqE => x. by rewrite /hom (block_mxEdl (rot_of_hom (M x))). rewrite (_ : j = rshift 3 j0) ?mxE; last exact/val_inj. rewrite (ord1 j0). case: (@splitP 3 1 i) => [i0 ii0|i0 ii0]. rewrite (_ : i = lshift 1 i0); last exact/val_inj. - rewrite (_ : (fun _ => _) = (fun=> 0)) ?derive1_cst ?mxE //. - rewrite funeqE => x; by rewrite /hom (block_mxEur (rot_of_hom (M x))) mxE. + rewrite (_ : (fun _ => _) = fun=> 0). + by rewrite derive_cst mxE. + by rewrite funeqE => x; rewrite /hom (block_mxEur (rot_of_hom (M x))) mxE. rewrite (_ : i = rshift 3 i0); last exact/val_inj. -rewrite (_ : (fun _ => _) = (fun=> 1)) ?derive1_cst // (ord1 i0) ?mxE //. +rewrite (_ : (fun _ => _) = (fun=> 1)) ?derive_cst // (ord1 i0) ?mxE //. by rewrite funeqE => x; rewrite /hom (block_mxEdr (rot_of_hom (M x))) mxE. Qed. -End derive_mx_SE. +End derive_SE. Section row_belast. @@ -234,7 +465,8 @@ case: fintype.splitP => /= [j Hj|[] [] //= ? ni]; rewrite mxE /=. rewrite mulr1n; congr (_ ``_ _); apply val_inj; by rewrite /= ni addn0. Qed. -Lemma derivable_row_belast (R : realFieldType) n (u : R -> 'rV[R^o]_n.+1) (t : R) (v : R): +Lemma derivable_row_belast (R : realFieldType) {V : normedModType R} + n (u : V -> 'rV[R]_n.+1) (t : V) (v : V): derivable_mx u t v -> derivable_mx (fun x => row_belast (u x)) t v. Proof. move=> H i j; move: (H ord0 (widen_ord (leqnSn n) j)) => {H}. @@ -251,13 +483,15 @@ rewrite -dotmulDr; congr dotmul; apply/matrixP => i j; rewrite !(castmxE,mxE) /= case: fintype.splitP => [k /= jk|[] [] // ? /= jn]; by rewrite !(mxE,addr0,add0r,mul0rn). Qed. -Lemma derive1mx_dotmul_belast (R : realFieldType) n (u v : R^o -> 'rV[R^o]_n.+1) t : +Lemma derive1mx_dotmul_belast {R : realFieldType} {V : normedModType R} n + (u v : V -> 'rV[R]_n.+1) t w : + derivable v t w -> let u' x := row_belast (u x) in let v' x := row_belast (v x) in - u' t *d derive1mx v' t + (u t)``_ord_max *: derive (fun x => (v x)``_ord_max) t 1 = - u t *d derive1mx v t. + u' t *d 'D_w v' t + (u t)``_ord_max *: derive (fun x => (v x)``_ord_max) t w = + u t *d 'D_w v t. Proof. -move=> u' v'. -rewrite (row_belast_last (derive1mx v t)) ?addn1 // => ?. +move=> vt1 u' v'. +rewrite (row_belast_last ('D_w v t)) ?addn1 // => /= ?. rewrite dotmul_belast; congr (_ + _). rewrite 2!dotmulE [in RHS]big_ord_recr /=. rewrite castmxE mxE /=; case: fintype.splitP => [j /= /eqP/negPn|j _]. @@ -265,9 +499,16 @@ rewrite dotmul_belast; congr (_ + _). rewrite !mxE (_ : _ == _); last by apply/eqP/val_inj => /=; move: j => [[] ?]. rewrite mulr0 addr0; apply/eq_bigr => i _; rewrite castmxE !mxE; congr (_ * _). case: fintype.splitP => [k /= ik|[] [] //= ?]; rewrite !mxE. + rewrite derive_mx//; last first. + rewrite /v'. + apply/derivable_mxP/derivable_row_belast. + exact/derivable_mxP. + rewrite /= !mxE/=. + rewrite derive_mx//. + rewrite mxE/=. f_equal. - rewrite funeqE => x; rewrite /v' !mxE; congr ((v _) _ _); by apply/val_inj. - rewrite addn0 => /eqP/negPn; by rewrite (ltn_eqF (ltn_ord i)). + by rewrite funeqE => x; rewrite /v' !mxE; congr ((v _) _ _); by apply/val_inj. + by rewrite addn0 => /eqP/negPn; rewrite (ltn_eqF (ltn_ord i)). apply/esym. rewrite dotmulE big_ord_recr /= (eq_bigr (fun=> 0)); last first. move=> i _. @@ -277,7 +518,8 @@ rewrite dotmulE big_ord_recr /= (eq_bigr (fun=> 0)); last first. rewrite sumr_const mul0rn add0r castmxE /=; congr (_ * _); rewrite !mxE. case: fintype.splitP => [j /= /eqP/negPn | [] [] //= ? Hn]. by rewrite (gtn_eqF (ltn_ord j)). -by rewrite mxE derive1E (_ : _ == _). +rewrite mxE/= mulr1n. +by rewrite derive_mx// mxE. Qed. End row_belast. @@ -285,79 +527,207 @@ End row_belast. (* TODO: could be derived from more generic lemmas about bilinearity in derive.v? *) Section product_rules. -Lemma derive1mx_dotmul (R : realFieldType) n (u v : R^o -> 'rV[R^o]_n) (t : R^o) : - derivable_mx u t 1 -> derivable_mx v t 1 -> - derive1 (fun x => u x *d v x : R^o) t = - derive1mx u t *d v t + u t *d derive1mx v t. -Proof. -move=> U V. -evar (f : R -> R); rewrite (_ : (fun x : R => u x *d v x : R^o) = f); last first. - rewrite funeqE => x /=; exact: dotmulE. -rewrite derive1E {}/f. -set f := fun i : 'I__ => fun x => ((u x) ``_ i * (v x) ``_ i). -rewrite (_ : (fun _ : R => _) = \sum_(k < _) f k); last first. +Global Instance is_diff_sum {R : numFieldType} {V W : normedModType R} + n (h : 'I_n -> V -> W) (x : V) + (dh : 'I_n -> V -> W) : (forall i, is_diff x (h i) (dh i)) -> + is_diff x (\sum_(i < n) h i) (\sum_(i < n) dh i). +Proof. +by elim/big_ind2 : _ => // [|] *; [exact: is_diff_cst|exact: is_diffD]. +Qed. + +Lemma derive_dotmul {R : realFieldType} {V : normedModType R} n + (u v : V -> 'rV[R]_n) (t : V) (w : V) : + derivable u t w -> derivable v t w -> + 'D_w (fun x => u x *d v x) t = 'D_w u t *d v t + u t *d 'D_w v t. +Proof. +move=> /derivable_mxP utw /derivable_mxP vtw. +under eq_fun do rewrite dotmulE. +set f := fun i : 'I__ => fun x => (u x) ``_ i * (v x) ``_ i. +rewrite (_ : (fun _ : V => _) = \sum_(k < _) f k); last first. by rewrite funeqE => x; rewrite /f /= fct_sumE. -rewrite derive_sum; last by move=> ?; exact: derivableM (U _ _) (V _ _). -rewrite {}/f. -elim: n u v => [|n IH] u v in U V *. - rewrite big_ord0 (_ : v t = 0) ?dotmulv0 ?add0r; last by apply/rowP => [[]]. - rewrite (_ : u t = 0) ?dotmul0v //; by apply/rowP => [[]]. -rewrite [LHS]big_ord_recr /=. -set u' := fun x => row_belast (u x). set v' := fun x => row_belast (v x). -transitivity (derive1mx u' t *d v' t + u' t *d derive1mx v' t + - derive (fun x => (u x)``_ord_max * (v x)``_ord_max) t 1). - rewrite -(IH _ _ (derivable_row_belast U) (derivable_row_belast V)). - apply: f_equal2; last by []. - apply eq_bigr => i _; congr (derive _ t 1). - by rewrite funeqE => x; rewrite !mxE. -rewrite (deriveM (U _ _) (V _ _)) /= -!addrA addrC addrA. -rewrite -(addrA (_ + _)) [in RHS]addrC derive1mx_dotmul_belast; congr (_ + _). -by rewrite [in RHS]dotmulC -derive1mx_dotmul_belast addrC dotmulC. +rewrite derive_sum; last by move=> i; exact: derivableM. +rewrite !dotmulE -big_split/=; apply: eq_bigr => i _. +by rewrite {}/f deriveM// mulrC addrC; congr (_ * _ + _ * _); + rewrite derive_mx ?mxE//=; exact/derivable_mxP. +Qed. + +(* NB: from Damien's LaSalle *) +Global Instance is_diff_component {R : realFieldType} n i (p : 'rV[R]_n) : + is_diff p (fun q => q..[i] : R^o) (fun q => q..[i]). +Proof. +have comp_lin : linear (fun q : 'rV[R]_n => q..[i] : R^o). + by move=> ???; rewrite !mxE. +have comp_cont : continuous (fun q : 'rV[R]_n => q..[i] : R^o). + move=> q A [_/posnumP[e] Ae] /=; apply/nbhs_ballP; exists e%:num => //=. + by move=> r [e0] /(_ ord0) /(_ i) /Ae. +pose glM := GRing.isLinear.Build _ _ _ _ _ comp_lin. +pose gL : {linear 'rV_n -> R^o} := HB.pack (fun q : 'rV_n => q ..[ i]) glM. +apply: DiffDef; first exact: (@linear_differentiable _ _ _ gL). +by rewrite (@diff_lin _ _ _ gL). +Qed. + +Global Instance is_diff_component_comp {R : realFieldType} (V : normedModType R) n + (f : V -> 'rV[R]_n) i p df : is_diff p f df -> + is_diff p (fun q => (f q)..[i] : R^o) (fun q => (df q)..[i]). +Proof. +move=> dfp. +have -> : (fun q => (f q)..[i]) = (fun v => v..[i]) \o f by rewrite funeqE. +(* This should work *) +(* apply: is_diff_eq. *) +exact: is_diff_comp. Qed. +(* /NB: from Damien's LaSalle *) -Lemma derive1mxM (R : realFieldType) n m p (M : R -> 'M[R^o]_(n, m)) - (N : R^o -> 'M[R^o]_(m, p)) (t : R^o) : - derivable_mx M t 1 -> derivable_mx N t 1 -> - derive1mx (fun t => M t *m N t) t = - derive1mx M t *m N t + M t *m (derive1mx N t). +Global Instance is_diff_dotmul {R : realFieldType} m n (V := 'rV[R]_m) + (u v du dv : V -> 'rV[R]_n) (t : V) : + is_diff t u du -> is_diff t v dv -> + is_diff t (fun x => u x *d v x) + (fun x => u t *d dv x + v t *d du x). Proof. -move=> HM HN; apply/matrixP => i j; rewrite ![in LHS]mxE. +move=> udu vdv/=. +under eq_fun do rewrite dotmulE. +set f := fun i : 'I__ => (fun x => (u x) ``_ i) * (fun x => (v x) ``_ i). +rewrite [X in is_diff _ X _](_ : _ = \sum_(k < _) f k); last first. + by rewrite funeqE => x; rewrite /f /= fct_sumE. +rewrite [X in is_diff _ _ X](_ : _ = \sum_(i < n) + ((u t)``_i *: (fun x => (dv x)``_i) + (v t)``_i *: (fun x => (du x)``_i))); last first. + by apply/funext => x; rewrite 2!dotmulE -big_split/= fct_sumE. +apply: is_diff_sum => i. +rewrite {}/f /=. +exact: is_diffM. +Qed. + +Lemma differentiable_dotmul {R : realFieldType} m n (V := 'rV[R]_m) + (u v : V -> 'rV[R]_n) (t : V) : + differentiable u t -> + differentiable v t -> + differentiable (fun x => u x *d v x) t. +Proof. +move=> /differentiableP udu /differentiableP vdv/=. +by have [/=] := is_diff_dotmul udu vdv. +Qed. + +Lemma derive_mulmx {R : realFieldType} {V : normedModType R} n m p + (M : V -> 'M[R]_(n.+1, m.+1)) + (N : V -> 'M[R]_(m.+1, p.+1)) (t : V) w : + derivable M t w -> derivable N t w -> + 'D_w (fun t => M t *m N t) t = 'D_w M t *m N t + M t *m 'D_w N t. +Proof. +move=> HM HN; apply/matrixP => i j. +rewrite derive_mx/=; last exact/derivable_mulmx. +rewrite ![in LHS]mxE. rewrite (_ : (fun x => _) = fun x => \sum_k (M x) i k * (N x) k j); last first. by rewrite funeqE => x; rewrite !mxE. rewrite (_ : (fun x => _) = fun x => (row i (M x)) *d (col j (N x))^T); last first. rewrite funeqE => z; rewrite dotmulE; apply eq_bigr => k _. by rewrite 3!mxE. -rewrite (derive1mx_dotmul (derivable_mx_row HM) (derivable_mx_col HN)). -by rewrite [in RHS]mxE; congr (_ + _); rewrite [in RHS]mxE dotmulE; - apply/eq_bigr => /= k _; rewrite !mxE; apply: f_equal2; - try by congr (@derive1 _ R^o _ t); - rewrite funeqE => z; rewrite !mxE. +rewrite (derive_dotmul (derivable_row HM)); last first. + by rewrite derivable_trmx/=; exact: derivable_col. +rewrite [in RHS]mxE; congr +%R. + rewrite dotmulE. + rewrite [in RHS]mxE. + apply: eq_bigr => /= k _. + rewrite !mxE/=. + congr *%R. + rewrite derive_mx//=; last first. + exact: derivable_row. + rewrite mxE. + rewrite derive_mx//=. + rewrite mxE/=. + congr ('D_w _ t). + by apply/funext => y; rewrite !mxE. +rewrite dotmulE. +rewrite [in RHS]mxE. +apply: eq_bigr => /= k _. +rewrite !mxE/=. +congr *%R. +rewrite derive_mx//=; last first. + by rewrite derivable_trmx//=; exact/derivable_col. +rewrite !mxE//=. +rewrite derive_mx//= !mxE. +congr ('D_w _ t). +by apply/funext => y; rewrite !mxE. +Qed. + +Lemma derivable_dotmul {R : realFieldType} {n} + (u v : R -> 'rV[R]_n) t : + derivable u t 1 -> derivable v t 1 -> + derivable (fun x => u x *d v x) t 1. +Proof. +move=> ut1 vt1/=. +rewrite /dotmul. +rewrite (_ : (fun x : R => _) = + \sum_k (fun x : R => (u x)``_k * (v x) 0 k)); last first. + apply/funext => x. + rewrite !mxE. + under eq_bigr do rewrite !mxE. + elim/big_ind2 : _ => //= f a g b -> ->. + by rewrite fctE. +apply: derivable_sum => i. +by apply: derivableM => //=; exact: derivable_coord. Qed. -Lemma derive1mx_crossmul (R : realFieldType) (u v : R -> 'rV[R^o]_3) t : - derivable_mx u t 1 -> derivable_mx v t 1 -> - derive1mx (fun x => (u x *v v x) : 'rV[R^o]_3) t = - derive1mx u t *v v t + u t *v derive1mx v t. -Proof. -move=> U V. -evar (f : R -> 'rV[R]_3); rewrite (_ : (fun x : R => _) = f); last first. - rewrite funeqE => x; exact: crossmulE. -rewrite {}/f {1}/derive1mx; apply/rowP => i; rewrite mxE derive1E. -rewrite (mxE_funeqE (fun x : R^o => _)) /= mxE 2!crossmulE !{1}[in RHS]mxE /=. -case: ifPn => [/eqP _|/ifnot0P/orP[]/eqP -> /=]; - rewrite ?derive1E (deriveD (derivableM (U _ _) (V _ _)) - (derivableN (derivableM (U _ _) (V _ _)))); - rewrite (deriveN (derivableM (U _ _) (V _ _))) 2!(deriveM (U _ _) (V _ _)); - rewrite addrCA -!addrA; congr (_ + (_ + _)); by [ rewrite mulrC | - rewrite opprD addrC; congr (_ + _); rewrite mulrC ]. +Lemma derive_crossmul {R : realFieldType} {V : normedModType R} + (u v : V -> 'rV[R]_3) t w : + derivable u t w -> derivable v t w -> + 'D_w (fun x => u x *v v x) t = 'D_w u t *v v t + u t *v 'D_w v t. +Proof. +move=> utw vtw. +evar (f : V -> 'rV[R]_3); rewrite (_ : (fun x : V => _) = f); last first. + by rewrite funeqE => x; exact: crossmulE. +rewrite {}/f; apply/rowP => i; rewrite mxE. +rewrite derive_mx/=; last first. + by apply: derivable_row3; + apply: derivableB => //=; + by apply: derivableM => //=; exact: derivable_coord. +rewrite !mxE/=. +under eq_fun do rewrite !mxE/=. +rewrite 2!crossmulE !{1}[in RHS]mxE /=. +case: ifPn => [/eqP _|/ifnot0P/orP[]/eqP -> /=]. +- rewrite deriveB//=; [ | + by apply: derivableM => //=; exact: derivable_coord..]. + rewrite deriveM//=; [|exact: derivable_coord..]. + rewrite deriveM//=; [|exact: derivable_coord..]. + rewrite addrCA -!addrA; congr (_ + (_ + _)). + by rewrite derive_mx//= mxE. + by rewrite mulrC derive_mx//= mxE. + rewrite [in LHS]addrC. + rewrite opprD mulrC. + rewrite derive_mx//= mxE. + congr (_ - _)%R. + by rewrite derive_mx//= mxE. +- (*TOOD: copipe *) + rewrite deriveB//=; [ | + by apply: derivableM => //=; exact: derivable_coord..]. + rewrite deriveM//=; [|exact: derivable_coord..]. + rewrite deriveM//=; [|exact: derivable_coord..]. + rewrite addrCA -!addrA; congr (_ + (_ + _)). + by rewrite derive_mx//= mxE. + by rewrite mulrC derive_mx//= mxE. + rewrite [in LHS]addrC opprD mulrC. + rewrite derive_mx//= mxE. + congr (_ - _)%R. + by rewrite derive_mx//= mxE. +- (*TOOD: copipe *) + rewrite deriveB//=; [ | + by apply: derivableM => //=; exact: derivable_coord..]. + rewrite deriveM//=; [|exact: derivable_coord..]. + rewrite deriveM//=; [|exact: derivable_coord..]. + rewrite addrCA -!addrA; congr (_ + (_ + _)). + by rewrite derive_mx//= mxE. + by rewrite mulrC derive_mx//= mxE. + rewrite [in LHS]addrC opprD mulrC. + rewrite derive_mx//= mxE. + congr (_ - _)%R. + by rewrite derive_mx//= mxE. Qed. End product_rules. Section cross_product_matrix. -Lemma differential_cross_product (R : realFieldType) (v : 'rV[R^o]_3) y : +Lemma differential_crossmul {R : realFieldType} (v : 'rV[R]_3) y : 'd (crossmul v) y = mx_lin1 \S( v ) :> (_ -> _). Proof. rewrite (_ : crossmul v = (fun x => x *m \S( v ))); last first. @@ -374,11 +744,11 @@ apply: differentiable_sum => i. exact/differentiableZl/differentiable_coord. Qed. -Lemma differential_cross_product2 (R : realFieldType) (v y : 'rV[R^o]_3) : - 'd (fun x : 'rV[R^o]_3 => x *v v) y = -1 \*: mx_lin1 \S( v ) :> (_ -> _). +Lemma differential_crossmul2 (R : realFieldType) (v y : 'rV[R]_3) : + 'd (fun x : 'rV[R]_3 => x *v v) y = -1 \*: mx_lin1 \S( v ) :> (_ -> _). Proof. transitivity ('d (crossmul (- v)) y); last first. - by rewrite differential_cross_product spinN mx_lin1N. + by rewrite differential_crossmul spinN mx_lin1N. congr diff. by rewrite funeqE => /= u; rewrite (@lieC _ (vec3 R)) linearNl. Qed. @@ -387,53 +757,48 @@ End cross_product_matrix. (* [sciavicco] p.80-81 *) Section derivative_of_a_rotation_matrix. +Context {R : realFieldType}. +Variable M : R -> 'M[R]_3. -Variables (R : realFieldType) (M : R -> 'M[R^o]_3). +Definition ang_vel_mx t : 'M_3 := (M t)^T * 'D_1 M t. -Definition ang_vel_mx t : 'M_3 := (M t)^T * derive1mx M t. +Definition body_ang_vel_mx t : 'M_3 := 'D_1 M t *m (M t)^T. -Definition body_ang_vel_mx t : 'M_3 := derive1mx M t *m (M t)^T. +Hypothesis MO : forall t, M t \is 'O[ R ]_3. -(* angular velocity (a free vector) *) -Definition ang_vel t := unspin (ang_vel_mx t). +(* [sciavicco] eqn 3.7 *) +Lemma derive1mx_ang_vel t : 'D_1 M t = M t * ang_vel_mx t. +Proof. +by rewrite /ang_vel_mx mulrA -mulmxE orthogonal_mul_tr// mul1mx. +Qed. -Hypothesis MO : forall t, M t \is 'O[ R ]_3. -Hypothesis derivable_M : forall t, derivable_mx M t 1. +Hypothesis derivable_M : forall t, derivable M t 1. Lemma ang_vel_mx_is_so t : ang_vel_mx t \is 'so[ R ]_3. Proof. have : (fun t => (M t)^T * M t) = cst 1. rewrite funeqE => x; by rewrite -orthogonal_inv // mulVr // orthogonal_unit. -move/(congr1 (fun f => derive1mx f t)); rewrite derive1mx_cst -[cst 0 _]/(0). -rewrite derive1mxM // -?trmx_derivable // derive1mx_tr. +move/(congr1 (fun f => 'D_1 f t)). +rewrite derive_cst. +rewrite derive_mulmx // ?derivable_trmx // derive_trmx//. move=> /eqP; rewrite addr_eq0 => /eqP H. by rewrite antiE /ang_vel_mx trmx_mul trmxK H opprK. Qed. +(* angular velocity (a free vector) *) +Definition ang_vel t := unspin (ang_vel_mx t). + Lemma ang_vel_mxE t : ang_vel_mx t = \S( ang_vel t). Proof. by rewrite /ang_vel unspinK // ang_vel_mx_is_so. Qed. -(* [sciavicco] eqn 3.7 *) -Lemma derive1mx_ang_vel t : derive1mx M t = M t * ang_vel_mx t. -Proof. -move: (ang_vel_mx_is_so t); rewrite antiE -subr_eq0 opprK => /eqP. -rewrite {1 2}/ang_vel_mx trmx_mul trmxK => /(congr1 (fun x => (M t) * x)). -rewrite mulr0 mulrDr !mulrA -{1}(orthogonal_inv (MO t)). -rewrite divrr ?orthogonal_unit // mul1r. -move=> /eqP; rewrite addr_eq0 => /eqP {1}->. -rewrite -mulrA -mulrN -mulrA; congr (_ * _). -move: (ang_vel_mx_is_so t); rewrite antiE -/(ang_vel_mx t) => /eqP ->. -by rewrite /ang_vel_mx trmx_mul trmxK mulmxE. -Qed. - -Lemma derive1mx_rot (p' : 'rV[R^o]_3 (* constant vector *)) : +Lemma derive1mx_rot (p' : 'rV[R]_3 (* constant vector *)) : let p := fun t => p' *m M t in - forall t, derive1mx p t = ang_vel t *v p t. + forall t, 'D_1 p t = ang_vel t *v p t. Proof. -move=> p t; rewrite /p derive1mxM; last first. +move=> p t; rewrite /p derive_mulmx; last first. exact: derivable_M. rewrite /derivable_mx => i j; exact: ex_derive. -rewrite derive1mx_cst mul0mx add0r derive1mx_ang_vel mulmxA. +rewrite derive_cst mul0mx add0r derive1mx_ang_vel mulmxA. by rewrite -{1}(unspinK (ang_vel_mx_is_so t)) spinE. Qed. diff --git a/dh.v b/dh.v index 0292a4f4..46adb9b4 100644 --- a/dh.v +++ b/dh.v @@ -1,4 +1,4 @@ -(* coq-robot (c) 2017 AIST and INRIA. License: LGPL-2.1-or-later. *) +(* robot-rocq (c) 2026 AIST and INRIA. License: LGPL-2.1-or-later. *) From mathcomp Require Import all_ssreflect ssralg ssrint ssrnum rat poly. From mathcomp Require Import closed_field polyrcf matrix mxalgebra mxpoly zmodp. From mathcomp Require Import realalg complex fingroup perm. @@ -54,7 +54,7 @@ Implicit Types l : Line.t T. Definition normalized_plucker_direction l := let p1 := \pt( l ) in let p2 := \pt2( l ) in - (norm (p2 - p1))^-1 *: (p2 - p1). + (`|p2 - p1|_e)^-1 *: (p2 - p1). Lemma normalized_plucker_directionP (l : Line.t T) : \vec( l ) != 0 -> let e := normalized_plucker_direction l in e *d e == 1. @@ -62,8 +62,8 @@ Proof. move=> l0 /=. rewrite /normalized_plucker_direction dotmulZv dotmulvZ dotmulvv. rewrite -Line.vectorE. -rewrite mulrA mulrAC expr2 mulrA mulVr ?unitfE ?norm_eq0 // mul1r. -by rewrite divrr // unitfE norm_eq0. +rewrite mulrA mulrAC expr2 mulrA mulVr ?unitfE ?enorm_eq0// mul1r. +by rewrite divrr // unitfE enorm_eq0. Qed. Definition normalized_plucker_position l := @@ -88,22 +88,22 @@ Lemma normalized_pluckerP l : let p1 := \pt( l ) in let p2 := \pt2( l ) in \vec( l ) != 0 -> - plucker_of_line l = norm (p2 - p1) *: normalized_plucker l. + plucker_of_line l = `|p2 - p1|_e *: normalized_plucker l. Proof. move=> p1 p2 l0. rewrite /normalized_plucker /normalized_plucker_direction /normalized_plucker_position. rewrite -/p1 -/p2 (linearZr_LR crossmul) -scale_row_mx scalerA. -by rewrite divrr ?scale1r // unitfE norm_eq0 /p2 -Line.vectorE. +by rewrite divrr ?scale1r // unitfE enorm_eq0 /p2 -Line.vectorE. Qed. Lemma plucker_of_lineE l (l0 : \vec( l ) != 0) : - plucker_of_line l = norm (\pt2( l ) - \pt( l )) *: + plucker_of_line l = `|\pt2( l ) - \pt( l )|_e *: (Plucker.mkArray (normalized_plucker_directionP l0) (normalized_plucker_positionP l) : 'M__). Proof. rewrite /plucker_of_line /plucker_array_mx /=. rewrite /normalized_plucker_direction /normalized_plucker_position. rewrite (linearZr_LR crossmul) -scale_row_mx. -by rewrite scalerA divrr ?scale1r // unitfE norm_eq0 -Line.vectorE. +by rewrite scalerA divrr ?scale1r // unitfE enorm_eq0 -Line.vectorE. Qed. Definition plucker_eqn p l := @@ -196,7 +196,7 @@ Variables F0 F1 : tframe T. Definition From1To0 := locked (F1 _R^ F0). Definition p1_in_0 : 'rV[T]_3 := (\o{F1} - \o{F0}) *m (can_tframe T) _R^ F0. -Goal `[ p1_in_0 $ F0 ] = rmap F0 `[ \o{F1} - \o{F0} $ can_tframe T ]. +Goal '[ p1_in_0 $ F0 ] = rmap F0 '[ \o{F1} - \o{F0} $ can_tframe T ]. Proof. rewrite /p1_in_0. by rewrite /rmap. @@ -218,14 +218,14 @@ have H1 : From1To0 0 2%:R = 0. by rewrite !rowframeE. have [H2a H2b] : From1To0 0 0 ^+ 2 + From1To0 0 1 ^+ 2 = 1 /\ From1To0 1 2%:R ^+ 2 + From1To0 2%:R 2%:R ^+ 2 = 1. - move: (norm_row_of_O (FromTo_is_O F1 F0) 0) => /= /(congr1 (fun x => x ^+ 2)). + move: (enorm_row_of_O (FromTo_is_O F1 F0) 0) => /= /(congr1 (fun x => x ^+ 2)). rewrite expr1n -dotmulvv dotmulE sum3E [_ 0 2%:R]mxE. move: (H1); rewrite {1}/From1To0 -lock => ->. rewrite mulr0 addr0 -!expr2 => H1a. split. rewrite [_ 0 0]mxE [_ 0 1]mxE in H1a. by rewrite /From1To0 -lock. - move: (norm_col_of_O (FromTo_is_O F1 F0) 2%:R) => /= /(congr1 (fun x => x ^+ 2)). + move: (enorm_col_of_O (FromTo_is_O F1 F0) 2%:R) => /= /(congr1 (fun x => x ^+ 2)). rewrite expr1n -dotmulvv dotmulE sum3E 2![_ 0 0]mxE. move: (H1); rewrite {1}/From1To0 -lock => ->. by rewrite mulr0 add0r -!expr2 tr_col [_ 0 1]mxE [_ 0 2%:R]mxE /From1To0 -lock !mxE. @@ -256,8 +256,8 @@ move: (H22); rewrite {1}/From1To0 -lock => ->. rewrite 2![_ 0 2%:R]mxE => /eqP. rewrite addr_eq0 => /eqP H10_H20. -move: (norm_col_of_O (FromTo_is_O F1 F0) 1) => /= /(congr1 (fun x => x ^+ 2)). -rewrite expr1n sqr_norm sum3E tr_col [_ 0 0]mxE [_ 1 0]mxE. +move: (enorm_col_of_O (FromTo_is_O F1 F0) 1) => /= /(congr1 (fun x => x ^+ 2)). +rewrite expr1n sqr_enorm sum3E tr_col [_ 0 0]mxE [_ 1 0]mxE. move: (H01); rewrite {1}/From1To0 -lock => ->. rewrite [_ 0 1]mxE [_ 1 1]mxE [_ 0 2%:R]mxE [_ 1 2%:R]mxE. move/eqP. rewrite -addrA eq_sym addrC -subr_eq -cos2sin2. move/eqP. @@ -266,8 +266,8 @@ rewrite mulrDr -(@exprMn _ _ (sin alpha) (_ 1 1)) (mulrC _ (_ 1 1)) H11_H21. rewrite sqrrN exprMn [in X in _ = X -> _](mulrC (sin alpha ^+ 2)). rewrite -mulrDr cos2Dsin2 mulr1 => /esym sqr_H21. -move: (norm_col_of_O (FromTo_is_O F1 F0) 0) => /= /(congr1 (fun x => x ^+ 2)). -rewrite sqr_norm sum3E 2![_ 0 0]mxE. +move: (enorm_col_of_O (FromTo_is_O F1 F0) 0) => /= /(congr1 (fun x => x ^+ 2)). +rewrite sqr_enorm sum3E 2![_ 0 0]mxE. move: (H00); rewrite {1}/From1To0 -lock => ->. rewrite expr1n [_ 0 1]mxE [_ 1 0]mxE [_ 0 2%:R]mxE [_ 2%:R 0]mxE. move=> H10_H20_save; move: (H10_H20_save). @@ -296,8 +296,8 @@ have H4 : From1To0 = dh_rot theta alpha. move/eqP : (sa0) => /sin0cos1 /eqP. rewrite eqr_norml ler01 andbT. - move: (norm_row_of_O (FromTo_is_O F1 F0) 1) => /= /(congr1 (fun x => x ^+ 2)). - rewrite expr1n sqr_norm sum3E [_ 0 0]mxE [_ 0 1]mxE [_ 0 2%:R]mxE. + move: (enorm_row_of_O (FromTo_is_O F1 F0) 1) => /= /(congr1 (fun x => x ^+ 2)). + rewrite expr1n sqr_enorm sum3E [_ 0 0]mxE [_ 0 1]mxE [_ 0 2%:R]mxE. move: (H12); rewrite {1}/From1To0 -lock => ->; rewrite (eqP sa0) expr0n addr0. move=> H10_H11. @@ -457,7 +457,7 @@ Variable T : rcfType. Let vector := 'rV[T]_3. Record t := mk { vaxis : vector ; - norm_vaxis : norm vaxis = 1 ; + norm_vaxis : `|vaxis|_e = 1 ; angle : T (* between to successive X axes *) }. End joint. End Joint. @@ -530,7 +530,7 @@ Definition link_offset (frames : frame ^ n.+1) (links : link ^ n.+1) (i : 'I_n) let: (o_succi, x_succi) := let f := frames succi in (\o{f}, f~i) in let: (o_i, x_i, z_i) := let f := frames i' in (\o{f}, f~i, f~k) in if intersection (zaxis (frames i')) (xaxis (frames succi)) is some o'_i then - (norm (o'_i - o_i)(*the Zi-coordiante of o'_i*) == Link.offset (links i')) && + (`|o'_i - o_i|_e(*the Zi-coordiante of o'_i*) == Link.offset (links i')) && (`| Link.offset (links i') | == distance_between_lines (xaxis (frames i')) (xaxis (frames succi))) else false (* should not happen since Zi always intersects Xi.+1 (see condidion 2.) *). diff --git a/differential_kinematics.v b/differential_kinematics.v index 00d7785e..0417f93f 100644 --- a/differential_kinematics.v +++ b/differential_kinematics.v @@ -1,4 +1,4 @@ -(* coq-robot (c) 2017 AIST and INRIA. License: LGPL-2.1-or-later. *) +(* robot-rocq (c) 2017 AIST and INRIA. License: LGPL-2.1-or-later. *) From mathcomp Require Import all_ssreflect ssralg ssrint ssrnum rat. From mathcomp Require Import interval_inference. From mathcomp Require Import closed_field polyrcf matrix mxalgebra mxpoly zmodp. @@ -6,7 +6,7 @@ From mathcomp Require Import realalg complex fingroup perm. From mathcomp Require Import sesquilinear. From mathcomp Require Import boolp reals classical_sets. From mathcomp Require Import topology normedtype landau derive. -From mathcomp Require Import functions. +From mathcomp Require Import functions trigo. Require Import ssr_ext derive_matrix euclidean frame rot skew rigid. (******************************************************************************) @@ -38,6 +38,42 @@ Import Order.TTheory GRing.Theory Num.Def Num.Theory. Import numFieldNormedType.Exports. Local Open Scope ring_scope. + +Lemma derive1_cos (R : realType) (t : R) : derive1 (cos : _ -> R^o) t = - sin t. +Proof. +rewrite derive1E. +have u := is_derive_cos t. +by have := @derive_val _ _ _ _ _ _ _ u. +Qed. + +Lemma derive1_sin (R : realType) (t : R) : derive1 (sin : _ -> R^o) t = cos t. +Proof. +rewrite derive1E. +have u := is_derive_sin t. +by have := @derive_val _ _ _ _ _ _ _ u. +Qed. + +Lemma derivable_sin (R : realType) (t : R) : derivable (sin : R^o -> R^o) t 1. +Proof. exact: ex_derive. Qed. + +Lemma derivable_cos (R : realType) (t : R) : derivable (cos : R^o -> R^o) t 1. +Proof. exact: ex_derive. Qed. + +Lemma derivable_cos_comp (R : realType) (t : R) (a : R^o -> R^o) : + derivable a t 1 -> derivable (cos \o a : _ -> R^o) t 1. +Proof. by move=> /derivableP Hs; exact: ex_derive. Qed. + +Lemma derivable_sin_comp (R : realType) (t : R) (a : R^o -> R^o) : + derivable a t 1 -> derivable ((sin : _ -> R^o) \o a) t 1. +Proof. by move=> /derivableP Hs; exact: ex_derive. Qed. + +Lemma derive1_cos_comp (R : realType) t (a : R^o -> R^o) : derivable a t 1 -> + derive1 (cos \o a : _ -> R^o) t = - (derive1 a t) * sin (a t). +Proof. +move=> H; rewrite (derive1_comp H); last exact: derivable_cos. +by rewrite derive1_cos mulrC mulNr mulrN. +Qed. + Local Open Scope frame_scope. Module BoundVect. (* i.e., point of application prescribed *) @@ -59,7 +95,7 @@ Section about_bound_vectors. Variables (T : pzRingType) (F : tframe T). -Definition FramedVect_of_Bound (p : bvec F) : fvec F := `[ BoundVect.endp p $ F ]. +Definition FramedVect_of_Bound (p : bvec F) : fvec F := '[ BoundVect.endp p $ F ]. Definition BoundVect_add (a b : bvec F) : bvec F := BoundVect.mk F (BoundVect.endp a + BoundVect.endp b). @@ -74,7 +110,7 @@ Lemma BoundFramed_addA (a : bvec F) (b c : fvec F) : Proof. by rewrite /BoundFramed_add /= addrA. Qed. Definition BoundVect_sub (F : tframe T) (a b : bvec F) : fvec F := - `[ BoundVect.endp a - BoundVect.endp b $ F ]. + '[ BoundVect.endp a - BoundVect.endp b $ F ]. Local Notation "a \-b b" := (BoundVect_sub a b). @@ -90,14 +126,14 @@ Lemma derive1mx_BoundFramed_add (R : realFieldType) (F : tframe R^o) (Q : R -> bvec F) (Z : R -> fvec F) t : derivable_mx (fun x => BoundVect.endp (Q x)) t 1 -> derivable_mx (fun x => FramedVect.v (Z x)) t 1 -> - derive1mx (fun x => BoundVect.endp (Q x \+b Z x)) t = - derive1mx (fun x => BoundVect.endp (Q x)) t + - derive1mx (fun x => FramedVect.v (Z x)) t. + 'D_1 (fun x => BoundVect.endp (Q x \+b Z x)) t = + 'D_1 (fun x => BoundVect.endp (Q x)) t + + 'D_1 (fun x => FramedVect.v (Z x)) t. Proof. -move=> H H'. +move=> /derivable_mxP H /derivable_mxP H'. rewrite (_ : (fun x : R => _) = (fun x : R => BoundVect.endp (Q x) + (FramedVect.v (Z x)))); last by rewrite funeqE. -rewrite derive1mxD. +rewrite deriveD. - by []. - exact: H. - exact H'. @@ -159,7 +195,7 @@ Proof. move=> HF HG a b. have @G' : forall t0, rframe (F t0). move=> t0. - exact: (@RFrame.mk _ _ (@BoundVect.mk _ _ \o{F t0}) `[(F t0)~i $ F t0] `[(F t0)~j $ F t0] `[(F t0)~k $ F t0] (F t0)). + exact: (@RFrame.mk _ _ (@BoundVect.mk _ _ \o{F t0}) '[(F t0)~i $ F t0] '[(F t0)~j $ F t0] '[(F t0)~k $ F t0] (F t0)). apply: (@derivable_mx_FromTo' R F G' G). by []. by []. @@ -176,8 +212,8 @@ Qed. Lemma derivable_mx_FromTo_tr (R : realFieldType) (F : tframe R^o) (G : R -> rframe F) t : - derivable_mx (fun x => F _R^ (G x)) t 1 = derivable_mx (fun x => F _R^ (G x)) t 1. -Proof. by rewrite trmx_derivable. Qed. + derivable (fun x => F _R^ (G x)) t 1 = derivable (fun x => F _R^ (G x)) t 1. +Proof. by rewrite -derivable_trmx. Qed. End derivable_FromTo. @@ -218,61 +254,68 @@ apply fv_eq => /=; rewrite -mulmxDl; congr (_ *m _). by rewrite addrCA subrr addr0. Qed. -Lemma derivable_mx_Q t : derivable_mx (fun x => BoundVect.endp (Q x)) t 1. +Lemma derivable_Q t : derivable (fun x => BoundVect.endp (Q x)) t 1. Proof. -rewrite /Q /=; apply derivable_mxD. +rewrite /Q/=; apply: derivableD. +- apply/derivable_mxP. move=> a b. move: (@derivable_F1o t a b). - rewrite (_ : (fun x => \o{F1 x} a b) = - (fun x => BoundVect.endp (RFrame.o (F1 x)) a b)) // funeqE => x. - destruct (F1 x) => /=; by rewrite e. -apply derivable_mxM; last exact: derivable_mx_FromTo. -rewrite (_ : (fun x => _) = (fun _ => BoundVect.endp (Q1 0))); last first. - rewrite funeqE => x; by rewrite Q1_fixed_in_F1. -move=> a b; exact: ex_derive. + rewrite [X in derivable X _ _ -> _](_ : _ = + (fun x => BoundVect.endp (RFrame.o (F1 x)) a b)); last first. + apply/funext => x/=. + by destruct (F1 x) => /=; by rewrite e. + by []. +- apply: derivable_mulmx; last first. + exact/derivable_mxP/derivable_mx_FromTo. + rewrite (_ : (fun x => _) = (fun _ => BoundVect.endp (Q1 0))); last first. + by rewrite funeqE => x; rewrite Q1_fixed_in_F1. + by move=> a b; exact: ex_derive. Qed. Let Rot := fun t => (F1 t) _R^ F. (* generalization of B.4 *) Lemma velocity_composition_rule (t : R) : - derive1mx (fun x => BoundVect.endp (P x)) t = - derive1mx (fun x => BoundVect.endp (Q x)) t + - derive1mx P1 t *m Rot t (* rate of change of the coordinates P1 expressed in the frame F *) + + 'D_1 (fun x => BoundVect.endp (P x)) t = + 'D_1 (fun x => BoundVect.endp (Q x)) t + + 'D_1 (fun x => P1 x : 'M__) t *m Rot t (* rate of change of the coordinates P1 expressed in the frame F *) + ang_vel Rot t *v FramedVect.v (P t \-b Q t). Proof. rewrite {1}(_ : P = fun t => Q t \+b rmap F (P1 t \-b Q1 t)); last first. by rewrite funeqE => t'; rewrite eqnB3. -rewrite (derive1mx_BoundFramed_add (@derivable_mx_Q t)); last first. - apply derivable_mxM; last exact: derivable_mx_FromTo. +have /derivable_mxP tmp := (@derivable_Q t). +rewrite (derive1mx_BoundFramed_add tmp); last first. + apply/derivable_mxP. + apply: derivable_mulmx; last first. + exact/derivable_mxP/derivable_mx_FromTo. rewrite (_ : (fun x => _) = (fun x => FramedVect.v (FramedVect_of_Bound (P1 x)) - FramedVect.v (FramedVect_of_Bound (Q1 0)))); last first. rewrite funeqE => x; by rewrite /= Q1_fixed_in_F1. - apply: derivable_mxB => /=. - exact: derivable_mxP1. - move=> a b; exact: ex_derive. + apply: derivableB => //=. + exact/derivable_mxP/derivable_mxP1. rewrite -addrA; congr (_ + _). -rewrite [in LHS]/rmap [in LHS]/= derive1mxM; last 2 first. +rewrite [in LHS]/rmap [in LHS]/= derive_mulmx; last 2 first. rewrite {1}(_ : (fun x => _) = (fun x => BoundVect.endp (P1 x) - BoundVect.endp (Q1 0))); last first. by rewrite funeqE => ?; rewrite Q1_fixed_in_F1. - apply: derivable_mxB. - exact: derivable_mxP1. - move=> a b; exact: ex_derive. - exact: derivable_mx_FromTo. -rewrite derive1mxB; last 2 first. - exact: derivable_mxP1. + apply: derivableB. + exact/derivable_mxP/derivable_mxP1. + by move=> a b; exact: ex_derive. + exact/derivable_mxP/derivable_mx_FromTo. +rewrite deriveB; last 2 first. + exact/derivable_mxP/derivable_mxP1. rewrite (_ : (fun x => _) = cst (BoundVect.endp (Q1 0))); last first. by rewrite funeqE => x; rewrite Q1_fixed_in_F1. - exact: derivable_mx_cst. -congr (_*m _ + _). + exact: derivable_cst. +congr (_ *m _ + _). rewrite [in X in _ + X = _](_ : (fun x => _) = cst (BoundVect.endp (Q1 0))); last first. by rewrite funeqE => x; rewrite Q1_fixed_in_F1. - by rewrite derive1mx_cst subr0. + by rewrite derive_cst//= subr0. rewrite -spinE unspinK; last first. rewrite ang_vel_mx_is_so; first by []. - move=> t'; by rewrite FromTo_is_O. - move=> t'; exact: derivable_mx_FromTo. + by move=> t'; by rewrite FromTo_is_O. + move=> t'. + exact/derivable_mxP/derivable_mx_FromTo. rewrite /ang_vel_mx mulmxA; congr (_ *m _). rewrite /P /Q /= opprD addrACA subrr add0r mulmxBl -!mulmxA. by rewrite orthogonal_mul_tr ?FromTo_is_O // !mulmx1. @@ -282,16 +325,18 @@ Hypothesis P1_fixed_in_F1 : forall t, BoundVect.endp (P1 t) = BoundVect.endp (P1 (* eqn B.4 *) Lemma velocity_composition_rule_spec (t : R) : - derive1mx (fun x => BoundVect.endp (P x)) t = - derive1mx (fun x => BoundVect.endp (Q x)) t + + 'D_1 (fun x => BoundVect.endp (P x)) t = + 'D_1 (fun x => BoundVect.endp (Q x)) t + ang_vel Rot t *v (FramedVect.v (P t \-b Q t)). Proof. rewrite velocity_composition_rule; congr (_ + _). -suff -> : derive1mx P1 t = 0 by rewrite mul0mx addr0. -apply/matrixP => a b; rewrite !mxE. +suff -> : 'D_1 (fun x => P1 x : 'M__) t = 0 by rewrite mul0mx addr0. +apply/matrixP => a b; rewrite !mxE/=. +rewrite derive_mx//=; last exact/derivable_mxP/derivable_mxP1. +rewrite mxE/=. rewrite (_ : (fun x => _) = cst (P1 0 a b)); last first. rewrite funeqE => x /=; by rewrite /boundvectendp (P1_fixed_in_F1 x). -by rewrite derive1_cst. +by rewrite derive_cst. Qed. End kinematics. @@ -309,13 +354,14 @@ Hypothesis derivable_F1o : forall t, derivable_mx (@TFrame.o R^o \o F1) t 1. Definition p0 := motion p1. Lemma eqn312 t : - derive1mx (fun x => BoundVect.endp (motion p1 x)) t = - derive1mx (fun x => BoundVect.endp (motion (fun=> bvec0 (F1 x)) t)) t + - derive1mx p1 t *m (F1 t) _R^ F + + 'D_1 (fun x => BoundVect.endp (motion p1 x)) t = + 'D_1 (fun x => BoundVect.endp (motion (fun=> bvec0 (F1 x)) t)) t + + 'D_1 (fun x => p1 x : 'M__) t *m (F1 t) _R^ F + ang_vel (fun t => (F1 t) _R^ F) t *v (p1 t *m (F1 t) _R^ F). Proof. rewrite (@velocity_composition_rule _ F _ derivable_F1 derivable_F1o p1 derivable_mx_p1 (fun t => bvec0 (F1 t)) (@BoundVect0_fixed _ _ _ F1)). +rewrite /=. congr (_ + _ *v _). by rewrite /= mul0mx addr0 addrAC subrr add0r. Qed. @@ -330,15 +376,15 @@ Section rigid_body_velocity. Section spatial_velocity. Variables (R : realType) (M : R -> 'M[R^o]_4). -Hypothesis derivableM : forall t, derivable_mx M t 1. +Hypothesis derivableM : forall t, derivable M t 1. Hypothesis MSE : forall t, M t \in 'SE3[R]. -Definition spatial_velocity t : 'M_4 := (M t)^-1 * derive1mx M t. +Definition spatial_velocity t : 'M_4 := (M t)^-1 * 'D_1 M t. Definition spatial_lin_vel := let r : R -> 'M[R^o]_3 := @rot_of_hom _ \o M in let p : R -> 'rV[R^o]_3:= @trans_of_hom _ \o M in - fun t => - p t *m (r t)^T *m derive1mx r t + derive1mx p t. + fun t => - p t *m (r t)^T *m 'D_1 r t + 'D_1 p t. Lemma spatial_velocityE t : let r : R -> 'M[R^o]_3 := @rot_of_hom _ \o M in @@ -346,14 +392,14 @@ Lemma spatial_velocityE t : Proof. move=> r. rewrite /spatial_velocity. -transitivity (inv_hom (M t) * derive1mx M t) => //. +transitivity (inv_hom (M t) * 'D_1 M t) => //. by rewrite inv_homE. rewrite /inv_hom. rewrite /hom. -rewrite derive1mx_SE //. +rewrite derive1mx_SE//=. rewrite (_ : rot_of_hom (M t) = r t) // -/r. rewrite -mulmxE. -rewrite (mulmx_block (r t)^T _ _ _ (derive1mx r t)). +rewrite (mulmx_block (r t)^T _ _ _ ('D_1 r t)). rewrite !(mul0mx,add0r,mul1mx,mulmx0,trmx0,addr0,mulmx1). by rewrite mulmxE -/(ang_vel_mx r t). Qed. @@ -364,7 +410,7 @@ rewrite spatial_velocityE. set r := @rot_of_hom _. rewrite qualifE block_mxKul block_mxKur block_mxKdr 2!eqxx 2!andbT. rewrite ang_vel_mx_is_so // => t0. by rewrite rotation_sub // rot_of_hom_is_SO. -exact: derivable_rot_of_hom. +apply: derivable_rot_of_hom => //=. Qed. Lemma spatial_velocity_is_twist x : @@ -376,7 +422,7 @@ rewrite spatial_velocityE. rewrite /wedge lin_tcoorE ang_tcoorE unspinK //. rewrite ang_vel_mx_is_so // => t0. by rewrite rotation_sub // rot_of_hom_is_SO. -exact: derivable_rot_of_hom. +by apply: derivable_rot_of_hom => //=. Qed. End spatial_velocity. @@ -384,22 +430,24 @@ End spatial_velocity. Section body_velocity. Variables (R : realType) (M : R -> 'M[R^o]_4). -Hypothesis derivableM : forall t, derivable_mx M t 1. +Hypothesis Mt1 : forall t, derivable M t 1. Hypothesis MSE : forall t, M t \in 'SE3[R]. -Definition body_velocity t : 'M_4 := derive1mx M t * (M t)^-1. +Definition body_velocity t : 'M_4 := 'D_1 M t * (M t)^-1. Definition body_lin_vel := let r : R -> 'M[R^o]_3 := @rot_of_hom _ \o M in let p : R -> 'rV[R^o]_3:= @trans_of_hom _ \o M in - fun t => derive1mx p t *m (r t)^T. + fun t => 'D_1 p t *m (r t)^T. -Lemma body_ang_vel_is_so t : body_ang_vel_mx (@rot_of_hom _ \o M) t \is 'so[R]_3. +Lemma body_ang_vel_is_so (t : R) : + body_ang_vel_mx (@rot_of_hom _ \o M) t \is 'so[R]_3. Proof. rewrite /body_ang_vel_mx. have : forall t, (@rot_of_hom R^o \o M) t \is 'O[R]_3. - move=> t0; by rewrite rotation_sub // rot_of_hom_is_SO. -move/ang_vel_mx_is_so => /(_ (derivable_rot_of_hom derivableM))/(_ t). + by move=> t0; rewrite rotation_sub // rot_of_hom_is_SO. +move/ang_vel_mx_is_so => /=. +move => /(_ (fun t => derivable_rot_of_hom (@Mt1 t)))/(_ t). rewrite /ang_vel_mx. move/(conj_so (((rot_of_hom (T:=R) \o M) t)^T)). rewrite !mulmxA !trmxK orthogonal_mul_tr ?rotation_sub // ?rot_of_hom_is_SO //. @@ -411,14 +459,14 @@ Lemma body_velocityE t : let r : R -> 'M[R^o]_3 := @rot_of_hom _ \o M in Proof. move=> r. rewrite /body_velocity. -transitivity (derive1mx M t * inv_hom (M t)). +transitivity ('D_1 M t * inv_hom (M t)). by rewrite inv_homE. rewrite /inv_hom. rewrite /hom. rewrite derive1mx_SE //. rewrite (_ : rot_of_hom (M t) = r t) // -/r. rewrite -mulmxE. -rewrite (mulmx_block (derive1mx r t) _ _ _ (r t)^T). +rewrite (mulmx_block ('D_1 r t) _ _ _ (r t)^T). rewrite !(mul0mx,add0r,mul1mx,mulmx0,trmx0,addr0,mulmx1). by rewrite -/(body_ang_vel_mx _) -/(body_lin_vel _). Qed. @@ -435,7 +483,7 @@ End body_velocity. Section spatial_body_adjoint. Variables (R : realType) (M : R -> 'M[R^o]_4). -Hypothesis derivableM : forall t, derivable_mx M t 1. +Hypothesis derivableM : forall t, derivable M t 1. Hypothesis MSE : forall t, M t \in 'SE3[R]. Lemma spatial_body_velocity x : @@ -443,7 +491,8 @@ Lemma spatial_body_velocity x : Proof. rewrite -/(SE3_action _ _) action_Adjoint; last by []. congr vee; rewrite /spatial_velocity -mulmxE -mulmxA; congr (_ * _). -rewrite veeK; last by rewrite body_velocity_is_se. +rewrite veeK; last first. + by rewrite body_velocity_is_se//=. by rewrite /body_velocity -mulmxA mulVmx ?mulmx1 // SE3_in_unitmx. Qed. @@ -462,7 +511,7 @@ Let o2 t : bvec F := RFrame.o (F2 t). Let r12 : forall t : R, bvec (F1 t) := fun t => BoundVect.mk (F1 t) - (FramedVect.v (rmap (F1 t) `[ \o{F2 t} - \o{F1 t} $ F ])). + (FramedVect.v (rmap (F1 t) '[ \o{F2 t} - \o{F1 t} $ F ])). Hypothesis derivable_F1 : forall t, derivable_mx F1 t 1. Hypothesis derivable_F1o : forall t, derivable_mx (@TFrame.o R^o \o F1) t 1. @@ -478,19 +527,19 @@ Qed. Definition w1 := ang_vel (fun t => (F1 t) _R^ F). -Lemma eqn314_helper t : FramedVect.v (rmap F `[r12 t $ F1 t]) = \o{F2 t} - \o{F1 t}. +Lemma eqn314_helper t : FramedVect.v (rmap F '[r12 t $ F1 t]) = \o{F2 t} - \o{F1 t}. Proof. by rewrite /= -mulmxA FromTo_comp FromToI mulmx1. Qed. (* lin. vel. of Link i as a function of the translational and rotational velocities of Link i-1 *) -Lemma eqn314 t : derive1mx o2 t = derive1mx o1 t + - FramedVect.v (rmap F `[derive1mx r12 t $ F1 t]) +Lemma eqn314 t : 'D_1 (fun x => o2 x : 'M__) t = 'D_1 (fun x => o1 x : 'M__) t + + FramedVect.v (rmap F '['D_1 (fun x => r12 x : 'M__) t $ F1 t]) (* velocity of the origin of Frame i w.r.t. the origin of Frame i-1 *) + w1 t *v (\o{F2 t} - \o{F1 t}). Proof. rewrite -eqn314_helper. move: (@eqn312 _ F _ derivable_F1 _ derivable_r12 derivable_F1o t). -have -> : derive1mx (fun x => BoundVect.endp (motion r12 x)) t = derive1mx o2 t. +have -> : 'D_1 (fun x => BoundVect.endp (motion r12 x)) t = 'D_1 (fun x => o2 x : 'M__) t. rewrite (_ : (fun x => BoundVect.endp (motion r12 x)) = o2) //. rewrite funeqE => t' /=; rewrite -mulmxA FromTo_comp FromToI mulmx1. rewrite addrCA RFrame_o subrr addr0. @@ -510,30 +559,29 @@ Lemma eqn316 t : w2 t = w1 t + w12 t *m ((F1 t) _R^ F). Proof. have : (fun t => (F2 t) _R^ F) = (fun t => ((F2 t) _R^ (F1 t)) *m ((F1 t) _R^ F)). by rewrite funeqE => ?; rewrite FromTo_comp. -move/(congr1 (fun x => derive1mx x)). +move/(congr1 (fun x => 'D_(1:R^o) x)). rewrite funeqE. move/(_ t). -rewrite derive1mxM; last 2 first. - move=> t'; exact: derivable_mx_FromTo'. - move=> t'; exact: derivable_mx_FromTo. -rewrite derive1mx_ang_vel; last 2 first. - move=> t'; by rewrite FromTo_is_O. - move=> t'; exact: derivable_mx_FromTo. -rewrite derive1mx_ang_vel; last 2 first. - move=> t'; by rewrite FromTo_is_O. - move=> t'; exact: derivable_mx_FromTo'. -rewrite derive1mx_ang_vel; last 2 first. - move=> t'; by rewrite FromTo_is_O. - move=> t'; exact: derivable_mx_FromTo. +rewrite derive_mulmx; last 2 first. + exact/derivable_mxP/derivable_mx_FromTo'. + exact/derivable_mxP/derivable_mx_FromTo. +rewrite derive1mx_ang_vel; last first. + by move=> t'; rewrite FromTo_is_O. +rewrite derive1mx_ang_vel; last first. + by move=> t'; rewrite FromTo_is_O. +rewrite derive1mx_ang_vel; last first. + by move=> t'; rewrite FromTo_is_O. rewrite ang_vel_mxE; last 2 first. - move=> t'; by rewrite FromTo_is_O. - move=> t'; exact: derivable_mx_FromTo. + by move=> t'; rewrite FromTo_is_O. + move=> t'; apply/derivable_mxP. + by apply/derivable_mx_FromTo. rewrite ang_vel_mxE; last 2 first. - move=> t'; by rewrite FromTo_is_O. - move=> t'; exact: derivable_mx_FromTo'. + by move=> t'; rewrite FromTo_is_O. + move=> t'; apply/derivable_mxP. + by apply/derivable_mx_FromTo'. rewrite ang_vel_mxE; last 2 first. - move=> t'; by rewrite FromTo_is_O. - move=> t'; exact: derivable_mx_FromTo. + by move=> t'; rewrite FromTo_is_O. + by move=> t'; exact/derivable_mxP/derivable_mx_FromTo. rewrite mulmxE -[in X in _ = X + _](mulr1 ((F2 t) _R^ (F1 t))). rewrite -(@orthogonal_tr_mul _ _ (F _R^ (F1 t))) ?FromTo_is_O //. rewrite -{2}(trmx_FromTo (F1 t) F). @@ -557,77 +605,100 @@ Qed. End link_velocity. -From mathcomp Require Import trigo. +Definition Rz' (T : realType) (a : T) := + col_mx3 (row3 (- sin a) (cos a) 0) (row3 (- cos a) (sin a) 0) 'e_2. -Lemma derive1_cos (R : realType) (t : R) : derive1 (cos : _ -> R^o) t = - sin t. -Proof. -rewrite derive1E. -have u := is_derive_cos t. -by have := @derive_val _ _ _ _ _ _ _ u. -Qed. - -Lemma derive1_sin (R : realType) (t : R) : derive1 (sin : _ -> R^o) t = cos t. -Proof. -rewrite derive1E. -have u := is_derive_sin t. -by have := @derive_val _ _ _ _ _ _ _ u. -Qed. - -Lemma derivable_sin (R : realType) (t : R) : derivable (sin : R^o -> R^o) t 1. -Proof. exact: ex_derive. Qed. - -Lemma derivable_cos (R : realType) (t : R) : derivable (cos : R^o -> R^o) t 1. -Proof. exact: ex_derive. Qed. - -Lemma derivable_cos_comp (R : realType) (t : R) (a : R^o -> R^o) : - derivable a t 1 -> derivable (cos \o a : _ -> R^o) t 1. -Proof. by move=> /derivableP Hs; exact: ex_derive. Qed. - -Lemma derivable_sin_comp (R : realType) (t : R) (a : R^o -> R^o) : - derivable a t 1 -> derivable ((sin : _ -> R^o) \o a) t 1. -Proof. by move=> /derivableP Hs; exact: ex_derive. Qed. - -Lemma derive1_cos_comp (R : realType) t (a : R^o -> R^o) : derivable a t 1 -> - derive1 (cos \o a : _ -> R^o) t = - (derive1 a t) * sin (a t). +Lemma derivable_Rz {R : realType} (a : R -> R) t : + derivable a t 1 -> + derivable (fun x : R^o => Rz (a x)) t 1. Proof. -move=> H; rewrite (derive1_comp H); last exact: derivable_cos. -by rewrite derive1_cos mulrC mulNr mulrN. +move=> at1. +apply/derivable_mxP. +move=> [[|[|[|//=]]]] ? [[|[|[|//=]]]] ?. +- rewrite [X in derivable X t 1](_ : _ = cos \o a); last first. + by apply/funext => x/=; rewrite !mxE/=. + exact/derivable_cos_comp. +- rewrite [X in derivable X t 1](_ : _ = sin \o a); last first. + by apply/funext => x/=; rewrite !mxE/=. + exact/derivable_sin_comp. +- rewrite [X in derivable X t 1](_ : _ = 0); last first. + by apply/funext => x/=; rewrite !mxE/=. + exact/derivable_cst. +- rewrite [X in derivable X t 1](_ : _ = - sin \o a); last first. + by apply/funext => x/=; rewrite !mxE/=. + apply/derivableN. + exact/derivable_sin_comp. +- rewrite [X in derivable X t 1](_ : _ = cos \o a); last first. + by apply/funext => x/=; rewrite !mxE/=. + exact/derivable_cos_comp. +- rewrite [X in derivable X t 1](_ : _ = 0); last first. + by apply/funext => x/=; rewrite !mxE/=. + exact/derivable_cst. +- rewrite [X in derivable X t 1](_ : _ = 0); last first. + by apply/funext => x/=; rewrite !mxE/=. + exact/derivable_cst. +- rewrite [X in derivable X t 1](_ : _ = 0); last first. + by apply/funext => x/=; rewrite !mxE/=. + exact/derivable_cst. +- rewrite [X in derivable X t 1](_ : _ = 1); last first. + by apply/funext => x/=; rewrite !mxE/=. + exact/derivable_cst. Qed. Lemma derive1mx_RzE (R : realType) (a : R^o -> R^o) t : derivable a t 1 -> - derive1mx (fun x => Rz (a x) : 'M[R^o]__) t = + 'D_1 (fun x => Rz (a x) : 'M[R^o]__) t = derive1 a t *: col_mx3 (row3 (- sin (a t)) (cos (a t)) 0) (row3 (- cos (a t)) (- sin (a t)) 0) 0. Proof. move=> Ha. apply/matrix3P/and9P; split; rewrite !mxE /=. -- rewrite (_ : (fun _ => _) = cos \o a); last by rewrite funeqE => x; rewrite !mxE. +- rewrite derive_mx; last exact: derivable_Rz. + rewrite mxE/=. + rewrite (_ : (fun _ => _) = cos \o a); last by rewrite funeqE => x; rewrite !mxE. + rewrite -derive1E. rewrite (derive1_comp Ha); last exact/derivable_cos. by rewrite derive1_cos mulrC. -- rewrite (_ : (fun _ => _) = sin \o a); last by rewrite funeqE => x; rewrite !mxE. +- rewrite derive_mx; last exact: derivable_Rz. + rewrite mxE/=. + rewrite (_ : (fun _ => _) = sin \o a); last by rewrite funeqE => x; rewrite !mxE. + rewrite -derive1E. rewrite (derive1_comp Ha); last exact/derivable_sin. by rewrite derive1_sin mulrC. -- rewrite (_ : (fun _ => _) = \0); last by rewrite funeqE => x; rewrite !mxE. - by rewrite derive1_cst mulr0. -- rewrite (_ : (fun _ => _) = - sin \o a); last by rewrite funeqE => x; rewrite !mxE. +- rewrite derive_mx; last exact: derivable_Rz. + rewrite mxE/=. + rewrite (_ : (fun _ => _) = \0); last by rewrite funeqE => x; rewrite !mxE. + by rewrite derive_cst mulr0. +- rewrite derive_mx; last exact: derivable_Rz. + rewrite mxE/=. + rewrite (_ : (fun _ => _) = - sin \o a); last by rewrite funeqE => x; rewrite !mxE. rewrite (_ : - _ \o _ = - (sin \o a)) // derive1E deriveN; last first. apply/derivable1_diffP/differentiable_comp. exact/derivable1_diffP. exact/derivable1_diffP/derivable_sin. - rewrite -derive1E (derive1_comp Ha); last exact/derivable_sin. + rewrite -!derive1E (derive1_comp Ha); last exact/derivable_sin. by rewrite derive1_sin mulrN mulrC. -- rewrite (_ : (fun _ => _) = cos \o a); last by rewrite funeqE => x; rewrite !mxE. - rewrite (derive1_comp Ha); last exact/derivable_cos. +- rewrite derive_mx; last exact: derivable_Rz. + rewrite mxE/=. + rewrite (_ : (fun _ => _) = cos \o a); last by rewrite funeqE => x; rewrite !mxE. + rewrite -derive1E (derive1_comp Ha); last exact/derivable_cos. by rewrite derive1_cos mulrN mulNr mulrC. -- rewrite (_ : (fun _ => _) = \0); last by rewrite funeqE => x; rewrite !mxE. - by rewrite derive1_cst mulr0. -- rewrite (_ : (fun _ => _) = \0); last by rewrite funeqE => x; rewrite !mxE. - by rewrite derive1_cst mulr0. -- rewrite (_ : (fun _ => _) = \0); last by rewrite funeqE => x; rewrite !mxE. - by rewrite derive1_cst mulr0. -- rewrite (_ : (fun _ => _) = cst 1); last by rewrite funeqE => x; rewrite !mxE. - by rewrite derive1_cst mulr0. +- rewrite derive_mx; last exact: derivable_Rz. + rewrite mxE/=. + rewrite (_ : (fun _ => _) = \0); last by rewrite funeqE => x; rewrite !mxE. + by rewrite derive_cst mulr0. +- rewrite derive_mx; last exact: derivable_Rz. + rewrite mxE/=. + rewrite (_ : (fun _ => _) = \0); last by rewrite funeqE => x; rewrite !mxE. + by rewrite derive_cst mulr0. +- rewrite derive_mx; last exact: derivable_Rz. + rewrite mxE/=. + rewrite (_ : (fun _ => _) = \0); last by rewrite funeqE => x; rewrite !mxE. + by rewrite derive_cst mulr0. +- rewrite derive_mx; last exact: derivable_Rz. + rewrite mxE/=. + rewrite (_ : (fun _ => _) = cst 1); last by rewrite funeqE => x; rewrite !mxE. + by rewrite derive_cst mulr0. Qed. (* example 3.1 [sciavicco]*) @@ -696,11 +767,15 @@ Section scara_geometric_jacobian. Variable R : realType. Variable theta1 : R -> R. +Hypothesis derivable_theta1 : forall t, derivable theta1 t 1. Variable a1 : R. Variable theta2 : R -> R. +Hypothesis derivable_theta2 : forall t, derivable theta2 t 1. Variable a2 : R. Variable d3 : R -> R. +Hypothesis derivable_d3 : forall t, derivable d3 t 1. Variable theta4 : R -> R. +Hypothesis derivable_theta4 : forall t, derivable theta4 t 1. Variable d4 : R. (* direct kinematics equation written in function of the joint variables, from scara.v *) @@ -709,7 +784,7 @@ Let trans t := scara_trans (theta1 t) a1 (theta2 t) a2 (d3 t) d4. Definition scara_end_effector t : 'M[R]_4 := hom (rot t) (trans t). Let scara_lin_vel : R -> 'rV[R]_3 := - derive1mx (@trans_of_hom R^o \o scara_end_effector). + 'D_1 (@trans_of_hom R^o \o scara_end_effector). Let scara_ang_vel : R -> 'rV[R]_3 := ang_vel (@rot_of_hom R^o \o scara_end_effector). @@ -723,7 +798,7 @@ Definition scara_joints : 'I_4 -> joint R := Definition scara_joint_variables t : 'rV[R^o]_4 := \row_i (joint_variable (scara_joints i) t). -Let scara_joint_velocities : R -> 'rV[R^o]_4 := derive1mx scara_joint_variables. +Let scara_joint_velocities : R -> 'rV[R^o]_4 := 'D_1 scara_joint_variables. (* specification of scara frames *) Variables scara_frames : 'I_5 -> R -> tframe R. @@ -740,6 +815,22 @@ Hypothesis o2E : forall t, \o{Fim1 2%:R t} = \o{Fim1 1 t} + Hypothesis o3E : forall t, \o{Fim1 3%:R t} = \o{Fim1 2%:R t} + (d3 t) *: 'e_2. Hypothesis o4E : forall t, \o{Fmax t} = \o{Fim1 3%:R t} + d4 *: 'e_2. +Lemma derivable_joint_variable t : + derivable (fun t0 : R^o => \row_i joint_variable (scara_joints i) t0) t 1. +Proof. +apply/derivable_mxP => a b. +rewrite (ord1 a)/=. +move: b => [[|[|[|[|//]]]]]/= ?. +- under eq_fun do rewrite mxE/=. + exact: derivable_theta1. +- under eq_fun do rewrite mxE/=. + exact: derivable_theta2. +- under eq_fun do rewrite mxE/=. + exact: derivable_d3. +- under eq_fun do rewrite mxE/=. + exact: derivable_theta4. +Qed. + Lemma scale_realType (K : realType) (k1 : K) (k2 : K^o) : k1 *: k2 = k1 * k2. Proof. by []. Qed. @@ -756,24 +847,46 @@ rewrite /geo_jac; set a := (X in _ *m @row_mx _ _ 3 3 X _). rewrite (mul_mx_row _ a) {}/a; congr (@row_mx _ _ 3 3 _ _). - rewrite /scara_lin_vel (_ : @trans_of_hom R \o _ = trans); last first. rewrite funeqE => x /=; exact: trans_of_hom_hom. - rewrite /trans /scara_trans derive1mxE [RHS]row3_proj /= ![in RHS]mxE [in RHS]/=. + rewrite /trans /scara_trans. + rewrite derive_mx//=; last first. + apply: derivable_row3; apply: derivableD => /=; [ | | | + | exact: derivable_cst + | exact: H3]. + apply: derivableM; first exact: derivable_cst. + by apply: derivable_cos_comp; exact: derivableD. + apply: derivableM; first exact: derivable_cst. + exact: derivable_cos_comp. + apply: derivableM; first exact: derivable_cst. + by apply: derivable_sin_comp; exact: derivableD. + apply: derivableM; first exact: derivable_cst. + exact: derivable_sin_comp. + rewrite [RHS]row3_proj /= ![in RHS]mxE [in RHS]/=. transitivity ( derive1 (theta1 : R^o -> R^o) t *: (Fim1 0 t)~k *v (\o{Fmax t} - \o{Fim1 0 t}) + derive1 (theta2 : R^o -> R^o) t *: (Fim1 1 t)~k *v (\o{Fmax t} - \o{Fim1 1 t}) + derive1 (d3 : R^o -> R^o) t *: (Fim1 2 t)~k + derive1 (theta4 : R^o -> R^o) t *: (Fim1 3%:R t)~k *v (\o{Fmax t} - \o{Fim1 3%:R t})). - rewrite /scara_joint_velocities /scara_joint_variables derive1mxE /geo_jac_lin /=. + rewrite /scara_joint_velocities /scara_joint_variables. + rewrite derive_mx; last exact: derivable_joint_variable. + rewrite /geo_jac_lin /=. apply/rowP => i; rewrite 3![in RHS]mxE [in LHS]mxE sum4E; (repeat apply: f_equal2). - rewrite 2!mxE /=. rewrite (linearZl_LR _ (\o{Fmax t} - \o{Fim1``_t}))/=. - by rewrite [in RHS]mxE. + rewrite [in RHS]mxE !derive1E//=. + by under eq_fun do rewrite !mxE/=. - rewrite 2!mxE /=. rewrite (linearZl_LR _ (\o{Fmax t} - \o{Fim1 1 t}))/=. - by rewrite [in RHS]mxE. - - by rewrite 2!mxE [in RHS]mxE. + under eq_fun do rewrite !mxE/=. + rewrite derive1E/=. + by rewrite !mxE. + - rewrite 2!mxE [in RHS]mxE/=. + rewrite derive1E/=. + by under eq_fun do rewrite !mxE/=. - rewrite 2!mxE /=. - by rewrite (linearZl_LR _ (\o{Fmax t} - \o{Fim1 3 t}))/= [in RHS]mxE. + rewrite (linearZl_LR _ (\o{Fmax t} - \o{Fim1 3 t}))/= [in RHS]mxE. + rewrite derive1E. + by under eq_fun do rewrite !mxE/=. rewrite o0E subr0. rewrite {1}o4E. rewrite (linearDr _ (_ *: Fim1``_t|,2)) /=. @@ -811,15 +924,21 @@ rewrite (mul_mx_row _ a) {}/a; congr (@row_mx _ _ 3 3 _ _). rewrite {1}o2E {1}o1E. rewrite (_ : (fun _ => _) = (a2 \*: (cos \o (theta2 + theta1) : R^o -> R^o)) + - (a1 *: (cos \o theta1 : R^o -> R^o))) //. + (a1 *: (cos \o theta1 : R^o -> R^o))); last first. + apply/funext => x/=. + by rewrite !mxE/=. rewrite (_ : (fun _ => _) = (a2 \*: (sin \o (theta2 + theta1) : _ -> R^o)) + - (a1 *: (sin \o theta1 : _ -> R^o))) //. + (a1 *: (sin \o theta1 : _ -> R^o))); last first. + apply/funext => x/=. + by rewrite !mxE/=. rewrite row3e2; congr (_ + _ *: _); last first. - by rewrite Hzvec. - - rewrite [in RHS]derive1E [in RHS]deriveD; last 2 first. + - rewrite derive1E. + under eq_fun do rewrite !mxE/=. + rewrite [in RHS]deriveD; last 2 first. exact: ex_derive. exact: H3. - by rewrite deriveE // diff_cst add0r derive1E. + by rewrite derive_cst// add0r. - rewrite 3!(linearDr _ ((theta1^`())%classic t *: Fim1``_t|,2))/=. rewrite (linearDr _ (Fim1 1 t)|,2)/=. rewrite (linearZr_LR _ _ (a1 * cos (theta1 t)))/=. @@ -834,8 +953,8 @@ rewrite (mul_mx_row _ a) {}/a; congr (@row_mx _ _ 3 3 _ _). rewrite scalerBr. rewrite -!addrA addrCA addrC -!addrA (addrCA (- _)) !addrA. rewrite -2!addrA [in RHS]addrC; congr (_ + _). - - rewrite !scalerA -2!scalerDl row3e1; congr (_ *: _). - rewrite [in RHS]derive1E deriveD; last 2 first. + + rewrite !scalerA -2!scalerDl row3e1; congr (_ *: _). + rewrite deriveD; last 2 first. apply/derivableZ/derivable_sin_comp/derivableD; [exact H2 | exact H1]. exact/derivableZ/derivable_sin_comp. rewrite deriveZ /=; last first. @@ -859,9 +978,9 @@ rewrite (mul_mx_row _ a) {}/a; congr (@row_mx _ _ 3 3 _ _). rewrite derive1E. by rewrite addrC. by rewrite derive1E addrC. - - rewrite !{1}scalerA !addrA -3!{1}scaleNr -2!scalerDl row3e0. + + rewrite !{1}scalerA !addrA -3!{1}scaleNr -2!scalerDl row3e0. congr (_ *: _). - rewrite [in RHS]derive1E deriveD; last 2 first. + rewrite deriveD; last 2 first. by apply/derivableZ/derivable_cos_comp/derivableD; [exact H2 | exact H1]. by apply/derivableZ/derivable_cos_comp; exact H1. rewrite deriveZ /=; last first. @@ -895,9 +1014,22 @@ rewrite (mul_mx_row _ a) {}/a; congr (@row_mx _ _ 3 3 _ _). transitivity (derive1 (theta1 : R^o -> R^o) t *: (Fim1 0 t)~k + derive1 (theta2 : R^o -> R^o) t *: (Fim1 1 t)~k + derive1 (theta4 : R^o -> R^o) t *: (Fim1 3%:R t)~k). - rewrite /scara_joint_velocities /scara_joint_variables derive1mxE /geo_jac_ang /=. + rewrite /scara_joint_velocities /scara_joint_variables. + rewrite derive_mx; last first. + (* derivable (fun t0 : R^o => \row_i joint_variable (scara_joints i) t0) t 1 *) + exact: derivable_joint_variable. + rewrite /geo_jac_ang /=. apply/rowP => i; rewrite !mxE sum4E !mxE {1}mulr0 addr0. - by rewrite -!/(Fim1 _) [Fim1 0 _]lock [Fim1 1 _]lock [Fim1 3%:R _]lock /= -!lock. + rewrite -!/(Fim1 _) [Fim1 0 _]lock [Fim1 1 _]lock [Fim1 3%:R _]lock /= -!lock. + rewrite !derive1E. + under eq_fun do rewrite !mxE/=. + rewrite -[RHS]addrA. + rewrite -[LHS]addrA. + congr (_ + _). + under eq_fun do rewrite !mxE/=. + congr (_ + _). + under eq_fun do rewrite !mxE/=. + done. rewrite !Hzvec -2!scalerDl e2row row3Z mulr0 mulr1. rewrite [in RHS]derive1E deriveD; [|apply/derivableD|by []]; last 2 first. exact: H1. @@ -918,10 +1050,9 @@ Variable (phi : 'rV[R^o]_n -> 'rV[R^o]_3). Let Jphi := jacobian phi. Lemma dp (q : R^o -> 'rV[R^o]_n) t : - derive1mx (p \o q) t = derive1mx q t *m Jp (q t). (* 3.56 *) + 'D_1 (p \o q) t = 'D_1 q t *m Jp (q t). (* 3.56 *) Proof. rewrite /Jp /jacobian mul_rV_lin1. -rewrite /derive1mx. Abort. End analytical_jacobian. diff --git a/euclidean.v b/euclidean.v index 2765d591..ed35b7d3 100644 --- a/euclidean.v +++ b/euclidean.v @@ -1,4 +1,4 @@ -(* coq-robot (c) 2017 AIST and INRIA. License: LGPL-2.1-or-later. *) +(* robot-rocq (c) 2026 AIST and INRIA. License: LGPL-2.1-or-later. *) From HB Require Import structures. From mathcomp Require Import all_ssreflect ssralg ssrint ssrnum rat poly. From mathcomp Require Import sesquilinear. @@ -7,8 +7,8 @@ From mathcomp Require Import realalg complex fingroup perm. From mathcomp Require Import reals. Require Import ssr_ext. -(******************************************************************************) -(* Elements of Euclidean geometry *) +(**md**************************************************************************) +(* # Elements of Euclidean geometry *) (* *) (* This file provides elements of Euclidean geometry, with specializations to *) (* the 3D case. It develops the theory of the dot-product and of the *) @@ -17,20 +17,25 @@ Require Import ssr_ext. (* preservation of the dot-product by orthogonal matrices or a closed formula *) (* for the characteristic polynomial of a 3x3 matrix. *) (* *) +(* ``` *) (* jacobi_identity == Jacobi identity *) (* lieAlgebraType R == the type of Lie algebra over R *) (* lie[x, y] == Lie brackets *) +(* ``` *) (* *) +(* ``` *) (* u *d w == the dot-product of the vectors u and v, i.e., the only *) (* component of the 1x1-matrix u * v^T *) -(* norm u == the norm of vector u, i.e., the square root of u *d u *) +(* enorm u == the norm of vector u, i.e., the square root of u *d u *) (* normalize u == scales vector u to be of unit norm *) (* A _|_ B == A and B are normal *) (* 'O[T]_n == the type of orthogonal matrices of size n *) (* 'SO[T]_n == the type of rotation matrices of size n *) (* cross M == generalized cross-product *) +(* ``` *) (* *) (* Specializations to the 3D case: *) +(* ``` *) (* row2 a b == the row vector [a,b] *) (* row3 a b c == the row vector [a,b,c] *) (* col_mx2 u v == specialization of col_mx two row vectors of size 2 *) @@ -41,6 +46,7 @@ Require Import ssr_ext. (* algebra *) (* vaxis_euler M == the vector-axis of the rotation matrix M of Euler's *) (* theorem *) +(* ``` *) (* *) (******************************************************************************) @@ -199,8 +205,8 @@ Section dotmul_bilinear_Pz. Variables (R : comPzRingType) (n : nat). Definition dotmul_rev (v u : 'rV[R]_n) := u *d v. -Canonical rev_dotmul := @RevOp _ _ _ dotmul_rev (@dotmul R n) - (fun _ _ => erefl). +(*Canonical rev_dotmul := @RevOp _ _ _ dotmul_rev (@dotmul R n) + (fun _ _ => erefl).*) Lemma dotmul_is_linear u : linear (dotmul u : 'rV[R]_n -> R^o). Proof. move=> /= k v w; by rewrite dotmulDr dotmulvZ. Qed. @@ -252,50 +258,75 @@ move/allP => H; apply/eqP/rowP => i. apply/eqP; by rewrite mxE -sqrf_eq0 expr2 -(implyTb ( _ == _)) H. Qed. -End dot_product. +Lemma dotmul_is_hermitian x y : + (@dotmul T n) x y = (-1) ^+ false * idfun ((@dotmul T n) y x). +Proof. +by rewrite /= expr0 mul1r dotmulC. +Qed. + +HB.instance Definition _ := + @isHermitianSesquilinear.Build _ _ _ _ _ dotmul_is_hermitian. -Section norm. +Check @dotmul _ _ : {symmetric 'rV[T]_n}. -Variables (T : rcfType) (n : nat). +Let neq0_enorm_gt0 (u : 'rV[T]_n) : u != 0 -> 0 < dotmul u u. +Proof. +move=> u0. +by rewrite lt_neqAle eq_sym dotmulvv0 u0 le0dotmul. +Qed. + +HB.instance Definition _ := isDotProduct.Build _ _ (@dotmul T n) neq0_enorm_gt0. + +End dot_product. + +Section euclidean_norm. +Context {T : rcfType} {n : nat}. Implicit Types u v : 'rV[T]_n. -Definition norm u := Num.sqrt (u *d u). +Local Notation "''[' u , v ]" := (dotmul u v) : ring_scope. +Local Notation "''[' u ]" := '[u, u]%R : ring_scope. + +Definition enorm u : T := Num.sqrt '[u]. + +Local Notation "`| x |_e" := (enorm x). -Lemma normN u : norm (- u) = norm u. -Proof. by rewrite /norm dotmulNv dotmulvN opprK. Qed. +Lemma enormN u : `| - u |_e = enorm u. +Proof. +by rewrite /enorm (@hnormN T false idfun). +Qed. -Lemma norm0 : norm 0 = 0. -Proof. by rewrite /norm dotmul0v sqrtr0. Qed. +Lemma enorm0 : `| 0 |_e = 0. +Proof. by rewrite /enorm dotmul0v sqrtr0. Qed. -Lemma norm_delta_mx i : norm 'e_i = 1. -Proof. by rewrite /norm /dotmul trmx_delta mul_delta_mx mxE !eqxx sqrtr1. Qed. +Lemma enorm_delta_mx i : `| 'e_i |_e = 1. +Proof. by rewrite /enorm /dotmul trmx_delta mul_delta_mx mxE !eqxx sqrtr1. Qed. -Lemma norm_ge0 u : norm u >= 0. -Proof. by apply sqrtr_ge0. Qed. -Hint Resolve norm_ge0 : core. +Lemma enorm_ge0 u : `| u |_e >= 0. +Proof. exact: sqrtr_ge0. Qed. +Hint Resolve enorm_ge0 : core. -Lemma normr_norm u : `|norm u| = norm u. +Lemma normr_enorm u : `| `| u |_e | = `| u |_e. Proof. by rewrite ger0_norm. Qed. -Lemma norm_eq0 u : (norm u == 0) = (u == 0). +Lemma enorm_eq0 u : (`| u |_e == 0) = (u == 0). Proof. by rewrite -sqrtr0 eqr_sqrt // ?dotmulvv0 // le0dotmul. Qed. -Lemma norm_gt0 u : (0 < norm u) = (u != 0). -Proof. by rewrite lt_neqAle norm_ge0 andbT eq_sym norm_eq0. Qed. +Lemma enorm_gt0 u : (0 < `| u |_e ) = (u != 0). +Proof. by rewrite lt_neqAle enorm_ge0 andbT eq_sym enorm_eq0. Qed. -Lemma normZ (k : T) u : norm (k *: u) = `|k| * norm u. +Lemma enormZ (k : T) u : `| k *: u |_e = `| k | * `| u |_e. Proof. -by rewrite /norm dotmulvZ dotmulZv mulrA sqrtrM -expr2 ?sqrtr_sqr // sqr_ge0. +by rewrite /enorm dotmulvZ dotmulZv mulrA sqrtrM -expr2 ?sqrtr_sqr // sqr_ge0. Qed. -Lemma dotmulvv u : u *d u = norm u ^+ 2. +Lemma dotmulvv u : u *d u = `| u |_e ^+ 2. Proof. -rewrite /norm [_ ^+ _]sqr_sqrtr // dotmulE sumr_ge0 //. +rewrite /enorm [_ ^+ _]sqr_sqrtr // dotmulE sumr_ge0 //. by move=> i _; rewrite sqr_ge0. Qed. Lemma polarization_identity v u : - v *d u = 1 / 4%:R * (norm (v + u) ^+ 2 - norm (v - u) ^+ 2). + v *d u = 1 / 4%:R * (`|v + u|_e ^+ 2 - `|v - u|_e ^+ 2). Proof. apply: (@mulrI _ 4%:R); first exact: pnatf_unit. rewrite [in RHS]mulrA div1r divrr ?pnatf_unit // mul1r. @@ -306,74 +337,75 @@ rewrite opprD (addrCA (u *d u)) subrr addr0. by rewrite opprD addrA subrr add0r dotmulvN -mulNrn opprK. Qed. -Lemma sqr_norm u : norm u ^+ 2 = \sum_i u``_i ^+ 2. -Proof. rewrite -dotmulvv dotmulE; apply/eq_bigr => /= i _; by rewrite expr2. Qed. +Lemma sqr_enorm u : `| u |_e ^+ 2 = \sum_i u``_i ^+ 2. +Proof. by rewrite -dotmulvv dotmulE; apply/eq_bigr => /= i _; rewrite expr2. Qed. -Lemma mxtrace_tr_mul u : \tr (u^T *m u) = norm u ^+ 2. +Lemma mxtrace_tr_mul u : \tr (u^T *m u) = `| u |_e ^+ 2. Proof. -rewrite /mxtrace sqr_norm; apply/eq_bigr => /= i _; by rewrite mulmx_trE -expr2. +by rewrite /mxtrace sqr_enorm; apply/eq_bigr => /= i _; rewrite mulmx_trE -expr2. Qed. -Section norm1. - +Section enorm1. Variable u : 'rV[T]_n. -Hypothesis u1 : norm u = 1. +Hypothesis u1 : `| u |_e = 1. Lemma norm1_neq0 : u != 0. -Proof. move: u1; rewrite -norm_eq0 => ->; exact: oner_neq0. Qed. +Proof. move: u1; rewrite -enorm_eq0 => ->; exact: oner_neq0. Qed. Lemma dotmul1 : u *m u^T = 1. Proof. by rewrite dotmulP dotmulvv u1 expr1n. Qed. -End norm1. +End enorm1. -End norm. +End euclidean_norm. -Section normalize. +Notation "`| x |_e" := (enorm x). +Section normalize. Variables (T : rcfType) (n : nat). Implicit Type u v : 'rV[T]_3. -Definition normalize v := (norm v)^-1 *: v. +Definition normalize v := (`| v |_e)^-1 *: v. Lemma normalize0 : normalize 0 = 0. Proof. by rewrite /normalize scaler0. Qed. Lemma normalizeN u : normalize (- u) = - normalize u. -Proof. by rewrite /normalize normN scalerN. Qed. +Proof. by rewrite /normalize enormN scalerN. Qed. -Lemma normalizeI v : norm v = 1 -> normalize v = v. +Lemma normalizeI v : `| v |_e = 1 -> normalize v = v. Proof. by move=> v1; rewrite /normalize v1 invr1 scale1r. Qed. -Lemma norm_normalize v : v != 0 -> norm (normalize v) = 1. +Lemma norm_normalize v : v != 0 -> `| normalize v |_e = 1. Proof. -move=> v0; rewrite normZ ger0_norm; last by rewrite invr_ge0 // norm_ge0. -by rewrite mulVr // unitfE norm_eq0. +move=> v0; rewrite enormZ ger0_norm; last by rewrite invr_ge0// enorm_ge0. +by rewrite mulVr// unitfE enorm_eq0. Qed. Lemma normalize_eq0 v : (normalize v == 0) = (v == 0). Proof. apply/idP/idP => [|/eqP ->]; last by rewrite normalize0. case/boolP : (v == 0) => [//| /norm_normalize]. -rewrite -norm_eq0 => -> /negPn; by rewrite oner_neq0. +by rewrite -enorm_eq0 => -> /negPn; rewrite oner_neq0. Qed. -Lemma norm_scale_normalize u : norm u *: normalize u = u. +Lemma norm_scale_normalize u : `| u |_e *: normalize u = u. Proof. -case/boolP : (u == 0) => [/eqP -> {u}|u0]; first by rewrite norm0 scale0r. -by rewrite /normalize scalerA divrr ?scale1r // unitfE norm_eq0. +have [->|u0] := eqVneq u 0; first by rewrite enorm0 scale0r. +by rewrite /normalize scalerA divrr ?scale1r // unitfE enorm_eq0. Qed. -Lemma normalizeZ u (u0 : u != 0) k (k0 : 0 < k) : normalize (k *: u) = normalize u. +Lemma normalizeZ u (u0 : u != 0) k (k0 : 0 < k) : + normalize (k *: u) = normalize u. Proof. -rewrite {1}/normalize normZ gtr0_norm // invrM ?unitfE ?gt_eqF // ?norm_gt0 //. +rewrite {1}/normalize enormZ gtr0_norm // invrM ?unitfE ?gt_eqF ?enorm_gt0//. by rewrite scalerA -mulrA mulVr ?mulr1 ?unitfE ?gt_eqF. Qed. (* NB: not used *) -Lemma dotmul_normalize_norm u : u *d normalize u = norm u. +Lemma dotmul_normalize_enorm u : u *d normalize u = `| u |_e. Proof. -case/boolP : (u == 0) => [/eqP ->{u}|u0]; first by rewrite norm0 dotmul0v. +have [->|u0] := eqVneq u 0; first by rewrite enorm0 dotmul0v. rewrite -{1}(norm_scale_normalize u) dotmulZv dotmulvv norm_normalize //. by rewrite expr1n mulr1. Qed. @@ -382,9 +414,9 @@ Lemma dotmul_normalize u v : (normalize u *d v == 0) = (u *d v == 0). Proof. case/boolP : (u == 0) => [/eqP ->|u0]; first by rewrite normalize0. apply/idP/idP. - rewrite /normalize dotmulZv mulf_eq0 => /orP [|//]. - by rewrite invr_eq0 norm_eq0 (negbTE u0). -rewrite /normalize dotmulZv => /eqP ->; by rewrite mulr0. + rewrite /normalize dotmulZv mulf_eq0 => /orP[|//]. + by rewrite invr_eq0 enorm_eq0 (negbTE u0). +by rewrite /normalize dotmulZv => /eqP ->; rewrite mulr0. Qed. End normalize. @@ -657,23 +689,25 @@ rewrite -subr_eq0 -{1}(scale1r (v *m _)) -scalerBl scaler_eq0 => /orP []. by rewrite dotmul_conjc_eq0 (negbTE v0). Qed. -Lemma norm_row_of_O (T : rcfType) n M : M \is 'O[T]_n.+1 -> forall i, norm (row i M) = 1. +Lemma enorm_row_of_O (T : rcfType) n M : M \is 'O[T]_n.+1 -> + forall i, `|row i M|_e = 1. Proof. move=> MSO i. -apply/eqP; rewrite -(@eqrXn2 _ 2) // ?norm_ge0 // expr1n; apply/eqP. -rewrite -dotmulvv; move/orthogonalP : MSO => /(_ i i) ->; by rewrite eqxx. +apply/eqP; rewrite -(@eqrXn2 _ 2) ?enorm_ge0// expr1n; apply/eqP. +by rewrite -dotmulvv; move/orthogonalP : MSO => /(_ i i) ->; rewrite eqxx. Qed. Lemma dot_row_of_O (T : pzRingType) n M : M \is 'O[T]_n.+1 -> forall i j, row i M *d row j M = (i == j)%:R. Proof. by move/orthogonalP. Qed. -Lemma norm_col_of_O (T : rcfType) n M : M \is 'O[T]_n.+1 -> forall i, norm (col i M)^T = 1. +Lemma enorm_col_of_O (T : rcfType) n M : M \is 'O[T]_n.+1 -> + forall i, `| (col i M)^T |_e = 1. Proof. move=> MSO i. apply/eqP. -rewrite -(@eqrXn2 _ 2) // ?norm_ge0 // expr1n -dotmulvv tr_col dotmulvv. -by rewrite norm_row_of_O ?expr1n // orthogonalV. +rewrite -(@eqrXn2 _ 2) ?enorm_ge0// expr1n -dotmulvv tr_col dotmulvv. +by rewrite enorm_row_of_O ?expr1n// orthogonalV. Qed. Lemma orth_preserves_sqr_norm (T : comPzRingType) n M : M \is 'O[T]_n.+1 -> @@ -703,23 +737,25 @@ by rewrite eqr_pMn2r // => /eqP. Qed. Lemma orth_preserves_norm (T : rcfType) n M : M \is 'O[T]_n.+1 -> - {mono (fun u => u *m M) : x / norm x }. -Proof. move=> HM v; by rewrite /norm (proj2 (orth_preserves_dotmul M) HM). Qed. + {mono (fun u => u *m M) : x / `| x |_e }. +Proof. move=> HM v; by rewrite /enorm (proj2 (orth_preserves_dotmul M) HM). Qed. -Lemma Oij_ub (T : rcfType) n (M : 'M[T]_n.+1) : M \is 'O[T]_n.+1 -> forall i j, `| M i j | <= 1. +Lemma Oij_ub (T : rcfType) n (M : 'M[T]_n.+1) : M \is 'O[T]_n.+1 -> + forall i j, `| M i j | <= 1. Proof. -move=> /norm_row_of_O MO i j; rewrite leNgt; apply/negP => abs. +move=> /enorm_row_of_O MO i j; rewrite leNgt; apply/negP => abs. move: (MO i) => /(congr1 (fun x => x ^+ 2)); apply/eqP. -rewrite gt_eqF // sqr_norm (bigD1 j) //= !mxE -(addr0 (1 ^+ 2)) ltr_leD //. +rewrite gt_eqF // sqr_enorm (bigD1 j) //= !mxE -(addr0 (1 ^+ 2)) ltr_leD //. by rewrite -(sqr_normr (M _ _)) ltrXn2r. rewrite sumr_ge0 // => k ij; by rewrite sqr_ge0. Qed. -Lemma O_tr_idmx (T : rcfType) n (M : 'M[T]_n.+1) : M \is 'O[T]_n.+1 -> \tr M = n.+1%:R -> M = 1. +Lemma O_tr_idmx (T : rcfType) n (M : 'M[T]_n.+1) : M \is 'O[T]_n.+1 -> + \tr M = n.+1%:R -> M = 1. Proof. -move=> MO; move: (MO) => /norm_row_of_O MO' tr3. -have Mdiag : forall i, M i i = 1. - move=> i; apply/eqP/negPn/negP => Mii; move: tr3; apply/eqP. +move=> MO; move: (MO) => /enorm_row_of_O MO' tr3. +have Mdiag i : M i i = 1. + apply/eqP/negPn/negP => Mii; move: tr3; apply/eqP. rewrite lt_eqF // /mxtrace. rewrite (bigD1 i) //=. rewrite (eq_bigr (fun i : 'I_n.+1 => M (inord i) (inord i))); last first. @@ -734,7 +770,7 @@ have Mdiag : forall i, M i i = 1. apply/matrixP => i j; rewrite !mxE. case/boolP : (i == j) => [/eqP ->|ij]; first by move : Mdiag => /(_ j). move: (MO' i) => /(congr1 (fun x => x ^+ 2)). -rewrite expr1n sqr_norm (bigD1 i) //= mxE. +rewrite expr1n sqr_enorm (bigD1 i) //= mxE. move: Mdiag => /(_ i) -> /eqP. rewrite expr1n addrC eq_sym -subr_eq subrr eq_sym psumr_eq0 /=; last first. by move=> *; rewrite sqr_ge0. @@ -904,8 +940,8 @@ Proof. by rewrite e2row row3Z mulr1 mulr0. Qed. End row3. -Lemma norm_row3z (T : rcfType) (z : T) : norm (row3 0 0 z) = `|z|. -Proof. by rewrite /norm dotmulE sum3E !mxE /= ?(mul0r,add0r) sqrtr_sqr. Qed. +Lemma enorm_row3z (T : rcfType) (z : T) : `|row3 0 0 z|_e = `|z|. +Proof. by rewrite /enorm dotmulE sum3E !mxE /= ?(mul0r,add0r) sqrtr_sqr. Qed. Section col_mx2. Variable (T : pzRingType). @@ -1421,10 +1457,10 @@ Section norm3. Variable T : rcfType. Implicit Types u : 'rV[T]_3. -Lemma norm_crossmul' u v : - (norm (u *v v)) ^+ 2 = (norm u * norm v) ^+ 2 - (u *d v) ^+ 2. +Lemma enorm_crossmul' u v : + `| u *v v |_e ^+ 2 = (`| u |_e * `| v |_e) ^+ 2 - (u *d v) ^+ 2. Proof. -rewrite sqr_norm sum3E crossmulE /SimplFunDelta /= !mxE /=. +rewrite sqr_enorm sum3E crossmulE /SimplFunDelta /= !mxE /=. transitivity (((u``_0)^+2 + (u``_1)^+2 + (u``_2%:R)^+2) * ((v``_0)^+2 + (v``_1)^+2 + (v``_2%:R)^+2) - (u``_0 * v``_0 + u``_1 * v``_1 + u``_2%:R * v``_2%:R)^+2). @@ -1487,40 +1523,41 @@ transitivity (((u``_0)^+2 + (u``_1)^+2 + (u``_2%:R)^+2) rewrite -!mulNrn !mulr2n !opprD. rewrite addrC -!addrA; congr (_ + _). by rewrite addrCA. -rewrite exprMn -(sum3E (fun i => u``_i ^+ 2)) -(sum3E (fun i => v``_i ^+ 2)) -2!sqr_norm; congr (_ - _ ^+ 2). +rewrite exprMn -(sum3E (fun i => u``_i ^+ 2)) -(sum3E (fun i => v``_i ^+ 2)) -2!sqr_enorm; congr (_ - _ ^+ 2). by rewrite dotmulE sum3E. Qed. -Lemma orth_preserves_norm_crossmul M : M \is 'O[T]_3 -> - {mono (fun u => u *m M) : x y / norm (x *v y)}. +Lemma orth_preserves_enorm_crossmul M : M \is 'O[T]_3 -> + {mono (fun u => u *m M) : x y / `| x *v y |_e}. Proof. move=> MO u v. -by rewrite -[in RHS](orth_preserves_norm MO) mulmxr_crossmulr // normZ orthogonal_det // mul1r. +by rewrite -[in RHS](orth_preserves_norm MO) mulmxr_crossmulr // enormZ orthogonal_det // mul1r. Qed. -Lemma norm_crossmul_normal u v : u *d v = 0 -> - norm u = 1 -> norm v = 1 -> norm (u *v v) = 1. +Lemma enorm_crossmul_normal u v : u *d v = 0 -> + `| u |_e = 1 -> `| v |_e = 1 -> `| u *v v |_e = 1. Proof. move=> uv0 u1 v1; apply/eqP. -rewrite -(@eqrXn2 _ 2) // ?norm_ge0 //. -by rewrite norm_crossmul' u1 v1 uv0 expr0n /= subr0 mulr1 // norm_ge0. +rewrite -(@eqrXn2 _ 2) ?enorm_ge0//. +by rewrite enorm_crossmul' u1 v1 uv0 expr0n /= subr0 mulr1 // norm_ge0. Qed. -Lemma dotmul_eq0_crossmul_neq0 (u v : 'rV[T]_3) : u != 0 -> v != 0 -> u *d v == 0 -> u *v v != 0. +Lemma dotmul_eq0_crossmul_neq0 (u v : 'rV[T]_3) : u != 0 -> v != 0 -> + u *d v == 0 -> u *v v != 0. Proof. move=> u0 v0 uv0. -rewrite -norm_eq0 -(@eqrXn2 _ 2) // ?norm_ge0 // exprnP expr0n -exprnP. -rewrite norm_crossmul' (eqP uv0) expr0n subr0 -expr0n eqrXn2 //. -by rewrite mulf_eq0 negb_or 2!norm_eq0 u0. -by rewrite mulr_ge0 // ?norm_ge0. +rewrite -enorm_eq0 -(@eqrXn2 _ 2) ?enorm_ge0// exprnP expr0n -exprnP. +rewrite enorm_crossmul' (eqP uv0) expr0n subr0 -expr0n eqrXn2 //. + by rewrite mulf_eq0 negb_or 2!enorm_eq0 u0. +by rewrite mulr_ge0 ?enorm_ge0. Qed. End norm3. Section properties_of_canonical_vectors. -Lemma normeE (T : rcfType) i : norm ('e_i : 'rV_3) = 1 :> T. -Proof. by rewrite norm_delta_mx. Qed. +Lemma enormeE (T : rcfType) i : `| 'e_i : 'rV_3 |_e = 1 :> T. +Proof. by rewrite enorm_delta_mx. Qed. Variable T : comPzRingType. @@ -1570,8 +1607,8 @@ End properties_of_canonical_vectors. Lemma orthogonal3P (T : rcfType) (M : 'M[T]_3) : reflect (M \is 'O[T]_3) - [&& norm (row 0 M) == 1, norm (row 1 M) == 1, norm (row 2%:R M) == 1, - row 0 M *d row 1 M == 0, row 0 M *d row 2%:R M == 0 & row 1 M *d row 2%:R M == 0]. + [&& `|row 0 M|_e == 1, `|row 1 M|_e == 1, `|row 2 M|_e == 1, + row 0 M *d row 1 M == 0, row 0 M *d row 2 M == 0 & row 1 M *d row 2 M == 0]. Proof. apply (iffP idP). - case/and6P => /eqP ni /eqP nj /eqP nk /eqP xy0 /eqP xz0 /eqP yz0 /=. @@ -1583,20 +1620,20 @@ apply (iffP idP). + case/boolP : (j == 0) => [|/ifnot0P/orP[]]/eqP->; by [rewrite dotmulC xz0 | rewrite dotmulC yz0 | rewrite dotmulvv nk expr1n]. - move/orthogonalP => H; apply/and6P; split; first [ - by rewrite -(@eqrXn2 _ 2) // ?norm_ge0 // expr1n -dotmulvv H | + by rewrite -(@eqrXn2 _ 2) ?enorm_ge0// expr1n -dotmulvv H | by rewrite H ]. Qed. Lemma rotation3P (T : rcfType) (M : 'M[T]_3) : reflect (M \is 'SO[T]_3) - [&& norm (row 0 M) == 1, norm (row 1 M) == 1, - row 0 M *d row 1 M == 0 & row 2%:R M == row 0 M *v row 1 M]. + [&& `|row 0 M|_e == 1, `|row 1 M|_e == 1, + row 0 M *d row 1 M == 0 & row 2 M == row 0 M *v row 1 M]. Proof. apply (iffP idP). - case/and4P => /eqP ni /eqP nj /eqP xy0 /eqP zxy0 /=. rewrite rotationE; apply/andP; split. apply/orthogonal3P. - rewrite ni nj /= zxy0 norm_crossmul_normal // xy0 !eqxx /= dot_crossmulC. + rewrite ni nj /= zxy0 enorm_crossmul_normal // xy0 !eqxx /= dot_crossmulC. by rewrite (@liexx _ (vec3 T)) dotmul0v dot_crossmulCA (@liexx _ (vec3 T)) dotmulv0 !eqxx. rewrite -(col_mx3_row M) -crossmul_triple zxy0 double_crossmul dotmulvv nj expr1n. by rewrite scale1r (dotmulC (row 1 M)) xy0 scale0r subr0 dotmulvv ni expr1n. @@ -1606,18 +1643,18 @@ apply (iffP idP). Qed. Lemma SO_icrossj (T : rcfType) (r : 'M[T]_3) : r \is 'SO[T]_3 -> - row 0 r *v row 1 r = row 2%:R r. + row 0 r *v row 1 r = row 2 r. Proof. by case/rotation3P/and4P => _ _ _ /eqP ->. Qed. Lemma SO_icrossk (T : rcfType) (r : 'M[T]_3) : r \is 'SO[T]_3 -> - row 0 r *v row 2%:R r = - row 1 r. + row 0 r *v row 2 r = - row 1 r. Proof. case/rotation3P/and4P => /eqP H1 _ /eqP H3 /eqP ->. by rewrite double_crossmul H3 scale0r add0r dotmulvv H1 expr1n scale1r. Qed. Lemma SO_jcrossk (T : rcfType) (r : 'M[T]_3) : r \is 'SO[T]_3 -> - row 1 r *v row 2%:R r = row 0 r. + row 1 r *v row 2 r = row 0 r. Proof. case/rotation3P/and4P => _ /eqP H1 /eqP H3 /eqP ->. by rewrite double_crossmul dotmulvv H1 expr1n scale1r dotmulC H3 scale0r subr0. @@ -1671,8 +1708,7 @@ rewrite [X in _ + _ + X](_ : _ = - M 0 2%:R * M 2%:R 0); last first. rewrite [in X in X * _]/=. rewrite coefD coefM sum2E subn0 coefC coefC mulr0 add0r. rewrite coefC mul0r add0r coefM sum2E subn0 subnn coefC [in X in X * _`_1]/=. - rewrite !coefD !coefX !coefN !coefC/=. - rewrite !mul0r !addr0/= subr0 mulr1. + rewrite coefD coefX coefN !coefC/= !(subr0,mul0r,mulr0,mulr1,addr0). by rewrite mulNr. rewrite /Z. apply/(@mulrI _ 2%:R); first exact: pnatf_unit. diff --git a/extra_trigo.v b/extra_trigo.v index 39918779..16c36108 100644 --- a/extra_trigo.v +++ b/extra_trigo.v @@ -1,9 +1,9 @@ From mathcomp Require Import all_ssreflect ssralg ssrnum. -From mathcomp Require Import interval reals trigo. +From mathcomp Require Import boolp interval reals trigo. Require Import ssr_ext. -(******************************************************************************) -(* Extra material for trigo *) +(**md**************************************************************************) +(* # Extra material for trigo *) (* *) (******************************************************************************) @@ -121,78 +121,6 @@ rewrite sin_eq0_Npipi //; case: eqP => /= [aE _|_ /eqP //]. by move/eqP: caE; rewrite aE cos0 -eqr_oppLR eqrNxx oner_eq0. Qed. -(* NB: PR to analysis in progress *) -Lemma acos1 : acos (1 : R) = 0. -Proof. -have := @cosK R 0; rewrite cos0 => -> //. -by rewrite in_itv //= lexx pi_ge0. -Qed. - -Lemma acos0 : acos (0 : R) = pi / 2%:R. -Proof. -have := @cosK R (pi / 2%:R). -rewrite cos_pihalf => -> //. -rewrite in_itv //= divr_ge0 ?ler0n ?pi_ge0 //=. -rewrite ler_pdivrMr ?ltr0n //. -by rewrite mulr_natr mulr2n -lerBlDr subrr pi_ge0. -Qed. - -Lemma acosN1 : acos (- 1) = (pi : R). -Proof. -have oneB : -1 <= (-1 : R) <= 1 by rewrite lexx ge0_cp ?(ler0n _ 1). -apply: cos_inj; rewrite ?in_itv//= ?pi_ge0 ?lexx //. - by rewrite acos_ge0 // acos_lepi. -by rewrite acosK ?in_itv//= cospi. -Qed. - -Lemma acosN a : -1 <= a <= 1 -> acos (- a) = pi - acos a. -Proof. -move=> aB. -have aBN : -1 <= - a <= 1 by rewrite lerNl opprK lerNl andbC. -apply: cos_inj; first by rewrite in_itv/= acos_ge0 // acos_lepi. - rewrite in_itv/= subr_ge0 acos_lepi // -subr_le0 addrAC subrr sub0r. - by rewrite oppr_cp0 acos_ge0. -by rewrite addrC cosDpi cosN !acosK. -Qed. - -Lemma cosKN a : - pi <= a <= 0 -> acos (cos a) = - a. -Proof. -move=> Hs. -rewrite -(cosN a) cosK // ?in_itv/=. -by rewrite lerNr oppr0 lerNl andbC. -Qed. - -Lemma atan0 : atan 0 = 0 :> R. -Proof. -apply: tan_inj; first 2 last. -- by rewrite atanK tan0. -- by rewrite in_itv/= atan_gtNpi2 atan_ltpi2. -by rewrite in_itv/= oppr_cp0 divr_gt0 ?pi_gt0 // ltr0n. -Qed. - -Lemma atan1 : atan 1 = pi / 4%:R :> R. -Proof. -apply: tan_inj; first 2 last. -- by rewrite atanK tan_piquarter. -- by rewrite in_itv/= atan_gtNpi2 atan_ltpi2. -have v2_ge0 : 0 <= 2%:R :> R by rewrite ler0n. -have v2_gt0 : 0 < 2%:R :> R by rewrite ltr0n. -rewrite in_itv/= -mulNr (lt_trans _ (_ : 0 < _ )) /=; last 2 first. -- by rewrite mulNr oppr_cp0 divr_gt0 // pi_gt0. -- by rewrite divr_gt0 ?pi_gt0 // ltr0n. -rewrite (natrM _ 2 2) invfM mulrA lter_pdivrMr // divfK ?natr_eq0 //. - by rewrite ltr_pdivrMr // mulr_natr mulr2n -subr_gte0 addrK ?pi_gt0. -by case: ltgtP v2_gt0. -Qed. - -Lemma atanN (x : R) : atan (- x) = - atan x. -Proof. -apply: tan_inj; first by rewrite in_itv/= atan_ltpi2 atan_gtNpi2. - by rewrite in_itv/= ltrNl opprK ltrNl andbC atan_ltpi2 atan_gtNpi2. -by rewrite tanN !atanK. -Qed. -(* /NB: PR to analysis in progress *) - Lemma sin_half_angle a : `| sin (a / 2%:R) | = Num.sqrt ((1 - cos a) / 2%:R). Proof. move: (cosD (a / 2%:R) (a / 2%:R)). diff --git a/frame.v b/frame.v index 1b0829b2..bab1a344 100644 --- a/frame.v +++ b/frame.v @@ -1,4 +1,4 @@ -(* coq-robot (c) 2017 AIST and INRIA. License: LGPL-2.1-or-later. *) +(* robot-rocq (c) 2026 AIST and INRIA. License: LGPL-2.1-or-later. *) From HB Require Import structures. From mathcomp Require Import all_ssreflect ssralg ssrint ssrnum rat poly. From mathcomp Require Import closed_field polyrcf matrix mxalgebra mxpoly zmodp. @@ -57,9 +57,9 @@ Record t : Type := mk { i : 'rV[T]_3 ; j : 'rV[T]_3 ; k : 'rV[T]_3 ; - normi : norm i = 1 ; - normj : norm j = 1 ; - normk : norm k = 1 ; + normi : `|i|_e = 1 ; + normj : `|j|_e = 1 ; + normk : `|k|_e = 1 ; idotj : i *d j = 0 ; jdotk : j *d k = 0 ; idotk : i *d k = 0 @@ -102,8 +102,8 @@ Let vector := 'rV[T]_3. Implicit Types p : 'rV[T]_3. Variable f : noframe T. -Lemma noframe_norm (k : 'I_3) : norm f|,k = 1. -Proof. by rewrite rowframeE; apply norm_row_of_O; case: f. Qed. +Lemma noframe_norm (k : 'I_3) : `| f|,k |_e = 1. +Proof. by rewrite rowframeE; apply enorm_row_of_O; case: f. Qed. Lemma noframe_idotj : f~i *d f~j = 0. Proof. by rewrite !rowframeE; apply/orthogonalP; case: f. Qed. @@ -124,9 +124,9 @@ Proof. apply/orthogonal_unit. by case: f. Qed. Lemma noframe_inv : (matrix_of_noframe f)^-1 = f^T. Proof. rewrite -orthogonal_inv //; by case: f. Qed. -Lemma norm_icrossj : norm (f~i *v f~j) = 1. +Lemma norm_icrossj : `|f~i *v f~j|_e = 1. Proof. -by rewrite norm_crossmul_normal // ?idotj // ?normi // normj. +by rewrite enorm_crossmul_normal // ?idotj // ?normi // normj. Qed. Definition noframe_sgn := \det f. @@ -447,7 +447,7 @@ Qed. Module Base1. Section base1. Variables (T : realType) (i : 'rV[T]_3). -Hypothesis normi : norm i = 1. +Hypothesis normi : `|i|_e = 1. Definition j := if colinear i 'e_0 then 'e_1 else normalize (normalcomp 'e_0 i). @@ -458,7 +458,7 @@ Proof. rewrite /j; case: ifPn => [|_]; last first. by rewrite dotmulvZ -{3}(normalizeI normi) dotmul_orthogonalize mulr0. case/colinearP => [| [_ [k ->]]]. - by rewrite -norm_eq0 norm_delta_mx (negbTE (oner_neq0 _)). + by rewrite -enorm_eq0 enorm_delta_mx (negbTE (oner_neq0 _)). by rewrite dotmulZv dote2 mulr0. Qed. @@ -468,16 +468,16 @@ Proof. by rewrite /k dot_crossmulC (@liexx _ (vec3 T)) dotmul0v. Qed. Lemma jdotk : j *d k = 0. Proof. by rewrite /k dot_crossmulCA (@liexx _ (vec3 T)) dotmulv0. Qed. -Lemma normj : norm j = 1. +Lemma normj : `| j |_e = 1. Proof. -rewrite /j; case: ifPn => iVi; first by rewrite norm_delta_mx. +rewrite /j; case: ifPn => iVi; first by rewrite enorm_delta_mx. rewrite norm_normalize //; apply: contra iVi. -by rewrite normalcomp_colinear // ?norm1_neq0 // colinear_sym. +by rewrite normalcomp_colinear ?norm1_neq0// colinear_sym. Qed. -Lemma normk : norm k = 1. +Lemma normk : `| k |_e = 1. Proof. -by rewrite /k norm_crossmul_normal // ?norm_normalize// ?normj// idotj // mulr0. +by rewrite /k enorm_crossmul_normal // ?norm_normalize// ?normj// idotj // mulr0. Qed. Definition M := col_mx3 i j k. @@ -522,7 +522,7 @@ Qed. End base1_lemmas. End Base1. -Canonical base1_is_noframe (T : realType) (u : 'rV[T]_3) (u1 : norm u = 1) := +Canonical base1_is_noframe (T : realType) (u : 'rV[T]_3) (u1 : `|u|_e = 1) := NOFrameInterface.mk u1 (Base1.normj u1) (Base1.normk u1) (Base1.idotj u1) (Base1.jdotk u) (Base1.idotk u). @@ -536,9 +536,9 @@ Definition i := if u == 0 then 'e_0 else normalize u. Definition j := if u == 0 then 'e_1 else Base1.j i. Definition k := if u == 0 then 'e_2%:R else Base1.k i. -Lemma normi : norm i = 1. +Lemma normi : `| i |_e = 1. Proof. -rewrite /i; case: ifP => [_|/eqP/eqP ?]; by rewrite ?normeE // norm_normalize. +rewrite /i; case: ifP => [_|/eqP/eqP ?]; by rewrite ?enormeE// norm_normalize. Qed. Parameter frame : 'rV[T]_3 -> frame T. @@ -560,10 +560,10 @@ Qed. Lemma frame0E (u0 : u != 0) : (frame u)~i = normalize u. Proof. by rewrite -iE /i (negbTE u0). Qed. -Lemma normj : norm j = 1. -Proof. by rewrite jE rowframeE norm_row_of_O // NOFrame.MO. Qed. -Lemma normk : norm k = 1. -Proof. by rewrite kE rowframeE norm_row_of_O // NOFrame.MO. Qed. +Lemma normj : `| j |_e = 1. +Proof. by rewrite jE rowframeE enorm_row_of_O // NOFrame.MO. Qed. +Lemma normk : `| k |_e = 1. +Proof. by rewrite kE rowframeE enorm_row_of_O // NOFrame.MO. Qed. Lemma idotj : i *d j = 0. Proof. by rewrite iE jE !rowframeE dot_row_of_O // NOFrame.MO. Qed. @@ -689,7 +689,7 @@ Qed. End scalar_neg. End scalar. -Lemma j_tr_mul (v : 'rV[T]_3) (v1 : norm v = 1) : j v *m v^T = 0. +Lemma j_tr_mul (v : 'rV[T]_3) (v1 : `| v |_e = 1) : j v *m v^T = 0. Proof. rewrite /j (negbTE (norm1_neq0 v1)) /Base1.j. case: ifPn => [|_]. @@ -703,7 +703,7 @@ rewrite -scalemxAl scaler_eq0 {2}/i (negbTE (norm1_neq0 v1)) normalizeI //. by rewrite normalcomp_mul_tr // orbT. Qed. -Lemma k_tr_mul (v : 'rV[T]_3) (v1 : norm v = 1) : k v *m v^T *m v = 0. +Lemma k_tr_mul (v : 'rV[T]_3) (v1 : `| v |_e = 1) : k v *m v^T *m v = 0. Proof. rewrite /k (negbTE (norm1_neq0 v1)) /Base1.k /Base1.j. case: ifPn => [|_]. @@ -832,12 +832,12 @@ Qed. End FromTo_properties. (* TODO: move? *) -Lemma sqr_norm_frame (T : realType) (a : frame T) (v : 'rV[T]_3) : - norm v ^+ 2 = \sum_(i < 3) (v *d (a |, i%:R))^+2. +Lemma sqr_enorm_frame (T : realType) (a : frame T) (v : 'rV[T]_3) : + `| v |_e ^+ 2 = \sum_(i < 3) (v *d (a |, i%:R))^+2. Proof. -have H : norm v = norm (v *m (can_frame T) _R^ a). +have H : `| v |_e = `| v *m (can_frame T) _R^ a |_e. by rewrite orth_preserves_norm // FromTo_is_O. -rewrite H sqr_norm [in LHS]sum3E [in RHS]sum3E; congr (_ ^+ 2 + _ ^+ 2 + _ ^+ 2); +rewrite H sqr_enorm [in LHS]sum3E [in RHS]sum3E; congr (_ ^+ 2 + _ ^+ 2 + _ ^+ 2); by rewrite FromTo_from_can mxE_dotmul_row_col -tr_row trmxK row_id NOFrame.rowframeE. Qed. @@ -855,27 +855,29 @@ End framed_vector. End FramedVect. Notation fvec := FramedVect.t. -Notation "`[ v $ F ]" := (FramedVect.mk F v) - (at level 5, v, F at next level, format "`[ v $ F ]"). +Notation "''[' v $ F ]" := (FramedVect.mk F v) + (at level 5, v, F at next level, format "''[' v $ F ]") : frame_scope. Definition FramedVect_add (T : pzRingType) (F : tframe T) (a b : fvec F) : fvec F := - `[ FramedVect.v a + FramedVect.v b $ F ]. + '[ FramedVect.v a + FramedVect.v b $ F ]. Notation "a \+f b" := (FramedVect_add a b) (at level 39). -Lemma fv_eq (T : pzRingType) a b : a = b -> forall F : frame T, `[ a $ F ] = `[ b $ F ]. +Lemma fv_eq (T : pzRingType) a b : a = b -> forall F : frame T, '[ a $ F ] = '[ b $ F ]. Proof. by move=> ->. Qed. +Notation "a \+f b" := (FramedVect_add a b) (at level 39). + Section change_of_coordinate_by_rotation. Variable T : realType. Implicit Types A B : frame T. -Lemma FramedVectvK A (x : fvec A) : `[FramedVect.v x $ A] = x. +Lemma FramedVectvK A (x : fvec A) : '[FramedVect.v x $ A] = x. Proof. by case: x. Qed. (* change of coordinates: "rotation mapping" from frame A to frame B *) -Definition rmap A B (x : fvec A) : fvec B := `[FramedVect.v x *m (A _R^ B) $ B]. +Definition rmap A B (x : fvec A) : fvec B := '[FramedVect.v x *m (A _R^ B) $ B]. Lemma rmapK A B (x : fvec A) : rmap A (rmap B x) = x. Proof. @@ -885,15 +887,15 @@ by rewrite divrr ?noframe_is_unit // mulmx1 /= FramedVectvK. Qed. Lemma rmapE A B (x : 'rV[T]_3) : - rmap B `[x $ A] = `[x *m A (*A->can*) *m B^T(*can->B*) $ B]. + rmap B '[x $ A] = '[x *m A (*A->can*) *m B^T(*can->B*) $ B]. Proof. by rewrite /rmap FromToE noframe_inv mulmxA. Qed. Lemma rmapE_from_can A (x : 'rV[T]_3) : - rmap A `[x $ can_tframe T] = `[x *m A^T $ A]. + rmap A '[x $ can_tframe T] = '[x *m A^T $ A]. Proof. by rewrite rmapE can_frame_1 mulmx1. Qed. Lemma rmapE_to_can A (x : 'rV[T]_3) : - rmap (can_tframe T) `[x $ A] = `[x *m A $ can_tframe T]. + rmap (can_tframe T) '[x $ A] = '[x *m A $ can_tframe T]. Proof. by rewrite rmapE can_frame_1 trmx1 mulmx1. Qed. End change_of_coordinate_by_rotation. @@ -961,22 +963,22 @@ Definition t := (i, j, k). Let ac : a != c. Proof. by apply: contra abc => /eqP ->; rewrite subrr /colinear linear0r. Qed. -Lemma normi : norm i = 1. +Lemma normi : `| i |_e = 1. Proof. by rewrite /i norm_normalize // subr_eq0 eq_sym. Qed. Lemma i_neq0 : i != 0. -Proof. by rewrite -norm_eq0 normi oner_neq0. Qed. +Proof. by rewrite -enorm_eq0 normi oner_neq0. Qed. -Lemma normj : norm j = 1. +Lemma normj : `| j |_e = 1. Proof. rewrite /j norm_normalize // normalcomp_colinear; last first. - by rewrite -norm_eq0 normi oner_neq0. -apply: contra (abc); rewrite colinearvZ invr_eq0 norm_eq0 subr_eq0. + by rewrite -enorm_eq0 normi oner_neq0. +apply: contra (abc); rewrite colinearvZ invr_eq0 enorm_eq0 subr_eq0. by rewrite eq_sym (negPf ab) /= colinear_sym. Qed. Lemma j_neq0 : j != 0. -Proof. by rewrite -norm_eq0 normj oner_neq0. Qed. +Proof. by rewrite -enorm_eq0 normj oner_neq0. Qed. Lemma idotj : i *d j = 0. Proof. by rewrite /= /i /j dotmulZv dotmulvZ dotmul_orthogonalize 2!mulr0. Qed. @@ -987,11 +989,11 @@ Proof. by rewrite /k dot_crossmulCA (@liexx _ (vec3 T)) dotmulv0. Qed. Lemma idotk : i *d k = 0. Proof. by rewrite /k dot_crossmulC (@liexx _ (vec3 T)) dotmul0v. Qed. -Lemma normk : norm k = 1. -Proof. by rewrite norm_crossmul_normal // ?normi // ?normj // idotj. Qed. +Lemma normk : `| k |_e = 1. +Proof. by rewrite enorm_crossmul_normal // ?normi // ?normj // idotj. Qed. Lemma k_neq0 : k != 0. -Proof. by rewrite -norm_eq0 normk oner_neq0. Qed. +Proof. by rewrite -enorm_eq0 normk oner_neq0. Qed. Lemma is_O : col_mx3 i j k \is 'O[T]_3. Proof. diff --git a/lasalle.v b/lasalle.v new file mode 100644 index 00000000..b1114585 --- /dev/null +++ b/lasalle.v @@ -0,0 +1,467 @@ +(* LaSalle (c) 2025 Inria and AIST. Licence: CeCILL-C. *) +(* -------------------------------------------------------------------------- *) +(* Copyright (c) - 2017 -- 2019 Inria *) +(* -------------------------------------------------------------------------- *) +From HB Require Import structures. +From mathcomp Require Import ssreflect ssrfun ssrbool ssrnat eqtype choice seq. +From mathcomp Require Import order interval_inference. +From mathcomp Require Import fintype bigop ssralg ssrnum finmap interval ssrint. +From mathcomp Require Import boolp reals classical_sets functions. +From mathcomp Require Import topology normedtype landau derive. + +Set Implicit Arguments. +Unset Strict Implicit. +Unset Printing Implicit Defensive. + +Import GRing.Theory Num.Def Num.Theory Order.POrderTheory Order.TotalTheory. +Import numFieldTopology.Exports. + +Local Open Scope classical_set_scope. + +Lemma mul2r (R : ringType) (x : R) : (2 * x = x + x)%R. +Proof. by rewrite -mulr2n mulr_natl. Qed. + +Section pseudoMetricType_numDomainType. +Context {R : numDomainType} {M : pseudoMetricType R}. + +Definition ball_set (A : set M) e := \bigcup_(p in A) ball p e. + +(*HB.instance Definition _ := isPointed.Build (set M) [set point].*) + +HB.instance Definition _ := isFiltered.Build M (set M) (nbhs_ball_ ball_set). + +End pseudoMetricType_numDomainType. + +Section PositiveLimitingSet. +Variable R : realFieldType. +Variable U : pseudoPMetricType R. + +Definition pos_limit_set (y : R -> U) := + \bigcap_(eps in [set e | 0 < e]%R) \bigcap_(T in [set T | 0 < T]%R) + [set p | ltr T `&` (y @^-1` ball p eps) !=set0]. + +Lemma plim_cluster (y : R -> U) : + pos_limit_set y = cluster (y @ +oo%R). +Proof. +rewrite predeqE => p; split. + move=> plim_p A B [M [Mreal ygtM_A]]. + move=> /nbhs_ballP [e egt0 pe_B]. + wlog Mgt0 : M Mreal ygtM_A / (0 < M)%R; last first. + by have [t [/ygtM_A Ayt /pe_B Byt]] := plim_p _ egt0 _ Mgt0; exists (y t). + move=> /(_ (maxr M 1%R)) []; last by move=> q ?; exists q. + by rewrite max_real// real1. + by move=> ?; rewrite gt_max => /andP [/ygtM_A]. + by rewrite lt_max orbC ltr01. +move=> clyp e egt0 T Tgt0. +have [] := clyp (y @` ltr T) (ball p e). + by exists T; rewrite num_real; split => //; exact: imageP. + by rewrite -nbhs_ballE; exists e. +by move=> _ [[t ? <-] ?]; exists t. +Qed. + +Lemma plimn0 (y : R -> U) (A : set U) : + compact A -> (y @ +oo%R) A -> cluster (y @ +oo%R) !=set0. +Proof. by move=> Aco /Aco [p []]; exists p. Qed. + +Lemma closed_plim (y : R -> U) : closed (cluster (y @ +oo%R)). +Proof. +by rewrite clusterE; apply: closed_bigI => ??; apply: closed_closure. +Qed. + +Lemma filter_cluster (F : set (set U)) (A : set U) : + ProperFilter F -> F A -> compact A -> + forall e, (0 < e)%R -> F (ball_set (cluster F) e). +Proof. +move=> FF FA; rewrite compact_In0 => Aco e egt0. +set B := ball_set (cluster F) e. +have Fn0 : F !=set0 by exists A. +have : A `&` (cluster F `\` B°) = set0. + suff -> : cluster F `\` B° = set0 by rewrite setI0. + rewrite setD_eq0 => p clFp. + by rewrite /interior -nbhs_ballE; exists e => // ??; exists p. +rewrite clusterE. +rewrite -[_ `\` _]bigcapIl // setIC. +rewrite -bigcapIl // => IFBoA0. +set f := fun C => closure C `&` ~` B° `&` A. +have [G sGF IGBoA0] : exists2 G : {fset (set U)}, + {subset G <= F} & \bigcap_(C in [set C | C \in G]) f C = set0. + have {}IFBoA0 : ~ (\bigcap_(C in F) f C !=set0). + by move=> [p IFBoAp]; rewrite -[False]/(set0 p) -IFBoA0. + have /Aco : closed_fam_of A F f. + exists (fun C => closure C `&` ~` B°). + move=> C _; apply: closedI (@closed_closure _ _) _. + by rewrite closedC; exact/open_interior. + by move=> ? _; rewrite setIC. + move=> /contra_not /(_ IFBoA0) /asboolPn /existsp_asboolPn [H /asboolPn]. + move=> /imply_asboolPn [sHF IHBoA0]; exists H => //. + by rewrite predeqE => p; split=> // IHBoAp; apply: IHBoA0; exists p. +have Gn0 : [set C | C \in G] !=set0. + apply: contrapT => /asboolPn /forallp_asboolPn G0. + by rewrite -[False]/(@set0 U point) -IGBoA0 => ? /G0. +move: IGBoA0; have -> : \bigcap_(C in [set C | C \in G]) f C = + \bigcap_(C in [set C | C \in G]) (A `&` closure C `&` ~` B°). + by rewrite predeqE => a; split=> IGBoAa ? /IGBoAa [[]]. +rewrite bigcapIl // setD_eq0 => sIGABo. +suff : F B° by apply: filterS => ?; apply: nbhs_singleton. +apply: filterS sIGABo _; apply: filter_bigI => C /sGF; rewrite in_setE => FC. +by apply: filterI FA _; apply: filterS (@subset_closure _ C) _. +Qed. + +Lemma cvg_to_plim (y : R -> U) (A : set U) : + (y @ +oo%R) A -> compact A -> y @ +oo%R --> cluster (y @ +oo%R). +Proof. +move=> yinftyA coA B [e egt0 scleB]. +by apply: filterS scleB _; exact: filter_cluster coA _ egt0. +Qed. + +(* Lemma cvg_to_plim y (A : set U) : *) +(* (y @ +oo) A -> compact A -> y @ +oo --> cluster (y @ +oo). *) +(* Proof. *) +(* move=> yinftyA coA; apply/NNP. *) +(* move=> /asboolPn /existsp_asboolPn [B] /asboolPn /imply_asboolPn. *) +(* move=> [[e egt0 plim_e_B] /asboolPn /forallp_asboolPn nygtxB]. *) +(* suff : ~` B `&` B !=set0 by case=> ? []. *) +(* have proper_within_CB : ProperFilter (within (~` B) (y @ +oo)). *) +(* apply: Build_ProperFilter=> C [T ygtTsBC]. *) +(* have /asboolPn /existsp_asboolPn [t /asboolPn /imply_asboolPn [tgtT nByt]] *) +(* := nygtxB T. *) +(* by exists (y t); apply: ygtTsBC. *) +(* have [|p [Ap plimnBp]] := coA _ proper_within_CB. *) +(* exact: flim_within yinftyA. *) +(* apply plimnBp; first exact: withinT. *) +(* rewrite -locally_ballE; exists e => // q pe_q; apply: plim_e_B. *) +(* by exists p => // C D yinftyC; apply/plimnBp; apply: flim_within yinftyC. *) +(* Qed. *) + +Lemma sub_image_at_infty (y : R -> U) (A : set U) : + y @` (>= 0)%R `<=` A -> (y @ +oo%R) A. +Proof. +move=> syRpA; exists 0%R; rewrite real0; split => // t tgt0. +exact/syRpA/imageP/ltW. +Qed. + +Lemma sub_plim_clos_invar (y : R -> U) (A : set U) : + y @` (>= 0)%R `<=` A -> cluster (y @ +oo%R) `<=` closure A. +Proof. by move=> syRpA p ypp B /ypp; apply; exact: sub_image_at_infty. Qed. + +Lemma map_sub_cluster (S T : topologicalType) (F : set_system S) (f : S -> T) + (A : set S) : Filter F -> {within A, continuous f} -> F A -> closed A -> + f @` (cluster F) `<=` cluster (f @ F). +Proof. +move=> Ffilt fcont FA Acl _ [p clFp <-] B C fFB. +have Ap : A p by apply: Acl => ? /clFp - /(_ _ FA). +move/subspace_continuousP in fcont. +move=> /(fcont _ Ap) fp_C. +suff /clFp /(_ fp_C) [q [[Aq ?] /(_ Aq)]] : F (A `&` f @^-1` B) by exists (f q). +exact: filterI. +Qed. + +Lemma c0_cvg_cst_on_plim A (y : R -> U) (V : U -> R^o) (l : R^o) : + {within A, continuous V} -> V \o y @ +oo%R --> l -> + closed A -> y @` (>= 0)%R `<=` A -> cluster (y @ +oo%R) `<=` V @^-1` [set l]. +Proof. +move=> Vcont Vypl Acl syRpA p plimp. +have Aypinfty : (y @ +oo%R) A by apply: sub_image_at_infty. +have : (V @` cluster (y @ +oo%R)) (V p) by exists p. +move=> /(map_sub_cluster _ Vcont Aypinfty Acl). +by move=> /(cvg_cluster Vypl) /Rhausdorff ->. +Qed. + +End PositiveLimitingSet. + +Lemma bounded_plim (K : realFieldType) (V : normedModType K) (y : K -> V) : + bounded_set (y @` (>= 0)%R) -> bounded_set (cluster (y @ +oo%R)). +Proof. +rewrite /bounded_set => - [N [Nreal ybndN]]. +wlog Ngt0 : N Nreal ybndN / (0 < N)%R. + move=> bnd_plim; apply: (bnd_plim (maxr N 1%R)); last first. + by rewrite lt_max orbC ltr01. + by move=> ?; rewrite gt_max => /andP [/ybndN]. + by rewrite max_real// real1. +rewrite /bounded_set. +red. +near=> M => p plimp. +have [] := plimp (y @` (>= 0)%R) (ball_ Num.norm p (PosNum Ngt0)%:num). +- exact: sub_image_at_infty. +- exact: nbhs_ball_norm. +move=> _ [[t tge0 <-] pN_yt]; rewrite -[p](subrK (y t)). +apply: (le_trans (ler_normD _ _)). +rewrite -lerBrDr. +apply/ltW; apply: lt_le_trans pN_yt _. +rewrite lerBrDr addrC -lerBrDr; apply: ybndN; last by exists t. +by rewrite ltrBrDr; near: M; exists (N + N)%R; rewrite realD. +Unshelve. all: by end_near. Qed. + +(* TODO: update lasalle on github *) +Lemma nearN (R : realFieldType) (P : set R) : + (\forall x \near (0%R : R^o), P x) = (\forall x \near (0%R : R^o), P (- x)%R). +Proof. +by rewrite propeqE; split; rewrite -nearN oppr0. +Qed. + +Section DifferentialSystem. +Context {R : realType}. +Variable U : normedModType R. +Let hU : hausdorff_space U := @norm_hausdorff _ U. + +(* function defining the differential system *) +Variable F : U -> U. + +Definition is_sol (y : [the normedModType _ of R^o] -> U) := + (forall t, t < 0 -> y t = 2 *: (y 0) - (y (- t)))%R /\ + forall t, (0 <= t)%R -> is_derive (t : R^o) 1%R y (F (y t)). + +(* compact set used in LaSalle's invariance principle *) +Variable K : set U. +Hypothesis Kco : compact K. + +(* solution function *) +Variable sol : U -> R -> U. +Hypothesis (sol0 : forall p, sol p 0 = p). +Hypothesis solP : forall y : R -> U, K (y 0%R) -> is_sol y <-> y = sol (y 0%R). +Hypothesis sol_cont : forall t, {within K, continuous (sol^~ t)}. + +Lemma sol_is_sol p : K p -> is_sol (sol p). +Proof. by move=> Kp; apply/solP; rewrite sol0. Qed. +Hint Resolve sol_is_sol : core. + +Lemma uniq_sol (x y : R -> U) : + K (x 0%R) -> K (y 0%R) -> is_sol x -> is_sol y -> x 0%R = y 0%R -> x = y. +Proof. by move=> Kx0 Ky0 /(solP Kx0)-> /(solP Ky0)->; rewrite !sol0 => ->. Qed. + +Definition is_invariant A := forall p, A p -> forall t, (0 <= t)%R -> A (sol p t). + +Hypothesis Kinvar : is_invariant K. + +Definition shift_sol p t0 t := + (if t >= 0 then sol p (t + t0) else 2 *: (sol p t0) - (sol p (- t + t0)))%R. + +Lemma sol_shift p (t0 : R^o) : K p -> (0 <= t0)%R -> is_sol (shift_sol p t0). +Proof. +move=> Kp t0ge0; split=> [t tlt0|t tge0]. + rewrite /shift_sol leNgt tlt0/= lexx/=. + rewrite ltW ?oppr_gt0//. + rewrite [X in _ = (2 *: sol p X - _)%R](_ : _ = t0)//. + by rewrite add0r. +suff dshift : (shift_sol p t0) \o shift t = (cst (shift_sol p t0 t) + + (fun h : R^o => h *: F (shift_sol p t0 t)))%R +o_ (0%R : R^o) (id : R^o -> R^o). + move=> [:dshiftE]. + have diff_shift : differentiable (shift_sol p t0 : R^o -> _) t. + apply/diff_locallyP; split; last first. + apply/eqaddoE; rewrite dshift. + congr +%R. +(* 0.3.6: + (cst (shift_sol p t0 t) + *:%R^~ (F (shift_sol p t0 t)))%R = + (cst (shift_sol p t0 t) + 'd (shift_sol p t0) t)%R *) + congr +%R. + abstract: dshiftE. + have lin_scal : linear (fun h : R^o => h *: F (shift_sol p t0 t))%R. + by move=> ???; rewrite scalerDl scalerA. + pose glM := GRing.isLinear.Build _ _ _ _ _ lin_scal. + pose gL : {linear R^o -> U} := HB.pack ( *:%R^~ (F (shift_sol p t0 t))) glM. + have -> : (fun h : R^o => h *: F (shift_sol p t0 t))%R = gL by []. + apply/esym. + apply: diff_unique; first exact: scalel_continuous. + apply/eqaddoE; rewrite dshift. +(* 0.3.6: + (cst (shift_sol p t0 t) + *:%R^~ (F (shift_sol p t0 t)) + 'o_[filter of 0] id )%R = + (cst (shift_sol p t0 t) + Linear lin_scal + 'a_o_(nbhs_filter_on 0) id )%R *) + by []. + by rewrite -dshiftE; apply: scalel_continuous. + apply: DeriveDef; first exact/derivable1_diffP. + by rewrite deriveE // -dshiftE scale1r. +have /sol_is_sol [_ solp] := Kp. +have /solp solp' : (0 <= t + t0)%R by apply: addr_ge0 => //; apply: ltrW. +rewrite /shift_sol tge0. +move: tge0; rewrite le_eqVlt orbC => /orP [tgt0|/eqP teq0]. + apply/eqaddoP => _ /posnumP[e]; near=> s. + rewrite -![(_ + _ : _ -> _)%R _]/(_ + _)%R /=. + have /derivable_nbhs : derivable (sol p : R^o -> U) (t + t0) 1 by []. + rewrite funeqE => /(_ s) /=; rewrite addrA [(_%:A)%R]mulr1 =>->. + suff -> /= : (0 <= s + t)%R. + rewrite derive_val addrC addrA [(_ s + _)%R]addrC subrr add0r. + near: s. + case: e => /= e. + rewrite /Itv.num_sem/= num_real/= in_itv/= andbT. + move: e. + apply/(eqoP (nbhs_filter_on (0%R : R))). + (* 0.3.6: 'o_[filter of nbhs 0%R] id = 'o_(nbhs_filter_on 0%R) id *) + by []. + near: s; exists t => // s; rewrite /ball_ /= => ltst. + rewrite -lerBlDl sub0r; apply/ltW; apply: le_lt_trans ltst. + by rewrite sub0r ler_norm. +rewrite -teq0. +rewrite shift0. +rewrite add0r. +apply/eqaddoP => _ /posnumP[e]; near=> s. +rewrite -![(_ + _ : _ -> _)%R _]/(_ + _)%R /=. +rewrite -[t0]add0r/=. +rewrite {1 2 3 4 5 6}teq0. +have /derivable_nbhs dsol : derivable (sol p : R^o -> U) (t + t0) 1 by []. +have := dsol; rewrite funeqE => /(_ (- s)%R) /=; rewrite [(_%:A)%R]mulr1 =>->. +have := dsol; rewrite funeqE => /(_ s) /=; rewrite [(_%:A)%R]mulr1 =>->. +rewrite -{1}teq0 derive_val; case: (lerP 0 s) => [le0s|lts0]. + rewrite addrC addrA [(_ s + _)%R]addrC subrr add0r; near: s. + case: e => /= e. + rewrite /Itv.num_sem num_real in_itv/= andbT. + move: e. + apply/(eqoP (nbhs_filter_on (0%R : R))). +(* 0.3.6: + 'o_[filter of nbhs 0%R] id = 'o_(nbhs_filter_on 0%R) id *) + by []. +rewrite !opprD oppox /cst /= addrACA -[(- _ : _ -> _)%R _]/(- _)%R !addrA. +rewrite [X in (X *: _)%R](_ : _ = (1 + 1)%R); last by []. +rewrite scalerDl scale1r -[(_ - _ - sol _ _)%R]addrA -opprD subrr sub0r. +rewrite scaleNr opprK addrC addKr -[in X in (_ <= X)%R]normrN; near: s. +rewrite !near_simpl. +rewrite -(nearN (fun x : R^o => `|_ x| <= e%:num * `|x|%R))%R. +case: e => /= e. +rewrite /Itv.num_sem num_real in_itv/= andbT => e0. +near=> x. +set u := (X in `|X x|%R). +near: x. +exact: (@eqoP _ _ _ _ (nbhs_filter_on (0%R : R^o)) id u).1. +Unshelve. all: by end_near. Qed. + +Lemma solD p t0 t : + K p -> (0 <= t0)%R -> (0 <= t)%R -> sol p (t + t0) = sol (sol p t0) t. +Proof. +move=> Kp t0ge0 tge0; have /sol_shift /(_ t0ge0) /solP := Kp. +rewrite [shift_sol _ _ _]/shift_sol lexx. +rewrite add0r. +move=> <-; last exact: Kinvar. +by rewrite /shift_sol tge0. +Qed. + +Lemma invariant_plim p : K p -> is_invariant (cluster (sol p @ +oo%R)). +Proof. +move=> Kp q plim_q t0 t0_ge0 A B [M]. +wlog Mge0 : M / (0 <= M)%R => [sufMge0|] [Mreal solpMinfty_A]. + apply: (sufMge0 (maxr 0%R M)); first by rewrite le_max lexx. + split. + by rewrite max_real// real0. + by move=> x; rewrite gt_max => /andP[_]; apply: solpMinfty_A. +have Kq : K q. + apply: compact_closed => // C qC. + move: plim_q; apply => //. + exists 0%R; split => // t /ltW tge0. + exact: Kinvar. +have sol_cont' : forall t : R, + (forall x : U, K x -> (sol^~ t) x @[x --> within K (nbhs x)] --> (sol^~ t) x). + by move=> t; exact/subspace_continuousP/sol_cont. +move=> /(sol_cont' t0 _ Kq) /plim_q q_Bsolt0. +have /q_Bsolt0 [_ [[[t tgtM <-] _]]] : (sol p @ +oo%R) (sol p @` (> M)%R `&` A). + by exists M; split => // => t tgtM; split; [apply: imageP|apply: solpMinfty_A]. +have tge0 : (0 <= t)%R by apply/ltW; apply: le_lt_trans tgtM. +have Ksolpt : K (sol p t) by apply: Kinvar. +move=> /(_ Ksolpt) /=; rewrite -solD // => Bsolpt0t; exists (sol p (t0 + t)). +by split=> //; exact/solpMinfty_A/ltr_wpDl. +Qed. + +Definition limS (A : set U) := \bigcup_(q in A) cluster (sol q @ +oo%R). + +Lemma invariant_limS A : A `<=` K -> is_invariant (limS A). +Proof. +move=> sAK p [q Aq plimp] t tge0. +by exists q => //; apply: invariant_plim => //; apply: sAK. +Qed. + +Lemma nincr_lb_cvg (f : R -> R) : + (forall x y, 0 <= x <= y -> f y <= f x)%R -> + (exists M, f @` (>= 0)%R `<=` (> M)%R) -> cvg (f @ +oo%R). +Proof. +move=> fnincr [M ltMf]. +apply/cvg_ex; exists (inf (fun x => x \in f @` (>= 0)%R)). +move=> A /nbhs_ballP [_ /posnumP[e] infe_A]. +have imf_inf : has_inf (fun x => x \in f @` (>= 0)%R). + split; first by exists (f 0%R); rewrite in_setE; apply: imageP. + by exists M; apply/lbP => ?; rewrite in_setE => /ltMf /ltW. +have := imf_inf => /inf_adherent => /(_ e%:num)%R. +move=> /(_ (gt0 e)) [x]. +rewrite in_setE => -[t tge0 <-] ltftinfe. +exists t; rewrite num_real; split => // s ltts; apply: infe_A. +rewrite /ball/=. +rewrite distrC ger0_norm. + rewrite ltrBlDl. + by apply: le_lt_trans ltftinfe; apply: fnincr; rewrite tge0 (ltW ltts). +rewrite subr_ge0. +apply: inf_lbound => //. + by case: imf_inf. +rewrite in_setE; apply: imageP. +by apply: ltW; exact: le_lt_trans ltts. +Qed. + +(* todo: use directional derivative *) +Lemma stable_limS (V : U -> R^o) : + {within K, continuous V} -> + (forall p t, K p -> (0 <= t)%R -> derivable (V \o sol p : R^o -> R^o) t 1) -> + (forall (p : U), K p -> (V \o sol p)^`() 0 <= 0)%R -> + limS K `<=` [set p | (V \o sol p)^`() 0 = 0]%R. +Proof. +move=> Vcont Vsol_drvbl Vsol'le0 p [q Kq plimp]. +have ssqRpK : sol q @` (>= 0)%R `<=` K by move=> _ [t tge0 <-]; apply: Kinvar. +(* should be inferred *) +(*have atrF := at_right_proper_filter 0%R. (* is it now?*) *) +suff : exists l, cluster (sol q @ +oo%R) `<=` V @^-1` [set l]. + move=> [l Vpliml]/=; rewrite derive1E /derive cvg_at_rightE; last first. + apply: Vsol_drvbl => //; apply: compact_closed => //. + exact: sub_plim_clos_invar plimp. + apply: (@cvg_lim _ _ _ (at_right _)) => // A A0. + rewrite !near_simpl; near=> h. + rewrite /= sol0 addr0. + rewrite [X in sol p X](_ : _ = h); last by rewrite scaler1. + rewrite Vpliml//. + by rewrite Vpliml // subrr scaler0; apply: nbhs_singleton. + by apply: invariant_plim => //; apply: ltW; near: h; exists 1%R. +suff cvVsol : cvg (V \o sol q @ +oo%R). + exists (lim (V \o sol q @ +oo%R)); apply: (c0_cvg_cst_on_plim Vcont) => //. + exact: compact_closed. +apply: nincr_lb_cvg; last first. + have: compact (V @` K) by exact: continuous_compact. + move=> /compact_bounded [N imVltN]. + exists (- (N + 2))%R=> _ [t tge0 <-]. + suff : (`|(V \o sol q) t| < N + 2)%R by rewrite ltr_norml => /andP[]. + rewrite (@le_lt_trans _ _ (N + 1)%R)// ?ltrD2l ?ltr1n//. + by apply: imVltN.2; [rewrite ltrDl|apply/imageP/Kinvar]. +move=> s t /andP [sge0 slet]. +apply: (@ler0_derive1_le_cc _ _ s t); first 2 last. + apply: continuous_in_subspaceT => x. + rewrite inE/= in_itv/= => /andP[sx xt]. + have := Vsol_drvbl _ _ Kq (le_trans sge0 sx). + move/derivable1_diffP/differentiable_continuous. + exact. + by rewrite in_itv/= slet lexx. + by rewrite in_itv/= lexx slet. + by []. + move=> r rst. + apply: Vsol_drvbl => //; apply: le_trans sge0 _. + by rewrite (itvP rst). +move=> r rst. +have rge0 : (0 <= r)%R by apply: le_trans sge0 _; rewrite (itvP rst). +suff -> : derive1 (V \o sol q) r = derive1 (V \o (sol (sol q r))) 0. + exact/Vsol'le0/Kinvar. +rewrite derive1E /derive cvg_at_rightE; last exact: Vsol_drvbl. +rewrite derive1E /derive cvg_at_rightE; last first. + by apply: Vsol_drvbl => //; apply: Kinvar. +congr (lim _); rewrite predeqE /= nbhs_filterE => A; split. + move=> [_/posnumP[e] Ae]; exists e%:num%R=> //= x xe xgt0. + rewrite sol0/=. + rewrite addr0 -solD //; [exact: Ae|]. + by rewrite scaler1 ltW. +move=> [_/posnumP[e] Ae]; exists e%:num%R => //= x xe xgt0. +have /Ae - /(_ xe) := xgt0. +by rewrite sol0/= addr0 -solD// scaler1 ltW. +Unshelve. all: by end_near. Qed. + +Lemma cvg_to_limS (A : set U) : compact A -> is_invariant A -> + forall p, A p -> sol p @ +oo%R --> (limS A : set U). +Proof. +move=> Aco Ainvar p Ap B [_/posnumP[e] limSeB]. +apply: (cvg_to_plim _ Aco). + exists 0%R; split => //. + by move=> _/posnumP[?]; exact: Ainvar. +exists e%:num%R=> //= q [r plimr re_q]. +by apply: limSeB; exists r => //; exists p. +Qed. + +End DifferentialSystem. diff --git a/octonion.v b/octonion.v index 919c7a2f..99a8eeb9 100644 --- a/octonion.v +++ b/octonion.v @@ -1,4 +1,4 @@ -(* coq-robot (c) 2017 AIST and INRIA. License: LGPL-2.1-or-later. *) +(* robot-rocq (c) 2026 AIST and INRIA. License: LGPL-2.1-or-later. *) From HB Require Import structures. From mathcomp Require Import all_ssreflect ssralg ssrint ssrnum rat poly. From mathcomp Require Import closed_field polyrcf matrix mxalgebra mxpoly zmodp. @@ -862,8 +862,8 @@ apply/eqP; rewrite eq_oct; apply/andP; split; apply/eqP. rewrite [in LHS]/= scaleoctE /=. rewrite !{1}(linear0, mul0r, mulr0, sub0r, add0r, subr0). rewrite [a.1 + _^*q]addrC addrK -scalerA addr0 -conjqE !mulrA !conjq_comm. - rewrite !conjqP /sqrq /= norm0 !expr0n expr1n /= !add0r !addr0. - rewrite !normeE !mul1r expr1n mul1r -3!opprD addrA -!mulr2n scalerN. + rewrite !conjqP /sqrq /= enorm0 !expr0n expr1n /= !add0r !addr0. + rewrite !enormeE !mul1r expr1n mul1r -3!opprD addrA -!mulr2n scalerN. rewrite -mulrnA -scaler_nat !scalerA -scalerBl. rewrite -{1}[3%:R^-1]mulr1 -mulrA -mulrBr natrM mulrA mulNr. rewrite mulVf ?(eqr_nat _ _ 0) //. @@ -874,7 +874,7 @@ apply: etrans (_ : -(2%:R / 3%:R) *: a.2 + -(1 / 3%:R) *: a.2 = _). rewrite -scalerDl -opprD -mulrDl -(natrD _ _ 1) mulfV ?scaleN1r //. by rewrite (eqr_nat _ _ 0). congr (_ + _). - rewrite 3!addr0 -scalerA -!{1}mulrA !{1}conjqP /sqrq !normeE /= + rewrite 3!addr0 -scalerA -!{1}mulrA !{1}conjqP /sqrq !enormeE /= !expr0n !expr1n /=. rewrite !add0r !mul1r !mulr1 mulrC -mulrN -scalerA. rewrite -addrA -!mulr2n -mulrnA -scaler_nat !scalerA natrM mulrA. diff --git a/ode.v b/ode.v new file mode 100644 index 00000000..5c871b3e --- /dev/null +++ b/ode.v @@ -0,0 +1,2497 @@ +From HB Require Import structures. +From mathcomp Require Import all_boot all_order ssralg ssrnum matrix interval. +From mathcomp Require Import poly archimedean generic_quotient ring_quotient. +From mathcomp Require Import interval_inference. +From mathcomp Require Import mathcomp_extra unstable boolp classical_sets. +From mathcomp Require Import contra functions constructive_ereal reals. +From mathcomp Require Import topology prodnormedzmodule tvs normedtype. +From mathcomp Require Import landau ereal sequences derive numfun measure. +From mathcomp Require Import realfun lebesgue_measure lebesgue_integral ftc. +Require Import tilt_mathcomp tilt_analysis ode_common ode_contseg. + +(**md**************************************************************************) +(* # Proof of the Cauchy-Lipschitz theorem *) +(* *) +(* The main purpose of this file is to formalized the Cauchy-Lipschitz *) +(* theorem (a.k.a. Picard-Lindelof). *) +(* *) +(* We consider an ODE defined by a function phi : K -> 'rV[K]_n -> 'rV[K]_n. *) +(* The idea of the proof is to define a function *) +(* picard := fun t => u0 + \int[mu]_(x in `[a, t]) phi x (g x) *) +(* and to study the solution of the integral equation g t = picard t. *) +(* *) +(* Preliminaries: *) +(* \vint[mu]_(x in A) f x == integral of f of type R -> 'rV_n *) +(* *) +(* picard_fun_subdef u0 r phi a b g gabB == *) +(* fun t => u0 + \vint_(x in `[a, t]) phi x (g x) *) +(* defined as a continuous function from `[a, b] to 'rV_n *) +(* morally, takes a function g and returns a function g *) +(* gabB is a proof that g @` `[a, b] `<=` closed_ball u0 r *) +(* *) +(* picard_fun lip2 cont1 g == same as picard_fun_subdef when *) +(* g @` `[a, b] `<=` closed_ball u0 r and cst 0 o.w. *) +(* *) +(* Technical constants needed for the proof: *) +(* sup_phi == sup {phi t u0 | t \in [a, b]} *) +(* safe_dist == min (b - a, r / (k * r + sup_phi), rho / k) *) +(* upper-bound of delta *) +(* The dependence of safe_dist on the initial state u0 comes *) +(* from sup_phi in the second term. *) +(* @img_cball R n f a b k u0 r k0 rho == *) +(* set of functions of type `C([a, b] U) s.t. *) +(* f @` `[a, a + safe_dist] `<=` closed_ball u0 r *) +(* *) +(* picard == similar to picard_fun *) +(* as a function from/to the quotient of functions continuous over `[a, b] *) +(* more precisely, function of type {fun img_cball >-> img_cball} *) +(* *) +(* picard_fix == fixpoint of the integral equation defined by picard *) +(* *) +(******************************************************************************) + +Set Implicit Arguments. +Unset Strict Implicit. +Unset Printing Implicit Defensive. + +Import Order.TTheory GRing.Theory Num.Def Num.Theory. +Import numFieldNormedType.Exports. + +Open Scope ring_scope. +Open Scope classical_set_scope. + +(* start of preliminaries *) + +Reserved Notation "\vint [ mu ]_ ( i 'in' D ) F" + (at level 36, F at level 36, i, D at level 60, + format "'[' \vint [ mu ]_ ( i 'in' D ) '/ ' F ']'"). +Reserved Notation "\vint [ mu ]_ i F" + (F at level 36, i at level 0, + right associativity, format "'[' \vint [ mu ]_ i '/ ' F ']'"). + +(* TODO: move *) +Section row_Rintegral. +Context {R : realType} (d : measure_display) {T : measurableType d}. +Variable (mu : {measure set T -> \bar R}). +Variable (D : set T) (n : nat). + +Definition rowRintegral (f : T -> 'rV[R]_n) : 'rV[R]_n := + \row_i (\int[mu]_(x in D) (f x) ord0 i). + +Local Notation "\vint_ i F" := + (rowRintegral (fun i => F)%R) (at level 36, i at level 0, + format "'[' \vint_ i '/ ' F ']'") : ring_scope. + +Lemma rowRintegralE (f : T -> 'rV[R]_n) i : + (\vint_x f x) ord0 i = \int[mu]_(x in D) (f x) ord0 i. +Proof. by rewrite /rowRintegral mxE. Qed. + +End row_Rintegral. + +Notation "\vint [ mu ]_ ( x 'in' D ) f" := + (rowRintegral mu D (fun x => f)%R) : ring_scope. +Notation "\vint [ mu ]_ x f" := + (rowRintegral mu setT (fun x => f)%R) : ring_scope. + +Section rowRintegral. +Context {R : realType}. +Let mu := @lebesgue_measure R. + +Lemma rowRintegral_set1 n (f : R -> 'rV[R]_n) (r : R) : + \vint[mu]_(x in [set r]) f x = 0. +Proof. by apply/rowP => i; rewrite !mxE Rintegral_set1. Qed. + +Lemma eq_rowRintegral n (D : set R) (f : R -> 'rV[R]_n) (g : R -> 'rV[R]_n): + {in D, f =1 g} -> \vint[mu]_(x in D) f x = \vint[mu]_(x in D) g x. +Proof. +move => h. +apply /rowP => i. +rewrite !rowRintegralE. +apply eq_Rintegral => /= x Dx. +by rewrite h. +Qed. + +End rowRintegral. + +Section rowRintegral_itv_split. +Local Notation mu := lebesgue_measure. + +Lemma rowRintegral_itv_split {R : realType} (n : nat) (F : R -> 'rV[R]_n) + (a c b : R) : + a <= c <= b -> + (forall i, mu.-integrable `[a, b] (EFin \o (fun x : R => F x ord0 i))) -> + \vint[mu]_(s in `[a, b]) F s = + \vint[mu]_(s in `[a, c]) F s + \vint[mu]_(s in `[c, b]) F s. +Proof. +move=> /andP[t0t1 t1t2] intF. +apply/rowP=> i. +rewrite !rowRintegralE !mxE. +apply/eqP. +rewrite addrC -subr_eq. +apply/eqP. +rewrite (@Rintegral_itvB _ (fun x => F x ord0 i) (BLeft a) (BRight b) c) //=. +apply Rintegral_itv_obnd_cbnd. +apply (@integrableS _ _ _ lebesgue_measure `[a, b] `]c, b] (EFin \o (fun x => F x ord0 i))) =>//. +exact: subset_itvScc. +Qed. + +End rowRintegral_itv_split. + +Lemma vec_norm_le_sum {R : realType} {n : nat} (x : 'rV[R]_n) : + `| x | <= \sum_(i < n) `|x ord0 i|. +Proof. +rewrite {1}/Num.norm/= mx_normrE. +apply: bigmax_le => /=;first by apply sumr_ge0 => i _; exact: normr_ge0. +move => [i0 i] _ /=. +rewrite {i0}(ord1 i0)/=. +rewrite (bigD1 i) //= lerDl. +by apply: sumr_ge0 => j _; exact: normr_ge0. +Qed. + +(* TODO: PR *) +Lemma measurable_fun_bigmaxr d (T : measurableType d) (R : realType) + (D : set T) (n : nat) (f : 'I_n -> T -> R) : + d.-measurable D -> + (forall i, measurable_fun D (f i)) -> + measurable_fun D (fun x => \big[maxr/0]_(i < n) f i x). +Proof. +move=> mD mf. +elim: n f mf => [|n IH] f mf. + have -> : (fun x : T => \big[maxr/0]_(i < 0) f i x) = 0. + apply funext => x. + by rewrite big_ord0. + exact: measurable_cst. +have -> : (fun x : T => \big[maxr/0]_(i < n.+1) f i x) = + fun x => maxr (f ord0 x) (\big[maxr/0]_(i < n) (f (lift ord0 i) x)). + by apply funext => x;apply big_ord_recl. +apply: measurable_maxr. + exact: mf. +by apply: IH => i; exact: mf. +Qed. + +Lemma vmeasurable_norm {R : realType} {n : nat} (D : set R) (F : R -> 'rV[R]_n): + measurable D -> (forall i, measurable_fun D (fun t => F t ord0 i)) -> + measurable_fun D (Num.norm \o F). +Proof. +move=> mD h. +have -> : normr \o F = (fun x => \big[maxr/0]_(i < n) `| F x ord0 i |). + apply: funext => x. + rewrite {1}/Num.norm/= mx_normrE. + rewrite (reindex (fun i : 'I_n => (ord0, i))) => //=. + exists (@snd 'I_1 'I_n) => /=. + + by move => i. + + move => [i j] /= _. + by rewrite {i}(ord1 i). +apply: measurable_fun_bigmaxr => //= i. +by apply: measurableT_comp => //=. +Qed. + +Lemma vintegrable_norm {R : realType} {n : nat} (D : set R) (F : R -> 'rV[R]_n): + measurable D -> + (forall i, lebesgue_measure.-integrable D (EFin \o (fun t => F t ord0 i))) -> + lebesgue_measure.-integrable D (EFin \o (Num.norm \o F)). +Proof. +move => mD intf. +apply (le_integrable (mu:=lebesgue_measure) mD (f := EFin \o (normr \o F)) + (g := EFin \o fun x => (\sum_(i < n) `| F x ord0 i|))). +- apply/measurable_EFinP. + apply vmeasurable_norm => // i. + have /integrableP[+ _]/= := intf i. + by move/measurable_EFinP. +- move => /= x0 Dx0. + rewrite normr_id. + rewrite lee_fin. + rewrite ger0_norm. + apply vec_norm_le_sum. + exact: sumr_ge0. +- have -> : EFin \o (fun x => \sum_(i < n) `|F x ord0 i|) = + fun x => (\sum_(i < n) `|F x ord0 i|%:E). + by apply/funext => x; rewrite sumEFin. + apply: integrable_sum => //= i _. + exact: integrable_norm. +Qed. + +Lemma closed_ball_vecE {R : realType} {n} (x0 : 'rV[R]_n) (r : {posnum R}) x : + closed_ball x0 r%:num x <-> + forall i, closed_ball (x0 ord0 i) r%:num (x ord0 i). +Proof. +split. +- rewrite closed_ballE /closed_ball_ //=. + rewrite /Num.norm/= mx_normrE => h i. + rewrite closed_ballE// /closed_ball_/=. + apply/le_trans/h. + have -> : x0 ord0 i - x ord0 i = (x0 - x) ord0 i by rewrite !mxE. + exact: (le_bigmax _ _ (ord0, i)). +- move=> h. + rewrite closed_ballE// /closed_ball_/=. + rewrite [in leLHS]/Num.norm/= mx_normrE. + apply: bigmax_le => //= -[i j] _ /=. + rewrite {i}(ord1 i)/=. + move /(_ j) : h. + by rewrite closed_ballE// /closed_ball_ /= 2!mxE. +Qed. + +Section lipschitz_componentE. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n. +Variables (phi : R -> U -> U) (a b : R) (k : R). +Variables (u0 : U) (r : {posnum R}). +Let B := closed_ball u0 r%:num. +Hypothesis k0 : 0 <= k. + +Lemma lipschitz_componentE x : k.-lipschitz_B (phi x) <-> + forall i, k.-lipschitz_B (fun y => phi x y ord0 i). +Proof. +split. +- move => lip i /= [x1 x2] /= Bx12. + move /(_ (x1,x2) Bx12) : lip. + apply le_trans => /=. + rewrite /Num.norm/= mx_normrE. + have -> : phi x x1 ord0 i - phi x x2 ord0 i = (phi x x1 - phi x x2) ord0 i by rewrite !mxE. + exact: (le_bigmax _ _ (ord0,i)). +- move => h /= [x1 x2] Bx12 /=. + rewrite [in leLHS]/Num.norm/= mx_normrE. + apply/bigmax_le. + by rewrite mulr_ge0 //= ltW. + move => //= -[i j] _ /=. + rewrite {i}(ord1 i)/=. + move /(_ j (x1,x2) Bx12) : h. + by rewrite !mxE. +Qed. + +End lipschitz_componentE. + +Definition measure_rV_display : measure_display -> measure_display. +Proof. exact. Qed. + +Section measurable_rV. +Context {d} {T : sigmaRingType d}. +Variable n : nat. + +Let coors : 'I_n -> 'rV[T]_n -> T := fun i x => x ord0 i. + +Let rV_set0 : g_sigma_preimage coors set0. +Proof. exact: sigma_algebra0. Qed. + +Let rV_setC A : g_sigma_preimage coors A -> g_sigma_preimage coors (~` A). +Proof. exact: sigma_algebraC. Qed. + +Let rV_bigcup (F : _^nat) : (forall i, g_sigma_preimage coors (F i)) -> + g_sigma_preimage coors (\bigcup_i (F i)). +Proof. exact: sigma_algebra_bigcup. Qed. + +HB.instance Definition _ := @isMeasurable.Build (measure_rV_display d) + 'rV[T]_n (g_sigma_preimage coors) rV_set0 rV_setC rV_bigcup. + +End measurable_rV. + +(* end of preliminaries *) + +(* cauchy-lipschitz really starts here *) + +Definition picard_fun_subdef {R : realType} n (U := 'rV[R]_n) (u0 : U) (r : R) + (B := closed_ball u0 r) (phi : R -> U -> U) (a b : R) (g : R -> U) + (gabB : g @` `[a, b] `<=` B) : R -> U := + fun t => u0 + (\vint[lebesgue_measure]_(x in `[a, t]) phi x (g x))%R. + +Section picard_fun_subdef_isFun. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n. +Variables (phi : R -> U -> U) (a b : R). +Variables (u0 : U) (r : {posnum R}). +Let B : set U := closed_ball u0 r%:num. +Variable g : R -> U. +Hypothesis gabB : g @` `[a, b] `<=` B. + +Let set_fun_picard_fun_subdef : + {homo picard_fun_subdef phi gabB : x / `[a, b] x >-> [set: U] x}. +Proof. by []. Qed. + +HB.instance Definition _ := @isFun.Build + (subspace `[a, b]) _ `[a, b] [set: U] (picard_fun_subdef phi gabB) + (set_fun_picard_fun_subdef). + +End picard_fun_subdef_isFun. + +Section picard_fun_subdef_isContinuous. +Local Notation mu := lebesgue_measure. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n. +Variables (phi : R -> U -> U) (a b : R). +Variables (u0 : U) (r : {posnum R}). +Let B : set U := closed_ball u0 r%:num. + +Variable k : R. +Hypothesis k0 : k != 0. +Hypothesis lip2 : {in `[a, b]%R, forall x, k.-lipschitz_B (phi x)}. +Hypothesis cont1 : {in B, forall y, {within `[a, b], continuous phi ^~ y}}. +Variable g : R -> U. +Variable cg : {within `[a, b], continuous g}. +Hypothesis gabB : g @` `[a, b] `<=` B. + +Lemma within_continuous_picard_fun_subdef : + {within `[a, b], continuous (picard_fun_subdef phi gabB)}. +Proof. +have [ab|] := ltP a b; last first. + rewrite le_eqVlt => /predU1P[ab|ab]. + rewrite [X in {within X, continuous _}](_ : _ = [set a]); last first. + by rewrite ab set_itv1. + exact: continuous_subspace1. + rewrite set_itv_ge// ?bnd_simp -?ltNge//. + exact: continuous_subspace0. +apply/within_continuous_coord => i. +rewrite /picard_fun_subdef. +suff: {within `[a, b], + continuous (fun t => \int[mu]_(y in `[a, t]) phi y (g y) ord0 i)}. + move=> abf x. + rewrite (_ : (fun r => (u0 + \vint[mu]_(y in `[a, r]) phi y (g y)) ord0 i) = + (fun r => u0 ord0 i + \int[mu]_(y in `[a, r]) (phi y (g y)) ord0 i)). + by apply: cvgD; [exact: cvg_cst|exact: abf]. + by apply/funext=> r0; rewrite mxE rowRintegralE. +move=> /= x. +apply: parameterized_integral_continuous. + exact: ltW. +apply: continuous_compact_integrable; first exact: segment_compact. +move=> {x}. +move: i; apply/within_continuous_coord. +exact: (within_continuous_lipschitz cg _ lip2 cont1). +Qed. + +HB.instance Definition _ := isContinuous.Build (subspace `[a, b]) U + (picard_fun_subdef phi gabB : subspace _ -> _) + within_continuous_picard_fun_subdef. + + +End picard_fun_subdef_isContinuous. + +Section picard_fun. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n. +Variables (phi : R -> U -> U) (a b : R). +Variables (u0 : U) (r : {posnum R}). +Let B := closed_ball u0 r%:num. + +Definition picard_fun + (k : R) (k0 : k != 0) (lip2 : {in `[a, b]%R, forall x, k.-lipschitz_B (phi x)}) + (cont1 : {in B, forall y, {within `[a, b], continuous phi ^~ y}}) + (g : R -> U) : R -> U := + match pselect (g @` `[a, b] `<=` B) with + | left gabB => picard_fun_subdef phi gabB + | _ => cst 0 + end. + +End picard_fun. + +Section sup_phi. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n. +Variables (phi : R -> U -> U) (a b : R). +Variables (u0 : U). + +Definition sup_phi : R := sup [set `|phi t u0| | t in `[a, b]]. + +Lemma sup_phi_ge0 : 0 <= sup_phi. +Proof. by rewrite /sup_phi sup_ge0//= => x [y _ <-]. Qed. + +End sup_phi. + +Section sup_phi_lemmas. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n. +Variables (phi : R -> U -> U). +Variables (u0 : U). + +Lemma sup_phiS a b c d : {within `[a, b], continuous (phi ^~ u0)} -> + a <= b -> `[c, d] `<=` `[a, b] -> + sup_phi phi c d u0 <= sup_phi phi a b u0. +Proof. +move=> cf ab cdab. +rewrite /sup_phi. +have [cd|dc] := leP c d. + apply: sup_le => //. + - move=> _/= [r rcd <-]. + red. + simpl. + exists `|phi r u0|; split => //. + exists r => //. + by apply: cdab. + - exists `|phi c u0| => /=. + exists c => //. + by rewrite in_itv/= lexx cd. + - split. + exists `|phi a u0| => //=. + exists a => //. + by rewrite in_itv/= lexx ab. + have : {within `[a, b], continuous fun t : R => `|phi t u0|}. + by apply: within_continuous_comp_norm => //. + move/(@EVT_max R (fun t => `|phi t u0|) _ _ ab) => [e eab Hmax]. + exists (`|phi e u0|) => x/= [r rab <-//]. + exact: Hmax. +rewrite set_itv_ge ?bnd_simp/= -?ltNge// image_set0 sup0. +by apply: sup_ge0 => x/= [y _ <-//]. +Qed. + +End sup_phi_lemmas. + +Section safe_dist. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n. +Variables (phi : R -> U -> U) (a b : R) (k : R). +Hypothesis ab : a < b. +Variables (u0 : U) (r : {posnum R}). +Hypothesis k0 : 0 < k. +Variable rho : {posnum R}. (* rho < 1 *) + +Local Notation sup_phi := (sup_phi phi a b u0). + +Definition safe_dist := Num.min (b - a) + (Num.min (r%:num / (k * r%:num + sup_phi)) + (rho%:num / k)). + +Lemma safe_dist_gt0 : 0 < safe_dist. +Proof. +rewrite lt_min subr_gt0 ab/= lt_min mulr_gt0 ?divr_gt0//. +by rewrite invr_gt0// ltr_wpDr ?sup_phi_ge0// mulr_gt0. +Qed. + +Lemma ltDl_safe_dist : a < a + safe_dist. +Proof. by rewrite ltrDl safe_dist_gt0. Qed. + +Lemma leDl_safe_dist : a <= a + safe_dist. +Proof. by rewrite ltW// ltDl_safe_dist. Qed. + +Lemma safe_dist_itv : safe_dist <= b - a. +Proof. by rewrite /safe_dist ge_min lexx. Qed. + +End safe_dist. + +Section image_in_closed_ball. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n. +Variables (phi : R -> U -> U) (a b : R) (k : R). +Variables (u0 : U) (r : {posnum R}). +Hypothesis k0 : 0 < k. +Variable rho : {posnum R}. (* rho < 1 *) + +Import ContSeg_quot. + +Local Notation safe_dist := (@safe_dist R n phi a b k u0 r rho). +Local Notation C := (`C([a, a + safe_dist] U)). + +Definition img_cball : set C := + [set f : C | f @` `[a, a + safe_dist] `<=` closed_ball u0 r%:num]. + +Lemma img_cball_nonempty : img_cball !=set0. +Proof. +exists (pi C (cst u0)) => _ [y aay] <-. +suff -> : fun_of_quot_contSeg (\pi_C%qT (cst u0)) y = u0. + exact: closed_ballxx. +rewrite /fun_of_quot_contSeg/=. +have /eqmod_on_itv : (repr (\pi_C%qT (cst u0)) = cst u0 %[mod C])%qT. + by rewrite reprK. +by apply; rewrite inE. +Qed. + +Lemma img_cballE : a < b -> img_cball = + @closed_ball R C (pi C (@cst (subspace `[a, a + safe_dist]) U u0)) r%:num. +Proof. +move=> ab; rewrite closed_ballE//. +apply: eq_set => /= f; apply propext; split => h. +- rewrite -(@reprK _ C f). + rewrite /GRing.opp /= -Quotient.pi_opp /GRing.add /= -Quotient.pi_add. + rewrite infty_norm_pi infty_norm0_le//. + by rewrite /= lerDl ltW// safe_dist_gt0. + move=> x adx. + move /(_ (f x)) : h. + rewrite closed_ballE//. + apply. + by exists x. +- move => _ [x xad] <-. + rewrite closed_ballE// /closed_ball_ /=. + have -> : u0 - f x = ((pi C (cst u0)) - f : C) x. + rewrite -(@reprK _ C f) /GRing.opp /=. + rewrite -Quotient.pi_opp /GRing.add /= -Quotient.pi_add. + by rewrite !eval_mod_on_itv// inE. + rewrite -(@reprK _ C f). + rewrite /GRing.opp /= -Quotient.pi_opp /GRing.add /= -Quotient.pi_add. + rewrite eval_mod_on_itv; last by rewrite inE. + apply: (le_trans (infty_norm0_ge (leDl_safe_dist phi ab u0 r k0 rho) _ xad)). + rewrite -infty_norm_pi. + by rewrite Quotient.pi_add Quotient.pi_opp reprK. +Qed. + +Lemma closed_img_cball : a < b -> closed img_cball. +Proof. by move=> ?; rewrite img_cballE//; exact: closed_ball_closed. Qed. + +End image_in_closed_ball. + +Section picard_fun_isFun. +Local Notation mu := lebesgue_measure. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n. +Variables (phi : R -> U -> U) (a b : R) (k : R). +Variables (u0 : U) (r : {posnum R}). +Let B := closed_ball u0 r%:num. +Hypothesis k0 : k != 0. +Hypothesis lip2 : {in `[a, b]%R, forall x, k.-lipschitz_B (phi x)}. +Hypothesis cont1 : {in B, forall y, {within `[a, b], continuous phi ^~ y}}. + +Variable rho : {posnum R}. + +Local Notation safe_dist := (safe_dist phi a b k u0 r rho). + +Lemma lip2_safe_dist : {in `[a, a + safe_dist]%R, forall x, k.-lipschitz_B (phi x)}. +Proof. +move/in_switch : lip2 => lip2'. +apply/in_switch. +apply: lipschitzW lip2'. +apply: subset_itvl. +by rewrite bnd_simp -lerBrDl; exact: safe_dist_itv. +Qed. + +Lemma cont1_safe_dist : + {in B, forall y, {within `[a, a + safe_dist], continuous phi ^~ y}}. +Proof. +move=> /= x xB. +apply: continuous_subspaceW; last exact: cont1. +apply: subset_itvl. +by rewrite bnd_simp -lerBrDl; exact: safe_dist_itv. +Qed. + +Local Notation picard_fun := + (@picard_fun _ n phi a (a + safe_dist) u0 r k k0 lip2_safe_dist cont1_safe_dist). + +Lemma picard_funE g t : g @` `[a, a + safe_dist] `<=` B -> + picard_fun g t = u0 + \vint[mu]_(x in `[a, t]) phi x (g x). +Proof. by rewrite /picard_fun; case: pselect. Qed. + +Lemma picard_fun_init g : g @` `[a, a + safe_dist] `<=` B -> + picard_fun g a = u0. +Proof. +by move => h; rewrite picard_funE// set_itv1 rowRintegral_set1 addr0. +Qed. + +Import ContSeg_quot. + +Local Notation C := (`C([a, a + safe_dist] U)). + +Let set_fun_picard_fun (g : C) : + set_fun `[a, a + safe_dist] [set: U] (picard_fun g). +Proof. by []. Qed. + +HB.instance Definition _ (g : C) := @isFun.Build + (subspace `[a, a + safe_dist]) _ + `[a, a + safe_dist] setT (picard_fun g) (set_fun_picard_fun g). + +End picard_fun_isFun. + +Section picard_fun_isContinuous. +Local Notation mu := lebesgue_measure. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n. +Variables (phi : R -> U -> U) (a b : R) (k : R). +Variables (u0 : U) (r : {posnum R}). +Let B := closed_ball u0 r%:num. +Hypothesis k0 : k != 0. +Hypothesis lip2 : {in `[a, b]%R, forall x, k.-lipschitz_B (phi x)}. +Hypothesis cont1 : {in B, forall y, {within `[a, b], continuous phi ^~ y}}. + +Variable rho : {posnum R}. + +Local Notation safe_dist := (safe_dist phi a b k u0 r rho). + +Local Notation picard_fun := (@picard_fun _ n phi a (a + safe_dist) u0 r k k0 + (@lip2_safe_dist R n phi a b k u0 r lip2 rho) + (@cont1_safe_dist R n phi a b k u0 r cont1 rho)). + +Import ContSeg_quot. + +Local Notation C := (`C([a, a + safe_dist] U)). + +Let continuous_picard_fun (g : C) : + {within `[a, a + safe_dist], continuous (picard_fun g)}. +Proof. +have [aaD|] := ltP a (a + safe_dist); last first. + rewrite le_eqVlt => /predU1P[aaD|aaD]. + rewrite [X in {within X, continuous _}](_ : _ = [set a]); last first. + by rewrite aaD set_itv1. + exact: continuous_subspace1. + rewrite set_itv_ge// ?bnd_simp -?ltNge//. + exact: continuous_subspace0. +have := @cts_fun _ _ g. +rewrite /picard_fun; case: pselect => /=. + move => z cg. + apply: (@cts_fun (subspace `[a, a + safe_dist]) U (picard_fun_subdef phi z)). + - exact: k0. + - exact: lip2_safe_dist. + - exact: cont1_safe_dist. + - exact: cg. +by move=> _ _; apply: continuous_subspaceT => z; exact: cvg_cst. +Qed. + +HB.instance Definition _ (g : C) := @isContinuous.Build _ _ + (picard_fun g : subspace _ -> _) (@continuous_picard_fun g). + +Check fun g : C => picard_fun g : continuousFunType _ _. + +Check fun g : C => (\pi_C%qT (picard_fun g)) : C. + +End picard_fun_isContinuous. + +Section integrable_comp. +Local Notation mu := lebesgue_measure. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n. +Variables (phi : R -> U -> U) (a b : R) (k : R). +Variables (u0 : U) (r : {posnum R}). +Let B := closed_ball u0 r%:num. +Hypothesis k0 : k != 0. +Hypothesis lip2 : {in `[a, b]%R, forall x, k.-lipschitz_B (phi x)}. +Hypothesis cont1 : {in B, forall y, {within `[a, b], continuous phi ^~ y}}. + +Variable rho : {posnum R}. + +Local Notation safe_dist := (safe_dist phi a b k u0 r rho). + +Import ContSeg_quot. + +Local Notation C := (`C([a, a + safe_dist] U)). + +Lemma integrable_comp (F : C) y i : y \in `[a, a + safe_dist]%R -> + F @` `[a, y] `<=` B -> + mu.-integrable `[a, y] (EFin \o (fun t => phi t (F t) ord0 i)). +Proof. +move=> yaadelta ab0r. +apply: continuous_compact_integrable; first exact: segment_compact. +move: (yaadelta); rewrite in_itv/= => /andP[ay yadelta]. +move: i; apply/within_continuous_coord. +apply/(within_continuous_lipschitz _ k0). +- have := @cts_fun _ _ F. + by apply/continuous_subspaceW/subset_itvl; rewrite bnd_simp. +- apply/in_switch. + move/in_switch : (@lip2_safe_dist R n phi a b k u0 r lip2 rho). + by apply/lipschitzW/subset_itvl; rewrite bnd_simp. +- rewrite -/B => x xB. + have := @cont1_safe_dist R n phi a b k u0 r cont1 rho _ xB. + by apply/continuous_subspaceW/subset_itvl; rewrite bnd_simp. +- exact: ab0r. +Qed. + +End integrable_comp. + +Section picard. +Local Notation mu := lebesgue_measure. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n. +Variables (phi : R -> U -> U) (a b : R) (k : R). +Variables (u0 : U) (r : {posnum R}). +Let B := closed_ball u0 r%:num. +Hypothesis k0 : 0 < k. +Let k0' : k != 0. Proof. by rewrite gt_eqF. Qed. + +Hypothesis lip2 : {in `[a, b]%R, forall x, k.-lipschitz_B (phi x)}. +Hypothesis cont1 : {in B, forall y, {within `[a, b], continuous phi ^~ y}}. + +Variable rho : {posnum R}. + +Local Notation safe_dist := (safe_dist phi a b k u0 r rho). +Local Notation picard_fun := (@picard_fun _ n phi a (a + safe_dist) u0 r k k0' + (@lip2_safe_dist R n phi a b k u0 r lip2 rho) + (@cont1_safe_dist R n phi a b k u0 r cont1 rho)). + +Import ContSeg_quot. + +Local Notation C := (`C([a, a + safe_dist] U)). + +Definition picard (f : C) : C := \pi_C%qT (picard_fun f). + +Local Notation img_cball := (@img_cball R n phi a b k u0 r rho). +Local Notation sup_phi := (@sup_phi R n phi a b u0). + +Let set_fun_picard : set_fun img_cball img_cball picard. +Proof. +move=> F. +rewrite /img_cball/= => invariant _/= [y yaaDelta <-]. +rewrite /picard. +apply closed_ball_vecE => i. +rewrite closed_ball_itv//=. +rewrite in_itv//=. +rewrite [X in _ <= X <= _](_ : _ = (picard_fun F) y ord0 i); last first. + have /eqmod_on_itv : (repr (\pi_C%qT (picard_fun F)) = + picard_fun F %[mod C])%qT. + by rewrite reprK. + by move=> <- //; rewrite inE. +rewrite /picard_fun; case: pselect => /= abu0r; last by []. +rewrite /picard_fun_subdef /=. +rewrite mxE/=. +rewrite -ler_distl. +rewrite -addrA subrKC. +rewrite rowRintegralE. +rewrite (le_trans (le_normr_Rintegral _ _))//=. + apply: integrable_comp => //. + apply: subset_trans abu0r. + apply/image_subset/subset_itvl; rewrite bnd_simp. + by move : yaaDelta; rewrite in_itv /= => /andP[]. +have integrable2 : mu.-integrable `[a, y] (EFin \o (fun x => phi x (F x) ord0 i)). + apply integrable_comp => //=. + apply: subset_trans abu0r. + apply/image_subset/subset_itvl; rewrite bnd_simp. + by move: yaaDelta; rewrite in_itv /= => /andP[]. +have integrable1 : mu.-integrable `[a, y] + (fun x => `|phi x (F x) ord0 i - phi x u0 ord0 i|%:E + `|phi x u0 ord0 i|%:E). + rewrite integrableD//=. + apply integrable_norm => /=. + under [x in integrable _ _ x]eq_fun do rewrite EFinD. + rewrite integrableD //=. + under [x in integrable _ _ x]eq_fun do rewrite EFinN. + rewrite integrableN //=. + apply: continuous_compact_integrable => //=; first exact: segment_compact. + apply within_continuous_coord. + apply/continuous_subspaceW/(@cont1_safe_dist R n phi a b k u0 r cont1 rho). + apply: subset_itvl; rewrite bnd_simp. + by move : yaaDelta;rewrite in_itv /= => /andP[]. + by rewrite /B inE; exact: closed_ballxx. + apply integrable_norm => /=. + apply continuous_compact_integrable => //=; first exact: segment_compact. + apply within_continuous_coord. + apply/continuous_subspaceW/(@cont1_safe_dist R n phi a b k u0 r cont1 rho). + apply: subset_itvl; rewrite bnd_simp. + by move : yaaDelta;rewrite in_itv /= => /andP[]. + rewrite /B inE. + exact: closed_ballxx. +rewrite (@le_trans _ _ (\int[mu]_(x in `[a, y]) + (`|phi x (F x) ord0 i - phi x u0 ord0 i| + `|phi x u0 ord0 i|)))//. + apply: le_Rintegral => //=. + - exact: integrable_norm. + - move=> x xay. + by rewrite (le_trans _ (ler_normD _ _))// subrK. +rewrite (@le_trans _ _ (\int[mu]_(x in `[a, y]) (k * `|F x - u0| + sup_phi)))//. + apply: le_Rintegral => //=. + under [x in integrable _ _ x]eq_fun do rewrite EFinD. + rewrite integrableD //=. + under [x in integrable _ _ x]eq_fun do rewrite EFinM. + rewrite integrableMr //=. + exact: bounded_cst. + apply: vintegrable_norm => //. + move => j //=. + under [x in integrable _ _ x]eq_fun do rewrite !mxE EFinB. + rewrite integrableB //=. + apply continuous_compact_integrable => //; first exact: segment_compact. + apply within_continuous_coord. + apply/continuous_subspaceW/cts_fun. + apply: subset_itvl; rewrite bnd_simp. + by move : yaaDelta; rewrite in_itv /= => /andP[]. + apply measurable_bounded_integrable => //=. + rewrite lebesgue_measure_itv //=. + case: ifPn => //=. + by rewrite -EFinD ltry. + exact: bounded_cst. + apply measurable_bounded_integrable => //=. + rewrite lebesgue_measure_itv //=. + case: ifPn => //=. + by rewrite -EFinD ltry. + exact: bounded_cst. + move=> x xay. + rewrite lerD//. + have xaaDelta : x \in `[a, a + safe_dist]%R. + move: x xay. + apply: subset_itvl; rewrite bnd_simp. + by rewrite (itvP yaaDelta). + move/(lip2_safe_dist lip2) : xaaDelta. + rewrite lipschitz_componentE//; last exact: ltW. + move/(_ i (F x, u0)) => /=. + apply. + split => /=. + apply: invariant => /=. + exists x => //. + move : xay. + apply: subset_itvl; rewrite bnd_simp. + by rewrite (itvP yaaDelta). + exact: closed_ballxx. + apply: (@le_trans _ _ `|phi x u0|) => //. + by rewrite /Num.norm/= mx_normrE /= (le_bigmax _ _ (ord0, i)). + rewrite /sup_phi ub_le_sup//. + have [M [Mb1 Mb2]] : bounded_set [set `|phi t u0| | t in `[a,b]]. + apply/compact_bounded/continuous_compact; last exact: segment_compact. + have [ab|] := ltP a b; last first. + rewrite le_eqVlt => /predU1P[ab|ab]. + rewrite [X in {within X, continuous _}](_ : _ = [set a]); last first. + by rewrite ab set_itv1. + exact: continuous_subspace1. + rewrite set_itv_ge// ?bnd_simp -?ltNge//. + exact: continuous_subspace0. + apply: within_continuous_comp_norm. + by rewrite ltW. + by apply cont1;rewrite inE; exact: closed_ballxx. + exists (M + 1) => _ [x0 x0ab] <- /=. + rewrite -normr_id. + apply Mb2. + by rewrite ltrDl. + by exists x0. + exists x => //. + move: xay; rewrite in_itv/= in_itv/= => /andP[] -> /=. + move/le_trans; apply. + move : yaaDelta; rewrite in_itv /= => /andP[]. + move => _ /le_trans; apply. + by rewrite -lerBrDl safe_dist_itv. +rewrite (@le_trans _ _ (\int[mu]_(x in `[a, y]) (k * r%:num + sup_phi)))//. + apply: le_Rintegral => //=. + - under [x in integrable _ _ x]eq_fun do rewrite EFinD. + rewrite integrableD //=. + under [x in integrable _ _ x]eq_fun do rewrite EFinM. + rewrite integrableMr //=. + exact: bounded_cst. + apply: vintegrable_norm => // j /=. + under [x in integrable _ _ x]eq_fun do rewrite !mxE EFinB. + rewrite integrableB //=. + apply continuous_compact_integrable => //. + exact: segment_compact. + apply within_continuous_coord. + apply /continuous_subspaceW/cts_fun. + apply: subset_itvl; rewrite bnd_simp. + by move : yaaDelta; rewrite in_itv /= => /andP[]. + apply: measurable_bounded_integrable => //=. + rewrite lebesgue_measure_itv//=. + case: ifPn => //=. + by rewrite -EFinD ltry. + exact: bounded_cst. + apply measurable_bounded_integrable => //=. + rewrite lebesgue_measure_itv //=. + case: ifPn => //=. + by rewrite -EFinD ltry. + exact: bounded_cst. + apply measurable_bounded_integrable => //=. + rewrite lebesgue_measure_itv //=. + case: ifPn => //=. + by rewrite -EFinD ltry. + exact: bounded_cst. + - move=> x xay. + rewrite lerD2r ler_pM2l//. + have : B (F x). + apply: invariant => /=. + exists x => //. + move: xay; rewrite !in_itv/= => /andP[] -> /= /le_trans. + apply. + by move: yaaDelta; rewrite in_itv /= => /andP[]. + by rewrite /B closed_ballE// /closed_ball_/=; rewrite distrC. +rewrite Rintegral_cst//. +rewrite /= (* to remove a reverse_coercion *). +rewrite lebesgue_measure_itv/=. +rewrite lte_fin. +move: (yaaDelta); rewrite in_itv/= => /andP[+ yadelta]. +rewrite le_eqVlt => /predU1P[->|ay]. + by rewrite ltxx/= mulr0. +rewrite (@le_trans _ _ ((k * r%:num + sup_phi) * safe_dist))//. + rewrite ler_wpM2l//. + by rewrite addr_ge0 ?mulr_ge0 ?(ltW k0)// sup_phi_ge0. + by rewrite ay//= lerBlDl. +rewrite -ler_pdivlMl//; last first. + by rewrite ltr_pwDl ?mulr_gt0// sup_phi_ge0. +by rewrite 2!ge_min mulrC lexx/= orbT. +Qed. + +Fail Check picard_to_cont : {fun [set: V] >-> [set: V]}. + +HB.instance Definition _ := @isFun.Build _ _ _ _ picard set_fun_picard. + +Check picard : {fun img_cball >-> img_cball}. +(* still, we can't state that it is a contraction for typing reasons *) + +Fail Lemma tmp : is_contraction (picard : {fun [set: _] >-> [set: _]}). +About is_contraction. + +End picard. + +(* (* see measurable_fun_tnthP *) *) +(* Lemma rV_measurable_fun {d} {T : measurableType d} {R : realType} *) +(* (D : set T) n (f : T -> 'rV[R]_n) : *) +(* measurable_fun D f <-> forall i, measurable_fun D (fun t => f t ord0 i). *) +(* Proof. *) +(* split => [mf i mD /= Y mY|mf mD /= Y mY]. *) +(* admit. *) +(* admit. *) +(* Admitted. *) + +(* Definition proj (T : Type) n (A : set (n.-tuple T)) (i : 'I_n) : set T := *) +(* [set t | exists x, A x /\ t = tnth x i]. *) + +(* Lemma vnormr_measurable {R : realType} n (D : set 'rV[R]_n) : *) +(* measurable_fun D (@Num.norm R 'rV[R]_n). *) +(* Proof. *) +(* move=> mD /= Y mY. *) +(* rewrite /normr/=. *) +(* Admitted. *) + +(* Lemma vintegrable_norm {d} {T : measurableType d} {R : realType} *) +(* (mu : {measure set T -> \bar R}) (D : set T) n (f : T -> 'rV[R]_n) : *) +(* (forall i, mu.-integrable D (EFin \o (fun t => f t ord0 i))) -> *) +(* mu.-integrable D (EFin \o (Num.norm \o f)). *) +(* Proof. *) +(* move=> intf. *) +(* apply/integrableP; split. *) +(* apply/measurable_EFinP. *) +(* apply/measurableT_comp. *) +(* exact: vnormr_measurable. *) +(* apply/rV_measurable_fun => i. *) +(* have /integrableP[+ _]/= := intf i. *) +(* by move/measurable_EFinP. *) +(* rewrite (@le_lt_trans _ _ *) +(* (\big[maxe/-oo]_(i < n) \int[mu]_(x in D) `|f x ord0 i|%:E )%E)//. *) +(* rewrite /=. *) +(* under eq_integral do rewrite normr_id. *) +(* rewrite [in leLHS]/Num.norm/=. *) +(* under eq_integral do rewrite mx_normrE. *) +(* admit. *) +(* apply: bigmax_lt => //= i _. *) +(* have /integrableP[_]/= := intf i. *) +(* exact. *) + +Section is_contraction_picard. +Local Notation mu := lebesgue_measure. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n. +Variables (phi : R -> U -> U) (a b : R). +Hypothesis ab : a < b. +Variable k : R. +Hypothesis k0 : 0 < k. +Variables (u0 : U) (r : {posnum R}). +Let B := closed_ball u0 r%:num. +Hypothesis lip2 : {in `[a, b]%R, forall x, k.-lipschitz_B (phi x)}. +Hypothesis cont1 : {in B, forall y, {within `[a, b], continuous phi ^~ y}}. + +Variable rho : {posnum R}. (* rho < 1 *) +Hypothesis rho1 : (rho%:num < 1). + +Import ContSeg_quot. + +Local Notation safe_dist := (safe_dist phi a b k u0 r rho). + +Notation C := (quot_contSeg a (a + safe_dist) U). +Notation img_cball := (@img_cball _ n phi a b k u0 r rho). + +Check @cst (subspace `[a, a + safe_dist]) U u0 + : {fun `[a, a + safe_dist] >-> [set: U]}. + +Check @cst (subspace `[a, a + safe_dist]) U u0 + : continuousType (subspace `[a, a + safe_dist]) U. + +Local Notation picard := (@picard R n phi a b k u0 r k0 lip2 cont1 rho). + +Lemma is_contraction_picard : is_contraction picard. +Proof. +rewrite /is_contraction /contraction. +rewrite /picard /picard_fun /picard_fun_subdef. +exists (NngNum (ge0 rho)); split => //=. +move=> /= [/= x y] [Vrx Vry]. +rewrite /picard/=. +rewrite !piE/=. +rewrite infty_norm_pi/=. +rewrite /infty_norm0/=. +apply: ge_sup => //=. + set u := _ \o _; exists (u a) => /=; exists a => //. + by rewrite in_itv/= lexx leDl_safe_dist. +move=> _ /= [t tNdd <-]. +have tb : t <= b. + move: tNdd. + rewrite in_itv/= => /andP[Ndt]. + move=> /le_trans; apply. + by rewrite -lerBrDl; exact: safe_dist_itv. +rewrite /picard_fun/=; case: pselect => //= Hg; case: pselect => [Hg2|//]. +rewrite /picard_fun_subdef/=. +rewrite !fctE. +rewrite (addrC u0). +rewrite addrKA. +rewrite [in leLHS]/Num.norm/= mx_normrE. +apply: bigmax_le => //= -[i j] _. +rewrite {i}(ord1 i)/=. +rewrite mxE rowRintegralE mxE rowRintegralE. +have integrable1 : mu.-integrable `[a, t] (EFin \o (fun x0 => phi x0 (x x0) ord0 j)). + apply: integrable_comp => //=. + by rewrite gt_eqF. + apply: subset_trans Hg; apply: image_subset. + apply/subset_itvl; rewrite bnd_simp. + by move: tNdd; rewrite !in_itv/= => /andP[]. +have integrable2 : mu.-integrable `[a, t] (EFin \o (fun x0 => phi x0 (y x0) ord0 j)). + apply: integrable_comp => //=. + by rewrite gt_eqF. + move=> _ [x0 h] <-. + apply: Hg2 => /=. + exists x0 => //. + apply/subset_itvl/h; rewrite bnd_simp. + by move: tNdd; rewrite !in_itv/= => /andP[]. +rewrite -RintegralB//=. +rewrite (le_trans (le_normr_Rintegral _ _))//=. + under [x in integrable _ _ x]eq_fun do rewrite EFinB. + by rewrite integrableB. +have integrable3 : mu.-integrable `[a, t] (fun x0 => `|x x0 - y x0|%:E). + rewrite /=. + apply : vintegrable_norm. + exact: measurable_itv. + move => i. + under [x in integrable _ _ x]eq_fun do rewrite !mxE EFinB. + rewrite integrableB//=. + apply continuous_compact_integrable => //=. + exact: segment_compact. + apply within_continuous_coord. + apply/continuous_subspaceW/cts_fun. + apply: subset_itvl; rewrite bnd_simp. + by move: tNdd; rewrite in_itv /= => /andP[]. + apply continuous_compact_integrable => //=. + exact: segment_compact. + apply within_continuous_coord. + apply/continuous_subspaceW/cts_fun. + apply: subset_itvl; rewrite bnd_simp. + by move: tNdd; rewrite in_itv /= => /andP[]. +rewrite (@le_trans _ _ (k * \int[mu]_(t0 in `[a, t]) `| x t0 - y t0|))//. + rewrite (@le_trans _ _ (\int[mu]_(t0 in `[a, t]) (k * `|x t0 - y t0|)))//. + apply: le_Rintegral => //=. + apply integrable_norm => //=. + under [x in integrable _ _ x]eq_fun do rewrite EFinB. + rewrite integrableB //=. + under [x in integrable _ _ x]eq_fun do rewrite EFinM. + rewrite integrableMr//=. + exact: bounded_cst. + move=> x0 x0at. + have : x0 \in `[a, b]%R by apply /subset_itvl/x0at. + move/lip2. + rewrite /dominated_by/= => /(_ (x x0, y x0)) /=. + have Bxy : B (x x0) /\ B (y x0). + split. + apply: Vrx => /=. + exists x0 => //. + apply/subset_itvl/x0at. + by move: tNdd; rewrite in_itv/= => /andP[Ndt]. + apply: Vry => /=. + exists x0 => //. + apply/subset_itvl/x0at. + by move: tNdd; rewrite in_itv/= => /andP[Ndt]. + move=> /(_ Bxy); apply: le_trans. + rewrite [in leRHS]/Num.norm/= mx_normrE. + apply: le_trans; last first. + by apply: le_bigmax => /=; exact: (ord0, j). + by rewrite /= !mxE. + by rewrite RintegralZl. +rewrite (@le_trans _ _ (k * \int[mu]_(t0 in `[a, t]) `|x - y| ))//. + rewrite ler_pM2l//. + apply: le_Rintegral => //=. + apply measurable_bounded_integrable => //=. + rewrite lebesgue_measure_itv //=. + case: ifPn => //=. + by rewrite -EFinD ltry. + exact: bounded_cst. + move=> x0 x0at. + have x0ad : x0 \in `[a, a + safe_dist]%R. + apply: subset_itvl x0at; rewrite bnd_simp. + by move: tNdd; rewrite in_itv/= => /andP[]. + have -> : x x0 - y x0 = (x - y : C) x0. + apply (@eqmod_on_itv _ _ _ _ (repr x - repr y)) => //. + by rewrite Quotient.pi_add Quotient.pi_opp !reprK. + by rewrite infty_norm0_ge// leDl_safe_dist. +rewrite (@le_trans _ _ (k * `|x - y| * (t - a)))//. + rewrite -mulrA ler_wpM2l//; first exact: ltW. + rewrite Rintegral_cst// ler_pM//. + move: tNdd; rewrite in_itv/= => /andP[+ _]. + rewrite le_eqVlt => /predU1P[->|]. + by rewrite set_itv1 lebesgue_measure_set1 subrr lexx. + by rewrite /= (lebesgue_measure_itv `[a,t]%R) /= lte_fin => ->. +rewrite [leLHS]mulrAC ler_wpM2r//. +move: tNdd; rewrite in_itv/= => /andP[Ndt]. +rewrite -lerBlDl. +rewrite /safe_dist !le_min => /andP[_ /andP[_]]. +by rewrite ler_pdivlMr// mulrC. +Qed. + +End is_contraction_picard. + +Definition row_vector {R : realType} (n : nat) := 'rV[R]_n. + +HB.instance Definition _ {R : realType} (n : nat) := Complete.on (@row_vector R n). +HB.instance Definition _ {R : realType} (n : nat) := NormedModule.on (@row_vector R n). +(*HB.instance Definition _ {R : realType} (n : nat) := CompleteNormedModule.on (@row_vector R n).*) + +Section is_sol. +Context {R : realType} {n : nat}. +Notation U := 'rV[R]_n. +Variable phi : R -> U -> U. + +Definition sol_is_deriv_cbnd (a : R) (b : itv_bound R) (f : R -> U) := + {in Interval (BLeft a) b, forall t, derivable f t 1 /\ f^`() t = phi t (f t)}. + +Definition sol_is_deriv_co a b := sol_is_deriv_cbnd a (BLeft b). + +Definition sol_is_deriv_cy a := sol_is_deriv_cbnd a +oo%O. + +Lemma sol_is_deriv_cy_co a b : sol_is_deriv_cy a `<=` + sol_is_deriv_cbnd a (BLeft b). +Proof. +move=> f H t tab. +apply H. +exact: subset_itvl tab. +Qed. + +Definition sol_is_deriv_obnd (a : R) (b : itv_bound R) (f : R -> U) := + {in Interval (BRight a) b, + forall t, derivable f t 1 /\ f^`() t = phi t (f t)}. + +Definition sol_is_deriv_oo a b := sol_is_deriv_obnd a (BLeft b). + +(*NB: b = (BLeft r) is open, + b = (BRight r) is closed, + b = +oo%R is +oo *) +Definition is_sol_obnd (u0 : U) (a : R) (b : itv_bound R) (f : R -> U) := + [/\ f a = u0, + sol_is_deriv_obnd a b f & + {within (closure [set` Interval (BRight a) b]), continuous f}]. + +Definition is_sol_oo u0 a b := is_sol_obnd u0 a (BLeft b). + +End is_sol. + +Section is_integral_sol. +Local Notation mu := lebesgue_measure. +Context {R : realType} {n : nat}. +Notation U := 'rV[R]_n. +Variables (phi : R -> U -> U) (u0 : U) (a b : R) (sol : R -> U). + +Definition is_integral_sol := sol a = u0 /\ + forall t, t \in `[a, b]%R -> sol t = sol a + (\vint[mu]_(s in `[a, t]) phi s (sol s))%R. + +End is_integral_sol. + +Section integral_ode. +Local Notation mu := lebesgue_measure. +Context {R : realType} {n : nat}. +Notation U := 'rV[R]_n. +Variables (phi : R -> U -> U) (u0 : U) (a b : R) (sol : R -> U) (k : R) (r : {posnum R}). +Hypothesis k0 : k != 0. +Hypothesis ab : a < b. + +Let B := closed_ball u0 r%:num. +Hypothesis lip2 : {in `[a, b]%R, forall x : R, k.-lipschitz_B (phi x)}. +Hypothesis cont1 : {in B, forall y, {within `[a, b], continuous phi ^~ y}}. +Hypothesis cont_sol : {within `[a, b], continuous sol}. +Hypothesis sol_bound : sol @` `[a, b] `<=` closed_ball u0 r%:num. + +Lemma picard_iterator_within_continuous i : + {within `[a, b], continuous (fun x => phi x (sol x) ord0 i)}. +Proof. +move: i. +apply/within_continuous_coord. +exact: (@within_continuous_lipschitz _ _ _ a b u0 r _ _ _ k0). +Qed. + +Lemma picard_iterator_continuous i t : t \in `]a, b[%R -> + {for t, continuous (fun x => phi x (sol x) ord0 i)}. +Proof. +move/within_continuous_continuous; apply => //. +exact: picard_iterator_within_continuous. +Qed. + +Lemma picard_iterator_integrable i : mu.-integrable `[a, b] + (EFin \o (fun x : R => phi x (sol x) ord0 i)). +Proof. +apply: continuous_compact_integrable; first exact: segment_compact. +exact: picard_iterator_within_continuous. +Qed. + +Lemma integral_sol_iff_sol : + is_integral_sol phi u0 a b sol <-> is_sol_oo phi u0 a b sol. +Proof. +split. +- move => [hinit h]. + split => //; last first. + apply: continuous_subspaceW cont_sol. + exact: itv_closure (* TODO: why not equality? *). + move=> t tab. + move: (tab); rewrite in_itv /= => /andP[ta tb]. + have -> : sol^`() t = (fun x => sol a + \vint[mu]_(s in `[a, x]) phi s (sol s))^`() t. + apply/eq_on_itv_deriv/tab => x xt01; apply h. + rewrite inE/= in xt01. + rewrite inE/=. + exact: subset_itv_oo_cc. + suff hi : forall i, derivable (fun x => sol x ord0 i) t 1 /\ + (fun x : R => (sol a + \vint[mu]_(s in `[a, x]) phi s (sol s))%E)^`() t ord0 i = + phi t (sol t) ord0 i. + split. + apply /derivable_mxP. + rewrite /derivable_mx => i j. + have [? _] := hi j. + by rewrite ord1. + apply/rowP => j. + by have [_ ?] := hi j. + move => j. + have [H1 H2] := @continuous_FTC1_closed _ (fun x => phi x (sol x) ord0 j) + a t b tb (picard_iterator_integrable j) ta (picard_iterator_continuous tab). + have Hderivable : derivable (fun x : R => \vint[mu]_(x0 in `[a, x]) phi x0 (sol x0)) t 1. + apply/(@derivable_mxP R R) => i0 i; rewrite (ord1 i0){i0}/=. + have [?] := @continuous_FTC1_closed _ (fun x => phi x (sol x) ord0 i) + a t b tb (picard_iterator_integrable i) ta (picard_iterator_continuous tab). + rewrite /rowRintegral. + rewrite [X in derivable X t 1](_ : _ = + (fun x => \int[mu]_(y in `[a, x]) phi y (sol y) ord0 i))//. + by apply/funext => x; rewrite mxE. + rewrite derive1E deriveD /=; last 2 first. + exact: derivable_cst. + exact: Hderivable. + split. + apply: (near_eq_derivable + (f := (fun x => (sol a + \vint[mu]_(s in `[a, x]) phi s (sol s)) ord0 j))) => //=. + near=> t'. + rewrite (h t')//= in_itv/=. + apply/andP; split. + - by apply: ltW; near: t'; exact: lt_nbhsr. + - by apply: ltW; near: t'; exact: lt_nbhsl. + have -> : (fun x => (sol a + \vint[mu]_(s in `[a, x]) phi s (sol s))%E ord0 j) = + cst (sol a ord0 j) + + (fun x => (\vint[mu]_(s in `[a, x]) (phi s (sol s))) ord0 j). + by apply funext => x; rewrite mxE. + apply: derivableD. + exact: derivable_cst. + by move/derivable_mxP : Hderivable; exact. + rewrite -!derive1E derive1_cst add0r -H2 !derive1E derive_mx//= mxE/=. + congr ('D_1 _ t). + by apply/funext => t'; rewrite mxE. +move => [hinit h]; split => // t tab. +have /= := tab; rewrite in_itv/= => /andP[ta tb]. +apply/rowP => i. +rewrite mxE rowRintegralE. +move: ta; rewrite le_eqVlt => /predU1P[<-|ta]. + by rewrite set_itv1 Rintegral_set1 addr0. +rewrite /Rintegral. +have cont_soli : {within `[a, b], continuous (fun x => sol x ord0 i)}. + by move: i; exact/within_continuous_coord. +rewrite (@continuous_FTC2 _ (fun x => phi x (sol x) ord0 i) (fun x => sol x ord0 i) _ _ ta). +- by rewrite -EFinB subrKC. +- apply: continuous_subspaceW; last exact: picard_iterator_within_continuous. + exact: subset_itvl. +- split. + + move=> t' tx'. + by have /h[/derivable_mxP] : t' \in `]a, b[%R by exact/subset_itvl/tx'. + + by move /(continuous_within_itvP _ ab) : cont_soli => [_ + _]. + + have cont_phii' : {within `[a, t], continuous fun x0 : R => sol x0 ord0 i}. + apply: continuous_subspaceW; last exact: cont_soli. + exact: subset_itvl. + by move/(continuous_within_itvP _ ta) : cont_phii' => [_ _ +]. +- move=> x xt. + have /h[? +] : x \in `]a, b[%R by exact/subset_itvl/xt. + by rewrite !derive1E derive_mx//= => <-; rewrite mxE. +Unshelve. all: by end_near. Qed. + +End integral_ode. + +Section picard. +Local Notation mu := lebesgue_measure. +Context {R : realType} {n : nat}. +Notation U := (@row_vector R n). +Variables (phi : R -> U -> U) (a b : R) (k : R) (u0 : U) (r : {posnum R}). +Hypothesis ab : a < b. +Hypothesis k0 : 0 < k. +Let k0' : k != 0. Proof. by rewrite gt_eqF. Qed. +Let B := closed_ball u0 r%:num. +Hypothesis lip2 : {in `[a, b]%R, forall x : R, k.-lipschitz_B (phi x)}. +Hypothesis cont1 : {in B, forall y, {within `[a, b], continuous phi ^~ y}}. +Variable rho : {posnum R}. +Hypothesis rho1 : rho%:num < 1. + +Import ContSeg_quot. + +Check U : completeType. +Check U : completePseudoMetricType R. +Check U : normedModType R. +Check U : completeNormedModType R. + +Local Notation safe_dist := (@safe_dist R n phi a b k u0 r rho). +Local Notation V := (@quot_contSeg R a (a + safe_dist) U). + +Check V : completeNormedModType _. + +Local Notation img_cball := (@img_cball R n phi a b k u0 r rho). +Local Notation img_cball_nonempty := (img_cball_nonempty phi a b k u0 r rho). +Local Notation closed_img_cball := (@closed_img_cball R n phi a b k u0 r k0 rho ab). + +Local Notation picard := (@picard _ n phi a b k u0 r k0 lip2 cont1 rho). + +Definition picard_fix : V := + sval (cid2 (@banach_fixed_point R V img_cball + picard + (@is_contraction_picard _ n phi a b ab k k0 u0 r lip2 cont1 rho rho1) + closed_img_cball + img_cball_nonempty)). + +Let picard_fixE : picard_fix = picard picard_fix. +Proof. by rewrite {}/picard_fix; case: cid2. Qed. + +Lemma img_cball_picard_fix : img_cball picard_fix. +Proof. +by apply (svalP (cid2 (@banach_fixed_point R V img_cball _ + (@is_contraction_picard R n phi _ _ ab k k0 u0 r lip2 cont1 _ rho1) + closed_img_cball img_cball_nonempty))). +Qed. + +Lemma picard_fix_init : picard_fix a = u0. +Proof. +rewrite picard_fixE eval_mod_on_itv. + by rewrite /picard_fun /= picard_fun_init//; exact: img_cball_picard_fix. +by rewrite in_itv/= lexx leDl_safe_dist. +Qed. + +Lemma picardE g t : img_cball g -> t \in `[a, a + safe_dist]%R -> + picard g t = u0 + \vint[mu]_(x in `[a, t]) phi x (g x). +Proof. +by move=> Hg taad; rewrite eval_mod_on_itv//; exact: picard_funE. +Qed. + +Lemma cauchy_lipschitz_integral_version : + is_integral_sol phi u0 a (a + safe_dist) picard_fix. +Proof. +split; first exact: picard_fix_init. +move=> t tad. +rewrite {1}picard_fixE// eval_mod_on_itv//. +rewrite picard_fix_init. +exact: picard_funE img_cball_picard_fix. +Qed. + +Theorem picard_fix_unique (picard_fix' : V) : img_cball picard_fix' -> + (forall t, t \in `[a, a + safe_dist]%R -> + picard_fix' t = u0 + \vint[mu]_(x in `[a, t]) phi x (picard_fix' x)) -> + picard_fix = picard_fix'. +Proof. +move=> imgpicard_fix'_cball h. +apply: (contraction_fixpoint_unique + (@is_contraction_picard R n phi a b ab k k0 u0 r lip2 cont1 rho rho1) + img_cball_picard_fix imgpicard_fix'_cball) => //=. +rewrite -(reprK picard_fix'). +apply/eqquotP. +rewrite /Quotient.equiv/=. +rewrite inE. +apply/funext => x. +rewrite /patch mem_setE; case: ifPn => [xK|xKnot]; last by []. +rewrite /fun_of_quot_contSeg/=. +rewrite !fctE. +rewrite !reprK. +rewrite picard_funE//=. +rewrite (_ : repr picard_fix' x = picard_fix' x)//. +by rewrite h// subrr. +Qed. + +Lemma cauchy_lipschitz_quot_ex : picard_fix a = u0 /\ + {in `]a, a + safe_dist[%R, forall x, picard_fix^`() x = phi x (picard_fix x)}. +Proof. +split; first exact: picard_fix_init. +move => t tad. +rewrite {1}picard_fixE. +apply/rowP => j. +suff -> : (picard picard_fix)^`() t = + (fun t => u0 + \vint[mu]_(x in `[a, t]) phi x (picard_fix x))^`() t. + move: (tad); rewrite in_itv /= => /andP[ta tadelta]. + have Fint i : mu.-integrable `[a, a + safe_dist] + (EFin \o (fun x => phi x (picard_fix x) ord0 i)). + apply: integrable_comp => //. + by rewrite in_itv /= lexx andbT leDl_safe_dist. + exact: img_cball_picard_fix. + have Fcont i : {for t, continuous (fun x => phi x (picard_fix x) ord0 i)}. + move: tad; rewrite inE. + apply/within_continuous_continuous => //=. + exact: ltDl_safe_dist. + clear Fint. + move: i; apply/within_continuous_coord. + apply: (@within_continuous_lipschitz _ _ _ a _ u0 r _ _ _ k0'). + + exact: cts_fun. + + exact: lip2_safe_dist. + + exact: cont1_safe_dist. + + exact: img_cball_picard_fix. + have [H1 H2] := @continuous_FTC1_closed _ (fun x => phi x (picard_fix x) ord0 j) + a t _ tadelta (Fint j) ta (Fcont j). + have Hderivable : derivable (fun x => \vint[mu]_(y in `[a, x]) phi y (picard_fix y)) t 1. + apply/derivable_mxP => i0 i; rewrite (ord1 i0){i0}/=. + have [?] := @continuous_FTC1_closed _ (fun x => phi x (picard_fix x) ord0 i) + a t _ tadelta (Fint i) ta (Fcont i). + rewrite /rowRintegral. + rewrite [X in derivable X t 1](_ : _ = + (fun x => \int[mu]_(y in `[a, x]) phi y (picard_fix y) ord0 i))//. + by apply/funext => x; rewrite mxE. + rewrite derive1E deriveD /=; last 2 first. + exact: derivable_cst. + exact: Hderivable. + rewrite -!derive1E derive1_cst add0r -H2 !derive1E derive_mx// mxE/=. + congr ('D_1 _ t). + by apply/funext => t0; rewrite mxE. +rewrite /picard /picard_fun. +move: t tad. +apply: eq_on_itv_deriv => t tad /=. +rewrite -(@picard_funE _ _ _ a b k _ r k0' lip2 cont1 rho)//=. + rewrite eval_mod_on_itv// inE; apply: subset_itv_oo_cc. + by rewrite inE in tad. +exact: img_cball_picard_fix. +Qed. + +Lemma cauchy_lipschitz_in_cball (t : R) : `[a, a + safe_dist] t -> + closed_ball u0 r%:num (picard_fix t). +Proof. by move=> taad; apply: img_cball_picard_fix => /=; exists t. Qed. + +End picard. + +Section picard_extension. +Context {R : realType} {n : nat}. +Notation U := 'rV[R]_n. +Variables (phi : R -> U -> U) (a b c : R) (u0 : U) (sol1 : R -> U) (sol2 : R -> U). +Hypothesis ab : a < b. +Hypothesis bc : b < c. +Hypothesis cont1 : {within `[a, b], continuous (fun x => phi x (sol1 x))}. +Hypothesis cont2 : {within `[b, c], continuous (fun x => phi x (sol2 x))}. +Hypothesis matchb : sol1 b = sol2 b. + +Lemma is_integral_sol_patch : + is_integral_sol phi u0 a b sol1 -> + is_integral_sol phi (sol1 b) b c sol2 -> + is_integral_sol phi u0 a c (patch sol2 `[a, b] sol1). +Proof. +move => [p0a p0s ] [p1a p1s]. +have h0 : patch sol2 `[a, b] sol1 a = u0. + rewrite /patch. + case: ifPn => [xK | xKnot] => //. + move /negP : xKnot. + by rewrite inE/=in_itv/=lexx ltW. +split=> //. +move=> t tac. +rewrite /patch mem_setE bound_itvE (ltW ab). +case: ifPn => [xK | xKnot] => /=. + rewrite p0s // p0a. + apply/rowP => i. + rewrite !mxE. + congr (_ + _)%E. + apply eq_Rintegral => /= x xat. + suff -> : x \in `[a, b]%R by []. + move : xat xK. + rewrite mem_setE /= !in_itv /= => /andP [xat1 xat2] /andP [tab1 tab2]. + apply/andP; split => //. + exact/le_trans/tab2. +have tbc : t \in `[b, c]%R. + move : tac. + move/negP : xKnot. + rewrite !in_itv /=. + have /orP := le_total b t. + case => // -> h1 /andP [h2 ->] //. + by move: h1; rewrite h2. +transitivity (sol1 a + \vint[lebesgue_measure]_(s in `[a, t]) + phi s (if (s \in `[a, b])%classic then sol1 s else sol2 s))%E; last first. + by under eq_rowRintegral do rewrite mem_setE. +rewrite (rowRintegral_itv_split (c := b) (F := (fun x => phi x (patch sol2 `[a, b] sol1 x)))). +- rewrite p1s//. + suff : sol2 b = u0 + \vint[lebesgue_measure]_(s in `[a, b]) phi s (patch sol2 `[a, b] sol1 s). + move=> ->. + rewrite -p0a. + rewrite [in RHS]addrA. + congr +%R. + apply eq_rowRintegral => /= x xbt. + rewrite /patch; case: ifPn => [ | ] => //. + rewrite inE/=in_itv/= => /andP [_ xleb]. + move : xbt. + rewrite !inE/=!in_itv/= => /andP [h _]. + suff -> : x = b by rewrite p1a. + apply le_anti. + by rewrite xleb. + rewrite p1a p0s;last by rewrite in_itv/= ltW/=. + rewrite p0a. + congr (u0 + _)%E. + rewrite /patch. + by apply eq_rowRintegral => /= x ->. +- by rewrite ltW //=; move : tbc; rewrite in_itv/= => /andP [-> _]. +- move=> i. + have cont' : {within `[a, t], continuous (fun x => phi x (patch sol2 `[a, b] sol1 x) ord0 i)}. + have -> : `[a, t] = `[a, b] `|` `[b, t]. + rewrite (@itv_bndbnd_setU _ _ _ (BRight b))// ?bnd_simp//=; last 2 first. + exact: ltW. + by move: tbc; rewrite in_itv/= => /andP[]. + apply/seteqP; split => x. + move=> []; [by left|right]. + exact: subset_itv_oc_cc b0. + move=> []; [by left|]. + rewrite -setU1itv ?bnd_simp//; last first. + by move: tbc; rewrite in_itv/= => /andP[]. + case; [|by right]. + move=> ->; left => /=. + by rewrite in_itv/= (ltW ab) lexx. + apply: (withinU_continuous (@itv_closed _ _ a b) (@itv_closed _ _ b t)). + move : i. + apply /within_continuous_coord. + have eq1 : {in `[a, b], (fun x0 => phi x0 (sol1 x0)) =1 + (fun x0 => phi x0 (patch sol2 `[a, b] sol1 x0))}. + move => x0 x0ab. + by rewrite /patch x0ab. + apply: (subspace_eq_continuous eq1). + exact: cont1. + move : i. + apply /within_continuous_coord. + have eq2 : {in `[b, c], (fun x0 => phi x0 (sol2 x0)) =1 + (fun x0 => phi x0 (patch sol2 `[a,b] sol1 x0))}. + move => x0 x0ab. + rewrite /patch mem_setE;case: ifPn => [xab | xabnot] => //. + suff -> : x0 = b by rewrite matchb. + apply: le_anti. + move: x0ab xab. + by rewrite inE/= !in_itv/= => /andP [-> _] /andP [_ ->]. + apply: (@continuous_subspaceW _ _ _ `[b, c]). + by apply: subset_itvl; rewrite bnd_simp (itvP tbc). + exact: (subspace_eq_continuous eq2). + apply: continuous_compact_integrable => //. + exact: segment_compact. +Qed. + +End picard_extension. + +Section cauchy_lipschitz_local. +Context {R : realType} {n : nat}. +Notation U := 'rV[R]_n. +Variables (phi : R -> U -> U) (a b : R) (k : R) (u0 : U) (r : {posnum R}). +Hypothesis ab : a < b. +Hypothesis k0 : 0 < k. +Let k0' : k != 0. Proof. by rewrite gt_eqF. Qed. +Let B := closed_ball u0 r%:num. +Hypothesis lip2 : {in `[a, b]%R, forall x : R, k.-lipschitz_B (phi x)}. +Hypothesis cont1 : {in B, forall y, {within `[a, b], continuous phi ^~ y}}. + +Variable rho : {posnum R}. +Hypothesis rho1 : rho%:num < 1. + +Let r2 := (r%:num/2)%:pos. +Let B2 := closed_ball u0 r2%:num. + +Let ler2 : r2%:num <= r%:num. +Proof. by rewrite /r2/= ler_pdivrMr // ler_pMr // lerDl. Qed. + +Let lip2' : {in `[a, b]%R, forall x, k.-lipschitz_B2 (phi x)}. +Proof. +move => x abx /= y By. +apply: lip2. +by move : abx; rewrite !inE/=; apply subset_itvr. +split. +by apply /le_closed_ball/By.1. +by apply /le_closed_ball/By.2. +Qed. + +Let cont1': {in B2, forall y, {within `[a, b], continuous phi ^~ y}}. +Proof. +move => /= x Bx. +apply /continuous_subspaceW/cont1. +by []. +apply mem_set. +apply set_mem in Bx. +by apply /le_closed_ball/Bx. +Qed. + +(* Let rho : {posnum R} := (2^-1)%:pos. *) + +(* Let rho1 : rho%:num < 1. *) +(* Proof. by rewrite /rho/= invf_lt1// ltr1n. Qed. *) + +Local Notation safe_dist := (safe_dist phi a b k u0 r2 rho). + +Definition cauchy_lipschitz_f : + continuousFunType `[a, a + safe_dist] [set: 'rV[R]_n] := + repr (picard_fix ab k0 lip2' cont1' rho1). + +Lemma is_sol_cauchy_lipschitz_f : + is_sol_oo phi u0 a (a + safe_dist) cauchy_lipschitz_f. +Proof. +apply/(integral_sol_iff_sol (k:=k) (r:=r)) => //. +- by rewrite ltDl_safe_dist. +- move=> t td. + apply: lip2. + move: td; rewrite /=!in_itv/= => /andP [-> h] /=. + by rewrite (le_trans h)// -lerBrDl; exact: safe_dist_itv. +- move=> /= x xB . + apply/continuous_subspaceW/cont1 => //. + apply: subset_itvl => //=. + by rewrite bnd_simp -lerBrDl safe_dist_itv. +- exact: cts_fun. +- apply (subset_trans (B:=B2)). + by move => _ [t tad] <-;apply: cauchy_lipschitz_in_cball. + by apply le_closed_ball. +- exact: cauchy_lipschitz_integral_version. +Qed. + +Lemma solution_stays_in_ball2 : + {in `[a, a + safe_dist]%R, + forall t, closed_ball u0 r2%:num (cauchy_lipschitz_f t)}. +Proof. by move=> t; move => /cauchy_lipschitz_in_cball; exact. Qed. + +Lemma solution_stays_in_ball : + {in `[a, a + safe_dist]%R, + forall t, closed_ball u0 r%:num (cauchy_lipschitz_f t)}. +Proof. + move => t ta. + apply /le_closed_ball/solution_stays_in_ball2=>//. +Qed. +Lemma solution_continuous : + {within `[a, a + safe_dist], continuous cauchy_lipschitz_f}. +Proof. exact: cts_fun. Qed. + +Let f := cauchy_lipschitz_f. + +Theorem cauchy_lipschitz_ex : is_sol_oo phi u0 a (a + safe_dist) f. +Proof. +apply/(integral_sol_iff_sol (k:=k) (r:=r)) => //. +- by rewrite ltDl_safe_dist. +- move=> t td. + apply: lip2. + move: td; rewrite /=!in_itv/= => /andP [-> h] /=. + by rewrite (le_trans h)// -lerBrDl; exact: safe_dist_itv. +- move=> /= x xB . + apply/continuous_subspaceW/cont1 => //. + apply: subset_itvl => //=. + by rewrite bnd_simp -lerBrDl safe_dist_itv. +- exact: cts_fun. +- apply (subset_trans (B:=B2)). + by move => _ [t tad] <-;apply: cauchy_lipschitz_in_cball. + by apply le_closed_ball. +- exact: cauchy_lipschitz_integral_version. +Qed. + + +Local Notation V := (@ContSeg_quot.quot_contSeg R a (a + safe_dist) U). + +Lemma cauchy_lipschitz_unique_restr f' : + {within `[a, a + safe_dist], continuous f'} -> + {in `[a, a + safe_dist]%R, forall t, closed_ball u0 r2%:num (f' t)} -> + is_sol_oo phi u0 a (a + safe_dist) f' -> + {in `[a, a + safe_dist]%R, f =1 f'}. +Proof. +move => cont bnd. +move/(@integral_sol_iff_sol _ _ _ _ _ _ _ _ r k0') => []//. +- exact: ltDl_safe_dist. +- move=> t td. + apply: lip2. + by apply: subset_itvl td; rewrite bnd_simp -lerBrDl safe_dist_itv. +- move=> /= x xB. + apply/continuous_subspaceW/cont1 => //. + by apply: subset_itvl => //=; rewrite bnd_simp -lerBrDl safe_dist_itv. + apply (subset_trans (B:=B2)). + by move => _ [t tad] <-;apply: bnd. + by apply le_closed_ball. +move=> f'au0 h1 t tab. +have fc : contseg a (a + safe_dist) f' by exact: mem_set. +have pieq : \pi_V%qT f = \pi_V%qT (contseg_Sub fc). + rewrite reprK. + apply: picard_fix_unique. + move => /= _ [t' tad' ] <- /=. + rewrite /ContSeg_quot.fun_of_quot_contSeg. + suff -> : (repr (\pi_V%qT (contseg_Sub fc))) t' = f' t'. + by apply: bnd; rewrite inE. + by apply: ContSeg_quot.eval_mod_on_itv; rewrite inE. + move=> t0 t0ad. + rewrite ContSeg_quot.eval_mod_on_itv //=. + rewrite h1//. + rewrite f'au0; congr (u0 + _). + apply: eq_rowRintegral => t' tad'. + rewrite ContSeg_quot.eval_mod_on_itv //=. + move: tad'; rewrite !inE/=; apply: subset_itvl; rewrite bnd_simp. + rewrite inE/= in t0ad. + by move/itvP : t0ad => ->. +suff -> : f t = (ContSeg_quot.fun_of_quot_contSeg (\pi_V%qT (contseg_Sub fc))) t. + rewrite /ContSeg_quot.fun_of_quot_contSeg/=. + exact: ContSeg_quot.eval_mod_on_itv. +rewrite -pieq. +by rewrite ContSeg_quot.eval_mod_on_itv. +Qed. + +End cauchy_lipschitz_local. + +(* TODO: move *) +Section continuous_confined. +Context {R : realType} {n : nat}. +Notation U := 'rV[R]_n. +Variables (a b : R) (u0 : U) (r : {posnum R}). +Hypothesis ab : a < b. +Let B := closed_ball u0 r%:num. + +Local Lemma continuous_confined (g : R -> U) : {within `[a, b], continuous g} -> + g a = u0 -> + exists Delta : {posnum R}, {in `[a, a + Delta%:num], forall t, g t \in B}. +Proof. +move /(continuous_within_itvP _ ab) => [cc cl cr] g0. +have : {within `[a,b], continuous (fun t => `| u0 - g t |) }. + apply: within_continuous_comp_norm. + by rewrite ltW. + apply/continuous_within_itvP => //=. + split. + - move => t tab. + exact: (cvgB (cvg_cst _) (cc _ tab)). + - exact: (cvgB (cvg_cst _) cl). + - exact: (cvgB (cvg_cst _) cr). +move/(continuous_within_itvP _ ab) => [_ /cvgrPdist_le + _]. +move=> /(_ r%:num). +case=> // Delta /= Delta0. +rewrite /ball_/= g0 subrr normr0/= => H. +have D20 : (0 < Delta / 2) by rewrite divr_gt0. +exists (PosNum D20) => t. +rewrite inE/= in_itv/= => /andP[]. +rewrite le_eqVlt => /predU1P[<-|ta td]. + by rewrite g0 /B inE => _; exact: closed_ballxx. +have /= := H t. +rewrite add0r normrN normr_id. +rewrite inE /B closed_ballE /closed_ball_//=; apply => //. +rewrite ltr0_norm ?subr_lt0// opprB ltrBlDl. +by rewrite (le_lt_trans td)// ltrD2l gtr_pMr// invf_lt1// ltr1n. +Qed. + +End continuous_confined. + +Section solution_locally_unique. +Context {R : realType} {n : nat}. +Notation U := 'rV[R]_n. +Variables (phi : R -> U -> U) (a b : R) (k : R) (u0 : U) (r : {posnum R}) + (f : R -> U). +Hypothesis ab : a < b. +Hypothesis k0 : 0 < k. +Let B := closed_ball u0 r%:num. +Hypothesis lip2 : {in `[a, b]%R, forall x : R, k.-lipschitz_B (phi x)}. +Hypothesis cont1 : {in B, forall y, {within `[a, b], continuous phi ^~ y}}. +Hypothesis cf : {within `[a, b], continuous f}. +Hypothesis sol1 : is_sol_oo phi u0 a b f. +Let rho_max : {posnum R} := (2^-1)%:pos. + +Let r2 := (r%:num/2)%:pos. +Let dmax rho := safe_dist phi a b k u0 r2 rho. +Let fc := cauchy_lipschitz_f ab k0 lip2 cont1. + +Lemma initial_solution_unique f' : {within `[a, b], continuous f'} -> + is_sol_oo phi u0 a b f' -> + exists D : {posnum R}, {in `[a, a + D%:num]%R, f =1 f'} /\ + {in `[a, a + D%:num]%R, forall t, closed_ball u0 (r2%:num) (f t)}. +Proof. +move => cf' sol2. +suff [rho [D [Hrho [Db P1 P2]]]] : exists rho D : {posnum R}, + exists (Hrho : rho%:num < 1), + [/\ D%:num <= dmax rho, + {in `[a, a + D%:num]%R, f =1 fc Hrho } & + {in `[a, a + D%:num]%R, f' =1 fc Hrho} ]. + exists D; split => t tab; first by rewrite P1// P2. + rewrite P1//. + apply: solution_stays_in_ball2. + by move: tab; rewrite !inE; apply: subset_itvl; rewrite bnd_simp lerD2l. +have [d1 D1] := continuous_confined r2 ab cf (And31 sol1). +have [d2 D2] := continuous_confined r2 ab cf' (And31 sol2). +have [rho [drho1 drho2]] : exists rho, dmax rho <= (Num.min d1%:num d2%:num) /\ rho%:num < 1. + rewrite /dmax/safe_dist. + have posk : 0 < Num.min rho_max%:num (Num.min (k * rho_max%:num) (k * (Num.min d1%:num d2%:num))). + by rewrite lt_min/= invr_gt0// ltr0n/= lt_min divr_gt0//= mulr_gt0. + exists (PosNum posk); split => //=. + rewrite !ge_min/= minA; apply/orP; right. + rewrite !minr_pMl//=; [|by rewrite ltW// invr_gt0..]. + do 2 rewrite ge_min; apply/orP; right. + apply/orP; right. + by rewrite mulrAC divff ?mul1r// gt_eqF//. + by rewrite gt_min; apply/orP; left; rewrite invf_lt1// ltr1n. +have drho_pos : 0 < dmax rho by exact: safe_dist_gt0. +exists rho, (PosNum drho_pos), drho2; split => //. +- move => t tad. + apply/esym; apply: cauchy_lipschitz_unique_restr. + - apply/continuous_subspaceW/cf => //. + apply: subset_itvl => //=. + by rewrite bnd_simp -lerBrDl;apply safe_dist_itv. + - move=> t0 t0ad. + suff : f t0 \in closed_ball u0 r2%:num by rewrite inE. + apply D1. + move: t0ad; rewrite !inE/=; apply: subset_itvl; rewrite bnd_simp/=. + by rewrite lerD2l// (le_trans drho1)// ge_min lexx. + - split; first by apply sol1. + move=> t0 t0ad. + have [_ + _] := sol1; apply. + by move: t0ad; rewrite !inE/=; apply: subset_itvl; rewrite bnd_simp -lerBrDl safe_dist_itv. + - apply: continuous_subspaceW cf. + apply: subset_trans; first exact: itv_closure. + by apply: subset_itvl; rewrite bnd_simp -lerBrDl safe_dist_itv. + - exact: tad. +move => t tad. +apply/esym; apply : cauchy_lipschitz_unique_restr. +- apply/continuous_subspaceW/cf' => //. + by apply: subset_itvl => /=; rewrite bnd_simp -lerBrDl;apply safe_dist_itv. +- move=> t0 t0ad. + suff : f' t0 \in closed_ball u0 r2%:num by rewrite inE. + apply D2. + move: t0ad; rewrite !inE; apply: subset_itvl; rewrite bnd_simp lerD2l. + by rewrite (le_trans drho1)// ge_min lexx orbT. +- split; first by apply sol2. + move=> t0 t0ad. + have [_ + _] := sol2; apply. + by move: t0ad; rewrite !inE; apply: subset_itvl; rewrite bnd_simp -lerBrDl safe_dist_itv. +- apply/continuous_subspaceW/cf' => //. + apply: subset_trans; first exact: itv_closure. + by apply: subset_itvl; rewrite bnd_simp -lerBrDl;apply safe_dist_itv. +exact: tad. +Qed. + +End solution_locally_unique. + +(* only for autonomous, used for tilt *) +Definition locally_lipschitz {R : realType} n (U := 'rV[R]_n) (phi : U -> U) := + forall x, exists r k : {posnum R}, k%:num.-lipschitz_(closed_ball x r%:num) phi. + +Section loc_lip_uniqueness. +Context {R : realType} {n : nat} (a b : R) (r0 : {posnum R}). +Notation U := 'rV[R]_n. +Variable phi : R -> U -> U. +Hypothesis ab : a < b. +Variable (u0 : U). + +Let B := closed_ball u0 r0%:num. + +Variables (f : R -> U) (f' : R -> U). +Hypothesis sol1 : is_sol_oo phi u0 a b f. +Hypothesis sol2 : is_sol_oo phi u0 a b f'. +Hypothesis sol1B : forall t, a <= t -> t < b -> B (f t). +Hypothesis phi_local_conds :forall t, a <= t -> t < b -> exists r k : {posnum R}, + forall t', a <= t' <= b -> (k%:num.-lipschitz_(closed_ball (f t) r%:num) (phi t') /\ forall y, closed_ball (f t) r%:num y -> {within `[a, b], continuous phi ^~ y}). + +Local Lemma cauchy_lipschitz_unique_right_extension t : a <= t < b -> f' t = f t -> + exists Delta : {posnum R}, {in `[t, t + Delta%:num]%R, f =1 f'}. +Proof. +move=> /andP[ta tb] eq. +have [r [k L]] := phi_local_conds ta tb. +have taab : `[t, b] `<=` `[a, b]. + by move=> ?/=; apply: subset_itvr; rewrite bnd_simp. +have cf0 : {within `[t, b], continuous f}. + have := And33 sol1. + rewrite closure_neitv_oo//; exact: continuous_subspaceW. +have cf'0 : {within `[t, b], continuous f'}. + have := And33 sol2. + by rewrite closure_neitv_oo//; exact: continuous_subspaceW. +have sol10 : is_sol_oo phi (f t) t b f. + split => //; last by rewrite closure_neitv_oo. + move=> t0 tab. + apply sol1. + by move: tab; rewrite !inE/=; apply: subset_itvr; rewrite bnd_simp. +have sol20 : is_sol_oo phi (f t) t b f'. + split => //; last by rewrite closure_neitv_oo. + move=> t0 tab. + apply sol2. + by move: tab; rewrite !inE/=; apply: subset_itvr; rewrite bnd_simp. +have lip20 : {in `[t, b]%R, forall x, k%:num.-lipschitz_(closed_ball (f t) r%:num) (phi x)}. + move => t0 tab; apply L. + move :tab; rewrite in_itv/= => /andP[h1 ->//=]. + by rewrite (le_trans _ h1). +have cont1' : {in closed_ball (f t) r%:num, + forall y : 'rV_n, {within `[t, b], continuous phi^~ y}}. + move => y ytb. + have : {within `[a,b], continuous phi^~ y}. + have [| _ +] := L t. + by rewrite ta ltW. + apply. + by apply set_mem. + apply /continuous_subspaceW. + by apply subset_itvr. +have k0 : 0 < k%:num by []. +have [D [P1 P2]] := initial_solution_unique tb k0 lip20 cont1' cf0 sol10 cf'0 sol20. +by exists D. +Qed. + +Let in1_eq1 : {in `[a, a]%R, f =1 f'}. +Proof. +move=> t; rewrite in_itv/= -eq_le => /eqP <-. +by rewrite (And31 sol1) (And31 sol2). +Qed. + +Lemma locally_cauchy_lipschitz_unique : {in `[a, b]%R, f =1 f'}. +Proof. +set E := `[a, b]%classic `&` [set t | {in `[a, t]%R, f =1 f'}]. +suff : E b by case. +have Ea : E a by split=> //=; rewrite bound_itvE/= ltW. +have Enonempty : E !=set0 by exists a. +have mon c : E c -> forall d, d \in `[a, c]%R -> E d. + move=> [/= cab] acff' d dac; split => /=. + by apply: subset_itvl dac; rewrite bnd_simp (itvP cab). + move=> t tad; apply: acff'. + by apply: subset_itvl tad; rewrite bnd_simp (itvP dac). +have monC c d : a <= d -> E c -> ~ E d -> c < d. + move=> ad Ec nEd. + rewrite ltNge; apply/negP => cd. + apply/nEd/(mon c) => //. + by rewrite in_itv/= ad. +have [hP|/(has_supPn Enonempty)] := lem (has_sup E); last first. + move=> /(_ b)[x Ex bx]. + by apply/(mon x) => //; rewrite in_itv/= !ltW. +have Eclosed : closed E. + rewrite closedE/= => p pn. + suff : forall x, ~ E x -> \forall y \near x, ~ E y. + by apply: contraPP => Ep /(_ _ Ep). + move=> x notEx. + have [xab|xnab] := boolP (x \in `[a, b]%R); last first. + suff : \forall y \near x, ~ (y \in `[a,b]%R). + by move=> ?; near do (rewrite not_andP; left). + move: xnab; rewrite in_itv/= negb_and/= -!ltNge => /orP[xa|xb]. + - near do (apply/negP; rewrite in_itv negb_and/= -!ltNge; apply/orP; left). + exact: lt_nbhsl. + - near do (apply/negP; rewrite in_itv negb_and/= -!ltNge; apply/orP; right). + exact: lt_nbhsr. + move: notEx;rewrite not_andP => -[//|notEx]. + have [t Et] : exists t, t \in `[a, x]%R /\ f t != f' t. + rewrite not_existsP => h. + apply: notEx => t tax. + have := h t. + by rewrite not_andP => -[//|/negP/negPn/eqP]. + have [xt|xt]:= eqVneq x t. + subst t. + set g := fun x => `|f x - f' x|. + have contg : {within `[a, b], continuous g}. + apply/(within_continuous_comp_norm (ltW ab))/within_continuousB. + - by have := And33 sol1; rewrite (closure_neitv_oo ab). + - by have := And33 sol2; rewrite (closure_neitv_oo ab). + have g0x : g x > 0 by rewrite normr_gt0 subr_eq0; case: Et. + have g0 t : t \in `[a, b]%R -> g t > 0 -> ~ {in `[a, t]%R, f =1 f'}. + move=> tab + atff'. + suff -> : g t = 0 by rewrite ltxx. + apply/normr0P; rewrite atff' ?subrr//. + by move: tab; rewrite !in_itv/= lexx => /andP[->]. + suff hgx: \forall y \near x^'-, 0 < g y. + near=> y. + have [yx|xy Ey] := ltP y x; last first. + have := mon _ Ey x. + move: xab. + by rewrite !in_itv/= xy => /andP[-> _] /(_ isT)[]. + apply/not_andP; rewrite -implyE => yab. + apply: g0 => //. + by move: yx; near: y. + apply: (@cvgr_gt _ _ (x^'-) _ g (g x)) => //. + have xa : a < x. + rewrite ltNge. + contra: notEx. + move: xab; rewrite in_itv/= => /andP[+ _] ax. + by move/(conj ax) => /andP; rewrite -eq_le => /eqP ->. + have /(continuous_within_itvP _ ab)[cg _ gbb] := contg. + move: xab; rewrite in_itv/= => /andP[_ ]. + rewrite le_eqVlt => /predU1P[-> //|xb]. + apply/cvg_at_left_filter/cg. + by rewrite in_itv/= xb xa. + have tx : t < x. + by case: Et; rewrite in_itv/= lt_neqAle (eq_sym t) xt => /andP[_ ->]. + near=> y. + move=> Ey. + have ta : a <= t by case: Et; rewrite in_itv/= => /andP[]. + have /(monC _ _ ta Ey) : ~ E t. + rewrite not_andP; right => /(_ t). + by rewrite bound_itvE/= ta => /(_ isT); apply/eqP; case: Et. + apply/negP; rewrite -leNgt. + by near: y; exact: nbhs_ge. +have supE : E (sup E). + by rewrite {1}(closure_id E).1//; apply: closure_sup => //; apply hP. +have sup_itv : a <= sup E by rewrite sup_upper_bound. +have supeq : f' (sup E) = f (sup E). + apply/esym; apply supE. + by rewrite in_itv/= lexx sup_itv. +have [h|h] := leP b (sup E). + apply: (mon _ supE) => //. + by rewrite in_itv/= (ltW ab). +have [|Delta Hdelta] := cauchy_lipschitz_unique_right_extension _ supeq; first by apply/andP. +have Delta0 : 0 < Delta%:num by []. +suff : Num.min b (sup E + Delta%:num) <= sup E. + rewrite ge_min => /orP[/(lt_le_trans h)|]. + by rewrite ltxx. + by rewrite gerDl leNgt Delta0. +apply: sup_upper_bound => //. +split. + by rewrite /= in_itv/= le_min (ltW ab)/= ler_wpDr//= ge_min lexx. +move=> t ta. +have [ht|ht] := leP t (sup E). + by apply supE; rewrite in_itv/= (itvP ta). +apply: Hdelta; rewrite in_itv/= ltW//=. +by move: ta; rewrite in_itv/= le_min => /and3P[_]. +Unshelve. all: by end_near. Qed. + +End loc_lip_uniqueness. + +Section uniqueness. +Context {R : realType} {n : nat}. +Notation U := 'rV[R]_n. +Variables (phi : R -> U -> U) (a b : R) (k : R) (u0 : U) (r : {posnum R}). +Hypothesis ab : a < b. +Hypothesis k0 : 0 < k. +Let B := closed_ball u0 r%:num. +Hypothesis lip2 : {in `[a, b]%R, forall x : R, k.-lipschitz_B (phi x)}. +Hypothesis cont1 : {in B, forall y, {within `[a, b], continuous phi ^~ y}}. + +Let r2 := (r%:num/2)%:pos. +Variable rho : {posnum R}. (* rho < 1 *) +Hypothesis rho1 : (rho%:num < 1). +Local Notation safe_dist := (safe_dist phi a b k u0 r2 rho). +Let f := cauchy_lipschitz_f ab k0 lip2 cont1 rho1. + +Lemma closed_ball_split (x1 x2 y : U) q : 0 < q -> + closed_ball x1 (q / 2) y -> closed_ball x2 (q / 2) x1 -> closed_ball x2 q y. +Proof. +move => hq. +have hq2 : 0 < q / 2 by rewrite divr_gt0. +rewrite !closed_ballE// /closed_ball_ /= => h1 h2. +rewrite -(subrKA x1 x2). +by rewrite (le_trans (ler_normD _ _))// (splitr q) lerD. +Qed. +Theorem cauchy_lipschitz_unique f' : + is_sol_oo phi u0 a (a + safe_dist) f' -> + {in `[a, a + safe_dist]%R, f =1 f'}. +Proof. +move => sol1. +have cont1' : forall y , B y -> {within `[a, (a + safe_dist)%E], continuous phi^~ y}. + move => y By . + apply /continuous_subspaceW/cont1. + apply subset_itvl. + rewrite bnd_simp -lerBrDl; apply safe_dist_itv. + by apply mem_set. +apply: (locally_cauchy_lipschitz_unique _ _ (u0 := u0) sol1 ) => //. +exact: ltDl_safe_dist. +exact: is_sol_cauchy_lipschitz_f. +move => t tad tbd. +have [r' rp] : exists (r' : {posnum R}), closed_ball (f t) r'%:num `<=` closed_ball u0 r%:num. + exists r2. + move => x x0. + have sb: closed_ball u0 (r%:num / 2) (f t). + apply solution_stays_in_ball2=> //. + by rewrite in_itv/= tad//= ltW. + apply/closed_ball_split/sb => //. +exists r',(PosNum k0). +move => t' /andP[at' bt']. +split. +move => /=[x1 x2] [Bx1 Bx2]. +apply lip2. +rewrite in_itv/= at' //=. +apply (le_trans bt'). +rewrite -lerBrDl. +apply safe_dist_itv. +split => /=;by apply rp. +move => y By. +have h : y \in B. + apply mem_set. + by apply: rp. +have := (cont1 h). +apply /continuous_subspaceW. +apply: subset_itvl. +rewrite bnd_simp -lerBrDl; apply safe_dist_itv. +Qed. +End uniqueness. + +Section cauchy_lipschitz_symmetric. +Context {R : realType} {n : nat}. +Notation U := 'rV[R]_n. +Variables (phi : R -> U -> U) (k : R) (u0 : U) (r : {posnum R}) (a b : R). +Hypothesis k0 : 0 < k. +Let B := closed_ball u0 r%:num. +Hypothesis cont1 : {in B, forall y, {within `[a, b], continuous phi ^~ y}}. +Hypothesis lip2 : {in `[a, b]%R, forall x, k.-lipschitz_B (phi x)}. +Definition phi_ (t : R) x := phi x. + +Definition is_sol_sym u0 t0 d (f : R -> U):= + f t0 = u0 /\ sol_is_deriv_oo phi (t0 - d) (t0 + d) f. + +Let rho : {posnum R} := 2^-1%:pos. + +Let rho1 : rho%:num < 1. +Proof. by rewrite /rho/= invf_lt1// ltr1n. Qed. + +Lemma patch_in {X : Type} (f g : R -> X) S x : x \in S -> patch f S g x = g x. +Proof. + move => xs. + rewrite /patch. + by rewrite xs. +Qed. + + +Let r2 := (r%:num/2)%:pos. +Let r4 := (r%:num/4)%:pos. + +Let ler4 : r4%:num <= r%:num. +Proof. by rewrite /r4/= ler_pdivrMr // ler_pMr // lerDl. Qed. +Let ler42 : r4%:num <= r2%:num. +Proof. by rewrite /r4/r2/= ler_pdivrMr// -mulrA ler_pMr // ler_pdivlMl // mulr1 lerD // lerDl. Qed. + +Let B4 := closed_ball u0 r4%:num. + +Let phi_lip2 t0: t0 \in `[a,b]%R -> {in `[t0, b]%R, forall x, k.-lipschitz_B4 (phi x)}. +Proof. +move => tab x abx /= y By. +apply: lip2. +move : abx; rewrite !inE/=; apply subset_itvr. +by move : tab; rewrite in_itv/= bnd_simp => /andP[-> _]. +split. +by apply /le_closed_ball/By.1. +by apply /le_closed_ball/By.2. +Qed. + +Let phi_cont1 t0 : t0 \in `[a,b]%R -> {in B4, forall y, {within `[t0, b], continuous phi ^~ y}}. +Proof. +move => /= tab x Bx. +apply /continuous_subspaceW/cont1 => //. +apply: subset_itvr. +by move : tab; rewrite in_itv/= bnd_simp => /andP[-> _]. +apply mem_set. +apply set_mem in Bx. +by apply /le_closed_ball/Bx. +Qed. + +Let phi_lip2' t0 : t0 \in `[a,b]%R -> {in `[-t0, -a]%R, forall x, k.-lipschitz_B4 (-phi (-x))}. +Proof. +move => t0ab /= y ab x B12. +rewrite /= -normrN opprD !opprK. +have B12' : (B `*` B) x. + split. + by apply /le_closed_ball/B12.1. + by apply /le_closed_ball/B12.2. +apply: (lip2 _ B12'). +move : ab. +rewrite !in_itv/= lerNl lerNr => /andP[h1 ->]//=. +apply (le_trans h1). +move : t0ab. +by rewrite in_itv/= => /andP[]. +Qed. + +Local Lemma phi_cont1' t0 : t0 \in `[a,b]%R -> + {in B4, forall y, {within `[-t0, -a], continuous -(fun t => phi (-t) y)}}. +Proof. +move => t0ab /= y By. +move => t. +apply: continuousN. +have /within_continuous_compN : {within `[-(-a), - (-t0)], continuous phi^~ y}. + rewrite !opprK. + apply /continuous_subspaceW/cont1 => //. + apply : subset_itvl. + by move: t0ab; rewrite /=in_itv/= bnd_simp => /andP[]. +apply set_mem in By. +apply mem_set. +by apply : le_closed_ball By. +apply. +Qed. + +Let dplus t0 := safe_dist phi t0 b k u0 (r4%:num/2)%:pos rho. +Let dminus t0 := safe_dist (fun t x => - phi (-t) x) (-t0) (-a) k u0 (r4%:num/2)%:pos rho. +Let dboth t0 := Num.min (b - t0) (Num.min (dplus t0) (dminus t0)). + +Section cauchy_lipschitz_sym. +Variable t0 : R. +Hypothesis t0ab : t0 \in `]a, b[%R. + +Let amin1 : - t0 < - a. Proof. by rewrite ltrN2 (itvP t0ab). Qed. + +Let t0ab' : t0 \in `[a, b]%R. Proof. by exact: subset_itv_oo_cc. Qed. + +Let fminus0 := @cauchy_lipschitz_f R n (fun t x => - phi (- t) x) (- t0) + _ k u0 r4 amin1 k0 (phi_lip2' t0ab') (phi_cont1' t0ab') rho rho1. + +Let fminus := fminus0 \o -%R. + +Let t0b : t0 < b. Proof. by rewrite (itvP t0ab). Qed. + +Let fplus := @cauchy_lipschitz_f R n phi t0 + _ k u0 r4 t0b k0 (phi_lip2 t0ab') (phi_cont1 t0ab') rho rho1. + +Let f := patch fplus `[t0 - dboth t0, t0] fminus. + +Lemma cauchy_lipschitz_sym : is_sol_sym u0 t0 (dboth t0) f. +Proof. +have solplus := + cauchy_lipschitz_ex t0b k0 (phi_lip2 t0ab') (phi_cont1 t0ab') rho1. +have cplus := solution_stays_in_ball. +have dminus0 : 0 < dminus t0 by exact: safe_dist_gt0. +have solminus := + cauchy_lipschitz_ex amin1 k0 (phi_lip2' t0ab') (phi_cont1' t0ab') rho1. +have cminus := solution_stays_in_ball. +have adplus : t0 < t0 + dplus t0 by rewrite ltrDl safe_dist_gt0. +have cfplus := And33 solplus. +rewrite closure_neitv_oo in cfplus; last by rewrite ltrDl safe_dist_gt0. +have amind : -t0 < -t0 + dminus t0 by rewrite ltrDl dminus0. +have cfminus' := And33 solminus. +rewrite closure_neitv_oo in cfminus'; last by rewrite ltrDl. +have cfminus : {within `[t0-dminus t0, t0], continuous fminus}. + rewrite /fminus. + apply: within_continuous_compN. + apply/continuous_subspaceW/cfminus'. + apply: subset_itvl; rewrite bnd_simp -/dminus. + by rewrite opprD opprK. +have dboth0 : 0 < dboth t0. + rewrite lt_min; apply /andP;split; last first. + by rewrite lt_min safe_dist_gt0 //= lt_min dminus0. + by rewrite subr_gt0 (itvP t0ab). +set uneg := f (t0 - dboth t0). +have Buneg : closed_ball uneg (r%:num / 2) `<=` closed_ball u0 r%:num. + rewrite /uneg/f patch_in /f/=; last first. + by rewrite inE/=in_itv/= gerBl lexx ltW. + move=> /= x xb. + apply: (closed_ball_split _ xb) => //. + suff : fminus (t0 - dboth t0) \in closed_ball u0 (r%:num/4). + rewrite !inE. + apply le_closed_ball. + rewrite ler_wpM2l// lef_pV2 ?posrE//. + by rewrite (natrD _ 2 2) lerDl ler0n. + apply/mem_set/cminus. + rewrite in_itv/= opprB lerDr ltW //= addrC lerD//. + by rewrite /dboth /dplus 3!ge_min lexx !orbT. +have f01intersect : fminus t0 = fplus t0. + by rewrite /fminus/= (And31 solminus) (And31 solplus). +have fa : f t0 = u0. + rewrite /f patch_in /fminus /=. + apply solminus. + by rewrite inE/= in_itv/= lexx gerBl ltW. +set B' := closed_ball uneg (r2%:num). +have lip2' : {in `[t0 - dboth t0 ,t0 + dboth t0], forall x, k.-lipschitz_B' (phi x)}. + move => /= t tab [x1 x2] [Bx1 Bx2]. + apply lip2 => //. + move : tab. + rewrite mem_setE. + apply: subset_itv; rewrite bnd_simp. + rewrite lerBrDl -lerBrDr. + by rewrite !ge_min opprK (addrC t0) lexx /= !orbT. + rewrite -lerBrDl. + by rewrite !ge_min lexx. + by split;apply Buneg. +have contf_minus : {within `[t0 - dboth t0, t0], continuous fminus}. + apply /continuous_subspaceW/cfminus. + apply: subset_itvr. + by rewrite bnd_simp /= lerD //= lerNr opprK 3!ge_min lexx !orbT. +have contf_plus : {within `[t0, t0+dboth t0], continuous fplus}. + apply /continuous_subspaceW/cfplus. + apply: subset_itvl. + by rewrite bnd_simp /= lerD //= 2!ge_min lexx !orbT. +have contf : {within `[t0 - dboth t0, (t0 + dboth t0)%E], continuous f}. + apply : within_continuous_patch => //. + by rewrite gtrBl. + by rewrite ltrDl. +have r42 : r4%:num = (r2%:num / 2). + rewrite /r4/r2/=. + rewrite -mulrA. + apply congr2 => //. + by rewrite -invfM -natrM. +have fc : {in `[t0-dboth t0, (t0 + dboth t0)], + forall t : R, closed_ball (fminus (t0 - dboth t0)) r2%:num (f t)}. + move => t tad. + rewrite /f/= /patch/=. + have : (closed_ball (fminus (t0 - dboth t0)) (r4%:num)) u0. + suff: (fminus (t0 - dboth t0)) \in closed_ball u0 (r4%:num). + by rewrite inE/= !closed_ballE/closed_ball_/= // distrC . + apply/mem_set/cminus. + rewrite !in_itv/= lerNr lerNl opprD !opprK gerBl ltW//= lerB//. + by rewrite /dboth/dminus 3!ge_min lexx !orbT. + rewrite r42 => c1. + case : ifP => ht. + - have : fminus t \in closed_ball u0 r4%:num. + apply/mem_set/cminus. + move: ht. + rewrite inE/=!in_itv/= lerNr lerNl opprD !opprK => /andP[h1 ->//=]. + apply: (le_trans _ h1). + by rewrite lerB // 3!ge_min lexx !orbT. + rewrite inE. + rewrite !r42. + move => c2. + by apply: (closed_ball_split _ c2) =>//. + - have : (fplus t) \in closed_ball u0 (r2%:num/2). + rewrite -r42. + have ht' : t \in `[t0, t0 + dboth t0]. + have := tad. + rewrite !inE /=!in_itv/= => /andP[h1 ->]; apply /andP; split => //. + have [hat | hat] := lerP t0 t => //. + rewrite -ht. + by rewrite inE/=in_itv/= h1//= ltW. + apply mem_set;apply cplus. + move : ht'. + rewrite inE/= !in_itv/= => /andP[-> h1//=]. + apply: (le_trans h1). + by rewrite lerD // /dboth /dplus 2!ge_min lexx !orbT. + rewrite inE. + move => c2. + by apply: (closed_ball_split _ c2). +split => //. +suff h : is_sol_oo phi (f (t0-dboth t0)) (t0-dboth t0) (t0+dboth t0) f by apply (And32 h). +have kn0 : k != 0 by apply lt0r_neq0. +apply /(integral_sol_iff_sol (r := r2) kn0) => //. + by rewrite ler_ltD // gtrN. + move => t tab /= x Bx. + apply: lip2. + move : tab. + apply: subset_itv; rewrite bnd_simp. + rewrite lerBrDl -lerBrDr. + by rewrite !ge_min opprK (addrC t0) lexx /= !orbT. + rewrite -lerBrDl. + by rewrite !ge_min lexx. + split. + apply Buneg. + by apply: Bx.1. + apply Buneg. + by apply: Bx.2. + move => t tab. + apply /continuous_subspaceW/cont1. + apply: subset_itv; rewrite bnd_simp. + rewrite lerBrDl -lerBrDr. + by rewrite !ge_min opprK (addrC t0) lexx /= !orbT. + rewrite -lerBrDl. + by rewrite !ge_min lexx. + apply mem_set. + apply Buneg. + by apply set_mem. + move => _ [t tp] <-. + rewrite {1}/f patch_in;last first. + by rewrite inE/=in_itv/= lexx //= gerBl ltW. + by apply fc; rewrite inE. +apply: is_integral_sol_patch => //. +- by rewrite gtrBl. +- apply: (within_continuous_lipschitz _ kn0 (u0 := u0) (r:=r)). + exact: contf_minus. + move => x bx. + apply lip2. + move : bx. + apply: subset_itv; rewrite bnd_simp. + rewrite lerBrDl -lerBrDr. + by rewrite !ge_min opprK (addrC t0) lexx /= !orbT. + move : t0ab. + by rewrite in_itv/= => /andP[_ /ltW//]. + move => t tab. + apply /continuous_subspaceW/cont1. + apply: subset_itv; rewrite bnd_simp. + rewrite lerBrDl -lerBrDr. + by rewrite !ge_min opprK (addrC t0) lexx /= !orbT. + by rewrite (itvP t0ab). + exact: tab. + move => _ [/= t' tp] <-. + apply (le_closed_ball (e1:=r4%:num)) => //. + suff : (fminus t') \in closed_ball u0 r4%:num by rewrite inE. + apply mem_set; apply cminus. + move : tp. + rewrite !in_itv/=lerNl opprK => /andP[h0 ->//=]. + rewrite lerNl opprD opprK //=. + apply: (le_trans _ h0). + by rewrite lerB // 3!ge_min lexx !orbT. +- apply : (within_continuous_lipschitz _ kn0 (u0 := u0) (r:=r)). + exact: contf_plus. + move => x bx. + apply lip2. + move : bx. + apply: subset_itv; rewrite bnd_simp. + by rewrite (itvP t0ab). + by rewrite -lerBrDl ge_min lexx. + move => t tab. + apply/continuous_subspaceW/cont1. + apply: subset_itv; rewrite bnd_simp. + by rewrite (itvP t0ab). + by rewrite -lerBrDl ge_min lexx. + exact: tab. + move => _ [/= t' tp] <-. + apply (le_closed_ball (e1:=r4%:num)) => //. + suff : (fplus t') \in closed_ball u0 r4%:num by rewrite inE. + apply mem_set;apply cplus. + move: tp. + apply: subset_itvl; rewrite bnd_simp lerD2l. + by rewrite /dboth /dplus 2!ge_min lexx !orbT. +- apply /(integral_sol_iff_sol (r:=r2) kn0). + + by rewrite gtrBl. + + move => x bx. + apply lip2'. + rewrite inE. + apply: subset_itvl bx; rewrite bnd_simp. + by rewrite lerDl ltW. + + move => t tab. + apply /continuous_subspaceW/cont1. + apply: subset_itv; rewrite bnd_simp. + rewrite lerBrDl -lerBrDr. + by rewrite !ge_min opprK (addrC t0) lexx !orbT. + by rewrite (itvP t0ab). + exact/mem_set/Buneg/set_mem. + + by []. + + move => _ [t tp] <-. + rewrite {1}/f patch_in;last first. + by rewrite inE/=in_itv/= lexx //= gerBl ltW. + have tin : t \in `[t0 - dboth t0, t0 + dboth t0]. + move : tp. + rewrite !inE. + apply: subset_itv; rewrite bnd_simp//. + by rewrite lerDl// ltW. + have := fc _ tin. + rewrite {1}/f patch_in; last by rewrite inE. + apply. + split. + * by rewrite /f patch_in; last rewrite inE/=in_itv/= lexx //= gerBl ltW. + * move => t tad. + case : (And32 solminus (-t)). + move : tad. + rewrite -/dminus /=!in_itv/= ltrNr ltrNl opprD !opprK => /andP[h1 ->//=]. + apply: (le_lt_trans _ h1). + by rewrite lerB// 3!ge_min lexx !orbT. + move => h1 h2. + have hd : derivable fminus t 1. + rewrite /fminus/=. + apply/derivable1_diffP. + apply/differentiable_comp => //. + apply/derivable1_diffP. + by apply h1. + split=>//. + rewrite /fminus/=. + apply /rowP => i /=. + rewrite derive1E/=. + rewrite !derive_mx //= !mxE. + rewrite -derive1E/=. + have -> : (fun t0 : R => fminus0 (- t0) ord0 i) = ((fun t => fminus0 t ord0 i) \o -%R). + by apply funext. + rewrite derive1_comp//=. + rewrite !derive1N//=derive1_id/=. + move /rowP : h2. + move /(_ i). + rewrite !derive1E /=!derive_mx. + rewrite /=!mxE => ->. + by rewrite mulrN1 !opprK. + apply h1. + by move /derivable_mxP: h1. + * by rewrite closure_neitv_oo; last rewrite gtrBl. +- apply /(integral_sol_iff_sol (r:=r2) kn0). + + by rewrite ltrDl. + + move=>x bx. + rewrite /fminus/=. + rewrite (And31 solminus). + move => [x1 x2] [ Bx1 Bx2]. + apply: lip2. + move : bx. + rewrite !inE. + apply: subset_itv; rewrite bnd_simp. + by rewrite (itvP t0ab). + rewrite -lerBrDl. + by rewrite ge_min lexx. + split => /=. + rewrite /B. + apply: (le_closed_ball _ Bx1). + by rewrite ler_pdivrMr // ler_pMr // lerDr. + apply: (le_closed_ball _ Bx2). + by rewrite ler_pdivrMr // ler_pMr // lerDr. + + move => t tab. + apply /continuous_subspaceW/cont1. + apply: subset_itv; rewrite bnd_simp. + by rewrite (itvP t0ab). + by rewrite -lerBrDl ge_min lexx. + rewrite /B. + suff -> : u0 = fminus t0. + apply mem_set. + apply set_mem in tab. + apply: le_closed_ball tab. + by rewrite /r2/= ler_piMr// invf_le1 // ler1n. + rewrite -fa. + rewrite /f. + rewrite patch_in//. + rewrite inE/= bound_itvE. + by rewrite lerBlDl lerDr ltW. + + by []. + + move => _ [t tp] <-. + rewrite /fminus /= (And31 solminus). + apply: (le_closed_ball ler42). + suff : fplus t \in closed_ball u0 r4%:num by rewrite inE. + apply/mem_set; apply cplus. + move/mem_set : tp. + rewrite inE /=!in_itv/= => /andP[-> //=]. + move/le_trans; apply. + by rewrite lerD// /dboth /dplus 2!ge_min lexx !orbT. + rewrite /fminus /=(And31 solminus). + split; first by apply solplus. + move=> t tad. + apply solplus. + apply: subset_itvl tad; rewrite bnd_simp lerD2l. + by rewrite /dboth /dplus 2!ge_min lexx !orbT. + apply/continuous_subspaceW/cfplus. + rewrite closure_neitv_oo;last by rewrite ltrDl. + apply: subset_itvl; rewrite bnd_simp lerD2l. + by rewrite /dboth /dplus 2!ge_min lexx !orbT. +Qed. + +End cauchy_lipschitz_sym. + +End cauchy_lipschitz_symmetric. diff --git a/ode_common.v b/ode_common.v new file mode 100644 index 00000000..02eec3c2 --- /dev/null +++ b/ode_common.v @@ -0,0 +1,883 @@ +From HB Require Import structures. +From mathcomp Require Import all_boot all_order ssralg ssrnum matrix interval. +From mathcomp Require Import poly generic_quotient ring_quotient. +From mathcomp Require Import mathcomp_extra unstable boolp classical_sets. +From mathcomp Require Import constructive_ereal. +From mathcomp Require Import functions reals interval_inference topology. +From mathcomp Require Import prodnormedzmodule tvs normedtype landau. +From mathcomp Require Import ereal sequences derive numfun measure realfun. +From mathcomp Require Import lebesgue_measure lebesgue_integral ftc. +Require Import tilt_mathcomp. + +(**md**************************************************************************) +(* # Preparation steps to ode_contfun.v *) +(* *) +(* ``` *) +(* contseg a b := pred type for functions continuous on [a; b] *) +(* infty_norm0 f == sup (|f|(K)) *) +(* f has type {fun K >-> [set: _]} *) +(* ``` *) +(******************************************************************************) + +Set Implicit Arguments. +Unset Strict Implicit. +Unset Printing Implicit Defensive. + +Import Order.TTheory GRing.Theory Num.Def Num.Theory. +Import numFieldNormedType.Exports. + +Open Scope ring_scope. +Open Scope classical_set_scope. + +Lemma eq_on_itv_deriv {R : realType} {W : normedModType R} c d (g h : R -> W) : + {in `]c, d[%R, g =1 h} -> {in `]c, d[%R, g^`() =1 h^`()}. +Proof. +move=> gh x xcd; rewrite !derive1E; apply: near_eq_derive => //. +near=> x0. +apply gh. +near: x0. +exact/near_in_itvoo. +Unshelve. all: by end_near. Qed. + +Section about_sup. + +Lemma sup_ge0 {R : realType} (A : set R) : + (forall x, A x -> 0 <= x) -> 0 <= sup A. +Proof. +move=> Ax. +have [->|/set0P[a Aa]] := eqVneq A set0; first by rewrite sup0. +have [supA|supA] := pselect (has_sup A). + rewrite (le_trans (Ax _ Aa))// ub_le_sup//. + by case: supA. +by rewrite /sup supremum_out. +Qed. + +Lemma has_sup_Mn {R : realType} (A : set R) n : + has_sup A -> has_sup [set x *+n | x in A ]. +Proof. +move => [-[] x Ax [y uby]]. +split; first by exists (x *+ n), x. +exists (y *+ n). +move => _ [y0 Ay0 <-] . +rewrite lerMn2r. +by apply /orP;right;apply uby. +Qed. + +Lemma sup_Mn {R : realType} (A : set R) n : + has_sup A -> sup [set x *+n | x in A ] = sup A *+ n. +Proof. +move => ex_sup. +elim: n. + rewrite !mulr0n -(sup1 0);congr (sup _). + apply eq_set => /= z ;apply propext; split => [[x _ <- ] | ->]; rewrite ?normr0 => //. + by case : ex_sup => -[] x Ax _; exists x. +move => n IH. +rewrite !mulrS. +rewrite -IH. +rewrite -sup_sumE => //; last by apply has_sup_Mn. +apply /eqP. +rewrite eq_le. +apply /andP;split; last first. + apply ge_sup. + case : ex_sup => -[] x Ax _;exists (x+x *+ n); exists x => //. + exists (x *+ n) => //. + by exists x. + move => _ /= [x Ax [_ [x0 Ax0] <-] <-]. + have /orP[ xx0| xx0] := le_total x x0. + rewrite (@le_trans _ _ (x0 *+ n.+1)) //. + by rewrite mulrS lerD2r. + rewrite ub_le_sup//; first by apply has_sup_Mn. + by exists x0. + rewrite (@le_trans _ _ (x *+ n.+1)) //. + rewrite mulrS lerD2l. + by rewrite lerMn2r xx0 orbT. + apply ub_le_sup; first by apply has_sup_Mn. + by exists x. +apply sup_le. +- apply: subset_trans; last by apply: le_down. + move => _ [x Ax <-] /=. + exists x => //. + exists (x *+ n)=> //. + exists x => //. + by rewrite mulrS. +- case : ex_sup => -[] x Ax _. + exists (x *+ n.+1)=> //=. + by exists x. +- case : ex_sup => -[] x Ax [y uby]. + split. + exists (x + x *+ n). + exists x => //. + exists (x *+ n) => //. + by exists x. +- exists (y + y *+ n) => _ [x0 Ax0 [_ [x1 Ax1] <-] <-]. + apply lerD;first by apply uby. + rewrite lerMn2r; apply /orP. + by right;apply uby. +Qed. + +Lemma sup_mult {R: realType} (A : set R) (a : R) : + has_sup A -> sup [set normr a * x | x in A ] = (normr a) * sup A . +Proof. +move =>ex_sup. +have []:= ex_sup => -[] x Ax ub. +apply /eqP. +rewrite eq_le. +apply /andP;split. +apply ge_sup; first by exists (normr a * x); exists x. +move => _ [x0 Axo <-]. +apply ler_wpM2l => //. +rewrite ub_le_sup//. +have [/eqP ->| ha0] := boolP (a == 0). +rewrite normr0 !mul0r . +suff ->: [set 0 * x0 | x0 in A] = [set 0] by rewrite sup1 lexx. +apply/predeqP => x0 /=;split => [ [x1 _ <-] | -> ]. + by rewrite mul0r. + by exists x => //=; rewrite mul0r. +rewrite -ler_pdivlMl; last by rewrite normr_gt0. +apply ge_sup; first by apply ex_sup. +move => x0 Ax0. +rewrite ler_pdivlMl; last by rewrite normr_gt0. +rewrite ub_le_sup//. + have [x1 ubx1] := ub. + exists (`|a| * x1). + move => _ [x2 Ax2 <-]. + apply ler_wpM2l => //. + by apply ubx1. +by exists x0. +Qed. + +End about_sup. + +(* TODO: PR to MCA *) +Lemma cst_is_fun {T1 T2} (A : set T1) x : @isFun T1 T2 A [set: T2] (cst x). +Proof. by constructor. Qed. + +HB.instance Definition _ {T1 T2} (A : set T1) x := @cst_is_fun T1 T2 A x. + +Lemma seg_nonempty {R : realType} (c d : R) : c <= d -> `[c, d] !=set0. +Proof. +move => h. +exists c. +by rewrite /=in_itv/= lexx. +Qed. + +(* TODO: PR *) +Lemma restrict0 [T : Type] (K : realFieldType) (D : set T) : + (cst 0 : T -> K) \_ D = cst 0. +Proof. +by apply/funext => x/=; rewrite patchE; case: ifPn. +Qed. + +(* TODO: rewrite rmorphD should work declare patch as a morphism: + erestrictD, erestrictM, *) +Lemma restrictD [T : pointedType] [R : realFieldType] (D : set T) (f g : T -> R) : + (f \+ g)%R \_ D = (f \_ D \+ g \_ D)%R. +Proof. +rewrite /patch. +apply/funext => /= x. +case: ifPn => xD. + by rewrite /GRing.add_fun xD. +by rewrite /GRing.add_fun (negbTE xD)// addr0. +Qed. + +Lemma restrictM [T : pointedType] [R : realFieldType] (D : set T) (f g : T -> R) : + (f \* g)%R \_ D = (f \_ D \* g \_ D)%R. +Proof. +rewrite /patch. +apply/funext => /= x. +case: ifPn => xD. + by rewrite /GRing.mul_fun xD. +by rewrite /GRing.mul_fun (negbTE xD)// mulr0. +Qed. + +(* TODO: now in MathComp-Analysis master *) +Section continuous_within_itvP. +Context {R : realType}. +Context {U : normedModType R}. + +Implicit Type f : R -> U. + +Let near_at_left (a : itv_bound R) b f eps : (a < BLeft b)%O -> 0 < eps -> + {within [set` Interval a (BRight b)], continuous f} -> + \forall t \near b^'-, `|f b - f t| < eps. +Proof. +move=> ab eps_gt0 cf. +move/continuous_withinNx/(@cvgrPdist_lt _ _)/(_ _ eps_gt0) : (cf b). +rewrite /dnbhs/= near_withinE !near_simpl /prop_near1 /nbhs/=. +rewrite -nbhs_subspace_in//; last first. + rewrite /= in_itv/= lexx andbT. + by move: a ab {cf} => [[a|a]/=|[|]//]; rewrite bnd_simp// => /ltW. +rewrite /within/= near_simpl; apply: filter_app. +move: a ab {cf} => [a0 a/= /[!bnd_simp] ab|[_|//]]. +- exists (b - a); rewrite /= ?subr_gt0// => c cba + ac. + apply=> //; rewrite ?lt_eqF// !in_itv/= (ltW ac)/= andbT; move: cba => /=. + rewrite gtr0_norm ?subr_gt0// ltrD2l ltrNr opprK => {}ac. + by case: a0 => //=; exact/ltW. +- by exists 1%R => //= c cb1 + bc; apply; rewrite ?lt_eqF ?in_itv/= ?ltW. +Qed. + +Let near_at_right a (b : itv_bound R) f eps : (BRight a < b)%O -> 0 < eps -> + {within [set` Interval (BLeft a) b], continuous f} -> + \forall t \near a^'+, `|f a - f t| < eps. +Proof. +move=> ab eps_gt0 cf. +move/continuous_withinNx/(@cvgrPdist_lt _ _)/(_ _ eps_gt0) : (cf a). +rewrite /dnbhs/= near_withinE !near_simpl// /prop_near1 /nbhs/=. +rewrite -nbhs_subspace_in//; last first. + rewrite /= in_itv/= lexx//=. + by move: b ab {cf} => [[b|b]/=|[|]//]; rewrite bnd_simp// => /ltW. +rewrite /within/= near_simpl; apply: filter_app. +move: b ab {cf} => [b0 b/= /[!bnd_simp] ab|[//|_]]. +- exists (b - a); rewrite /= ?subr_gt0// => c cba + ac. + apply=> //; rewrite ?gt_eqF// !in_itv/= (ltW ac)/=; move: cba => /=. + rewrite ltr0_norm ?subr_lt0// opprB ltrD2r. + by case: b0 => //= /ltW. +- by exists 2%R => //= c ca1 + ac; apply; rewrite ?gt_eqF ?in_itv/= ?ltW. +Qed. + +(* NB: PR *) +Lemma continuous_within_itvP_g a b f : a < b -> + {within `[a, b], continuous f} <-> + [/\ {in `]a, b[, continuous f}, f @ a^'+ --> f a & f @b^'- --> f b]. +Proof. +move=> ab; split=> [abf|]. + split; [|apply/(@cvgrPdist_lt _ _) => eps eps_gt0 /=..]. + - rewrite -continuous_open_subspace; last exact: interval_open. + by move: abf; exact/continuous_subspaceW/subset_itvW. + - by apply: near_at_right => //; rewrite bnd_simp. + - by apply: near_at_left => //; rewrite bnd_simp. +case=> ctsoo ctsL ctsR; apply/subspace_continuousP => x /andP[]. +rewrite !bnd_simp/= !le_eqVlt => /predU1P[<-{x}|ax] /predU1P[|]. +- by move/eqP; rewrite lt_eqF. +- move=> _; apply/(@cvgrPdist_lt _ _) => eps eps_gt0 /=. + move/(@cvgrPdist_lt _ _)/(_ _ eps_gt0): ctsL; rewrite /at_right !near_withinE. + apply: filter_app; exists (b - a); rewrite /= ?subr_gt0// => c cba + ac. + have : a <= c by move: ac => /andP[]. + by rewrite le_eqVlt => /predU1P[->|/[swap] /[apply]//]; rewrite subrr normr0. +- move=> ->; apply/(@cvgrPdist_lt _ _) => eps eps_gt0 /=. + move/(@cvgrPdist_lt _ _)/(_ _ eps_gt0): ctsR; rewrite /at_left !near_withinE. + apply: filter_app; exists (b - a); rewrite /= ?subr_gt0 // => c cba + ac. + have : c <= b by move: ac => /andP[]. + by rewrite le_eqVlt => /predU1P[->|/[swap] /[apply]//]; rewrite subrr normr0. +- move=> xb; have aboox : x \in `]a, b[ by rewrite inE /= !in_itv/= ax. + rewrite within_interior; first exact: ctsoo. + rewrite inE in aboox. + suff : `]a, b[ `<=` interior `[a, b] by exact. + by rewrite -open_subsetE; [exact: subset_itvW| exact: interval_open]. +Qed. + +End continuous_within_itvP. + + +Lemma within_continuous_comp_norm {R : realType} {U : normedModType R} a y (f : R -> U) : + a <= y -> + {within `[a, y], continuous fun x => f x} -> + {within `[a, y], continuous fun x => `|f x|}. +Proof. +rewrite le_eqVlt => /predU1P[<-|ay]. + rewrite set_itv1 => _. + exact: continuous_subspace1. +move/continuous_within_itvP => /(_ ay)[H1 H2 H3]. +apply/continuous_within_itvP => //; split => //. + move=> z zay. + apply: continuous_comp => //. + by apply: H1. + exact: norm_continuous. +apply: cvg_comp. + apply: H2. + by apply: cvg_norm. +apply: cvg_comp. +apply: H3. +by apply: cvg_norm. +Qed. + +Lemma lipschitzW {R : realType} {T U W : normedModType R} (A B : set T) C (f : T -> U -> W) k : + A `<=` B -> {in B, forall x, k.-lipschitz_C (f x)} -> {in A, forall x, k.-lipschitz_C (f x)}. +Proof. +move=> AB H x xA. +apply: H. +by apply/mem_set/AB/set_mem. +Qed. + +(* NB: why is in1_subset_itv so specialized?! *) + +Section lip_implies_cont. +Context {R : realType}. +Variables (f : R -> R -> R) (a t1 : R). +Hypothesis a1 : a < t1. +Variable k : R. +Variables (u0 : R) (r : {posnum R}). +Let B := closed_ball u0 r%:num. + +Hypothesis lip2 : {in `[a, t1]%R, forall x, k.-lipschitz_B (f x)}. + +Lemma lipschitz_within_continuous : {in `[a, t1]%R, forall x, {within B, continuous f x}}. +Proof. +move=> x xa1. +rewrite [B]closed_ball_itv//. +apply/continuous_within_itvP; first by rewrite ltrD2l gtrN. +split. +- move=> y ya1. + move: (xa1); have := @lip2 x => /[apply] kfx. + rewrite /continuous_at. + apply/cvgrPdist_le => /= e e0. + near=> y'. + move: kfx => /(_ (y, y'))/=. + have By : B y. + rewrite /B closed_ball_itv//=. + exact: subset_itv_oo_cc ya1. + have By' : B y'. + rewrite /B closed_ball_itv//=. + rewrite in_itv/=; apply/andP; split. + near: y'. + exists (y - (u0 - r%:num)). + by move: ya1; rewrite in_itv/= -subr_gt0 => /andP[]. + move=> z/=. + by rewrite ltr_distlC opprB addrCA subrr addr0 => /andP[/ltW]. + near: y'. + exists ((u0 + r%:num) - y). + by move: ya1; rewrite in_itv/= -(subr_gt0 y) => /andP[]. + move=> z/=. + rewrite ltr_distlC => /andP[_]. + by rewrite addrCA subrr addr0 => /ltW. + move=> /(_ (conj By By'))/le_trans; apply. + near: y'. + have [k0|k0] := ltP 0 k; last first. + near=> y'. + by rewrite (le_trans _ (ltW e0))// mulr_le0_ge0. + near=> y'. + rewrite -ler_pdivlMl// mulrC. + near: y'. + exists (e / k). + by rewrite divr_gt0. + by move=> z/= => /ltW. +- apply/cvgrPdist_le => /= e e0. + have [k0|k0] := ltP 0 k; last first. + (* TODO: clean, bad dup *) + near=> y'. + move: (xa1); have := @lip2 x => /[apply]. + move=> /(_ (u0 - r%:num, y'))/=. + have Bu0r : B (u0 - r%:num). + rewrite /B closed_ball_itv//=. + by rewrite bound_itvE lerD2l gerN. + have By' : B y'. + rewrite /B closed_ball_itv//=. + rewrite in_itv/=; apply/andP; split => //. + near: y'. + exists r%:num => //=. + move=> z/=. + rewrite ltr_distlC. + rewrite subrK => /andP[_ /ltW + _] => /le_trans; apply. + by rewrite lerDl. + move=> /(_ (conj Bu0r By'))/le_trans; apply. + by rewrite (le_trans _ (ltW e0))// mulr_le0_ge0. + near=> y'. + move: (xa1); have := @lip2 x => /[apply]. + move=> /(_ (u0 - r%:num, y'))/=. + have Bu0r : B (u0 - r%:num). + rewrite /B closed_ball_itv//=. + by rewrite bound_itvE lerD2l gerN. + have By' : B y'. + rewrite /B closed_ball_itv//=. + rewrite in_itv/=; apply/andP; split => //. + near: y'. + exists r%:num => //=. + move=> z/=. + rewrite ltr_distlC. + rewrite subrK => /andP[_ /ltW + _] => /le_trans; apply. + by rewrite lerDl. + move=> /(_ (conj Bu0r By'))/le_trans; apply. + rewrite -ler_pdivlMl// mulrC. + near: y'. + exists (e / k) => /=; first by rewrite divr_gt0. + by move=> z/= => /ltW. +- apply/cvgrPdist_le => /= e e0. + have [k0|k0] := ltP 0 k; last first. + (* TODO: clean, bad dup *) + near=> y'. + move: (xa1); have := @lip2 x => /[apply]. + move=> /(_ (y', u0 + r%:num))/=. + have By' : B y'. + rewrite /B closed_ball_itv//=. + rewrite in_itv/=; apply/andP; split => //. + near: y'. + exists r%:num => //=. + move=> z/=. + rewrite ltr_distlC addrK => /andP[/ltW + _ _]. + rewrite lerBlDl => /le_trans; apply. + by rewrite lerDr. + have Bu0r : B (u0 + r%:num). + rewrite /B closed_ball_itv//=. + by rewrite bound_itvE lerD2l gerN. + move=> /(_ (conj By' Bu0r)). + rewrite distrC. + move=> /le_trans; apply. + by rewrite (le_trans _ (ltW e0))// mulr_le0_ge0. + near=> y'. + move: (xa1); have := @lip2 x => /[apply]. + move=> /(_ (y', u0 + r%:num))/=. + have By' : B y'. + rewrite /B closed_ball_itv//=. + rewrite in_itv/=; apply/andP; split => //. + near: y'. + exists r%:num => //=. + move=> z/=. + rewrite ltr_distlC addrK => /andP[/ltW + _ _]. + rewrite lerBlDl => /le_trans; apply. + by rewrite lerDr. + have Bu0r : B (u0 + r%:num). + rewrite /B closed_ball_itv//=. + by rewrite bound_itvE lerD2l gerN. + move=> /(_ (conj By' Bu0r)). + rewrite distrC. + move=> /le_trans; apply. + rewrite -ler_pdivlMl// mulrC. + near: y'. + exists (e / k) => /=; first by rewrite divr_gt0. + move=> z/= => /ltW. + by rewrite distrC. +Unshelve. all: end_near. Qed. + +End lip_implies_cont. + +(* NB: should this be PRed or is a patch for our development? *) +Section cst_continuous_on_subspace. +Context {R : realType} {W : topologicalType}. +Variable A : set R. + +Lemma cst_continuous_subspace (r : W) : {within A, continuous (cst r)}. +Proof. by apply: continuous_subspaceT; exact: cst_continuous. Qed. + +HB.instance Definition _ x := isContinuous.Build (subspace A) W + (@cst _ W x) (@cst_continuous_subspace x). + +End cst_continuous_on_subspace. + +(* NB: continuousFunType is defined in subspace_topology.v *) + +HB.instance Definition _ (R : realType) (V : topologicalType) (A : set R) := + gen_eqMixin (continuousFunType A [set: V]). + +HB.instance Definition _ (R : realType) (V : topologicalType) (A : set R) := + gen_choiceMixin (continuousFunType A [set: V]). + +Section contseg_pred. +Context {R : realType} (a b : R) (V : topologicalType). + +Definition contseg : {pred R -> V} := + mem [set f | squashed (@ContinuousFun R V `[a, b] [set: V] f)]. +Definition contseg_key : pred_key contseg. Proof. exact. Qed. +Canonical contseg_keyed := KeyedPred contseg_key. + +End contseg_pred. +Arguments contseg {R} a b {V}. + +Section contseg_sub. +Context {R : realType} (a b : R) {V : topologicalType}. +Notation T := (continuousFunType `[a, b] [set: V]). + +Section Sub. +Context (f : R -> V) (fP : f \in contseg a b). + +Definition contseg_Sub_subproof := unsquash (set_mem fP). +#[local] HB.instance Definition _ := contseg_Sub_subproof. +Definition contseg_Sub : continuousFunType `[a, b] [set: V] := + {| ContinuousFun.sort := f; ContinuousFun.class := contseg_Sub_subproof |}. + +End Sub. + +Lemma contseg_rect (K : T -> Type) : + (forall f (Pf : f \in contseg a b), K (contseg_Sub Pf)) -> + forall u : T, K u. +Proof. +move=> Ksub [f Pf]. +rewrite (_ : K _ = K (contseg_Sub (mem_set (squash Pf))))//. +rewrite /contseg_Sub /contseg_Sub_subproof /= mem_setK. +rewrite /unsquash; case : cid => // /= => x _. +congr (K (ContinuousFun.Pack _)). +move : Pf x => [[H1] [H2]] [[K1] [K2]]. +by rewrite (Prop_irrelevance H1 K1) (Prop_irrelevance H2 K2). +Qed. + +Lemma contseg_valP f (Pf : f \in contseg a b) : contseg_Sub Pf = f :> (_ -> _). +Proof. by []. Qed. + +HB.instance Definition _ := isSub.Build _ _ T contseg_rect contseg_valP. + +Lemma contseg_eqP (f g : continuousFunType `[a, b] [set: V]) : + f = g <-> f =1 g. +Proof. by split=> [->//|fg]; exact/val_inj/funext. Qed. + +(* +HB.instance Definition _ := [Choice of continuousFunType `[a, b] [set: R] by <:]. +*) + +End contseg_sub. + +Definition contsegN {R : realType} (a b : R) (g : R -> R) := + g \o -%R. +Arguments contsegN {R} _ _. + +Section contsegN. +Context {R : realType}. +Variables a b : R. + +Let g'fun (g : continuousFunType `[a, b] [set: R]) : + set_fun `[- b, - a] setT (contsegN a b g). +Proof. by constructor => x/=. Qed. + +HB.instance Definition _ (g : continuousFunType `[a, b] [set: R]) := + @isFun.Build (subspace `[- b, - a]) R `[- b, - a] setT (contsegN a b g) (g'fun g). + +Let cg' (g : continuousFunType `[a, b] [set: R]) : + {within `[- b, - a], continuous (contsegN a b g)}. +Proof. +have [ab|] := ltP a b; last first. + rewrite le_eqVlt => /predU1P[ba|ba]. + subst b. + rewrite set_itv1. + exact: continuous_subspace1. + rewrite set_itv_ge ?bnd_simp ?leNgt ?ltrN2 ?negbK//. + exact: continuous_subspace0. +apply/continuous_within_itvP. + by rewrite ltrN2. +have /continuous_within_itvP[] := @cts_fun _ _ g. + by []. +move=> cg gR gL; split. +- move=> x xdd; apply: continuous_comp; first exact: continuousN. + by apply: cg; rewrite oppr_itvoo. +- by apply/cvg_at_leftNP; rewrite /contsegN/= opprK. +- move/cvg_at_rightNP : gR. + by rewrite /contsegN/= opprK. +Qed. + +HB.instance Definition _ (g : continuousFunType `[a, b] [set: R]) := + isContinuous.Build _ _ (contsegN a b g : subspace `[- b, - a] -> R) (@cg' g). + +End contsegN. + +Lemma contseg_zmod_closed {R : realType} (a b : R) (V : normedModType R) : + zmod_closed (@contseg _ a b V). +Proof. +split=> [|f g]; rewrite !inE/=. +- apply: squash. + do 2 split => //. + exact: cst_continuous. +- move=> /unsquash cf /unsquash cg. + apply: squash. + pose f' : continuousFunType `[a, b] setT := HB.pack f cf. + pose g' : continuousFunType `[a, b] setT := HB.pack g cg. + rewrite [f]/(f' : _ -> _). + rewrite [g]/(g' : _ -> _). + move: {f g cf cg} f' g' => f g. + have isfun_fg : @isFun _ _ `[a, b] setT (f \- g) by constructor. + have iscontfun_fg : @isContinuous _ _ (f \- g). + constructor => x. + by apply: continuousB; exact: cts_fun. + by split. +Qed. + +Lemma contfun_scaler_closed {R : realType} (a b : R) (V : normedModType R) : + GRing.scaler_closed (@contseg _ a b V). +Proof. +move=> r f; rewrite 2!inE/= => /unsquash[[_ cf]]. +apply: squash. +split => //. +constructor => x. +apply: continuousZ; first exact: cst_continuous. +by case: cf; exact. +Qed. + +Section within_continuous_lipschitz. +Context {R : realType} {U : normedModType R}. +Variables (f : R -> U -> U) (a b : R). +Variable (u0 : U) (r : {posnum R}). + +Variable (g : R -> U). +Hypothesis cg : {within `[a, b], continuous g}. + +Let B := closed_ball u0 r%:num. + +Variable k : R. +Hypothesis k0 : k != 0. +(* properties of the function f defining the differential equation: *) +(* k-lipschitz for all t *) +Hypothesis lip2 : {in `[a, b]%R, forall x, k.-lipschitz_B (f x)}. +(* within-continuous for all y *) +Hypothesis cont1 : {in B, forall y, {within `[a, b], continuous f ^~ y}}. + +Hypothesis imageg : g @` `[a, b] `<=` B. + +Let within_continuous_lipschitz_at_right (ab : a < b) : + f x (g x) @[x --> a^'+] --> f a (g a). +Proof. +apply/cvgrPdist_le => /= e e0. +have aab : a \in `[a, b]%R by rewrite bound_itvE ltW. +have e20 : 0 < e / 2 by rewrite divr_gt0. +(* use continuity in first variable *) +have c1_ineq : \forall t \near a^'+, `|f a (g a) - f t (g a)| <= e / 2. + have : g a \in (B : set U) by apply/mem_set/imageg => /=; exists a. + move /cont1/continuous_within_itvP_g => /(_ ab). + move=> [_ + _]. + rewrite cvgrPdist_le /=. + exact. +have gtd : \forall t \near a^'+, g t \in (B : set U). + near=> t. + apply/mem_set/imageg => /=; exists t => //. + rewrite in_itv/=; apply/andP; split => //. + by near: t; exact: nbhs_right_le. +(* use continuity of g *) +have cg_ineq : \forall t \near a^'+, `|g a - g t| <= `|k|^-1 * (e / 2). + have /continuous_within_itvP_g := cg. + move/(_ ab) => [_ + _]. + move/cvgrPdist_le => /(_ (`|k|^-1 * (e / 2)) ). + apply. + by rewrite mulr_gt0// invr_gt0 normr_gt0. +(* use Lipschitz continuity *) +have c2_ineq : \forall t \near a^'+, `|f t (g (a)) - f t (g t)| <= e / 2. + near=> t. + have td' : t \in `[a, b]%R. + by rewrite in_itv /=; apply/andP; split=>//; rewrite ltW. + have gNdB : B (g a) by apply: imageg => //=; exists a. + have Bgt : B (g t) by apply: imageg => //=; exists t. + move: lip2 => /(_ _ td'). + move /(_ (g a, g t) (conj gNdB Bgt)). + move/le_trans; apply. + move: k0; rewrite neq_lt => /orP[k_lt0|k_gt0]. + rewrite (@le_trans _ _ 0)//; last by rewrite divr_ge0// ltW. + by rewrite mulr_le0_ge0// ltW. + rewrite -ler_pdivlMl//. + rewrite (_ : k = `|k|). + by near: t. + by rewrite gtr0_norm. +near=>t. +rewrite -(subrKA (f t (g a)) (f a (g a))) (le_trans (ler_normD _ _))//. +by rewrite (splitr e) lerD//; near: t. +Unshelve. all: end_near. Qed. + +Let within_continuous_lipschitz_at_left (ab : a < b) : + f x (g x) @[x --> b^'-] --> f b (g b). +Proof. +apply/cvgrPdist_le => /= e e0. +have bbab : b \in `[a, b]%R by rewrite bound_itvE ltW. +have e20 : 0 < e / 2 by rewrite divr_gt0. +have c1_ineq : \forall t \near b^'-, `|f b (g b) - f t (g b)| <= e / 2. + have : g b \in (B : set U) by apply/mem_set/imageg => //=; exists b. + move /cont1/continuous_within_itvP_g => /(_ ab). + move=> [_ _ +]. + rewrite cvgrPdist_le /=. + exact. +have gtd : \forall t \near b^'-, g t \in (B : set U). + near=>t. + apply/mem_set/imageg => /=; exists t => //. + rewrite in_itv/=; apply/andP; split => //. + by near: t; exact: nbhs_left_ge. +have cg_ineq : \forall t \near (b)^'-, `|g b - g t| <= `|k|^-1 * (e / 2). + have /continuous_within_itvP_g := cg. + move/(_ ab) => [_ _ +]. + move/cvgrPdist_le => /(_ (`|k|^-1 * (e / 2))). + apply. + by rewrite mulr_gt0// invr_gt0// normr_gt0. +have c2_ineq : \forall t \near (b)^'-, `|f t (g b) - f t (g t)| <= e / 2. + near=> t. + have td' : t \in `[a, b]%R. + by rewrite in_itv /=; apply/andP; split=> //; rewrite ltW. + have gNdB : B (g b) by apply: imageg => /=; exists b. + have Bgt : B (g t) by apply: imageg; exists t. + move: lip2 => /(_ _ td'). + move /(_ (g b, g t) (conj gNdB Bgt)). + move/le_trans; apply. + move: k0; rewrite neq_lt => /orP[k_lt0|k_gt0]. + rewrite (@le_trans _ _ 0)//; last by rewrite divr_ge0// ltW. + by rewrite mulr_le0_ge0// ltW. + rewrite -ler_pdivlMl//. + rewrite (_ : k = `|k|). + by near: t. + by rewrite gtr0_norm. +near=>t. +rewrite -(subrKA (f t (g b)) (f b (g b))) (le_trans (ler_normD _ _))//. +by rewrite (splitr e) lerD//; near: t. +Unshelve. all: end_near. Qed. + +Lemma within_continuous_lipschitz : + {within `[a, b], continuous fun x0 : R => f x0 (g x0)}. +Proof. +have [ab|] := ltP a b; last first. + rewrite le_eqVlt => /predU1P[<-|ab]. + by rewrite set_itv1; exact: continuous_subspace1. + by rewrite set_itv_ge ?bnd_simp -?ltNge//; exact: continuous_subspace0. +apply/continuous_within_itvP_g; [by [] | split]. +- move=> x; rewrite inE /= in_itv/= => /andP[ndx dx]. + rewrite /continuous_at. + apply/cvgrPdist_le => /= e e0. + have gxB : g x \in (B : set U). + apply/mem_set/imageg => /=; exists x => //. + by rewrite in_itv/= (ltW ndx) (ltW dx). + have H : r%:num - `|g x - u0| >= 0. + rewrite subr_ge0 distrC. + by move: gxB; rewrite /B closed_ballE /closed_ball_ //= inE. + near=> t. + rewrite -(subrKA (f t (g x)) (f x (g x))) (le_trans (ler_normD _ _))//. + rewrite (splitr e) lerD//. + + near: t. + near_simpl. + have /cont1 : g x \in B. + apply/mem_set/imageg => /=; exists x => //. + by rewrite in_itv/= (ltW ndx) (ltW dx). + move/continuous_within_itvP_g => /(_ ab). + move=> [+ Htmp1 Htmp2]. + move/(_ x). + rewrite /continuous_at. + have e20 : 0 < e / 2 by rewrite divr_gt0. + rewrite inE /= !in_itv/= ndx dx => /(_ isT). + move/cvgrPdist_le => /(_ _ e20)[r0 /= r0_gt0 Br0]. + near=> t. + apply: Br0 => //. + rewrite -/(ball x r0 t). + near: t. + near_simpl. + exact: (near_ball x _ r0_gt0). + + have := @lip2 t. + have tab : t \in `[a, b]%R. + near: t. + exists (Num.min (b - x) (x - a)) => /=. + by rewrite lt_min subr_gt0 dx/= subr_gt0. + move=> z/=. + rewrite lt_min => /andP[H1 H2]. + rewrite in_itv/=; apply/andP; split. + move: H2. + by rewrite ltr_distlC subKr => /andP[/ltW]. + move: H1. + by rewrite ltr_distlC (addrC x (b-x)) subrK => /andP[_ /ltW]. + move/(_ tab). + move/set_mem in gxB. + have Bgt : B (g t) by apply: (imageg) => /=; exists t. + move/(_ (g x, g t) (conj gxB Bgt)). + move=> /le_trans; apply. + near: t. + move: k0; rewrite neq_lt => /orP[k_lt0|k_gt0]. + near=> t. + rewrite (@le_trans _ _ 0)//; last by rewrite divr_ge0// ltW. + by rewrite mulr_le0_ge0// ltW. + near=> t. + rewrite -ler_pdivlMl//. + near: t. + move/continuous_within_itvP_g : cg => /(_ ab)[+ _ _] => /(_ x). + rewrite inE /= in_itv/= ndx dx => /(_ isT). + rewrite /continuous_at => /cvgrPdist_le. + apply. + by rewrite mulr_gt0 ?divr_gt0 ?invr_gt0//. +- exact: within_continuous_lipschitz_at_right. +- exact: within_continuous_lipschitz_at_left. +Unshelve. all: end_near. Qed. + +End within_continuous_lipschitz. + +Lemma compact_has_ubound {R : realType} (A : set R) : compact A -> has_ubound A. +Proof. +move=> /compact_bounded[u [_ /= uA]]. +exists (u + 1) => x Ax. +by rewrite (le_trans (ler_norm x))// uA// ltrDl. +Qed. + +(* TODO: PR *) +Lemma cont_within_cont_comp {R : realType} {W : normedModType R} (f : W -> R) + (K : set R) (g : continuousFunType K [set: W]) : {in g @` K, continuous f} -> + {within K, continuous (f \o g)}. +Proof. +move=> ctf. +rewrite continuous_subspace_in => /= x Kx. +apply: continuous_comp; first exact: cts_fun. +apply: ctf. +exact: image_f Kx. +Qed. + +Lemma normr_has_sup {R : realType} (a b : R) {W : normedModType R} + (f : continuousFunType `[a, b] [set: W]) : + a <= b -> has_sup [set (normr \o f) z | z in `[a, b] ]. +Proof. +move=> /seg_nonempty[c Kc]. +split; first by exists `|f c|, c. +apply/compact_has_ubound/continuous_compact => //; last exact: segment_compact. +by apply:cont_within_cont_comp => w wK; exact: norm_continuous. +Qed. + +Definition infty_norm0 {R : realType} (K : set R) {W : normedModType R} + (f : {fun K >-> [set: W]}) := sup ((Num.norm \o f) @` K). + +Section infty_norm0_lemmas. +Context {R : realType} {W : normedModType R}. +Variables a b : R. +Hypothesis ab : a <= b. +Let K := `[a, b]%R. +Local Notation T := (continuousFunType [set` K] [set: W]). + +Lemma infty_norm0_le (g : T) (u : R) : {in K, forall x, `| g x | <= u} -> + infty_norm0 g <= u. +Proof. +have [c Kc] := seg_nonempty ab. +move=> h; rewrite /infty_norm0; apply: ge_sup. + by exists `|g c|; exists c => //; rewrite /= in_itv/= lexx. +by move => _ [x xab] <-;apply h; rewrite inE. +Qed. + +Lemma infty_norm0_ge (g : T) x : x \in K -> `|g x| <= infty_norm0 g. +Proof. +move=> xK. +rewrite sup_upper_bound //=. + exact: normr_has_sup. +by exists x. +Qed. + +Lemma infty_norm0_itv_eq (f g : T) : {in K, f =1 g} -> + infty_norm0 f = infty_norm0 g. +Proof. +move=> inK. +rewrite /infty_norm0 /=; congr (sup _). +by apply/seteqP; split; move => _ [ y ? <- ]; exists y; rewrite //= inK // inE. +Qed. + +End infty_norm0_lemmas. + +Section intermediate_lemma. +Context {R : realType}. +Variables (a b : R). +Hypothesis ab : a < b. +Variable u0 : R. +Variable r : {posnum R}. +Let B := closed_ball u0 r%:num. + +(* NB: not used anymore *) +Local Lemma imageg_closure (g : R -> R) : {within `[a, b], continuous g} -> + g @` `]a, b[ `<=` interior B -> g @` `[a, b] `<=` B. +Proof. +move => cont_g imageg _ [] x /= + <-. +rewrite in_itv /= => /andP[+ +]/=. +have /continuous_within_itvP := cont_g. +move=> /(_ ab)[]/=. +move => gcont gcontl gcontr. +have closea1 : closed `[a, b] by exact: interval_closed. +have h0 x0 : g x0 \in (interior B : set R) -> g x0 \in B. + rewrite /B interior_closed_ballE//. + rewrite closed_ball_itv//. + rewrite ball_itv 2!inE. + exact: subset_itv_oo_cc. +case: ltgtP => [hyd|_|<-] // => _. + case: ltgtP => [hyd'|_|->] // => _. + apply/set_mem/h0/mem_set/imageg => /=. + exists x => //=; rewrite in_itv /= hyd hyd' //. + apply: (@closed_cvg _ _ (b^'-) _ g B) => //=. + exact: closed_ball_closed. + near=>t. + apply/set_mem/h0/mem_set/imageg => /=. + exists t => //=. + by rewrite !in_itv/=; apply/andP; split. +move => _. +apply: (@closed_cvg _ _ (a^'+) _ g B) => //=. + exact: closed_ball_closed. +near=>t. +apply/set_mem/h0/mem_set/imageg; exists t => //=. +by rewrite !in_itv/=; apply/andP; split. +Unshelve. all: end_near. Qed. + +End intermediate_lemma. diff --git a/ode_contseg.v b/ode_contseg.v new file mode 100644 index 00000000..5f4c3f47 --- /dev/null +++ b/ode_contseg.v @@ -0,0 +1,780 @@ +From HB Require Import structures. +From mathcomp Require Import all_boot all_order ssralg ssrnum matrix interval. +From mathcomp Require Import poly generic_quotient ring_quotient. +From mathcomp Require Import mathcomp_extra unstable boolp classical_sets. +From mathcomp Require Import constructive_ereal. +From mathcomp Require Import functions reals interval_inference topology. +From mathcomp Require Import prodnormedzmodule tvs normedtype landau. +From mathcomp Require Import ereal sequences derive numfun measure realfun. +From mathcomp Require Import lebesgue_measure lebesgue_integral ftc. +Require Import ode_common. + +(**md**************************************************************************) +(* # Continuous functions over a closed interval *) +(* *) +(* The main purpose of this file is to define the quotient of continuous *) +(* function over a closed interval. It is shown to form a complete normed *) +(* type. *) +(* *) +(* ``` *) +(* infty_norm f := infty_norm0 (repr f) *) +(* quot_contSeg a b U := quotient of continuous functions over a closed *) +(* interval [a, b] to some normed module U *) +(* Notation: `C[a, b] or `C([a, b] U) *) +(* ``` *) +(* *) +(******************************************************************************) + +Reserved Notation "`C[ a , b ]" (at level 0, a, b at level 0, + format "`C[ a , b ]"). +Reserved Notation "`C([ a , b ] W )" (at level 1, a, b at next level, + format "`C([ a , b ] W )"). + +Set Implicit Arguments. +Unset Strict Implicit. +Unset Printing Implicit Defensive. +Import Order.TTheory GRing.Theory Num.Def Num.Theory. +Import numFieldNormedType.Exports. + +Open Scope ring_scope. +Open Scope classical_set_scope. + +Module ContSeg_zlmodType. +Section contSeg_zlmodtype. +Context {R : realType} (a b : R) (V : normedModType R). + +HB.instance Definition _ := GRing.isZmodClosed.Build _ _ + (contseg_zmod_closed a b V). + +Fail Check continuousFunType `[a, b] [set: V] : zmodType. + +HB.instance Definition _ := + [SubChoice_isSubZmodule of continuousFunType `[a, b] [set: V] by <:]. + +Check continuousFunType `[a, b] [set: V] : zmodType. + +HB.instance Definition _ := GRing.isScaleClosed.Build _ _ + (contseg a b) (@contfun_scaler_closed R a b V). + +Fail Check @continuousFunType R V `[a, b] [set: V] : lmodType _. + +HB.instance Definition _ := + [SubZmodule_isSubLmodule of continuousFunType `[a, b] [set: V] by <:]. + +Check continuousFunType `[a, b] [set: V] : lmodType _. + +End contSeg_zlmodtype. +End ContSeg_zlmodType. + +Section submod_contSeg. +Context {R : realType} (a b : R) {V : normedModType R}. +Local Notation T := (continuousFunType `[a, b] [set: V]). + +(* NB: point does not need to be 0, so rewrite f \_ K explicitly *) +Definition patch_contSeg0 : {pred T} := + [pred f : T | patch 0 `[a, b] f == 0]. + +End submod_contSeg. +Arguments patch_contSeg0 {R} {a b} V ab. + +Module ContSeg_submod. +Export ContSeg_zlmodType. + +Section submod_definition. +Context {R : realType} {V : normedModType R}. +Variables a b : R. + +Lemma submod_closed_contSeg : submod_closed (@patch_contSeg0 _ a b V). +Proof. +split => /=. +- rewrite inE/=; apply/funext => x. + by rewrite /patch; case: ifPn. +- move => f u v. + rewrite !inE => u0 v0. + apply/funext => u1. + rewrite /patch; case: ifPn => // u1ab. + move: u0 v0; rewrite /patch. + move=> /(congr1 (fun x => x u1)); rewrite u1ab => uu1. + move=> /(congr1 (fun x => x u1)); rewrite u1ab => vu1. + by rewrite -[LHS]/(f *: u u1 + v u1) uu1 vu1 addr0 scaler0. +Qed. + +Fail Check (patch_contSeg0 V ab) : zmodClosed _. + +HB.instance Definition _ := + GRing.isZmodClosed.Build _ _ (GRing.submod_closedB submod_closed_contSeg). + +Check (@patch_contSeg0 _ a b V) : zmodClosed _. + +End submod_definition. +End ContSeg_submod. + +Section contSeg_seminorm. +Context {R : realType} {W : normedModType R}. +Variables a b : R. +Let K := `[a, b]. +Local Notation T := (continuousFunType K [set: W]). + +Import ContSeg_zlmodType. + +(* NB: require Nmodule properties *) +Lemma infty_norm0_eq0 : infty_norm0 (0 : T) = 0. +Proof. +rewrite /infty_norm0. +have [K0|K0] := eqVneq K set0. + by rewrite [X in [set _ | _ in X]](_ : _ = set0)// image_set0// sup0. +rewrite -(sup1 0); congr sup. +apply: eq_set => /= z. +apply propext; split => [[x _ <- ] | ->]; rewrite ?normr0 => //. +move/set0P : K0 => [c Kc]. +by exists c => //; rewrite normr0. +Qed. + +(* NB: require Nmodule properties *) +Lemma infty_norm0rMn (f : T) n : infty_norm0 (f *+ n) = infty_norm0 f *+ n. +Proof. +rewrite /infty_norm0. +have [K0|K0] := eqVneq K set0. + do 2 rewrite [X in [set _ | _ in X]](_ : _ = set0)// image_set0//. + by rewrite sup0 mul0rn. +rewrite -sup_Mn; last first. + apply: normr_has_sup. + rewrite leNgt; apply: contra K0 => ba. + by rewrite /K set_itv_ge// bnd_simp -ltNge. +rewrite image_comp/=; congr (sup _). +apply: eq_imagel => z Kz /=; rewrite -normrMn /=. +have /(congr1 (@^~ z)) <- := natmulfctE f n. +congr (normr (_ z)). +(* NB: investigate *) +elim: n f => //= n IH f. +by rewrite !mulrS -IH. +Qed. + +Lemma infty_norm0N (f : T) : infty_norm0 (- f) = infty_norm0 f. +Proof. +rewrite /infty_norm0; congr sup; apply: eq_set => /= x0. +apply: propext; split => [[x1 in_itv] | [x1 in_itv]] H; exists x1 => //. + by rewrite -normrN. +by rewrite normrN. +Qed. + +End contSeg_seminorm. + +Module ContSeg_quot. +Export ContSeg_zlmodType. + +Import ContSeg_submod. +Import Quotient. + +Section contSeg_quotient. +Context {R : realType} (a b : R) {W : normedModType R}. + +(*Definition eq_seg (f g : continuousFunType a b) := `[< {in `[a, b], f =1 g} >]. + +Let eq_seg_refl : reflexive eq_seg. +Proof. by move=> f; apply/asboolP => r. Qed. + +Let eq_seg_sym : symmetric eq_seg. +Proof. by move=> f g; apply/idP/idP => /asboolP h; apply/asboolP => r /h. Qed. + +(* TODO: wait for quotient *) +Let eq_seg_trans : transitive eq_seg. +Proof. +by move=> f g h /asboolP fg /asboolP gh; apply/asboolP => r rab; rewrite fg// gh. +Qed. + +Canonical eq_seg_canonical := + EquivRel eq_seg eq_seg_refl eq_seg_sym eq_seg_trans.*) + +Local Open Scope quotient_scope. + +Definition quot_contSeg := {quot (@patch_contSeg0 R a b W)}. +Local Notation T := quot_contSeg. + +(* NB: ZmodQuotient is defined in ring_quotient.v *) +HB.instance Definition _ := ZmodQuotient.on T. + +Definition fun_of_quot_contSeg (f : T) : subspace `[a, b] -> W := repr f. +Coercion fun_of_quot_contSeg : T >-> Funclass. + +Lemma eq_segP (f g : T) : reflect ({in `[a, b], f =1 g}) (f == g %[mod T]). +Proof. +apply/(iffP idP); rewrite eqmodE//=. +- rewrite equivE inE => fgab0 x xab. + move/(congr1 (fun z => z x)) : fgab0. + by rewrite /patch xab => /subr0_eq. +- move=> abfg. + rewrite /equivE inE; apply/funext => x. + rewrite /patch; case: ifPn => //= xab. + rewrite !fctE. + by apply/eqP; rewrite subr_eq0; exact/eqP/abfg. +Qed. + +Lemma eqmod_on_itv f g : f = g %[mod T] -> {in `[a, b]%R, f =1 g}. +Proof. +move=> /eqmodP + x xab. +move/set_mem => abfg0. +apply: subr0_eq. +move/(congr1 (fun z => z x)) : abfg0. +by rewrite /patch mem_setE/= xab. +Qed. + +Lemma eval_mod_on_itv f x : x \in `[a, b]%R -> (\pi_T f : T) x = f x. +Proof. +move => xab. +apply: (@eqmod_on_itv (repr (\pi_T f)) f) => //. +by rewrite reprK. +Qed. + +Lemma quot_contSeg_fctB (f g : T) t : t \in `[a, b]%R -> + (f - g : T) t = (f : T) t - (g : T) t. +Proof. +move=> tab. +rewrite -(reprK f) -(reprK g). +rewrite /GRing.opp/=. +rewrite -Quotient.pi_opp. +rewrite /GRing.add/=. +rewrite -Quotient.pi_add. +by rewrite !eval_mod_on_itv. +Qed. + +End contSeg_quotient. +End ContSeg_quot. +Arguments ContSeg_quot.quot_contSeg {R} a b W. + +Notation "`C[ a , b ]" := (ContSeg_quot.quot_contSeg a b _). +Notation "`C([ a , b ] W )" := (ContSeg_quot.quot_contSeg a b W). + +Section zmodule_normed. +Context {R : realType} {W : normedModType R}. +Variables a b : R. + +Import ContSeg_quot. + +Definition infty_norm (f : `C([a , b] W)) := infty_norm0 (repr f). + +Local Open Scope quotient_scope. + +Lemma ler_infty_normD (x y : `C[a, b]) : + infty_norm (x + y) <= infty_norm x + infty_norm y :> R. +Proof. +rewrite /infty_norm/=. +have [K0|K0] := eqVneq `[a, b] set0. + rewrite /infty_norm0. + do ! rewrite [X in [set _ | _ in X]](_ : _ = set0)// image_set0//. + by rewrite sup0 addr0. +have ab : a <= b. + rewrite leNgt; apply: contra K0 => ba. + by rewrite set_itv_ge// bnd_simp -ltNge. +rewrite -sup_sumE; [|exact: normr_has_sup..]. +apply: sup_le. +- move=> A -[s sab] <-{A}. + rewrite /down/=. + eexists. + split. + exists `|repr x s|; first by exists s. + exists `|repr y s|; first by exists s. + reflexivity. + suff -> : repr (x + y) s = repr x s + repr y s by exact: ler_normD. + suff : repr (x + y) = repr x + repr y %[mod `C[a, b]]. + move=> /eqmod_on_itv ->. + by []. + by rewrite inE. + by rewrite Quotient.pi_add !reprK. +- exact: (normr_has_sup _ _).1. +- split. + + exists (`|x a| + `|repr y a|)=> /=. + exists (`|repr x a|) => //; [exists a => //; by rewrite in_itv/= lexx ab|]. + by exists `|repr y a| => //; exists a => //; rewrite bound_itvE. + + exists (sup [set `|repr x r| | r in `[a, b]] + sup [set `|repr y r| | r in `[a, b]]). + apply ubP => _ [x0 xs] [y0 ys] <-. + rewrite lerD// ub_le_sup//. + exact: (normr_has_sup x _).2. + exact: (normr_has_sup y _).2. +Qed. + +Lemma infty_normr0_eq0 (x : `C[a, b]) : infty_norm x = 0 -> x = 0. +Proof. +rewrite /infty_norm /infty_norm0 /= => H. +rewrite -(reprK x) -(reprK 0). +apply/eqquotP. +rewrite Quotient.equivE inE; apply: funext => r /=. +rewrite /patch; case : ifPn => // /set_mem in_itv. +rewrite 2!fctE. +have -> : {in `[a, b]%R, repr (0 : `C[a, b]) =1 (0 : @continuousFunType R W `[a, b] setT)}. +- apply/eqmod_on_itv. + by rewrite reprK /GRing.zero /= /Quotient.zero /= -lock. +- rewrite [LHS]subr0. + apply/eqP; rewrite -normr_le0. + have [ab|ab] := leP a b. + have := sup_upper_bound (normr_has_sup x ab). + rewrite H /ubound /=. + apply. + by exists r. + move: in_itv; rewrite /= in_itv/= => /andP[ar rb]. + by have := le_trans ar rb; rewrite leNgt ab. +- by rewrite inE. +Qed. + +Lemma infty_normrMn (x : `C[a, b]) n : infty_norm (x *+ n) = infty_norm x *+ n. +Proof. +rewrite /infty_norm -infty_norm0rMn => //. +apply: infty_norm0_itv_eq => r rab. +suff : repr (x *+ n) = repr x *+ n %[mod `C[a, b]] by move=> /eqmod_on_itv ->. +elim n; [rewrite !mulr0n // reprK /GRing.zero /= /Quotient.zero /= -lock // | ]. +move => n' IHn'; rewrite reprK !mulrS. +rewrite reprK in IHn'. +rewrite Quotient.pi_add reprK. +by move : IHn' <-. +Qed. + +Let infty_norm_pi0 x : infty_norm (\pi_`C[a, b] x) = infty_norm0 x. +Proof. +rewrite /infty_norm /=. +have /eqmod_on_itv Heq : repr (\pi_`C[a, b] x) = x %[mod `C[a, b]] by rewrite reprK. +exact: infty_norm0_itv_eq. +Qed. + +Lemma infty_normrN (x : `C[a, b]) : infty_norm (- x) = infty_norm x. +Proof. +rewrite -(reprK x) /GRing.opp /= -Quotient.pi_opp !infty_norm_pi0. +rewrite /infty_norm /infty_norm0; congr sup. +apply/eq_set => /= x0. +apply/propext; split => [[x1 in_itv] | [x1 in_itv]] H; exists x1 =>//. + by rewrite -normrN. +by rewrite normrN. +Qed. +(* TODO: dev the theory of sup following the theory of ess_sup *) + +Fail Check `C[a, b] : normedZmodType R. + +HB.instance Definition _ := @Num.Zmodule_isNormed.Build R `C[a, b] + infty_norm ler_infty_normD infty_normr0_eq0 infty_normrMn infty_normrN. + +Lemma infty_norm_pi x : `|\pi_`C[a, b] x| = infty_norm0 x. +Proof. by rewrite /Num.norm /= infty_norm_pi0. Qed. + +Lemma infty_norm_lt (f : `C[a, b]) e : + `| f | < e -> {in `[a, b]%R, forall x : R, `|f x| < e}. +Proof. +rewrite -{1}(reprK f) infty_norm_pi => h x xab. +have [ab|ab] := leP a b. + exact/le_lt_trans/h/infty_norm0_ge. +move: xab; rewrite in_itv/= => /andP[/le_trans /[apply]]. +by rewrite leNgt ab. +Qed. + +Lemma infty_norm_le (f : `C[a, b]) e : + `| f | <= e -> {in `[a, b]%R, forall x : R, `|f x| <= e}. +Proof. +rewrite -{1}(reprK f) infty_norm_pi => h x xab. +have [ab|ab] := leP a b. + exact/le_trans/h/infty_norm0_ge. +move: xab; rewrite in_itv/= => /andP[/le_trans /[apply]]. +by rewrite leNgt ab. +Qed. + +Lemma infty_norm_le2 (f : `C[a, b]) e : 0 <= e -> + {in `[a, b]%R, forall x : R, `|f x| <= e} -> `| f | <= e. +Proof. +move=> e0 h; have [ab|ba] := leP a b. + by rewrite -(reprK f) infty_norm_pi infty_norm0_le. +rewrite [leLHS](_ : _ = 0)//. +rewrite /Num.norm/= /infty_norm /infty_norm0. +rewrite [X in [set _ | _ in X]](_ : _ = set0) ?image_set0 ?sup0//. +by rewrite set_itv_ge// bnd_simp -ltNge. +Qed. + +Check `C[a, b] : normedZmodType R. + +Check (pseudoMetric_normed `C[a, b]) : pseudoMetricType R. +Check (pseudoMetric_normed `C[a, b]) : normedZmodType R. + +Fail Check (pseudoMetric_normed `C[a, b]) : normedModType R. + +End zmodule_normed. + +Section quot_contSeg_normedtype. +Context {R : realType} {W : normedModType R} {r s : R}. + +Import ContSeg_quot. + +Fail Check (pseudoMetric_normed `C[r, s]) : normedModType R. +HB.instance Definition _ := + PseudoMetric.copy `C([r, s] W) (pseudoMetric_normed `C([r, s] W)). +HB.instance Definition _ := isPointed.Build `C([r, s] W) 0. + +Lemma is_normZmod_contFunBallType : NormedZmod_PseudoMetric_eq R `C([r, s] W). +Proof. by constructor. Qed. + +Fail Check `C([r, s] W) : pseudoMetricNormedZmodType R. + +HB.instance Definition _ := is_normZmod_contFunBallType. + +Check `C([r, s] W) : pseudoMetricNormedZmodType R. +Import Quotient. +Open Scope quotient_scope. +Definition cont_scale (k : R) (f : `C([r, s] W)) : `C[r, s] := + \pi_`C[r, s] (k *: repr f). + +Let cont_scalerA a b f : cont_scale a (cont_scale b f) = cont_scale (a * b) f. +Proof. +rewrite /cont_scale. +have [-> | a0] := eqVneq a 0; first by rewrite !(scale0r, mul0r). +apply/eqmodP; rewrite /equiv_equiv/= /equiv/=. +rewrite -scalerA -scalerBr. +rewrite inE. +apply/funext => x/=. +rewrite /patch; case: ifPn => // xrs. +rewrite !fctE. +apply/eqP; rewrite scaler_eq0. +rewrite (negPf a0)/= subr_eq0. +apply/eqP. +case: piP => g. +rewrite mem_setE in xrs. +by move/eqmod_on_itv => /(_ _ xrs) <-. +Qed. + +Let cont_scale1r : left_id 1 cont_scale. +Proof. +move=> v. +rewrite /cont_scale/=. +rewrite [RHS](_ : _ = (\pi_`C[r, s] (repr v))%qT); last by rewrite reprK. +apply/eqmodP. +by rewrite scale1r. +Qed. + +Let cont_scalerDr : right_distributive cont_scale +%R. +Proof. +move=> k b c. +rewrite /cont_scale/=. +have [-> | k0] := eqVneq k 0. + by rewrite !scale0r piE//= add0r. +rewrite /cont_scale/=. +rewrite piE/=. +apply/eqmodP. +rewrite /equiv_equiv /equiv/=. +rewrite -scalerDr. +rewrite -scalerBr. +rewrite inE. +apply/funext => x/=. +rewrite /patch; case: ifPn => // xrs. +rewrite !fctE. +apply/eqP; rewrite scaler_eq0 (negPf k0)/=. +rewrite subr_eq0. +apply/eqP. +have := @eqmod_on_itv _ _ _ _ (repr (b + c)) (repr b + repr c). +move=> ->//; last by rewrite mem_setE in xrs. +rewrite pi_add//=. +by rewrite !reprK. +Qed. + +Let cont_scalerDl v : {morph cont_scale^~ v: a b / a + b}. +Proof. +move=> a b. +rewrite /cont_scale piE/=. +apply/eqmodP; rewrite /equiv_equiv/= /equiv/=. +rewrite -scalerDl subrr. +rewrite inE/=. +by apply/funext => x; rewrite /patch; case: ifP. +Qed. + +HB.instance Definition _ := + @GRing.Zmodule_isLmodule.Build R `C([r, s] W) cont_scale cont_scalerA cont_scale1r + cont_scalerDr cont_scalerDl. + +Local Lemma repr_mult l (x : `C[r, s]) a : a \in `[r, s]%R -> + repr (l *: x) a = l *: (repr x a). +Proof. +move=> ars. +have : repr (l *: x) = l *: repr x %[mod `C[r, s]]. + by case: piP. +move/(@eqmod_on_itv _ _ _ _ (repr (l *: x)) (l *: repr x)). +by move/(_ _ ars). +Qed. + +Lemma is_pmnormedZmod_contFunBallType : + PseudoMetricNormedZmod_Lmodule_isNormedModule R `C([r, s] W). +Proof. +constructor => l x. +rewrite /Num.norm/= /infty_norm /infty_norm0 /=. +have [rs|sr] := leP r s; last first. + rewrite /=. + have rs1 : `[r, s] = set0 by rewrite set_itv_ge// bnd_simp -ltNge. + rewrite (_ : [set (normr \o repr x) x0 | x0 in `[r, s]] = set0); last first. + rewrite -(image_set0 (normr \o repr x)). + by rewrite -rs1. + rewrite (_ : [set (normr \o repr (l *: x)) x0 | x0 in `[r, s]] = set0); last first. + rewrite -(image_set0 (normr \o repr (l *: x))). + by rewrite -rs1. + by rewrite !sup0 mulr0. +apply/eqP; rewrite eq_le; apply/andP; split. + apply: ge_sup. + exists `|repr (l *: x) r|, r => //=. + by rewrite bound_itvE. + move=> _/= [a ars] <-. + rewrite repr_mult; last by rewrite inE. + rewrite normrZ ler_wpM2l// ub_le_sup//. + exact: (normr_has_sup _ _).2. + by exists a. +rewrite -sup_mult => //; last by apply normr_has_sup. +apply sup_le; [ | | by apply normr_has_sup]. + move => _ [_ [x0 x0rs] <- <-]. + exists (`|l| * `|repr x x0|); split=> //=; exists x0. + by rewrite inE. + rewrite repr_mult; last by rewrite inE. + by rewrite normrZ. +exists `|l *: x r|, `|repr x r|. + by exists r => //=; rewrite bound_itvE. +by rewrite normrZ. +Qed. + +HB.instance Definition _ := is_pmnormedZmod_contFunBallType. +End quot_contSeg_normedtype. + +From mathcomp Require Import all_algebra. +From mathcomp Require Import matrix_topology. + +Section completeness. +Context {R : realType} {W : completeNormedModType R}. +Variables a b : R. + +Import ContSeg_quot. + +Check (`C([a, b] W) : pseudoMetricType R). +Check (`C([a, b] W) : normedModType R). + +Definition lim_fun (F : set_system `C[a, b]) (FF : ProperFilter F) (Fc : cauchy F) : + subspace `[a, b] -> W := + fun t => lim (@^~ t @ F). + +Lemma lim_fun_is_fun (F : set_system `C[a, b]) (FF : ProperFilter F) (Fc : cauchy F) : + @isFun (subspace `[a, b]) W `[a, b] [set: W] (@lim_fun F FF Fc). +Proof. by constructor. Qed. + +HB.instance Definition _ F FF Fc := (@lim_fun_is_fun F FF Fc). + +Lemma lim_fun_cvg_pt (F : set_system `C[a, b]) (FF: ProperFilter F) (Fc : cauchy F) : + forall e : R, e > 0 -> forall t, t \in `[a, b]%R -> + \forall f \near F, `|lim_fun FF Fc t - (f : `C[a, b]) t| <= e. +Proof. +have /(_ _ _) /cauchy_cvg /cvg_app_entourageP cvF : + forall t : R, t \in `[a, b]%R -> + cauchy (fmap (fun h : `C[a, b] => h t) (fun A : set `C[a, b] => nbhs F (fun g => A g))). + move=> t tab A /=. + rewrite -entourage_ballE => -[e /= e0 eA]. + rewrite near_simpl -near2E near_map2. + apply: Fc. + rewrite -entourage_ballE /nbhs/= /entourage_/=. + exists e => // -[f g]/= /infty_norm_lt => h. + apply: eA => /=. + rewrite -ball_normE /ball/=. + rewrite -quot_contSeg_fctB//. + exact: h. +have cvg_pt (t : R) : t \in `[a, b]%R -> + x @[x --> fmap (fun h : `C[a, b] => h t) F] --> lim_fun FF Fc t. + by move=> tab; exact/cvg_entourageP/cvF. +move=> e e0 t /cvg_pt /cvgrPdist_le. +exact. +Qed. + +Lemma lim_fun_cvg_uniform (F : set_system `C[a, b]) (FF: ProperFilter F) (Fc : cauchy F) : + forall e : R, e > 0 -> \forall f \near F, forall t, t \in `[a, b]%R -> + `|lim_fun FF Fc t - (f : `C[a, b]) t| <= e. +Proof. +move=> e e0. +have e20 : 0 < e / 2 by rewrite divr_gt0. +have [/= [A B] /= [n1 n2] H] := Fc _ (entourage_ball `C[a, b] (PosNum e20)). +near=> f. +move=> t tab. +near F => g. +rewrite -(subrKA (g t) (lim_fun FF Fc t)). +rewrite (le_trans (ler_normD _ _))// (splitr e) lerD//. + near: g. + by apply: lim_fun_cvg_pt => //; rewrite divr_gt0. +have : ball f (e /2 ) g. + by apply: (H (f, g)); split => //=; [near: f|near: g]. +rewrite /ball /= /pseudoMetric_from_normedZmodType.ball /=. +rewrite distrC. +rewrite -quot_contSeg_fctB//. +by move/ltW/infty_norm_le; exact. +Unshelve. all: by end_near. Qed. + +Lemma lim_fun_cont (F : set_system `C[a, b]) (FF : ProperFilter F) (Fc : cauchy F) : + {within `[a, b], continuous (@lim_fun F FF Fc)}. +Proof. +have [ab|] := ltP a b; last first. + rewrite le_eqVlt => /predU1P[<-|ab']. + by rewrite set_itv1; exact: continuous_subspace1. + rewrite set_itv_ge// ?bnd_simp -?ltNge//. + exact: continuous_subspace0. +have H (e : R) : e > 0 -> forall t, t \in `[a, b]%R -> + \forall t' \near t, t' \in `[a, b] -> + `|lim_fun FF Fc t - lim_fun FF Fc t'| <= e. + move=> e0 t tab. + near F => f. + have lim_fune2 : forall u, u \in `[a, b]%R -> `|lim_fun FF Fc u - f u| <= e / 2. + by near: f; apply: lim_fun_cvg_uniform => //; rewrite divr_gt0. + move/(continuous_within_itvP _ ab) : (@cts_fun _ _ f ) => [mc lc rc]. + have : t \in `[a, b] by rewrite inE. + rewrite -{1}setUitv1/=; last by rewrite bnd_simp ltW. + rewrite -{1}setU1itv/=; last by rewrite bnd_simp. + rewrite inE/= in_itv/= => -[[->|tab']|->]. + - near=> t' => t'ab. + rewrite -(subrKA (f a) (lim_fun FF Fc a)). + rewrite (le_trans (ler_normD _ _))// (splitr e) lerD//. + + by rewrite lim_fune2// bound_itvE ltW. + + rewrite -(subrKA (f t') (f a)). + rewrite (le_trans (ler_normD _ _))// (splitr (e/2)) lerD//. + * move: t'ab. + rewrite -{1}setU1itv/=; last by rewrite bnd_simp ltW. + rewrite inE/= in_itv/= => -[-> | ]. + by rewrite subrr normr0 ltW// !divr_gt0. + near: t'. + move/cvgrPdist_le : lc => /( _ (e/ 2/ 2)). + rewrite !divr_gt0// => /(_ isT)[e1 e10 eh]. + by exists e1 => // => x ae1x /andP [xa _]; exact: eh. + * rewrite distrC. + rewrite mem_setE in t'ab. + move: (t') t'ab. + near: f. + by apply lim_fun_cvg_uniform; rewrite !divr_gt0. + - near=> t' => t'ab. + rewrite -(subrKA (f t) (lim_fun FF Fc t)). + rewrite (le_trans (ler_normD _ _))// (splitr e) lerD//. + move: (t) tab. + near: f. + by apply: lim_fun_cvg_uniform => //; rewrite divr_gt0. + rewrite -(subrKA (f t') (f t)). + rewrite (le_trans (ler_normD _ _))// (splitr (e/2)) lerD//. + near: t'. + move /(_ _ tab') : mc => /cvgrPdist_le /=; apply. + by rewrite !divr_gt0. + rewrite distrC. + rewrite mem_setE in t'ab. + move: (t') t'ab. + near: f. + by apply: lim_fun_cvg_uniform; rewrite !divr_gt0. + - near=> t' => t'ab. + rewrite -(subrKA (f b) (lim_fun FF Fc b)). + rewrite (le_trans (ler_normD _ _))// (splitr e) lerD//. + by rewrite lim_fune2// bound_itvE ltW. + rewrite -(subrKA (f t') (f b)). + rewrite (le_trans (ler_normD _ _))// (splitr (e / 2)) lerD//. + move: t'ab. + rewrite -{1}setUitv1/=; last by rewrite bnd_simp ltW. + rewrite inE/= in_itv/= => -[ | -> ]; last first. + by rewrite subrr normr0 ltW// !divr_gt0. + near: t'. + move/cvgrPdist_le : rc => /( _ (e / 2 / 2)). + rewrite !divr_gt0// => /(_ isT)[e1 e10 eh]. + by exists e1 => // x be1x /andP [_ xb]; exact: eh. + rewrite distrC. + rewrite mem_setE in t'ab. + move: (t') t'ab. + near: f. + by apply: lim_fun_cvg_uniform; rewrite !divr_gt0. +apply/continuous_within_itvP => //; split. +- move=> t tab; apply/cvgrPdist_le => /= e e0. + near=> t'. + have : t' \in `[a, b]. + rewrite inE; apply: subset_itv_oo_cc. + by near: t'; exact/at_right_in_segment/open_itvcc_subset. + near: t'. + apply: H => //. + by rewrite inE; exact: subset_itv_oo_cc. +- apply/cvgrPdist_le => /= e e0. + near=> t'. + have : t' \in `[a,b]. + rewrite inE/= in_itv/=. + by apply/andP; split; near: t'; [exact: nbhs_right_ge|exact: nbhs_right_le]. + near: t'. + apply/(cvg_at_right_filter cvg_id)/H => //. + by rewrite bound_itvE// ltW. +- apply/cvgrPdist_le => /= e e0. + near=> t'. + have : t' \in `[a,b]. + rewrite inE /= in_itv/=. + by apply/andP; split; near: t'; [exact: nbhs_left_ge|exact: nbhs_left_le]. + near: t'. + apply/(cvg_at_left_filter cvg_id)/H => //. + by rewrite bound_itvE/= ltW. +Unshelve. all: by end_near. Qed. + +HB.instance Definition _ F FF Fc := + isContinuous.Build (subspace `[a, b]) W + (@lim_fun F FF Fc : subspace `[a, b] -> W) (@lim_fun_cont F FF Fc). + +Fail Check (V : completeType). + +Lemma cvg_V_entourageP (F : set_system `C([a, b] W)) (FF : Filter F) (f : `C[a, b]) : + F --> f <-> forall A, entourage A -> + \forall g \near F, {in `[a, b]%R, forall t : R, A (f t, (g : `C[a, b]) t)}. +Proof. +split => [/cvg_entourageP /= Ff A|/=Ff]. + rewrite -entourage_ballE => -[eps eps0 /= H]. + apply: (Ff [set fg : `C[a, b] * `C[a, b] | + {in `[a, b]%R, forall t : R, A (fg.1 t, fg.2 t)}]). + exists eps => //. + rewrite /pseudoMetric_from_normedZmodType.ball /=. + move=> /= x bx t tab. + apply: H => /=. + rewrite -ball_normE /ball/=. + rewrite -quot_contSeg_fctB//. + exact: infty_norm_lt. +apply/cvg_entourageP => /= A [e e0 sPA]. +have e20 : 0 < e / 2 by rewrite divr_gt0. +have e2 : e / 2 < e by rewrite gtr_pMr// invf_lt1// ltr1n. +near=> g. +apply: sPA => /=. +apply/le_lt_trans/e2. +apply/infty_norm_le2; first exact: ltW. +move => //= t tab. +rewrite quot_contSeg_fctB// ltW//. +suff: ball (f t) (e / 2) (g t) by rewrite -ball_normE. +move: t tab. +near: g. +exact: (Ff [set xy : W * W | ball xy.1 (PosNum e20)%:num xy.2] (entourage_ball _ _)). +Unshelve. all: by end_near. Qed. + +Lemma quot_cont_on_segType_cauchy_cvg (F : set_system `C([a, b] W)) : + ProperFilter F -> cauchy F -> cvg F. +Proof. +move=> FF Fc. +have /(_ _ _)/cauchy_cvg/cvg_app_entourageP cvF : + forall t, t \in `[a, b]%R -> + cauchy (fmap (fun h : `C[a, b] => h t) (fun A : set `C[a, b] => nbhs F (fun g => A g))). + move=> t tab A/=. + rewrite -entourage_ballE => -[e e0 ee]; rewrite near_simpl -near2E near_map2. + apply: Fc. + exists e => //= -[f g]. + move/infty_norm_lt => h. + apply: ee => /=. + rewrite -ball_normE /ball_/=. + by rewrite -quot_contSeg_fctB// h. +apply/cvg_ex; exists (pi `C[a, b] (@lim_fun F FF Fc : continuousFunType `[a, b] [set: W])). +apply/cvg_V_entourageP => /=. +move=> A /= entA. +near=> f. +move=> t tab. +near F => g. +apply: (entourage_split (g t)) => //. + by rewrite eval_mod_on_itv => //; first by near: g; exact: cvF. +move: (t) (tab); near: g; near: f; apply: nearP_dep; apply: Fc. +rewrite /nbhs /=. +have := entourage_split_ent entA. +rewrite -entourage_ballE => -[e e0 ee]. +rewrite -entourage_ballE. +exists e => // -[/= f1 f2]. +move/infty_norm_lt => h t tab. +apply: ee => /=. +rewrite -ball_normE /ball_ /=. +rewrite distrC. +by rewrite -quot_contSeg_fctB// h. +Unshelve. all: by end_near. Qed. + +HB.instance Definition _ := Uniform_isComplete.Build `C[a, b] + quot_cont_on_segType_cauchy_cvg. + +Check (`C[a, b] : completeType). +End completeness. diff --git a/pendulum.v b/pendulum.v new file mode 100644 index 00000000..9974b933 --- /dev/null +++ b/pendulum.v @@ -0,0 +1,1011 @@ +(* LaSalle (c) 2025 Inria and AIST. Licence: CeCILL-C. *) +(* -------------------------------------------------------------------------- *) +(* Copyright (c) - 2017 -- 2019 Inria *) +(* -------------------------------------------------------------------------- *) +From HB Require Import structures. +From mathcomp Require Import ssreflect ssrfun ssrbool ssrnat eqtype choice seq. +From mathcomp Require Import order interval_inference. +From mathcomp Require Import fintype bigop ssralg ssrnum finmap interval ssrint. +From mathcomp Require Import matrix zmodp ring. +From mathcomp Require Import mathcomp_extra. +From mathcomp Require Import boolp reals classical_sets functions. +From mathcomp Require Import topology normedtype prodnormedzmodule landau derive. +Require Import lasalle. + +Set Implicit Arguments. +Unset Strict Implicit. +Unset Printing Implicit Defensive. +Import GRing.Theory Num.Def Num.Theory Order.POrderTheory Order.TotalTheory. + +Import numFieldTopology.Exports. + +Local Open Scope classical_set_scope. +Local Open Scope ring_scope. + +Notation "p ..[ i ]" := (p 0 (inZp i)) (at level 10). + +Lemma poly2_factor {R : realType} (a b c x : R) : + a != 0 -> a * (x ^+ 2) + b * x + c = 0 -> + x = (- b + Num.sqrt (b ^+ 2 - 4%:R * a * c)) / (2 * a) \/ + x = (- b - Num.sqrt (b ^+ 2 - 4%:R * a * c)) / (2 * a). +Proof. +move=> ane0 xroot. +set dlt := b ^+ 2 - 4%:R * a * c. +set x1 := (- b + Num.sqrt dlt) / (2 * a). +set x2 := (- b - Num.sqrt dlt) / (2 * a). +suff poly_fact : a * (x ^+ 2) + b * x + c = a * (x - x1) * (x - x2). + move: xroot; rewrite poly_fact => /eqP; rewrite mulf_eq0 => /orP []. + by rewrite mulrI_eq0; [rewrite subr_eq0 => /eqP->; left|apply/lregP]. + by rewrite subr_eq0 => /eqP->; right. +rewrite /x1 /x2; case: (lerP 0 dlt) => [dltge0|dltlt0]. + rewrite -mulrA mulrBr mulrBl mulrBl opprB addrA [(x * x + _) + _]addrAC. + rewrite [_ / _ * x]mulrC. + rewrite -[in RHS](addrA (x * x + _)). + rewrite -(opprD (x * _)). + rewrite -mulrDr. + rewrite -mulrDl. + rewrite addrCA -[- b + _ - _]addrA subrr addr0 -mul2r. + rewrite invrM ?unitfE // [2 * _ * _]mulrC !mulrA mulfVK//. + rewrite addrAC mulrN opprK !mulrDr mulrA [a * (x / _ * _)]mulrCA !mulrA. + rewrite mulfVK// [b * _]mulrC; congr (_ + _ + _). + rewrite [a * _]mulrC -[_ * a * _]mulrA mulfV // mulr1. + rewrite ![_ * - _]mulrC !mulrA !mulrDr -!mulrDl !mulrN !mulNr !opprK. + rewrite [_ * Num.sqrt _]mulrC -addrA addKr -!expr2 sqr_sqrtr // /dlt. + rewrite opprD addrA subrr opprK add0r -mulrA -invrM ?unitfE //. + rewrite (_ : 4 = 2 * 2); last by rewrite -natrM. + rewrite mulrC !mulrA mulVf ?mul1r// (mulrC _ c) -mulrA divff ?mulr1//. + by rewrite mulf_eq0 negb_or ane0 pnatr_eq0. +move: xroot; have -> : a * (x ^+ 2) + b * x + c = + a * ((x + b / (2 * a)) ^+ 2) + (c - b ^+ 2 / (4%:R * a)). + rewrite [in RHS]expr2 -mulrA mulrDr mulrDl [c - _]addrC addrA !mulrDr. + rewrite -[_ - _]addrA -[a * _ + _ + _ in RHS]addrA; congr (_ + _ + _). + rewrite addrA [(x + _) * _]mulrDl mulrDr addrA -mulrDr [x * _]mulrC -mulrDl. + rewrite -[LHS]addr0 -addrA; congr (_ + _). + rewrite mulrA; congr (_ * _); rewrite -mulrDl invrM ?unitfE //. + rewrite mulrC -mulrA [_ * a]mulrC mulVKr ?unitfE // mulrDl. + exact: splitr. + rewrite !mulrA [a * _]mulrC -[b * a / _]mulrA invrM ?unitfE //. + rewrite mulVKr ?unitfE // [b / _ * _]mulrAC -[_ / 2 * _]mulrA -mulrBr. + rewrite [_^-1 * _]mulrCA invrM ?unitfE // -mulrBr -invrM ?unitfE //. + by rewrite -natrM subrr !mulr0. +suff : a * (x + b / (2 * a)) ^+ 2 + (c - b ^+ 2 / (4%:R * a)) != 0. + by move=> pn0 p0; move: pn0; rewrite p0 eq_refl. +have := ane0; rewrite neq_lt => /orP [alt0|agt0]; last first. + apply:lt0r_neq0; rewrite ltr_wpDl //; first by rewrite pmulr_rge0 // sqr_ge0. + rewrite subr_gt0 ltr_pdivrMr; last by rewrite pmulr_rgt0. + by rewrite mulrC -subr_lt0. +rewrite -oppr_eq0 opprD; apply: lt0r_neq0; rewrite ltr_wpDl //. + by rewrite oppr_ge0 nmulr_rle0 // sqr_ge0. +rewrite oppr_gt0 subr_lt0 ltr_ndivlMr; last by rewrite mulrC nmulr_rlt0. +by rewrite mulrC -subr_lt0. +Qed. + +Lemma deriveE' {R : realType} (V W : normedModType R) (f : V -> W) x v : + derive f x v = derive (fun h : R^o => f (h *: v + x)) 0 1. +Proof. +rewrite /derive. +set g1 := fun h => h^-1 *: _; set g2 := fun h => h^-1 *: _. +suff -> : g1 = g2 by []. +by rewrite funeqE /g1 /g2 => h /=; rewrite addr0 scale0r add0r [_%:A]mulr1. +Qed. + +Lemma bounded_poly {R : realType} (a b c d : R) : + 0 < a -> \forall M \near +oo, forall x, + a * (x ^+ 2) - (b * `|x|) - c < d -> `|x| < M. +Proof. +move=> agt0. +suff ptoinfty : (fun x => a * (x ^+ 2) - (b * `|x|) - c) @ +oo --> +oo. + have dleatinfty : +oo (>= d). + exists d; split => //. + by rewrite num_real. + by move=> // ? /ltW. + have /ptoinfty [M1 [M1real sgtM1pged]] := dleatinfty; near=> M. + move=> x pxltd; rewrite ltNge; apply/negP => Mlex. + move: pxltd; rewrite ltNge => /negP; apply. + rewrite -(@ger0_norm _ `|x|) // -(@ger0_norm _ (_ ^+ 2)) ?sqr_ge0 // normrX. + by apply: sgtM1pged; apply: lt_le_trans Mlex; near: M; exists M1. +move=> A [M [Mreal sgtMA]]; rewrite !near_simpl; near=> x. +have lt0x : 0 < x by []. +rewrite ger0_norm ?ltW //; apply: sgtMA. +rewrite ltrBrDr expr2 mulrA -mulrBl; apply: le_lt_trans (ler_norm _) _. +rewrite -[ `|_|%R]sqr_sqrtr // expr2; apply: ltr_pM; last 1 first. +- by near: x; exists (Num.sqrt `|M + c|); split => //. +- exact: sqrtr_ge0. +- exact: sqrtr_ge0. +rewrite ltrBrDr -ltr_pdivrMl //; near: x. +exists (a^-1 * (Num.sqrt `|M + c| + b)); split => //. +rewrite realM//. + by rewrite realV// num_real. +by rewrite realD// num_real. +Unshelve. all: by end_near. Qed. + +(* TODO: generalize *) +Lemma eq0_derive1_cst {R : realType} (f : R^o -> R^o) (a b : R) : + (forall t, t \in `[a, b] -> is_derive (t : R^o) 1 f 0) -> + forall t, t \in `[a, b] -> f t = f a. +Proof. +move=> f'eq0 t tab; apply/eqP; rewrite eq_le; apply/andP; split. + apply: (@ler0_derive1_le_cc _ _ a b) => //; rewrite ?(itvP tab) //;[ + by move=> x /subset_itv_oo_cc /f'eq0 // df; rewrite derive1E derive_val..|]. + apply: continuous_in_subspaceT => x. + rewrite inE/= => /f'eq0. + move=> /(@ex_derive _ [the normedModType R of R^o]). + move=> /derivable1_diffP /differentiable_continuous. + exact. +apply: (@ger0_derive1_ndecr _ _ a b) => //; rewrite ?(itvP tab) //;[ + by move=> x /subset_itv_oo_cc /f'eq0 // df; rewrite derive1E derive_val..|]. +apply: continuous_in_subspaceT => x. +rewrite inE/= => /f'eq0. +move=> /(@ex_derive _ [the normedModType R of R^o]). +move=> /derivable1_diffP /differentiable_continuous. +exact. +Qed. + +Lemma is_derive_nneg_eq {R : realType} (f h : R^o -> R^o) (t : R^o) l1 l2 : + (forall t, 0 <= t -> f t = h t) -> 0 <= t -> + is_derive t 1 f l1 -> is_derive t 1 h l2 -> l1 = l2. +Proof. +move=> feg tge0 df dh. +have /@derive_val <- := df; have /@derive_val <- := dh. +apply: subr0_eq; rewrite -deriveB // /derive cvg_at_rightE; last first. + by rewrite -[cvg _]/(derivable _ _ _). +apply: cvg_lim => A A0. + by rewrite -closeEnbhs norm_closeE. +rewrite !near_simpl; near=> r. +rewrite /= -![(_ - _ : _ -> _) _]/(_ - _) !feg //. + by rewrite !subrr scaler0; apply: nbhs_singleton. +by rewrite addr_ge0 // [_%:A]mulr1 ltW //; near: h; exists 1. +Unshelve. all: by end_near. Qed. + +Section System. +Context {R : realType}. +Variable m M l g : {posnum R}. + +Variable ke kv kx kd : {posnum R}. + +Notation U := 'rV[R]_5. + +(* p = (x, x', cos theta, sin theta, theta') *) +Definition E (p : U) := + (1 / 2) * ((M%:num + m%:num) * (p..[1] ^+ 2) + + m%:num * (l%:num ^+ 2) * (p..[4] ^+ 2)) + + m%:num * l%:num * p..[1] * p..[2] * p..[4] + + m%:num * l%:num * g%:num * (p..[2] - 1). + +Definition fctrl (p : U) := + (kv%:num * m%:num * p..[3] * (g%:num * p..[2] - l%:num * (p..[4] ^+ 2)) - + (M%:num + m%:num * (p..[3] ^+ 2)) * (kx%:num * p..[0] + kd%:num * p..[1])) / + (kv%:num + (M%:num + m%:num * (p..[3] ^+ 2)) * ke%:num * (E p)). + +Definition Fpendulum (p : U) : U := + \row_(i < 5) nth 0 + [:: p..[1] + ; ((m%:num * p..[3] * (l%:num * (p..[4] ^+ 2) - g%:num * p..[2]) + + (fctrl p)) / (M%:num + m%:num * (p..[3] ^+ 2))) + ; - p..[3] * p..[4] + ; p..[2] * p..[4] + ; (((M%:num + m%:num) * g%:num * p..[3] - + p..[2] * (m%:num * l%:num * (p..[4] ^+ 2) * p..[3] + (fctrl p))) / + (l%:num * (M%:num + m%:num * (p..[3] ^+ 2))))] i. + +Definition V (p : U) := + (ke%:num / 2) * ((E p) ^+ 2) + (kv%:num / 2) * (p..[1] ^+ 2) + + (kx%:num / 2) * (p..[0] ^+ 2). + +Global Instance is_diff_component n i (p : 'rV[R]_n.+1) : + is_diff p (fun q => q..[i] : R^o) (fun q => q..[i]). +Proof. +have comp_lin : linear (fun q : 'rV[R]_n.+1 => q..[i] : R^o). + by move=> ???; rewrite !mxE. +have comp_cont : continuous (fun q : 'rV[R]_n.+1 => q..[i] : R^o). + move=> q A [_/posnumP[e] Ae] /=; apply/nbhs_ballP; exists e%:num => //=. + by move=> r [e0] /(_ ord0) /(_ (inZp i)) /Ae. +pose glM := GRing.isLinear.Build _ _ _ _ _ comp_lin. +pose gL : {linear 'rV_n.+1 -> R^o} := HB.pack (fun q : 'rV_n.+1 => q ..[ i]) glM. +apply: DiffDef; first exact: (@linear_differentiable _ _ _ gL). +by rewrite (@diff_lin _ _ _ gL). +Qed. + +Global Instance is_diff_component_comp (V : normedModType R) n + (f : V -> 'rV[R]_n.+1) i p df : is_diff p f df -> + is_diff p (fun q => (f q)..[i] : R^o) (fun q => (df q)..[i]). +Proof. +move=> dfp. +have -> : (fun q => (f q)..[i]) = (fun v => v..[i]) \o f by rewrite funeqE. +(* This should work *) +(* apply: is_diff_eq. *) +exact: is_diff_comp. +Qed. + +Global Instance is_derive_component (V : normedModType R) n + (f : V -> 'rV[R]_n.+1) i x v df : + is_derive x v f df -> is_derive x v (fun q => (f q)..[i] : R^o) (df..[i]). +Proof. +move=> dfx. +have diff_f : is_diff (0 : [the normedModType _ of R^o]) (fun h => f (h *: v + x)) ( *:%R^~ df ). + have /derivable1P/derivable1_diffP fdrvbl : derivable f x v by []. + by apply: DiffDef => //; rewrite diff1E // derive1E -deriveE' derive_val. +apply: DeriveDef; first exact/derivable1P/derivable1_diffP. +by rewrite deriveE' deriveE // diff_val scale1r. +Qed. + +Lemma V_continuous : continuous V. +Proof. +by move=> ?; apply: (@differentiable_continuous _ _ R^o). +Qed. + +Variable k0 : R. +Let B := ke%:num * ((minr (kv%:num / (ke%:num * (M%:num + m%:num))) + (2 * m%:num * g%:num * l%:num)) ^+ 2) / 2. +(* restriction to make fctrl smooth *) +Hypothesis k0_valid : k0 < B. + +Definition K : set U := + [set p : U | (p..[2] ^+ 2) + (p..[3] ^+ 2) = 1 /\ V p <= k0]. + +Lemma expr_continuous n : continuous (fun x : R^o => x ^+ n.+1 : R^o). +Proof. +move=> x; suff : differentiable (fun y : R^o => y ^+ n.+1) x. + by apply: differentiable_continuous. +suff -> : (fun y => y ^+ n.+1) = ((id : R^o -> R^o) ^+ n.+1) by []. +by rewrite exprfctE. +Qed. + +Lemma circle_closed : closed [set p : U | p..[2] ^+ 2 + p..[3] ^+ 2 = 1]. +Proof. +move=> p clcircp. +apply/close_eq => //=; first exact: Rhausdorff. +rewrite (@ball_close _ R^o) => e /=. +have : nbhs (p ..[ 2] ^+ 2) (ball (p ..[ 2] ^+ 2) ((e%:num / 2)%:pos)%:num). + by apply: nbhsx_ballx. +move=> /expr_continuous [_/posnumP[e1] p2e1_sp2he]. +have : nbhs (p ..[ 3] ^+ 2) (ball (p ..[ 3] ^+ 2) ((e%:num / 2)%:pos)%:num). + by apply: nbhsx_ballx. +move=> /expr_continuous [_ /posnumP[e2] p3e2_sp3he]. +have [q [circq [e0 pme12_q]]] : + [set p : U | p..[2] ^+ 2 + p..[3] ^+ 2 = 1] `&` + ball p (minr e1%:num e2%:num) !=set0. + apply/clcircp. + rewrite /minr. + by case: ifPn => // ?; apply/nbhsx_ballx. +rewrite -circq. +rewrite /ball/=. +rewrite opprD addrACA; apply: le_lt_trans (ler_normD _ _) _. +by rewrite (splitr e%:num) ltrD //; [apply/p2e1_sp2he|apply/p3e2_sp3he]; + apply: le_ball (pme12_q _ _); rewrite ge_min lexx // orbC. +Qed. + +Lemma preimV_lek0_closed : closed (V @^-1` (<= k0 : _ -> _)). +Proof. +by apply: closed_comp; [move=> ??; apply: V_continuous|apply: closed_le]. +Qed. + +Lemma K_closed : closed K. +Proof. exact: closedI circle_closed preimV_lek0_closed. Qed. + +Lemma K_bounded : bounded_set K. +Proof. +suff : \forall M \near +oo, forall p, K p -> forall i, `|p ord0 i| < M. + rewrite /bounded_set; apply: filter_app; near=> M0. + move=> Kbnd /= p /Kbnd ltpM0. + rewrite /normr/=. + rewrite mx_normrE. + apply/bigmax_leP; split => //= i _. + rewrite ord1. + exact/ltW/ltpM0. +suff : \forall M \near +oo, forall p, K p -> `| p..[0] | < M /\ + `| p..[1] | < M /\ `| p..[2] | < M /\ `| p..[3] | < M /\ `| p..[4] | < M. + apply: filter_app; near=> M0. + move=> Kbnd p /Kbnd [ltp0M [ltp1M [ltp2M [ltp3M ltp4M]]]]. + case; do 5 ?[case; first by move=> ?; rewrite -[ Ordinal _ ]natr_Zp Zp_nat]. + by move=> n ?; suff : (n.+1.+4 < 5)%N by rewrite !ltnS ltn0. +have K1bnd : \forall M \near +oo, forall p, K p -> `| p..[1] | < M. + near=> M0 => p [_ Vps]. + suff /lt_trans : `| p..[1] | < Num.sqrt (2 * B / kv%:num). + by apply; near: M0; exists (Num.sqrt (2 * B / kv%:num)); split => //. + rewrite -sqrtr_sqr ltr_sqrt // mulrAC -ltr_pdivrMl // invf_div; last first. + by rewrite mulr0 /B/=. + apply: le_lt_trans k0_valid; apply: le_trans Vps. + by rewrite [V _]addrAC lerDr addr_ge0 // pmulr_rge0 // sqr_ge0. +apply: filter_app (K1bnd); near=> M0. +move=> K1ltM p Kp; have [circp Vps] := Kp; split. + suff /lt_trans : `| p..[0] | < Num.sqrt (2 * B / kx%:num). + by apply; near: M0; exists (Num.sqrt (2 * B / kx%:num)); split => //. + rewrite -sqrtr_sqr ltr_sqrt // mulrAC -ltr_pdivrMl // invf_div; last first. + by rewrite mulr0 /B. + apply: le_lt_trans k0_valid; apply: le_trans Vps. + by rewrite lerDr addr_ge0 // pmulr_rge0 // sqr_ge0. +split; first exact: K1ltM; split. + suff /le_lt_trans : `| p..[2] | <= 1. + apply. + by near: M0; exists 1. + by rewrite -sqrtr_sqr -sqrtr1 ler_sqrt // -circp lerDl sqr_ge0. +split. + suff /le_lt_trans : `| p..[3] | <= 1. + apply. + by near: M0; exists 1. + by rewrite -sqrtr_sqr -sqrtr1 ler_sqrt // -circp lerDr sqr_ge0. +move: p Kp {circp Vps}; near: M0; rewrite /= !near_simpl. +have [M1 [M1real sgtM1gtK1]] := K1bnd. +have := bounded_poly (m%:num * l%:num * ((`|M1| + 1) ^+ 2)) + (m%:num * l%:num * g%:num * ((`|M1| + 1) + 1)) (Num.sqrt (2 * B / ke%:num)) + [gt0 of m%:num * (l%:num ^+ 2) / 2]. +apply: filter_app; near=> M0 => sEsltM0 p Kp; have [circp Vps] := Kp. +apply: sEsltM0. +have : E p < Num.sqrt (2 * B / ke%:num). + apply: le_lt_trans (ler_norm _) _. + rewrite -sqrtr_sqr ltr_sqrt // mulrAC -ltr_pdivrMl // invf_div; last first. + by rewrite mulr0 /B. + apply: le_lt_trans k0_valid; apply: le_trans Vps. + by rewrite -[V _]addrA lerDl addr_ge0 // pmulr_rge0 // sqr_ge0. +apply: le_lt_trans; apply: lerD; last first. + rewrite -mulrN opprD ler_wpM2l //. + rewrite lerD2r lerNl. + rewrite ler_wpDl // (le_trans (ler_norm _)) // normrN. + rewrite -sqrtr_sqr. + by rewrite -sqrtr1 ler_sqrt // -circp lerDl sqr_ge0. +rewrite mulrDr [1 / 2 * _ + _]addrC -addrA [1 / 2 * _]mulrCA mul1r mulrA. +rewrite /=. +rewrite (expr2 l%:num) lerD2l; apply: ler_wpDl. + by rewrite pmulr_rge0 // pmulr_rge0 // sqr_ge0. +rewrite -mulrN -!mulrA ler_wpM2l // ler_wpM2l // !mulrN lerNl. +suff : `| p..[1] | * (`| p..[2] | * `| p..[4] |) <= + (`|M1| + 1) * ((`|M1| + 1) * `| p..[4] |). + by apply: le_trans; rewrite -!normrM -normrN ler_norm. +rewrite !mulrA ler_wpM2r // ler_pM //. + apply/ltW/sgtM1gtK1 => //; apply: le_lt_trans (ler_norm _) _. + by rewrite ltrDl. +have /(le_trans _) : 1 <= `|M1| + 1 by rewrite lerDr. +by apply; rewrite -sqrtr_sqr -sqrtr1 ler_sqrt // -circp lerDl sqr_ge0. +Unshelve. all: by end_near. Qed. + +Lemma K_compact : compact K. +Proof. exact: bounded_closed_compact K_bounded K_closed. Qed. + +Lemma Mp_ms_gt0 (p : U) : 0 < M%:num + m%:num * (p..[3] ^+ 2). +Proof. by rewrite ltr_pwDl // pmulr_rge0 // sqr_ge0. Qed. + +Lemma E_small p : V p < B -> `|E p| < kv%:num / (ke%:num * (M%:num + m%:num)). +Proof. +move=> Vp_s; rewrite -ltr_sqr ?nnegrE // -normrX ger0_norm ?sqr_ge0 //. +suff : 2 * (V p) / ke%:num < (kv%:num / (ke%:num * (M%:num + m%:num))) ^+ 2. + apply: le_lt_trans. + rewrite ler_pdivlMr // -ler_pdivrMl // mulrC -mulrA mulrC. + by rewrite /V -addrA lerDl addr_ge0 // pmulr_rge0 // sqr_ge0. +rewrite ltr_pdivrMr // mulrC -ltr_pdivlMr // (lt_le_trans Vp_s) //. +rewrite -mulrA mulrCA mulrA; apply: ler_pM => //; apply: ler_pM => //. +rewrite lerXn2r// ?nnegrE//. +by rewrite ge_min/= lexx. +Qed. + +Lemma fctrl_wdef (p : U) : (p..[2] ^+ 2) + (p..[3] ^+ 2) = 1 -> V p < B -> + kv%:num + (M%:num + m%:num * (p..[3] ^+ 2)) * ke%:num * (E p) != 0. +Proof. +move=> circp Vp_s; rewrite -normr_gt0. +rewrite -[X in X + _](@mulfVK _ ((M%:num + m%:num * (p..[3] ^+ 2)) * ke%:num)); + last by rewrite lt0r_neq0 // pmulr_rgt0 // Mp_ms_gt0. +rewrite mulrC -mulrDr normrM pmulr_rgt0; last first. + by rewrite normrM pmulr_rgt0 gtr0_norm // Mp_ms_gt0. +apply: lt_le_trans (lerB_normD _ _). +rewrite subr_gt0; apply: lt_le_trans (E_small Vp_s) _. +rewrite ger0_norm; last first. + by rewrite pmulr_rge0 // invr_ge0 pmulr_rge0 // Mp_ms_gt0. +rewrite ler_pM // lef_pV2 ?posrE //; last by rewrite pmulr_rgt0 // Mp_ms_gt0. +rewrite mulrC ler_pM //; first exact/ltW/Mp_ms_gt0. +rewrite lerD2l -{2}[m%:num]mulr1 ler_pM // ?sqr_ge0 //. +by rewrite -circp lerDr sqr_ge0. +Qed. + +(* TODO: show that Fpendulum is smooth in K and remove these hypotheses using + Cauchy-Lipschitz *) +Variable sol : U -> R -> U. +Hypothesis (sol0 : forall p, sol p 0 = p). +Hypothesis solP : forall y, K (y 0) -> is_sol Fpendulum y <-> y = sol (y 0). +Hypothesis sol_cont : forall t, {within K, continuous (sol^~ t)}. + +Lemma circ_invar p : + K p -> forall t, 0 <= t -> (sol p t)..[2] ^+ 2 + (sol p t)..[3] ^+ 2 = 1. +Proof. +move=> Kp /= t tge0; have [circp _] := Kp; rewrite -circp -[in RHS](sol0 p). +pose f s := (sol p s)..[2] ^+ 2 + (sol p s)..[3] ^+ 2; rewrite -!/(f _). +(* BUG in unification *) +apply (@eq0_derive1_cst R (f : R^o -> R^o) 0 t); last first. + by rewrite in_itv/= lexx tge0. +move=> s s0t; have sge0 : s >= 0 by rewrite (itvP s0t). +have [_ /(_ _ sge0) dsol] := sol_is_sol sol0 solP Kp. +apply: is_derive_eq. +rewrite 2!mxE/=. +rewrite /GRing.scale/=. +rewrite mulrCA. +by rewrite -!mulrDr addrC mulNr subrr. +Qed. + +Lemma is_derive_Esol p t : + K p -> 0 <= t -> is_derive (t : R^o) 1 (E \o (sol p) : _ -> R^o) + ((sol p t)..[1] * fctrl (sol p t)). +Proof. +move=> Kp tge0; have [_ /(_ _ tge0) sol_att] := sol_is_sol sol0 solP Kp. +apply: is_derive_eq. +have /eqP : (sol p t)..[2] ^+ 2 + (sol p t)..[3] ^+ 2 = 1 by apply: circ_invar. +rewrite eq_sym addrC -subr_eq => /eqP circp. +have Mpmsne0 : M%:num + m%:num * (sol p t)..[3] ^+ 2 != 0. + by rewrite lt0r_neq0 // Mp_ms_gt0. +rewrite subr0 !mxE /= -circp -![_ *: _]/(_ * _) invrM ?unitfE //; last first. + by rewrite circp. +set q := sol _ _ _; set x := (M%:num + m%:num * _)^-1; set y := fctrl _. +rewrite [x / _]mulrC; do ![rewrite ?[_ * (_ * x)]mulrA -?(mulrDl _ _ x)]. +rewrite [_ * (_ + _ * x)]mulrDr [_ * (_ * x)]mulrA [_ + _ * x]addrC. +do 2 rewrite addrA -(mulrDl _ _ x). +rewrite -!mul2r mul1r mulrDr; do 2 rewrite [2^-1 * _]mulrCA. +do 2 rewrite [2^-1 * _]mulrA mulVf // mul1r. +rewrite [_ / _]mulrC. +rewrite ![_ * (_^-1 * _)]mulrA. +rewrite [_ * (_ / _ * _)]mulrA. +rewrite -(addrA ((M%:num + m%:num) * + (q (inZp 1) * + (m%:num * q (inZp 3) * (l%:num * q (inZp 4) ^+ 2 - g%:num * q (inZp 2)) + y)))). +rewrite -mulrDl. +rewrite [in _ * x]addrAC ![_ * (_ * (_ + _))]mulrA -mulrDl. +rewrite -addrA [_ * (_ * (- _ * _))]mulrA -mulrDl. +apply/(canLR (subrK _))/(canLR (mulfK _)); first by rewrite circp. +rewrite [RHS]mulrDl !mulNr [in RHS]mulrAC; apply: (canRL (addrK _)). +rewrite [(_ + _) * _]mulrDr addrAC [_ + _ * y + _]addrAC. +by field; rewrite gt_eqF. +(* this used to work with MathComp 2.4.0: +apply: (canLR (subrK _)); rewrite -mulrBl [_ * (_ + y)]mulrDr opprD addrA. +rewrite [_ * (_ - _ * y)]mulrDr addrA -[- (_ * y)]mulNr [_ * (_ * y)]mulrA. +rewrite [_ + _ * y + _]addrAC; apply: (canLR (subrK _)); rewrite -mulrBl. +rewrite [in RHS]mulrN opprK mulrACA [_ ^+2 / _]mulrAC mulfVK//. +rewrite [_ / _]mulrC ![_^-1 * _]mulrA [_^-1 * _ * _]mulrC mulVKf//. +ring. +*) +Qed. + +Lemma is_deriv_Vsol p t : + K p -> 0 <= t -> V (sol p t) < B -> + is_derive (t : R^o) 1 (V \o (sol p) : _ -> R^o) + (- kd%:num * ((sol p t)..[1] ^+ 2)). +Proof. +move=> Kp tge0 Vsolpt_s. +have [_ /(_ _ tge0) sol_att] := sol_is_sol sol0 solP Kp. +have Esol' := is_derive_Esol Kp tge0; apply: is_derive_eq. +rewrite [in X in _ + X]mxE /= -!mul2r -![_ *: _]/(_ * _). +do 3 rewrite [_ / _]mulrC [_^-1 * _ * _]mulrCA -[_ ^-1 * _ * _]mulrA mulVKf //. +rewrite [_ * fctrl _]mulrC [_ * Fpendulum _ _ _]mulrC mulrA mulrA -addrA. +rewrite ![in X in _ + X]mulrA -!mulrDl expr2 [RHS]mulrA; congr (_ * _). +rewrite addrA mxE /=. +have Mpmsne0 : M%:num + m%:num * (sol p t)..[3] ^+ 2 != 0. + by rewrite lt0r_neq0 // Mp_ms_gt0. +apply: (canLR (subrK _)); rewrite [kv%:num * _]mulrA. +rewrite -[_ * fctrl _](mulfVK Mpmsne0) [_ / _ * _]mulrAC -mulrDl. +apply: (canLR (mulfK _)) => //; rewrite [kv%:num * _]mulrDr addrA addrAC. +apply: (canLR (subrK _)); rewrite mulrAC -mulrDl /fctrl [LHS]mulrA. +have circp : (sol p t)..[2] ^+ 2 + (sol p t)..[3] ^+ 2 = 1 by apply: circ_invar. +have ? := fctrl_wdef circp Vsolpt_s; apply: (canLR (mulfK _)) => //. +ring. +Qed. + +Lemma defset_invar p : K p -> forall t, 0 <= t -> + (sol p t)..[2] ^+ 2 + (sol p t)..[3] ^+ 2 = 1 /\ V (sol p t) < B. +Proof. +move=> Kp t tge0; split; first exact: circ_invar. +set A := [set t | (0 <= t) && (B <= V (sol p t))]. +case: (pselect (nonempty A))=> [An0 |]; last first. + move=> /asboolPn /forallp_asboolPn /(_ t) /negP. + by move => /nandP []; + [rewrite tge0|rewrite -ltNge]. +have infA : has_inf A. + by split=> //; exists 0; apply/lbP => ? /andP []. +exfalso=> {t tge0}; have infge0 : 0 <= inf A. + by apply: lb_le_inf => //; apply/lbP => ? /andP []. +have Vsolp_drvbl t : 0 <= t -> derivable (V \o (sol p) : R^o -> R^o) t 1. + by move=> tge0; have [_ /(_ _ tge0) sol_att] := sol_is_sol sol0 solP Kp. +have Vsolpinf_geB : B <= V (sol p (inf A)). + case: (lerP B (V (sol p (inf A)))) => // Vsolpinf_ltB; rewrite falseE. + have Vsolp_cont : {for inf A, continuous (V \o (sol p))}. + suff /differentiable_continuous : + differentiable (V \o sol p : R^o -> R^o) (inf A) by []. + exact/derivable1_diffP/Vsolp_drvbl. + have BmVsolps_gt0 : 0 < B - V (sol p (inf A)) by rewrite subr_gt0. + have /Vsolp_cont := nbhsx_ballx (V (sol p (inf A))) _ BmVsolps_gt0. + move=> [_ /posnumP[e] /= infe_Vsolp]. + suff : inf A + e%:num / 2 <= inf A. + by rewrite leNgt => /negP; apply; rewrite ltrDl. + apply: lb_le_inf An0 _; apply/lbP => s /andP [sge0 Vsolps_geB]. + rewrite leNgt; apply/negP => ltsinfphe; have leinfs : inf A <= s. + apply: inf_lbound => //. + by case: infA. + by rewrite /A/= sge0 Vsolps_geB. + suff /infe_Vsolp : ball (inf A) e%:num s. + rewrite /ball/= distrC => /(le_lt_trans (ler_norm _)). + by rewrite ltNge => /negP; apply; rewrite lerB. + rewrite /ball/= distrC ger0_norm ?subr_ge0 // ltrBlDl. + by apply: lt_trans ltsinfphe _; rewrite ltrD2l {2}[e%:num]splitr ltrDl. +have Vsol_drvbl t : t \in `]0, (inf A)[ -> + is_derive (t : R^o) 1 (V \o sol p : _ -> R^o) + (- kd%:num * (sol p t)..[1] ^+ 2). + move=> t0inf; apply: is_deriv_Vsol => //; first by rewrite (itvP t0inf). + rewrite ltNge; apply/negP => Vsolpt_geB; suff : inf A <= t. + by rewrite leNgt => /negP; apply; rewrite (itvP t0inf). + apply: inf_lbound => //. + by case: infA. + apply/andP; split=> //. + by rewrite (itvP t0inf). +have : {in `[0, (inf A)]%classic, continuous (V \o sol p)}. + move=> t t0inf; suff /differentiable_continuous : + differentiable (V \o sol p : R^o -> R^o) t by []. + apply/derivable1_diffP/Vsolp_drvbl. + rewrite inE/= in t0inf. + by rewrite (itvP t0inf). +move/continuous_in_subspaceT. +move=> /(MVT_segment infge0)[t t0inf]. +rewrite /comp sol0 subr0 => dVsol. +have infgt0 : 0 < inf A. + rewrite lt_def; apply/andP; split=> //. + apply/negP => /eqP infA0; have := Vsolpinf_geB. + rewrite leNgt => /negP; apply; rewrite infA0 sol0. + by apply: le_lt_trans k0_valid; have [] := Kp. +have : V (sol p (inf A)) - V p <= 0. + by rewrite dVsol !mulNr oppr_le0 pmulr_lge0 // pmulr_rge0 // sqr_ge0. +rewrite leNgt => /negP; apply. +rewrite subr_gt0; apply: lt_le_trans Vsolpinf_geB. +by apply: le_lt_trans k0_valid; have [] := Kp. +Qed. + +Lemma is_derive_Vsol p (t : R^o) : + K p -> 0 <= t -> is_derive t 1 (V \o sol p : _ -> R^o) + (- kd%:num * (sol p t)..[1] ^+ 2). +Proof. +move=> Kp tge0; have [circpt Vpts] := defset_invar Kp tge0. +exact: is_deriv_Vsol. +Qed. + +Lemma Kinvar : is_invariant sol K. +Proof. +move=> p Kp t tge0; have [_ Vp_s] := Kp; split; first exact: circ_invar. +apply: le_trans Vp_s; rewrite -{2}[p]sol0. +have Vsol_deriv : forall s, s \in `[0, t] -> + is_derive (s : R^o) 1 (V \o sol p : _ -> R^o) + (- kd%:num * (sol p s)..[1] ^+ 2) by move=> s /andP [/(is_derive_Vsol Kp)]. +apply: (@ler0_derive1_le_cc _ (V \o sol p) 0 t);[| | | | |by []]. +- move=> x /subset_itv_oo_cc /Vsol_deriv. + by apply: (@ex_derive _ [the normedModType R of R^o]). +- move=> x /subset_itv_oo_cc /Vsol_deriv. + rewrite derive1E. + case => _ ->. + by rewrite mulr_le0_ge0// sqr_ge0. +- apply: continuous_in_subspaceT => x. + rewrite inE/= => /Vsol_deriv. + move=> /(@ex_derive _ [the normedModType R of R^o]). + move=> /derivable1_diffP /differentiable_continuous. + exact. +- by rewrite in_itv/= lexx tge0. +- by rewrite in_itv/= lexx tge0. +Qed. + +Definition homoclinic_orbit : set U := [set p : U | p..[0] = 0 /\ p..[1] = 0 /\ + (1 / 2) * m%:num * (l%:num ^+ 2) * (p..[4] ^+ 2) = + m%:num * g%:num * l%:num * (1 - p..[2])]. + +Lemma homoclinicE : + homoclinic_orbit = [set p : U | p..[0] = 0 /\ p..[1] = 0 /\ E p = 0]. +Proof. +rewrite predeqE => p; split. + move=> [p0eq0 [p1eq0 /eqP]]; rewrite -subr_eq0 => /eqP homoeq. + split=> //; split=> //; rewrite -homoeq /E p1eq0 expr0n /=. + rewrite !mulr0 !mul0r addr0 add0r mulrA [_ / _ * _]mulrA -mulrN opprB. + by rewrite [_ * _ * g%:num]mulrAC. +move=> [p0eq0 [p1eq0 Epeq0]]; split=> //; split=> //. +apply: subr0_eq. +rewrite -[RHS]Epeq0 /E p1eq0 expr0n /=. +rewrite !mulr0 !mul0r addr0 add0r [in RHS] mulrA [_ / _ * _ in RHS]mulrA -mulrN. +by rewrite opprB [_ * _ * g%:num]mulrAC. +Qed. + +Lemma limSKinvar : is_invariant sol (limS sol K). +Proof. +move=> p limSKp t tge0. +exact: (@invariant_limS _ _ _ _ K_compact _ sol0 solP sol_cont Kinvar). +Qed. + +Lemma subset_limSK_K : limS sol K `<=` K. +Proof. +move=> p [q Kq solq_top]. +apply: compact_closed (@norm_hausdorff _ _) K_compact _ _. +have solqK : (sol q @ +oo) K. + exists 0; split. + by rewrite real0. + by move=> ? /ltW; exact: Kinvar. +by move=> A /solq_top - /(_ _ solqK) [r []]; exists r. +Qed. + +Lemma Vsol'_eq0 p t : + limS sol K p -> 0 <= t -> derive1 (V \o sol p : _ -> R^o) t = 0. +Proof. +move=> limSKp tge0; have limSKsolp : limS sol K (sol p t) by apply: limSKinvar. +have Kp : K p by apply: subset_limSK_K. +have -> : derive1 (V \o sol p : _ -> R^o) t = + derive1 (V \o sol (sol p t) : _ -> R^o) 0. + have dVsolt := is_derive_Vsol Kp tge0; rewrite derive1E derive_val. + have Ksolpt : K (sol p t) by apply: subset_limSK_K. + have dVsolt' := is_derive_Vsol Ksolpt (lexx _); rewrite derive1E derive_val. + rewrite -(solD sol0 solP Kinvar) //. + by rewrite add0r. +apply: (stable_limS K_compact sol0 solP sol_cont Kinvar (V:=V)) limSKsolp. +- apply/subspace_continuousP => q Kq; have /(_ q) := V_continuous; apply: cvg_trans. + exact: cvg_app (@cvg_within _ _ _ _). +- by move=> q s Kq sge0; have := is_derive_Vsol Kq sge0. +- move=> q Kq; have dVsolq := is_derive_Vsol Kq (lexx _). + by rewrite derive1E derive_val mulNr oppr_le0 pmulr_rge0 // sqr_ge0. +Qed. + +Lemma sol1_eq0 p t : limS sol K p -> 0 <= t -> (sol p t)..[1] = 0. +Proof. +move=> limSKp tge0; have Kp : K p by apply: subset_limSK_K. +have dVsol := is_derive_Vsol Kp tge0; have /eqP := Vsol'_eq0 limSKp tge0. +rewrite derive1E derive_val mulrI_eq0; last exact/lregN/lregP. +by rewrite sqrf_eq0 => /eqP. +Qed. + +Lemma sol1'_eq0 p t : limS sol K p -> 0 <= t -> (Fpendulum (sol p t))..[1] = 0. +Proof. +move=> limSKp tge0; have := is_derive_cst (0 : R^o) (t : R^o) 1. +have /subset_limSK_K Kp := limSKp. +have [_ /(_ _ tge0) /(is_derive_component 1)] := sol_is_sol sol0 solP Kp. +by apply: is_derive_nneg_eq => // s sge0; rewrite sol1_eq0. +Qed. + +Lemma sol0_const p t : limS sol K p -> 0 <= t -> (sol p t)..[0] = p..[0]. +Proof. +move=> limSKp tge0; rewrite -[p in RHS]sol0. +apply (@eq0_derive1_cst R (fun s => (sol p s)..[0]) 0 t); last first. + by rewrite in_itv/= lexx tge0. +move=> s /andP [sge0 _]; have /subset_limSK_K Kp := limSKp. +have [_ /(_ _ sge0) /(is_derive_component 0) dsol0] := sol_is_sol sol0 solP Kp. +by apply: DeriveDef => //; rewrite derive_val mxE /= sol1_eq0. +Qed. + +Lemma Esol_const p t : limS sol K p -> 0 <= t -> (E \o sol p) t = E p. +Proof. +move=> limSKp tge0; rewrite -[p in RHS]sol0. +apply (@eq0_derive1_cst R (E \o sol p) 0 t); last first. + by rewrite in_itv/= lexx tge0. +move=> s /andP [sge0 _]; have /subset_limSK_K Kp := limSKp. +have dEsol := is_derive_Esol Kp sge0; apply: DeriveDef => //. +by rewrite derive_val sol1_eq0 // mul0r. +Qed. + +Lemma Efctrl_psol0_eq0 p t : limS sol K p -> 0 <= t -> + ke%:num * (E (sol p t)) * (fctrl (sol p t)) + kx%:num * (sol p t)..[0] = 0. +Proof. +move=> limSKp tge0. +rewrite [RHS](_ : _ = + - (kd%:num * (sol p t)..[1] + kv%:num * (Fpendulum (sol p t))..[1])); last first. + by rewrite sol1'_eq0 // sol1_eq0 // !mulr0 add0r oppr0. +have [circsolt /le_lt_trans /(_ k0_valid) Vsolts] : K (sol p t). + by apply: Kinvar tge0; apply: subset_limSK_K. +have fctrl_def := fctrl_wdef circsolt Vsolts. +have Mpmsne0 : M%:num + m%:num * (sol p t)..[3] ^+ 2 != 0. + by rewrite lt0r_neq0 // Mp_ms_gt0. +rewrite /Fpendulum !mxE /= /fctrl; apply: (canLR (subrK _)); rewrite mulrA. +apply: (canLR (mulfK _)) => //; rewrite [RHS]mulrDl; apply: (canRL (subrK _)). +rewrite opprD [RHS]mulrDl [RHS]addrC; apply/(canRL (subrK _))/Logic.eq_sym. +rewrite mulrC -mulNr mulrA mulrA; apply: (canLR (mulfK _)) => //. +rewrite [RHS]mulrDr [LHS]mulrDr addrC; apply: (canLR (subrK _)). +rewrite mulrA -[in X in X / _]mulrA; apply: (canLR (mulfK _)) => //. +ring. +Qed. + +Lemma div_fctrl_mP p t : limS sol K p -> 0 <= t -> + (sol p t)..[3] * (g%:num * (sol p t)..[2] - l%:num * (sol p t)..[4] ^+ 2) = + (fctrl (sol p t)) / m%:num. +Proof. +move=> limSKp tge0; apply: (canRL (mulfK _)) => //; apply: subr0_eq. +have := sol1'_eq0 limSKp tge0; rewrite !mxE /= => /(canRL (mulfK _)). +rewrite mul0r => fctrl_val. +rewrite mulrC mulrA -[in X in X - _]opprB mulrN -opprD fctrl_val ?oppr0 //. +exact/invr_neq0/lt0r_neq0/Mp_ms_gt0. +Qed. + +Lemma Fpendulum4E p t : limS sol K p -> 0 <= t -> + (Fpendulum (sol p t))..[4] = g%:num / l%:num * (sol p t)..[3]. +Proof. +move=> limSKp tge0; rewrite !mxE /=. +have /(canLR (mulfVK _)) <- // := div_fctrl_mP limSKp tge0. +apply: (canLR (mulfK _)); last apply/esym. + by apply: lt0r_neq0; rewrite pmulr_rgt0 // Mp_ms_gt0. +rewrite mulrCA mulrA mulrA [l%:num * _ in LHS]mulrC mulfVK//. +have [] : K (sol p t) by apply/subset_limSK_K/limSKinvar. +rewrite addrC => /(canRL (addrK _)) -> _. +ring. +Qed. + +Lemma En0_fctrlsol_const p t : + limS sol K p -> E p != 0 -> 0 <= t -> fctrl (sol p t) = fctrl p. +Proof. +move=> limSKp Epn0 tge0. +have := Efctrl_psol0_eq0 limSKp tge0. +rewrite -[X in _ = X -> _](Efctrl_psol0_eq0 limSKp (lexx _)) sol0 + [E (sol p t)](Esol_const limSKp tge0) (sol0_const limSKp tge0). +have keEn0 : ke%:num * E p != 0 by rewrite mulrI_eq0 //; apply/lregP. +move/(canRL (addrK _)); rewrite -addrA subrr addr0 mulrC. +by move=> /(canRL (mulfK _)) - /(_ keEn0) ->; rewrite mulrAC -mulrA mulVKf. +Qed. + +Lemma inf_in_finset (A : {fset R}) : + has_inf [set t | t \in A] -> inf [set t | t \in A] \in A. +Proof. +move=> infA; have [[t At] _] := infA. +have Amin : \big[minr/t]_(s <- enum_fset A) s \in A. + have : forall s, s \in enum_fset A -> s \in A by []. + elim: (enum_fset A) => [inA|s l0 ihl0 inA]; first by rewrite big_nil. + rewrite big_cons. + have [sl|sl] := leP s _. + by apply: inA; rewrite mem_head. + by apply: ihl0 => r lr; apply: inA; rewrite inE orbC lr. +suff -> : inf [set t | t \in A] = \big[minr/t]_(s <- enum_fset A) s by []. +apply/eqP; rewrite eq_le; apply/andP; split. + apply: inf_lbound => //. + by case: infA. +apply: lb_le_inf; first by have [] := infA. +apply/lbP => s As; have : s \in enum_fset A by []. +elim: (enum_fset A) => // r l0 ihl0; rewrite inE => /orP [/eqP <-|]. + by rewrite big_cons ge_min lexx. +by rewrite big_cons ge_min orbC => /ihl0 ->. +Qed. + +Lemma continuous_finimage_cst (f : R -> R) n (h : 'I_n -> R) : + {in (>= 0), continuous f} -> + (forall t, 0 <= t -> exists i, f t = h i) -> + forall t, 0 <= t -> f t = f 0. +Proof. +case: n h => [h ? finim_f t tge0|]; first by have /finim_f [] := tge0; case. +case=> [|n] h fcont finim_f t tge0. + have /finim_f [i ->] := tge0; have /finim_f [j ->] := lexx (0 : R). + by rewrite !ord1. +case: (eqVneq (f t) (f 0)) => // ftnef0. +set fl := minr (f 0) (f t); set fr := maxr (f 0) (f t). +have ltflr : fl < fr. + rewrite /fr. + have [left0|lt0ft] := leP (f 0) _. + rewrite /fl; move: (left0) => /min_idPl => ->. + by rewrite lt_def ftnef0/= left0. + by rewrite /fl; move/ltW: (lt0ft) => /min_idPr => ->. +set img := [set x | (fl < x) && (x \in range h)]. +have imgfr : (range h) fr. + rewrite /fr. + have [f0ft|f0ft] := leP (f 0) (f t). + by have /finim_f [i] := tge0; exists i. + by have /finim_f [i] := lexx (0 : R); exists i. +have imgn0 : nonempty img. + exists fr. + by rewrite /img/= ltflr andTb; apply/asboolP. +have infimg : has_inf img. + by split=> //; exists fl; apply/lbP => ? /andP [/ltW]. +have [] := @IVT _ f _ _ ((fl + inf img) / 2) tge0. + apply: continuous_in_subspaceT => x. + rewrite inE/= in_itv/= => /andP[x0 xt]. + by apply: fcont => //=. + apply/andP; split. + rewrite ler_pdivlMr // mulrC mul2r lerD2l. + by apply: lb_le_inf imgn0 _; apply/lbP => ? /andP [/ltW]. + rewrite ler_pdivrMr // mulrC mul2r lerD //; first exact: ltW. + apply: inf_lbound => //. + by case: infimg. + by apply/andP; split=> //; apply/asboolP. +move=> s s0t fsemid; suff ltfl_inf : fl < inf img. + have : inf img <= (fl + inf img) / 2. + apply: inf_lbound. + by case: infimg. + apply/andP; split; last first. + have /finim_f [i] : 0 <= s by rewrite (itvP s0t). + by rewrite fsemid => midegi; apply/asboolP; exists i. + by rewrite ltr_pdivlMr // mulrC mul2r ltrD2l. + by rewrite ler_pdivlMr // mulrC mul2r lerD2r leNgt ltfl_inf. +have imgE : img = pred_of_finset [fset x in + [seq t <- [seq h i | i : 'I_n.+2] | fl < t]]%fset :> set R. + rewrite funeqE => x; rewrite /img /= /pred_of_finset in_fset/=. + apply/propext; split. + rewrite mem_filter => /andP[flx]. + rewrite inE => -[i _ gix]. + rewrite flx/=. + apply/mapP; exists i => //=. + by rewrite mem_enum. + rewrite mem_filter/= => /andP[flx /mapP[/= i _ xgi]]. + rewrite flx/= xgi. + by apply/asboolP; exists i. +rewrite imgE; set A := [fset x in _]%fset. +have : inf (pred_of_finset A) \in A. + by apply: inf_in_finset; rewrite -[X in has_inf X]imgE. +by rewrite /A in_fset mem_filter => /andP []. +Qed. + +Lemma En0_sol2_const p : + limS sol K p -> E p != 0 -> forall t, 0 <= t -> (sol p t)..[2] = p..[2]. +Proof. +move=> limSKp Epn0 t tge0. +have Kp : K p by apply: subset_limSK_K. +set C1 := - (2 * g%:num + 2 * (E p) / (m%:num * l%:num)). +set C2 := fctrl p / m%:num. +have sol32_val : forall s, 0 <= s -> + (sol p s)..[3] * (3%:R * g%:num * (sol p s)..[2] + C1) = C2. + move=> s sge0. + rewrite /C1 /C2 -(Esol_const limSKp sge0) /E /= (sol1_eq0 limSKp sge0) + -(En0_fctrlsol_const limSKp Epn0 sge0) -(div_fctrl_mP limSKp sge0). + rewrite !expr0n /= !mulr0 !mul0r add0r addr0. + rewrite (mulrDr 2). + rewrite mulrA [1 / _]mulrC. + rewrite mulVKr ?unitfE // mul1r mulrBr addrC; apply: (canLR (subrK _)). + rewrite -mulNr mulrDr addrC; apply: (canLR (subrK _)). + rewrite mulrA; apply: (canLR (mulfK _)) => //. + ring. +have sol423_val s : 0 <= s -> + (sol p s)..[4] * (3%:R * g%:num * ((sol p s)..[2] ^+ 2 - + (sol p s)..[3] ^+ 2) + C1 * (sol p s)..[2]) = 0. + move=> sge0; apply (is_derive_nneg_eq sol32_val sge0); last first. + exact: is_derive_cst. + have [_ /(_ _ sge0) sol_ats] := sol_is_sol sol0 solP Kp; apply: is_derive_eq. + rewrite !mxE /=. + rewrite /GRing.scale/=. + ring. +have sol432_val' s : 0 <= s -> + (sol p s)..[3] * (g%:num / l%:num * (3%:R * g%:num * ((sol p s)..[2] ^+ 2 - + (sol p s)..[3] ^+ 2) + C1 * (sol p s)..[2]) - + (sol p s)..[4] ^+ 2 * (12%:R * g%:num * (sol p s)..[2] + C1)) = 0. + move=> sge0; apply (is_derive_nneg_eq sol423_val sge0); last first. + exact: is_derive_cst. + have [_ /(_ _ sge0) sol_ats] := sol_is_sol sol0 solP Kp; apply: is_derive_eq. + rewrite Fpendulum4E // !mxE /= addrC; apply: (canLR (subrK _)). + rewrite -![_ *: _]/(_ * _) mulrA mulrAC mulrA; apply: (canLR (mulfK _)) => //. + rewrite [in RHS]mulrDl; apply: (canRL (subrK _)). + rewrite [(sol p s)..[3] * _]mulrDr [in RHS]mulrDl; apply: (canRL (subrK _)). + rewrite [_ / _ * _]mulrC [in RHS]mulrA [in RHS]mulrA mulfVK//. + ring. +set x1 := (- C1 + Num.sqrt (C1 ^+ 2 - 4%:R * (6%:R * g%:num) * + (- 3%:R * g%:num))) / (2 * (6%:R * g%:num)). +set x2 := (- C1 - Num.sqrt (C1 ^+ 2 - 4%:R * (6%:R * g%:num) * + (- 3%:R * g%:num))) / (2 * (6%:R * g%:num)). +set f := fun i : 'I_4 => if i == 0 then - 1 else + if i == 1 then 1 else + if i == 2 then x1 else x2. +rewrite -[p in RHS]sol0. +apply: (@continuous_finimage_cst (fun s => (sol p s)..[2]) _ f) tge0. + move=> s sge0; apply: (@differentiable_continuous _ R^o R^o). + have [_ /(_ _ sge0) sol_ats]:= sol_is_sol sol0 solP Kp. + exact/derivable1_diffP. +move=> s sge0. +have circsol : (sol p s)..[2] ^+ 2 + (sol p s)..[3] ^+ 2 = 1. + suff [] : K (sol p s) by []. + exact/subset_limSK_K/limSKinvar. +have solroot_imf : + 3%:R * g%:num * ((sol p s)..[2] ^+ 2 - (sol p s)..[3] ^+ 2) + + C1 * (sol p s)..[2] = 0 -> exists i, (sol p s)..[2] = f i. + have -> : (sol p s)..[3] ^+ 2 = 1 - (sol p s)..[2] ^+ 2. + by rewrite -circsol [X in X - _]addrC addrK. + move=> sol2_val. + have sol2_root : + 6%:R * g%:num * ((sol p s)..[2] ^+ 2) + C1 * (sol p s)..[2] + + (- 3%:R * g%:num) = 0. + rewrite -[RHS]sol2_val. + ring. + case/poly2_factor: sol2_root => {sol2_val} [|sol2_val|sol2_val] //. + by exists (2%:R); rewrite sol2_val. + by exists (3%:R); rewrite sol2_val. +case: (eqVneq ((sol p s)..[4]) 0) => [sol4e0|sol4ne0]; last first. + by have /sol423_val/eqP := sge0; rewrite mulrI_eq0 => [/eqP|]//; apply/lregP. +have /sol432_val' := sge0. +rewrite sol4e0 expr0n /= mul0r subr0. +case: (eqVneq ((sol p s)..[3]) 0) => [sol3e0|sol3ne0]. + move=> _; move: circsol; rewrite sol3e0 expr0n /= addr0. + rewrite -(expr1n R 2) => /eqP; rewrite eqf_sqr=> /orP [] /eqP->. + by exists 1. + by exists 0. +move=> /eqP; rewrite mulrI_eq0; last exact/lregP. +by rewrite mulrI_eq0=> [/eqP|] //; apply/lregP. +Qed. + +Lemma En0_sol3_const p : + limS sol K p -> E p != 0 -> forall t, 0 <= t -> (sol p t)..[3] = p..[3]. +Proof. +move=> limSKp Epn0 t tge0. +have circsol s : 0 <= s -> p..[2] ^+ 2 + (sol p s)..[3] ^+ 2 = 1. + move=> sge0; rewrite -(En0_sol2_const limSKp Epn0 sge0). + suff [] : K (sol p s) by []. + exact/subset_limSK_K/limSKinvar. +set h := fun i : 'I_2 => if i == 0 then Num.sqrt (1 - p..[2] ^+ 2) + else - (Num.sqrt (1 - p..[2] ^+ 2)). +rewrite -[p in RHS]sol0. +apply: (@continuous_finimage_cst (fun t => (sol p t)..[3]) _ h) tge0. + move=> s sge0; apply: (@differentiable_continuous _ R^o R^o). + have Kp : K p by apply: subset_limSK_K. + have [_ /(_ _ sge0) sol_ats]:= sol_is_sol sol0 solP Kp. + exact/derivable1_diffP. +move=> s sge0. +suff : (sol p s)..[3] ^+ 2 == (Num.sqrt (1 - p..[2] ^+ 2)) ^+2. + by rewrite eqf_sqr => /orP [/eqP ?|/eqP ?]; [exists 0|exists 1]. +have /circsol <- := sge0. +by rewrite -addrA addrCA addrA addrK sqr_sqrtr // sqr_ge0. +Qed. + +Lemma En0_sol4_eq0 p : + limS sol K p -> E p != 0 -> forall t, 0 <= t -> (sol p t)..[4] = 0. +Proof. +move=> limSKp Epn0 t tge0. +have Kp : K p by apply: subset_limSK_K. +have [_ /(_ _ tge0) sol't] := sol_is_sol sol0 solP Kp. +have : (sol p t)..[3] * (sol p t)..[4] == 0. + rewrite -oppr_eq0 -mulNr; apply/eqP. + apply (is_derive_nneg_eq (En0_sol2_const limSKp Epn0) tge0); last first. + exact: is_derive_cst. + by apply: is_derive_eq; rewrite mxE. +rewrite mulf_eq0 => /orP [] /eqP // sol3eq0. +have /eqP : (sol p t)..[2] * (sol p t)..[4] = 0. + apply (is_derive_nneg_eq (En0_sol3_const limSKp Epn0) tge0); last first. + exact: is_derive_cst. + by apply: is_derive_eq; rewrite mxE. +rewrite mulf_eq0 => /orP [] /eqP // sol2eq0. +have [] : K (sol p t) by apply/Kinvar. +by rewrite sol3eq0 sol2eq0 expr0n /= addr0 => /eqP; rewrite eq_sym oner_eq0. +Qed. + +Lemma En0_sol3_eq0 p t : + limS sol K p -> E p != 0 -> 0 <= t -> (sol p t)..[3] = 0. +Proof. +move=> limSKp Epn0 tge0; rewrite En0_sol3_const => //. +case: (eqVneq (p..[3]) 0) => // p3n0. +suff : (Fpendulum (sol p 0))..[4] = 0. + rewrite Fpendulum4E // sol0 => /eqP; rewrite mulrI_eq0; last exact/lregP. + by move/eqP. +apply (is_derive_nneg_eq (En0_sol4_eq0 limSKp Epn0) (lexx 0)); last first. + exact: is_derive_cst. +have Kp : K p by apply: subset_limSK_K. +have [_ /(_ _ (lexx 0))] := sol_is_sol sol0 solP Kp. +exact: is_derive_component. +Qed. + +Lemma En0_sol2_eq1 p t : + limS sol K p -> E p != 0 -> 0 <= t -> (sol p t)..[2] = 1. +Proof. +move=> limSKp Epn0 tge0. +have [] : K (sol p t) by apply/subset_limSK_K/limSKinvar. +rewrite En0_sol3_eq0 // expr0n /= addr0 -{1}(expr1n R 2). +move/eqP; rewrite eqf_sqr => /orP [] /eqP // sol2_eqN1 _. +suff : `|E (sol p t)| < 2 * m%:num * g%:num * l%:num. + rewrite /E sol1_eq0 // En0_sol4_eq0 // expr0n /= !mulr0 !addr0 mulr0 add0r. + rewrite sol2_eqN1 -opprD mulrN normrN mulrC !mulrA mulrAC. + by rewrite -(natrD _ 1 1) addn1 ltr_norml ltxx andbF. +rewrite -[X in _ < X]ger0_norm // -ltr_sqr ?nnegrE // -!normrX. +do 2 rewrite ger0_norm ?sqr_ge0 //. +suff : 2 * (V (sol p t)) / ke%:num < (2 * m%:num * g%:num * l%:num) ^+ 2. + apply: le_lt_trans. + rewrite -mulrA -ler_pdivrMl // ler_pdivlMr // mulrC mulrA. + by rewrite /V -addrA lerDl addr_ge0 // pmulr_rge0 // sqr_ge0. +rewrite ltr_pdivrMr // -ltr_pdivlMl // mulrC [_ * ke%:num]mulrC. +have /lt_le_trans : V (sol p t) < B. + have [_ Vsolp_s] : K (sol p t) by apply/subset_limSK_K/limSKinvar. + exact: le_lt_trans k0_valid. +rewrite /B; apply; apply: ler_pM => //; apply: ler_pM => //. +by rewrite lerXn2r // ?nnegrE // ge_min lexx orbC. +Qed. + +Lemma subset_limSK_homoclinic_orbit : limS sol K `<=` homoclinic_orbit. +Proof. +move=> p limSKp; rewrite homoclinicE; case: (eqVneq (E p) 0) => [Ep0|Epn0]. + have := sol1_eq0 limSKp (lexx _); rewrite sol0 => p10. + have := Efctrl_psol0_eq0 limSKp (lexx _). + rewrite sol0 Ep0 mulr0 mul0r add0r => /eqP. + by rewrite mulrI_eq0 => [/eqP|] //; apply/lregP. +suff Ep0 : E p == 0 by move: Epn0; rewrite Ep0. +rewrite /E -[p]sol0 sol1_eq0 // En0_sol4_eq0 // En0_sol2_eq1 // subrr expr0n /=. +by rewrite !mulr0 !addr0 mulr0. +Qed. + +Lemma cvg_to_homoclinic_orbit p : K p -> + sol p @ +oo --> (homoclinic_orbit : set [the pseudoMetricType _ of U]). +Proof. +move=> Kp A [_/posnumP[e] hoe_A]; apply: cvg_to_limS K_compact Kinvar _ Kp _ _. +exists e%:num => //= q [r /subset_limSK_homoclinic_orbit hor re_q]. +by apply: hoe_A; exists r. +Qed. + +End System. diff --git a/quaternion.v b/quaternion.v index 1d67660a..de7d5c94 100644 --- a/quaternion.v +++ b/quaternion.v @@ -1,4 +1,4 @@ -(* coq-robot (c) 2025 AIST and INRIA. License: LGPL-2.1-or-later. *) +(* robot-rocq (c) 2026 AIST and INRIA. License: LGPL-2.1-or-later. *) From HB Require Import structures. From mathcomp Require Import all_boot order ssralg ssrint ssrnum rat poly. From mathcomp Require Import closed_field polyrcf matrix mxalgebra mxpoly zmodp. @@ -9,14 +9,15 @@ From mathcomp Require Import interval reals trigo. Require Import ssr_ext euclidean vec_angle frame rot. Require Import extra_trigo. -(******************************************************************************) -(* Quaternions *) +(**md**************************************************************************) +(* # Quaternions *) (* *) (* This file develops the theory of quaternions. It defines the type of *) (* quaternions and the type of unit quaternions and show that quaternions *) (* form a ZmodType, a RingType, a LmodType, a UnitRingType. It also defines *) (* polar coordinates and dual quaternions. *) (* *) +(* ``` *) (* quat R == type of quaternions over the ringType R *) (* x%:q == quaternion with scalar part x and vector part 0 *) (* x \is realq == the quaternion x has no vector part *) @@ -30,28 +31,36 @@ Require Import extra_trigo. (* normq x == norm of the quaternion x *) (* uquat R == type of unit quaternions, i.e., quaternions with norm 1 *) (* conjugation x == v |-> x v x^* *) +(* ``` *) (* *) (* Polar coordinates: *) +(* ``` *) (* polar_of_quat a == polar coordinates of the quaternion a *) (* quat_of_polar a u == quaternion corresponding to the polar coordinates *) (* angle a and vector u *) (* quat_rot x == snd \o conjugation x (rotation of angle 2a about *) (* vector v where a,v are the polar coordinates of x, *) (* a unit quaternion *) +(* ``` *) +(* *) (* Dual numbers: *) +(* ``` *) (* dual R == the type of dual numbers over a ringType R *) (* x.1 == left part of the dual number x *) (* x.2 == right part of the dual number x *) +(* ``` *) (* Dual numbers are equipped with a structure of ZmodType, RingType, and of *) (* LmodType when R is a ringType, of Com/UnitRingType when R is a *) (* Com/UnitRingType. *) (* *) (* Dual quaternions: *) +(* ``` *) (* x +ɛ* y == dual number formed by x and y *) (* dquat == type of dual quaternions *) (* x \is puredq == the dual quaternion x is pure *) (* a \is dnum == a has no vector part *) (* x^*dq == conjugate of dual quaternion x *) +(* ``` *) (* *) (******************************************************************************) @@ -471,23 +480,23 @@ Section quaternion1. Variable R : realType. Implicit Types x y : quat R. -Definition sqrq x := x.1 ^+ 2 + norm (x.2) ^+ 2. +Definition sqrq x := x.1 ^+ 2 + `|x.2|_e ^+ 2. -Lemma sqrq0 : sqrq 0 = 0. Proof. by rewrite /sqrq norm0 expr0n add0r. Qed. +Lemma sqrq0 : sqrq 0 = 0. Proof. by rewrite /sqrq enorm0 expr0n add0r. Qed. Lemma sqrq_ge0 x : 0 <= sqrq x. Proof. by rewrite addr_ge0 // sqr_ge0. Qed. Lemma sqrq_eq0 x : (sqrq x == 0) = (x == 0). Proof. -rewrite /sqrq paddr_eq0 ?sqr_ge0// !sqrf_eq0 norm_eq0 -xpair_eqE. +rewrite /sqrq paddr_eq0 ?sqr_ge0// !sqrf_eq0 enorm_eq0 -xpair_eqE. by rewrite -surjective_pairing. Qed. Lemma sqrqN x : sqrq (- x) = sqrq x. -Proof. by rewrite /sqrq /= normN sqrrN. Qed. +Proof. by rewrite /sqrq /= enormN sqrrN. Qed. Lemma sqrq_conj x : sqrq (x ^*q) = sqrq x. -Proof. by rewrite /sqrq normN. Qed. +Proof. by rewrite /sqrq enormN. Qed. Lemma conjqP x : x * x^*q = (sqrq x)%:q. Proof. @@ -515,11 +524,11 @@ Proof. apply/eqP; rewrite eq_quat; apply/andP; split; apply/eqP. rewrite [in LHS]/= scaleqE /=. rewrite !(mul0r,mulr0,addr0) scale0r !add0r !dotmulDl. - rewrite dotmulZv dotmulvv normeE expr1n mulr1 dotmulC + rewrite dotmulZv dotmulvv enormeE expr1n mulr1 dotmulC dot_crossmulC (@liexx _ (vec3 R)) dotmul0v addr0. - rewrite subrr add0r dotmulZv dotmulvv normeE expr1n mulr1 + rewrite subrr add0r dotmulZv dotmulvv enormeE expr1n mulr1 dotmulC dot_crossmulC (@liexx _ (vec3 R)) . - rewrite dotmul0v addr0 dotmulZv dotmulvv normeE expr1n mulr1 + rewrite dotmul0v addr0 dotmulZv dotmulvv enormeE expr1n mulr1 opprD addrA dotmulC dot_crossmulC. rewrite (@liexx _ (vec3 R)) dotmul0v subr0 -opprD mulrN mulNr opprK -mulr2n -(mulr_natl x.1) mulrA. @@ -527,13 +536,13 @@ apply/eqP; rewrite eq_quat; apply/andP; split; apply/eqP. rewrite /= !(mul0r,scale0r,add0r,addr0). rewrite [_ *v 'e_0](@lieC _ (vec3 R)) /= ['e_0 *v _]linearD /=. rewrite ['e_0 *v (x.1 *: _)]linearZ /= (@liexx _ (vec3 R)) . -rewrite scaler0 add0r double_crossmul dotmulvv normeE expr1n scale1r. +rewrite scaler0 add0r double_crossmul dotmulvv enormeE expr1n scale1r. rewrite [_ *v 'e_1](@lieC _ (vec3 R)) /= ['e_1 *v _]linearD /=. rewrite ['e_1 *v (x.1 *: _)]linearZ /= (@liexx _ (vec3 R)) . -rewrite scaler0 add0r double_crossmul dotmulvv normeE expr1n scale1r. +rewrite scaler0 add0r double_crossmul dotmulvv enormeE expr1n scale1r. rewrite [_ *v 'e_2%:R](@lieC _ (vec3 R)) /= ['e_2%:R *v _]linearD /=. rewrite ['e_2%:R *v (x.1 *: _)]linearZ /= (@liexx _ (vec3 R)). -rewrite scaler0 add0r double_crossmul dotmulvv normeE expr1n scale1r. +rewrite scaler0 add0r double_crossmul dotmulvv enormeE expr1n scale1r. rewrite [X in _ = - _ *: X](_ : _ = 2%:R *:x.2). by rewrite scalerA mulNr div1r mulVr ?unitfE ?pnatr_eq0 // scaleN1r. rewrite !opprB (addrCA _ x.2). @@ -617,10 +626,10 @@ Lemma invqE x : x^-1 = invq x. Proof. by done. Qed. Definition normq x := Num.sqrt (sqrq x). Lemma normq0 : normq 0 = 0. -Proof. by rewrite /normq /sqrq expr0n /= norm0 add0r expr0n sqrtr0. Qed. +Proof. by rewrite /normq /sqrq expr0n /= enorm0 add0r expr0n sqrtr0. Qed. Lemma normqc x : normq x^*q = normq x. -Proof. by rewrite /normq /sqrq /= normN. Qed. +Proof. by rewrite /normq /sqrq /= enormN. Qed. Lemma normqE x : (normq x ^+ 2)%:q = x^*q * x. Proof. @@ -634,9 +643,9 @@ Proof. by apply sqrtr_ge0. Qed. Lemma normq_eq0 x : (normq x == 0) = (x == 0). Proof. by rewrite /normq -{1}sqrtr0 eqr_sqrt ?sqrq_ge0// sqrq_eq0. Qed. -Lemma normq_vector (u : 'rV[R]_3) : normq u%:v = norm u. +Lemma normq_vector (u : 'rV[R]_3) : normq u%:v = `|u|_e. Proof. -by rewrite /normq /sqrq /= expr0n add0r sqrtr_sqr ger0_norm ?norm_ge0. +by rewrite /normq /sqrq /= expr0n add0r sqrtr_sqr ger0_norm ?enorm_ge0. Qed. Lemma normqM x y : normq (x * y) = normq x * normq y. @@ -650,7 +659,7 @@ Qed. Lemma normqZ (k : R) x : normq (k *: x) = `|k| * normq x. Proof. -by rewrite /normq /sqrq /= normZ 2!exprMn sqr_normr -mulrDr sqrtrM ?sqr_ge0 // +by rewrite /normq /sqrq /= enormZ 2!exprMn sqr_normr -mulrDr sqrtrM ?sqr_ge0 // sqrtr_sqr. Qed. @@ -679,7 +688,7 @@ Definition lequat x y := (x.2 == y.2) && (x.1 <= y.1). Lemma lequat_normD x y : lequat (normQ (x + y)) (normQ x + normQ y). Proof. -rewrite /lequat /= add0r eqxx andTb /normq /sqrq !sqr_norm !sum3E /= !mxE. +rewrite /lequat /= add0r eqxx andTb /normq /sqrq !sqr_enorm !sum3E /= !mxE. pose X := nth 0 [:: x.1; x _i; x _j; x _k]. pose Y := nth 0 [:: y.1; y _i; y _j; y _k]. suff: Num.sqrt (\sum_(i < 4) (X i + Y i)^+2) <= @@ -769,12 +778,12 @@ apply/idP/idP. rewrite /lequat /=. case/andP => /eqP<- x0Ly0. apply/eqP; congr mkQuat; rewrite ?subrr ?expr0n ?addr0 //=. - rewrite norm0 expr0n addr0 sqrtr_sqr. + rewrite enorm0 expr0n addr0 sqrtr_sqr. by apply/eqP; rewrite -ger0_def subr_ge0. case/eqP => /eqP H H1. move: (sym_equal H1) H => /subr0_eq->. rewrite /lequat /= eqxx /=. -by rewrite subrr norm0 expr0n addr0 sqrtr_sqr -ger0_def subr_ge0. +by rewrite subrr enorm0 expr0n addr0 sqrtr_sqr -ger0_def subr_ge0. Qed. Lemma ltquat_def x y : ltquat x y = (y != x) && lequat x y. @@ -815,7 +824,7 @@ Lemma invuq_proof x : x \is uquat -> normq (x^-1) == 1. Proof. by move=> ux; rewrite invq_uquat // normqc. Qed. Lemma cos_atan_uquat x : x \is uquat -> x \isn't pureq -> - let a := atan (norm x.2 / x.1) in cos a ^+ 2 = x.1 ^+ 2. + let a := atan (`|x.2|_e / x.1) in cos a ^+ 2 = x.1 ^+ 2. Proof. move=> ux q00 a. rewrite cos_atan exprMn [x.1 ^-1 ^+2]exprVn. @@ -826,7 +835,7 @@ by rewrite -exprVn sqrtr_sqr normfV invrK sqr_normr. Qed. Lemma sin_atan_uquat x : x \is uquat -> x \isn't pureq -> - let a := atan (norm x.2 / x.1) in sin a ^+ 2 = norm x.2 ^+ 2. + let a := atan (`|x.2|_e / x.1) in sin a ^+ 2 = `|x.2|_e ^+ 2. Proof. move=> ux q00 a. rewrite /a sqr_sin_atan. @@ -852,7 +861,7 @@ by have := pureq_conj u%:v; rewrite qualifE /= eqxx => /esym/eqP ->; Simp.r. Qed. Lemma conjugationE x u : conjugation x u = - ((x.1 ^+ 2 - norm x.2 ^+ 2) *: u + + ((x.1 ^+ 2 - `|x.2|_e ^+ 2) *: u + ((x.2 *d u) *: x.2) *+ 2 + (x.1 *: (x.2 *v u)) *+ 2)%:v. Proof. @@ -882,7 +891,7 @@ move=> xu; rewrite /conjugation quat_vectZ -scalerAr -scalerAl. by rewrite -/(conjugation x x.2) conjugation_uquat. Qed. -Lemma norm_conjugation x u : x \is uquat -> normq (conjugation x u) = norm u. +Lemma norm_conjugation x u : x \is uquat -> normq (conjugation x u) = `|u|_e. Proof. rewrite qualifE => /eqP x1; rewrite /conjugation 2!normqM normqc x1; Simp.r. by rewrite normq_vector. @@ -905,18 +914,18 @@ Proof. by rewrite /quat_of_polar cospi sinpi scale0r. Qed. Lemma quat_of_polarpihalf v : quat_of_polar (pi / 2%:R) v = v%:v. Proof. by rewrite /quat_of_polar cos_pihalf sin_pihalf scale1r. Qed. -Lemma uquat_of_polar a v (v1 : norm v = 1) : quat_of_polar a v \is uquat. +Lemma uquat_of_polar a v (v1 : `|v|_e = 1) : quat_of_polar a v \is uquat. Proof. -by rewrite uquatE /quat_of_polar /sqrq /= normZ v1 mulr1 sqr_normr cos2Dsin2. +by rewrite uquatE /quat_of_polar /sqrq /= enormZ v1 mulr1 sqr_normr cos2Dsin2. Qed. Definition quat_rot x v : 'rV[R]_3 := (conjugation x v).2. -Lemma conjugation_quat_of_polar_axis v a : norm v = 1 -> +Lemma conjugation_quat_of_polar_axis v a : `|v|_e = 1 -> quat_rot (quat_of_polar a v) v = v. Proof. move=> v1. -rewrite /quat_rot conjugationE /= normZ exprMn v1 expr1n mulr1 sqr_normr. +rewrite /quat_rot conjugationE /= enormZ exprMn v1 expr1n mulr1 sqr_normr. rewrite dotmulZv dotmulvv v1 expr1n mulr1 linearZl_LR (@liexx _ (vec3 R)) /= 2!scaler0 mul0rn. rewrite addr0 scalerA -expr2 mulr2n scalerBl addrA subrK -scalerDl cos2Dsin2. by rewrite scale1r. @@ -928,8 +937,8 @@ Lemma conjugation_quat_of_polar_frame_j (f : frame R) a : quat_rot (quat_of_polar a f~i) f~j = cos (a *+ 2) *: f~j + sin (a *+ 2) *: f~k. Proof. -rewrite /quat_rot conjugationE /= normZ noframe_norm mulr1 sqr_normr dotmulZv. -have v0 : f~i != 0 by rewrite -norm_eq0 noframe_norm oner_neq0. +rewrite /quat_rot conjugationE /= enormZ noframe_norm mulr1 sqr_normr dotmulZv. +have v0 : f~i != 0 by rewrite -enorm_eq0 noframe_norm oner_neq0. rewrite (noframe_idotj f) mulr0 scale0r mul0rn addr0 linearZl_LR /=. rewrite (frame_icrossj f) scalerA [in RHS]mulr2n cosD sinD -!expr2. by congr (_ + _); rewrite (mulrC (sin a)) -mulr2n -scalerMnl. @@ -939,8 +948,8 @@ Lemma conjugation_quat_of_polar_frame_k (f : frame R) a : quat_rot (quat_of_polar a f~i) f~k = - sin (a *+ 2) *: f~j + cos (a *+ 2) *: f~k. Proof. -rewrite /quat_rot conjugationE /= normZ noframe_norm mulr1 sqr_normr dotmulZv. -have v0 : f~i != 0 by rewrite -norm_eq0 noframe_norm oner_neq0. +rewrite /quat_rot conjugationE /= enormZ noframe_norm mulr1 sqr_normr dotmulZv. +have v0 : f~i != 0 by rewrite -enorm_eq0 noframe_norm oner_neq0. rewrite (noframe_idotk f) mulr0 scale0r mul0rn addr0 linearZl_LR /=. rewrite (frame_icrossk f) 2!scalerN scalerA sinD cosD -!expr2 addrC scaleNr. by congr (_ + _); rewrite (mulrC (sin a)) -mulr2n -scalerMnl mulNrn. @@ -951,18 +960,18 @@ Definition polar_of_quat x : (R * 'rV_3)%type := if x.1 == 1 then (0, 'e_1) else (pi, 'e_1) else if x.1 == 0 then (pi / 2%:R, x.2) else let: u := normalize x.2 in - let: a := atan (norm x.2 / x.1) in + let: a := atan (`|x.2|_e / x.1) in if 0 < x.1 then (a, u) else (a + pi, u). Lemma polar_of_quat0 : polar_of_quat 0 = (pi, 'e_1). Proof. by rewrite /polar_of_quat eqxx eq_sym oner_eq0. Qed. -Lemma norm_polar_of_quat x : x \is uquat -> norm (polar_of_quat x).2 = 1. +Lemma norm_polar_of_quat x : x \is uquat -> `|(polar_of_quat x).2|_e = 1. Proof. case: x => a0 a1; rewrite /= qualifE /polar_of_quat /normq /sqrq /=. -have [/eqP ->|a10] := ifPn; first by case: ifPn; rewrite norm_delta_mx. +have [/eqP ->|a10] := ifPn; first by case: ifPn; rewrite enorm_delta_mx. case: (sgzP a0) => [-> /eqP| |]; try by rewrite norm_normalize. -by rewrite expr0n add0r sqrtr_sqr ger0_norm // norm_ge0. +by rewrite expr0n add0r sqrtr_sqr ger0_norm // enorm_ge0. Qed. Lemma polar_of_quatK x : x \is uquat -> @@ -970,7 +979,7 @@ Lemma polar_of_quatK x : x \is uquat -> Proof. case: x => a0 a1; rewrite /= qualifE /polar_of_quat /normq /sqrq /=. have [->|/eqP a1N u1] := a1 =P 0. - rewrite norm0 expr0n addr0 sqrtr_sqr; have [?/eqP->|?|_] := ltrgt0P a0. + rewrite enorm0 expr0n addr0 sqrtr_sqr; have [?/eqP->|?|_] := ltrgt0P a0. - by rewrite eqxx quat_of_polar01. - by rewrite eqr_oppLR => /eqP ->; rewrite eqrNxx oner_eq0 quat_of_polarpi1. - by rewrite eq_sym oner_eq0. @@ -1006,7 +1015,7 @@ Qed. HB.instance Definition _ x := @GRing.isLinear.Build _ _ _ _ _ (quat_rot_is_linear x). -Lemma quat_rot_isRot_polar v a : norm v = 1 -> +Lemma quat_rot_isRot_polar v a : `|v|_e = 1 -> isRot (a *+2) v (quat_rot (quat_of_polar a v)). Proof. move=> v1 /=. diff --git a/rigid.v b/rigid.v index 21fa4df6..10c03d7f 100644 --- a/rigid.v +++ b/rigid.v @@ -1,4 +1,4 @@ -(* coq-robot (c) 2017 AIST and INRIA. License: LGPL-2.1-or-later. *) +(* robot-rocq (c) 2026 AIST and INRIA. License: LGPL-2.1-or-later. *) From HB Require Import structures. From mathcomp Require Import all_ssreflect ssralg ssrint ssrnum rat poly. From mathcomp Require Import closed_field polyrcf matrix mxalgebra mxpoly zmodp. @@ -6,8 +6,8 @@ From mathcomp Require Import realalg complex finset fingroup perm. From mathcomp Require Import interval reals trigo. Require Import ssr_ext euclidean skew vec_angle rot frame extra_trigo. -(******************************************************************************) -(* Rigid Body Transformations *) +(**md**************************************************************************) +(* # Rigid Body Transformations *) (* *) (* This file develops the theory of isometries, proving basic properties such *) (* as the preservation of the cross-product by derivative maps, the facts *) @@ -16,6 +16,7 @@ Require Import ssr_ext euclidean skew vec_angle rot frame extra_trigo. (* body transformations are represented by elements of the special Euclidean *) (* group and are shown to preserve norms. *) (* *) +(* ``` *) (* 'Iso[T]_n == the type of isometries *) (* 'CIso[T]_n == the type of central isometries, i.e., isometries f such *) (* that f 0 = 0 *) @@ -38,6 +39,7 @@ Require Import ssr_ext euclidean skew vec_angle rot frame extra_trigo. (* homogeneous representation *) (* Adjoint g == adjoint transformation associated with the homogeneous *) (* matrix g *) +(* ``` *) (* *) (******************************************************************************) @@ -64,7 +66,7 @@ Section isometry. Variables (T : rcfType) (n : nat). Record t := mk { f :> 'rV[T]_n -> 'rV[T]_n ; - P : {mono f : a b / norm (a - b)} }. + P : {mono f : a b / `|a - b|_e} }. End isometry. End Iso. @@ -90,17 +92,17 @@ Section central_isometry_n. Variable (T : rcfType) (n : nat). Implicit Types f : 'CIso[T]_n. -Lemma central_isometry_preserves_norm f : {mono f : x / norm x}. +Lemma central_isometry_preserves_enorm f : {mono f : x / `|x|_e}. Proof. by case: f => f f0 p; rewrite -(subr0 (f p)) -f0 Iso.P subr0. Qed. (* [oneill] first part of lemma 1.6, p.100 *) Lemma central_isometry_preserves_dotmul f : {mono f : u v / u *d v}. Proof. case: f => f f0 a b. -have /eqP : norm (f a - f b) = norm (a - b) by rewrite (Iso.P f). -rewrite /norm eqr_sqrt ?le0dotmul // !dotmulDl !dotmulDr !dotmulvv !normN. -rewrite !(central_isometry_preserves_norm (CIso.mk f0)) !addrA. -rewrite 2!(addrC _ (norm b ^+ 2)) => /eqP/addrI. +have /eqP : `|f a - f b|_e = `|a - b|_e by rewrite (Iso.P f). +rewrite /enorm eqr_sqrt ?le0dotmul // !dotmulDl !dotmulDr !dotmulvv !enormN. +rewrite !(central_isometry_preserves_enorm (CIso.mk f0)) !addrA. +rewrite 2!(addrC _ (`|b|_e ^+ 2)) => /eqP/addrI. rewrite -2!addrA => /addrI. rewrite -(dotmulC (f a)) dotmulvN -(dotmulC a) dotmulvN -2!mulr2n => /eqP. rewrite -mulr_natr -[in X in _ == X -> _]mulr_natr 2!mulNr eqr_opp. @@ -119,7 +121,7 @@ Local Open Scope frame_scope. Definition frame_central_iso f (F : noframe T) : noframe T. apply: (@NOFrame.mk _ (col_mx3 (f F~i) (f F~j) (f F~k))). apply/orthogonal3P. -by rewrite !rowK /= 3!central_isometry_preserves_norm 3!noframe_norm +by rewrite !rowK /= 3!central_isometry_preserves_enorm 3!noframe_norm 3!central_isometry_preserves_dotmul idotj noframe_idotk jdotk !eqxx. Defined. @@ -163,7 +165,7 @@ Lemma trans_ortho_of_iso f : Proof. set m := f 0. set Tm1f := fun x => f x - m. -have Tm1f_is_iso : {mono Tm1f : a b / norm (a - b)}. +have Tm1f_is_iso : {mono Tm1f : a b / `|a - b|_e}. move=> ? ?; by rewrite /Tm1f -addrA opprB 2!addrA subrK (Iso.P f). have Tm1f0 : Tm1f 0 = 0 by rewrite /Tm1f subrr. set c := @CIso.mk _ _ (Iso.mk Tm1f_is_iso) Tm1f0. @@ -286,7 +288,7 @@ Lemma dmapE f (u : vector) b a : Proof. move=> uab; by rewrite /dmap /= uab img_vec_iso. Qed. Lemma derivative_map_preserves_length f : - {mono (fun x : vector => f`* x) : u v / norm (u - v)}. + {mono (fun x : vector => f`* x) : u v / `|u - v|_e}. Proof. move=> u v; rewrite /dmap /= -(mulmxBl u v (ortho_of_iso f)). by rewrite orth_preserves_norm // ortho_of_iso_is_O. @@ -352,7 +354,7 @@ apply (@NOFrame.mk _ (col_mx3 e1 e2 e3)). apply/orthogonal3P; rewrite !rowK /=. do 3! rewrite orth_preserves_norm ?ortho_of_iso_is_O //. rewrite /u1p /u2p /u3p. - rewrite !rowframeE !rowE !mulmx1 3!normeE !eqxx /=. + rewrite !rowframeE !rowE !mulmx1 3!enormeE !eqxx /=. rewrite !(proj2 (orth_preserves_dotmul _)) ?ortho_of_iso_is_O //. rewrite /u1p /u2p /u3p. by rewrite !rowframeE /= !rowE ?mulmx1 !dote2 //= eqxx. @@ -1001,8 +1003,8 @@ Qed. End euclidean_motion. -Lemma motion_vector_preserves_norm (T : realType) (m : t T) : - {mono (motion_vector m) : u / norm u}. +Lemma motion_vector_preserves_enorm (T : realType) (m : t T) : + {mono (motion_vector m) : u / `|u|_e}. Proof. move=> ?; rewrite motion_vectorE orth_preserves_norm // rotation_sub //. exact: rotP. @@ -1026,8 +1028,8 @@ case/boolP : (Aa.angle M == 0) => a0. transitivity (u *m M); last first. (* TODO: lemma? *) by rewrite motion_pointE /= (mul_mx_row u) mulmx0 add_row_mx addr0 add0r to_hpointK. -have w1 : norm w = 1. - by rewrite /w aaxis_of // ?Aa.vaxis_neq0 // norm_normalize // Aa.vaxis_neq0. +have w1 : `|w|_e = 1. + by rewrite /w aaxis_of ?Aa.vaxis_neq0// norm_normalize // Aa.vaxis_neq0. rewrite rodriguesP //; congr (_ *m _) => {u}. by rewrite (angle_axis_eskew_old MSO) // Aa.vaxis_neq0. Qed. @@ -1089,11 +1091,11 @@ by rewrite mul_mx_row mulmx0 add_row_mx add0r to_hpointK. Qed. Lemma SE_preserves_length m : - {mono (EuclideanMotion.motion_point m) : a b / norm (a - b)}. + {mono (EuclideanMotion.motion_point m) : a b / `|a - b|_e}. Proof. move=> m0 m1. rewrite EuclideanMotion.motion_pointB. -by rewrite EuclideanMotion.motion_vector_preserves_norm. +by rewrite EuclideanMotion.motion_vector_preserves_enorm. Qed. Lemma ortho_of_isoE m : diff --git a/robot-rocq.opam b/robot-rocq.opam index 1cf5dfd5..4e489bbe 100644 --- a/robot-rocq.opam +++ b/robot-rocq.opam @@ -26,7 +26,7 @@ depends: [ "coq-mathcomp-algebra" { (>= "2.5.0") } "coq-mathcomp-solvable" { (>= "2.5.0") } "coq-mathcomp-field" { (>= "2.5.0") } - "coq-mathcomp-analysis" { (>= "1.11.0") } + "coq-mathcomp-analysis" { (>= "1.15.0") } "coq-mathcomp-real-closed" { (>= "2.0.0") } "coq-mathcomp-algebra-tactics" { (>= "1.2.4") } ] diff --git a/rot.v b/rot.v index fb23246d..6d57b773 100644 --- a/rot.v +++ b/rot.v @@ -1,4 +1,4 @@ -(* coq-robot (c) 2017 AIST and INRIA. License: LGPL-2.1-or-later. *) +(* robot-rocq (c) 2026 AIST and INRIA. License: LGPL-2.1-or-later. *) From HB Require Import structures. From Stdlib Require Import NsatzTactic. From mathcomp Require Import all_boot order ssralg ssrint ssrnum rat poly. @@ -10,17 +10,20 @@ From mathcomp Require Import sesquilinear. Require Import extra_trigo. Require Import ssr_ext euclidean skew vec_angle frame. -(******************************************************************************) -(* Rotations *) +(**md**************************************************************************) +(* # Rotations *) (* *) (* This file develops the theory of 3D rotations with results such as *) (* Rodrigues formula, the fact that any rotation matrix can be represented *) (* by its exponential coordinates, angle-axis representation, Euler angles, *) (* etc. See also quaternion.v for rotations using quaternions. *) (* *) +(* ``` *) (* RO a, RO' a == two dimensional rotations of angle a *) +(* ``` *) (* *) (* Elementary rotations (row vector convention): *) +(* ``` *) (* Rx a, Rx' a == rotations about axis x of angle a *) (* Ry a == rotation about axis y of angle a *) (* Rz a == rotation about axis z of angle a *) @@ -29,7 +32,9 @@ Require Import ssr_ext euclidean skew vec_angle frame. (* sample lemmas: *) (* all rotations around a vector of angle a have trace "1 + 2 * cos a" *) (* equivalence SO[R]_3 <-> Rot (isRot_SO, SO_is_Rot) *) +(* ``` *) (* *) +(* ``` *) (* `e(a, M) == specialized exponential map for angle a and matrix M *) (* `e^(a, w) == specialized exponential map for the matrix \S(w), i.e., the *) (* skew-symmetric matrix corresponding to vector w *) @@ -37,40 +42,52 @@ Require Import ssr_ext euclidean skew vec_angle frame. (* inverse of the exponential map, *) (* exponential map of a skew matrix is a rotation *) (* *) +(* ``` *) (* rodrigues u a w == linear combination of the vectors u, (u *d w)w, w *v u *) (* that provides an alternative expression for the vector *) (* u * e^(a,w) *) +(* ``` *) (* *) (* Angle-axis representation: *) +(* ``` *) (* Aa.angle M == angle of angle-axis representation for the matrix M *) (* Aa.vaxis M == axis of angle-axis representation for the matrix M *) (* sample lemma *) (* a rotation matrix has Aa.angle M and normalize (Aa.vaxis M) for *) (* exponential coordinates *) +(* ``` *) (* *) (* Composition of elementary rotations (row vector convention): *) +(* ``` *) (* Rzyz a b c == composition of a Rz rotation of angle c, a Ry rotation of *) (* angle b, and a Rz rotation of angle a *) (* Rxyz a b c == composition of a Rx rotation of angle c, a Ry rotation of *) (* angle b, and a Rz notation of angle a *) +(* ``` *) (* *) (* ZYZ angles given a rotation matrix M (ref: [sciavicco] 2.4.1): *) (* with zyz_b in ]0;pi[: *) +(* ``` *) (* zyz_a M == angle of the last Rz rotation *) (* zyz_b M == angle of the Ry rotation *) (* zyz_c M == angle of the first Rz rotation *) +(* ``` *) (* *) (* Roll-Pitch-Yaw (ZYX) angles given a rotation matrix M *) (* with pitch in ]-pi/2;pi/2[ (ref: [sciavicco] 2.4.2): *) +(* ``` *) (* rpy_a M == angle about axis z (roll) *) (* rpy_b M == angle about axis y (pitch) *) (* rpy_c M == angle about axis x (yaw) *) +(* ``` *) (* *) (* Alternative formulation of ZYX angles: *) (* (ref: [Gregory G. Slabaugh, Computer Euler angles from a rotation matrix]) *) +(* ``` *) (* euler_a == angle about z *) (* euler_b == angle about y *) (* euler_c == angle about x *) +(* ``` *) (******************************************************************************) Reserved Notation "'`e(' a ',' M ')'" (format "'`e(' a ',' M ')'"). @@ -138,8 +155,8 @@ Lemma rot2d M : M \is 'SO[T]_2 -> {a | - pi < a <= pi & M = RO a}. Proof. move=> MSO. move: (MSO); rewrite rotationE => /andP[MO _]. -case: (norm1_cossin (norm_row_of_O MO 0)); rewrite !mxE => a [a1 a2]. -case: (norm1_cossin (norm_row_of_O MO 1)); rewrite !mxE => b [b1 b2]. +case: (enorm1_cossin (enorm_row_of_O MO 0)); rewrite !mxE => a [a1 a2]. +case: (enorm1_cossin (enorm_row_of_O MO 1)); rewrite !mxE => b [b1 b2]. move/orthogonalP : (MO) => /(_ 0 1) /=. rewrite dotmulE sum2E !mxE a1 a2 b1 b2 -cosB => cE. have : `|sin (a - b)| = 1 by apply: cos0sin1. @@ -178,8 +195,8 @@ Lemma rot2d' M : { - pi < a <= pi /\ M = RO' a}}. Proof. move=> MO. -case: (norm1_cossin (norm_row_of_O MO 0)); rewrite !mxE => a [a1 a2]. -case: (norm1_cossin (norm_row_of_O MO 1)); rewrite !mxE => b [b1 b2]. +case: (enorm1_cossin (enorm_row_of_O MO 0)); rewrite !mxE => a [a1 a2]. +case: (enorm1_cossin (enorm_row_of_O MO 1)); rewrite !mxE => b [b1 b2]. move/orthogonalP : (MO) => /(_ 0 1) /=. rewrite dotmulE sum2E !mxE a1 a2 b1 b2 -cosB. have HM : M = col_mx2 (row2 (cos a) (sin a)) (row2 (cos b) (sin b)). @@ -278,9 +295,9 @@ Definition Ry a := col_mx3 Lemma Ry_is_SO a : Ry a \is 'SO[T]_3. Proof. apply/rotation3P/and4P; split. -- rewrite -(@eqrXn2 _ 2) // ?norm_ge0 // expr1n. +- rewrite -(@eqrXn2 _ 2) // ?enorm_ge0 // expr1n. by rewrite -dotmulvv dotmulE sum3E !mxE /= mulr0 addr0 -2!expr2 sqrrN cos2Dsin2. -- rewrite -(@eqrXn2 _ 2) // ?norm_ge0 // expr1n. +- rewrite -(@eqrXn2 _ 2) // ?enorm_ge0 // expr1n. by rewrite -dotmulvv dotmulE sum3E !mxE /= mulr0 addr0 add0r mulr1. - by rewrite 2!rowK /= dotmulE sum3E !mxE /= !mulr0 mul0r !add0r. - rewrite 3!rowK /= crossmulE !mxE /=. by Simp.r. @@ -316,9 +333,9 @@ Qed. Lemma Rz_is_SO a : Rz a \is 'SO[T]_3. Proof. apply/rotation3P/and4P; split. -- rewrite -(@eqrXn2 _ 2) // ?norm_ge0 // expr1n. +- rewrite -(@eqrXn2 _ 2) ?enorm_ge0// expr1n. by rewrite -dotmulvv dotmulE sum3E !mxE /= mulr0 addr0 -2!expr2 cos2Dsin2. -- rewrite -(@eqrXn2 _ 2) // ?norm_ge0 // expr1n. +- rewrite -(@eqrXn2 _ 2) ?enorm_ge0// expr1n. - by rewrite -dotmulvv dotmulE sum3E !mxE /= mulr0 addr0 mulrN mulNr opprK addrC cos2Dsin2. - by rewrite 2!rowK /= dotmulE sum3E !mxE /= mulrN mulr0 addr0 addrC mulrC subrr. - rewrite 3!rowK /= crossmulE !mxE /=. Simp.r. by rewrite -!expr2 cos2Dsin2 e2row. @@ -328,8 +345,8 @@ Lemma RzE a : Rz a = (frame_of_SO (Rz_is_SO a)) _R^ (can_frame T). Proof. rewrite FromTo_to_can; by apply/matrix3P/and9P; split; rewrite !mxE. Qed. Lemma rmap_Rz_e0 a : - rmap (can_tframe T) `[ 'e_0 $ frame_of_SO (Rz_is_SO a) ] = - `[ row 0 (Rz a) $ can_tframe T ]. + rmap (can_tframe T) '[ 'e_0 $ frame_of_SO (Rz_is_SO a) ] = + '[ row 0 (Rz a) $ can_tframe T ]. Proof. by rewrite rmapE_to_can rowE [in RHS]RzE FromTo_to_can. Qed. Definition Rzy a b := col_mx3 @@ -389,7 +406,7 @@ by rewrite cos0 sin0 mulmx1 scale0r addr0 scale1r. by rewrite mulmx1 sin0 cos0 scaleNr scale0r oppr0 add0r scale1r. Qed. -Lemma isRotpi (u1 : norm u = 1) : isRot pi u (mx_lin1 (u^T *m u *+ 2 - 1)). +Lemma isRotpi (u1 : `|u|_e = 1) : isRot pi u (mx_lin1 (u^T *m u *+ 2 - 1)). Proof. apply/isRotP; split => /=. - by rewrite mulmxBr mulmx1 mulr2n mulmxDr mulmxA dotmul1 // ?mul1mx addrK. @@ -552,8 +569,8 @@ have cd : k *m M = c *: j + d *: k. by rewrite {1}(orthogonal_expansion (Base.frame e) (k *m M)) dotmulC iMk scale0r add0r. have H1 : a ^+ 2 + b ^+ 2 = 1. - move/eqP: (norm_row_of_O (NOFrame.MO (Base.frame e)) 1). - rewrite -(@eqrXn2 _ 2) // ?norm_ge0 // expr1n -dotmulvv. + move/eqP: (enorm_row_of_O (NOFrame.MO (Base.frame e)) 1). + rewrite -(@eqrXn2 _ 2) ?enorm_ge0// expr1n -dotmulvv. rewrite -(proj2 (orth_preserves_dotmul M) (rotation_sub MSO)). rewrite -rowframeE ab dotmulDr 2!dotmulDl 4!dotmulvZ 4!dotmulZv 2!dotmulvv. by rewrite normj // normk // !(expr1n,mulr1) -!expr2 dotmulC jdotk // !(mulr0,add0r,addr0) => /eqP. @@ -563,8 +580,8 @@ have H2 : a * c + b * d = 0. rewrite dotmulDr 2!dotmulDl 4!dotmulvZ 4!dotmulZv 2!dotmulvv normj // normk //. by rewrite expr1n !mulr1 dotmulC jdotk // 4!mulr0 add0r addr0 mulrC (mulrC d) => /eqP. have H3 : c ^+ 2 + d ^+ 2 = 1. - move/eqP: (norm_row_of_O (NOFrame.MO (Base.frame e)) 2%:R). - rewrite -(@eqrXn2 _ 2) // ?norm_ge0 // expr1n -dotmulvv. + move/eqP: (enorm_row_of_O (NOFrame.MO (Base.frame e)) 2%:R). + rewrite -(@eqrXn2 _ 2) ?enorm_ge0// expr1n -dotmulvv. rewrite -(proj2 (orth_preserves_dotmul M) (rotation_sub MSO)) -!rowframeE -/k cd. rewrite dotmulDr 2!dotmulDl 4!dotmulvZ 4!dotmulZv 2!dotmulvv normj // normk //. by rewrite expr1n 2!mulr1 -2!expr2 dotmulC jdotk // !(mulr0,addr0,add0r) => /eqP. @@ -677,7 +694,7 @@ Qed. Local Notation "'`e^(' a ',' w ')'" := (emx3 a \S( w )). -Lemma eskew_pi w : norm w = 1 -> `e^(pi, w) = w^T *m w *+ 2 - 1. +Lemma eskew_pi w : `| w |_e = 1 -> `e^(pi, w) = w^T *m w *+ 2 - 1. Proof. move=> w1. rewrite /emx3 sinpi scale0r addr0 cospi opprK -(natrD _ 1 1). @@ -687,7 +704,7 @@ by rewrite (_ : 1%:A = 1) // ?subrCA ?subrr ?addr0 // -idmxE scale1r. Qed. Lemma eskew_pi' w a : - norm w = 1 -> cos a = -1 -> sin a = 0 -> `e^(a, w) = w^T *m w *+ 2 - 1. + `| w |_e = 1 -> cos a = -1 -> sin a = 0 -> `e^(a, w) = w^T *m w *+ 2 - 1. Proof. move=> w1 Hs Hc. rewrite /emx3 Hs Hc scale0r addr0 opprK -(natrD _ 1 1). @@ -708,10 +725,10 @@ Qed. Lemma tr_eskew a w : `e^(a, w)^T = `e^(a, - w). Proof. by rewrite tr_emx3 tr_spin /emx3 spinN. Qed. -Lemma eskewM a b w : norm w = 1 -> `e^(a, w) * `e^(b, w) = `e^(a + b, w). +Lemma eskewM a b w : `| w |_e = 1 -> `e^(a, w) * `e^(b, w) = `e^(a + b, w). Proof. move=> w1; by rewrite emx3M // spin3 w1 expr1n scaleN1r. Qed. -Lemma trace_eskew a w : norm w = 1 -> \tr `e^(a, w) = 1 + 2%:R * cos a. +Lemma trace_eskew a w : `| w |_e = 1 -> \tr `e^(a, w) = 1 + 2%:R * cos a. Proof. move=> w1. rewrite 2!mxtraceD !mxtraceZ /= mxtrace1. @@ -736,7 +753,7 @@ Definition angle_axis_rot a u := (u``_1 * u``_2%:R * va - u``_0 * sa) (u``_2%:R ^+2 * va + ca)). -Lemma eskewE a u : norm u = 1 -> `e^(a, u) = angle_axis_rot a u. +Lemma eskewE a u : `| u |_e = 1 -> `e^(a, u) = angle_axis_rot a u. Proof. pose va := 1 - cos a. pose ca := cos a. pose sa := sin a. move=> w1; apply/matrix3P/and9P; split; apply/eqP. @@ -775,18 +792,18 @@ move=> w1; apply/matrix3P/and9P; split; apply/eqP. by rewrite /va opprB addrC subrK. Qed. -Lemma eskew_is_O a u : norm u = 1 -> `e^(a, u) \is 'O[T]_3. +Lemma eskew_is_O a u : `| u |_e = 1 -> `e^(a, u) \is 'O[T]_3. Proof. move=> u1. by rewrite orthogonalE tr_emx3 tr_spin inv_emx3 // exp_spin u1 expr1n scaleN1r. Qed. -Lemma rank_eskew a w : norm w = 1 -> \rank `e^(a, w) = 3%N. +Lemma rank_eskew a w : `| w |_e = 1 -> \rank `e^(a, w) = 3%N. Proof. move=> w1; by rewrite mxrank_unit // orthogonal_unit // eskew_is_O. Qed. -Lemma det_eskew a w : norm w = 1 -> \det `e^(a, w) = 1. +Lemma det_eskew a w : `| w |_e = 1 -> \det `e^(a, w) = 1. Proof. move=> w1. move/orthogonal_det/eqP : (eskew_is_O (a / 2%:R) w1). @@ -795,7 +812,7 @@ rewrite mulmxE emx3M; last by rewrite spin3 w1 expr1n scaleN1r. by move/eqP; rewrite -splitr. Qed. -Lemma eskew_is_SO a w : norm w = 1 -> `e^(a, w) \is 'SO[T]_3. +Lemma eskew_is_SO a w : `| w |_e = 1 -> `e^(a, w) \is 'SO[T]_3. Proof. by move=> w1; rewrite rotationE eskew_is_O //= det_eskew. Qed. Definition expi a := (cos a +i* sin a)%C. @@ -811,7 +828,7 @@ Proof. by rewrite /expi cos0 sin0. Qed. Definition eskew_eigenvalues a : seq T[i] := [:: 1; expi a; expi (- a)]. -Lemma eigenvalue_ekew a w : norm w = 1 -> +Lemma eigenvalue_ekew a w : `| w |_e = 1 -> eigenvalue (map_mx (fun x => x%:C%C) `e^(a, w)) =1 [pred k | k \in eskew_eigenvalues a]. Proof. @@ -859,7 +876,7 @@ Qed. Lemma Rz_eskew a : Rz a = `e^(a, 'e_2%:R). Proof. -rewrite /Rz eskewE /angle_axis_rot ?norm_delta_mx //. +rewrite /Rz eskewE /angle_axis_rot ?enorm_delta_mx //. rewrite !mxE /= expr0n /=. Simp.r. by rewrite expr1n mul1r subrK -e2row. Qed. @@ -874,7 +891,7 @@ Qed. Section rodrigues_formula. Definition rodrigues u a w := - u - (1 - cos a) *: (norm w ^+ 2 *: u) + (1 - cos a) * (u *d w) *: w + sin a *: (w *v u). + u - (1 - cos a) *: (`|w|_e ^+ 2 *: u) + (1 - cos a) * (u *d w) *: w + sin a *: (w *v u). Lemma rodriguesP u a w : rodrigues u a w = u *m `e^(a, w). Proof. @@ -892,7 +909,7 @@ Qed. Definition rodrigues_unit u a w := cos a *: u + (1 - cos a) * (u *d w) *: w + sin a *: (w *v u). -Lemma rodrigues_unitP u a w : norm w = 1 -> rodrigues_unit u a w = u *m `e^(a, w). +Lemma rodrigues_unitP u a w : `|w|_e = 1 -> rodrigues_unit u a w = u *m `e^(a, w). Proof. move=> w1; rewrite -(rodriguesP u a w). rewrite /rodrigues /rodrigues_unit w1 expr1n scale1r; congr (_ + _ + _). @@ -907,7 +924,7 @@ move=> w0. pose f := Base.frame w. apply/isRotP; split => /=. - rewrite -rodriguesP // /rodrigues (norm_normalize w0) expr1n scale1r. - rewrite dotmul_normalize_norm scalerA -mulrA divrr ?mulr1 ?unitfE ?norm_eq0 //. + rewrite dotmul_normalize_enorm scalerA -mulrA divrr ?mulr1 ?unitfE ?enorm_eq0//. by rewrite subrK (linearZl_LR _ w)/= (@liexx _ (vec3 T)) 2!scaler0 addr0. - rewrite -rodriguesP // /rodrigues dotmulC norm_normalize // expr1n scale1r. rewrite (_ : normalize w = Base.i w) (*NB: lemma?*); last by rewrite /Base.i (negbTE w0). @@ -922,10 +939,11 @@ apply/isRotP; split => /=. by rewrite -/(Base.i w) Base.icrossk // scalerN scaleNr. Qed. -Lemma isRot_eskew a w w' : normalize w' = w -> norm w = 1 -> isRot a w' (mx_lin1 `e^(a, w)). +Lemma isRot_eskew a w w' : normalize w' = w -> `|w|_e = 1 -> + isRot a w' (mx_lin1 `e^(a, w)). Proof. move=> <- w1. -by rewrite isRot_eskew_normalize // -normalize_eq0 -norm_eq0 w1 oner_eq0. +by rewrite isRot_eskew_normalize // -normalize_eq0 -enorm_eq0 w1 oner_eq0. Qed. Lemma eskew_is_onto_SO M : M \is 'SO[T]_3 -> @@ -935,12 +953,12 @@ move=> MSO. set w : vector := normalize _. case: (SO_isRot MSO) => a aB Ha. exists a => //. -apply: (@same_isRot _ _ _ _ _ (norm (vaxis_euler M)) _ _ _ _ Ha); last first. +apply: (@same_isRot _ _ _ _ _ `|vaxis_euler M|_e _ _ _ _ Ha); last first. apply (@isRot_eskew _ _ w). by rewrite normalizeI // norm_normalize // vaxis_euler_neq0. by rewrite norm_normalize // vaxis_euler_neq0. by rewrite norm_scale_normalize. -by rewrite norm_gt0 vaxis_euler_neq0. +by rewrite enorm_gt0 vaxis_euler_neq0. by rewrite vaxis_euler_neq0. Qed. @@ -950,7 +968,7 @@ Section alternative_definition_of_eskew. Definition eskew_unit (a : T) (e : 'rV[T]_3) := e^T *m e + (cos a) *: (1 - e^T *m e) + sin a *: \S( e ). -Lemma eskew_unitE w (a : T) : norm w = 1 -> eskew_unit a w = `e^(a, w). +Lemma eskew_unitE w (a : T) : `| w |_e = 1 -> eskew_unit a w = `e^(a, w). Proof. move=> w1. rewrite /eskew_unit /emx3 addrAC sqr_spin -addrA addrCA. @@ -963,7 +981,7 @@ Qed. Local Open Scope frame_scope. (* TODO: move? *) -Lemma normalcomp_double_crossmul p (e : 'rV[T]_3) : norm e = 1 -> +Lemma normalcomp_double_crossmul p (e : 'rV[T]_3) : `| e |_e = 1 -> normalcomp p e *v ((Base.frame e)|,2%:R *v (Base.frame e)|,1) = e *v p. Proof. move=> u1. @@ -975,7 +993,7 @@ rewrite crossmul_axialcomp add0r (@lieC _ (vec3 T)) /=. by rewrite (linearNl _ (normalcomp p e))/= opprK. Qed. -Lemma normalcomp_mulO' a Q u p : norm u = 1 -> isRot a u (mx_lin1 Q) -> +Lemma normalcomp_mulO' a Q u p : `| u |_e = 1 -> isRot a u (mx_lin1 Q) -> normalcomp p u *m Q = cos a *: normalcomp p u + sin a *: (u *v p). Proof. move=> u1 H. @@ -998,7 +1016,7 @@ by rewrite -double_crossmul normalcomp_double_crossmul. Qed. (* [angeles] p.42, eqn 2.49 *) -Lemma isRot_eskew_unit_inv a Q u : norm u = 1 -> +Lemma isRot_eskew_unit_inv a Q u : `| u |_e = 1 -> isRot a u (mx_lin1 Q) -> Q = eskew_unit a u. Proof. move=> u1 H; apply/eqP/mulmxP => p. @@ -1039,7 +1057,7 @@ Lemma isRot_pi_inv (R : 'M[T]_3) u : Proof. move=> u0 H. have /isRot_eskew_unit_inv {H} : isRot pi (normalize u) (mx_lin1 R). - by rewrite isRotZ // invr_gt0 norm_gt0. + by rewrite isRotZ // invr_gt0 enorm_gt0. rewrite norm_normalize // => /(_ erefl) ->. by rewrite eskew_unitE ?norm_normalize // eskew_pi // norm_normalize. Qed. @@ -1069,7 +1087,7 @@ Qed. (* reflection w.r.t. plan of normal u *) -Lemma anglepi (n : vector) (n1 : norm n = 1) : +Lemma anglepi (n : vector) (n1 : `| n |_e = 1) : angle (n^T *m n *+ 2 - 1) = pi. Proof. rewrite /angle mxtraceD linearN /= mxtrace1 mulr2n linearD /=. @@ -1107,14 +1125,14 @@ case/eskew_is_onto_SO : (MSO) => a aB Ma. move: (Msym). rewrite {1}Ma /emx3. rewrite symE !linearD /= trmx1 /= !linearZ /= sqr_spin !linearD /=. -do 2 rewrite (linearN _ (norm (normalize (vaxis_euler M)) ^+ 2)%:A)/=. -rewrite (linearN _ (norm (normalize (vaxis_euler M)) ^+ 2)%:A^T)/=. +do 2 rewrite (linearN _ (`|normalize (vaxis_euler M)|_e ^+ 2)%:A)/=. +rewrite (linearN _ (`|normalize (vaxis_euler M)|_e ^+ 2)%:A^T)/=. rewrite trmx_mul trmxK scalemx1 tr_scalar_mx tr_spin. rewrite !addrA subr_eq subrK. rewrite [in X in _ == X]addrC -subr_eq0 !addrA !opprD !addrA addrK. rewrite scalerN opprK -addrA addrCA !addrA (addrC _ 1) subrr add0r. rewrite -mulr2n scalerMnl scaler_eq0 mulrn_eq0 /=. -rewrite -spin0 spin_inj -norm_eq0 norm_normalize ?vaxis_euler_neq0 // oner_eq0 orbF. +rewrite -spin0 spin_inj -enorm_eq0 norm_normalize ?vaxis_euler_neq0 // oner_eq0 orbF. move=> /eqP Hs. have := sin0cos1 Hs; case: (ler0P (cos a)) => _ Hc; move: Ma; last first. by rewrite emx30M' // => ->; rewrite angle1; left. @@ -1160,7 +1178,7 @@ rewrite subrr add0r -(mulr_natr (cos a)) -mulrA divrr ?unitfE ?pnatr_eq0 // mulr split => Ha; by [rewrite cosK | rewrite cosKN]. Qed. -Lemma angle_eskew a u : norm u = 1 -> 0 <= a <= pi -> angle `e^(a, u) = a. +Lemma angle_eskew a u : `|u|_e = 1 -> 0 <= a <= pi -> angle `e^(a, u) = a. Proof. move=> u1 Ha. rewrite /angle trace_eskew // addrAC subrr add0r. @@ -1305,7 +1323,7 @@ by rewrite ?(acos_ge0, acos_lepi) // tr_interval. Qed. Lemma vaxis_eskew a (w : vector) : - sin a != 0 -> 0 <= a <= pi -> norm w = 1 -> vaxis `e^(a, w) = w. + sin a != 0 -> 0 <= a <= pi -> `|w|_e = 1 -> vaxis `e^(a, w) = w. Proof. move=> sphi Ha w1; rewrite /vaxis angle_eskew //. case: eqP => [aE|/eqP aD]; first by move: (sphi); rewrite aE sinpi eqxx. @@ -1342,7 +1360,7 @@ Let vector := 'rV[T]_3. Definition log_rot (M : 'M[T]_3) : T * 'rV[T]_3 := (Aa.angle M, Aa.vaxis M). Lemma log_exp_eskew (a : T) (w : 'rV[T]_3) : - sin a != 0 -> 0 <= a <= pi -> norm w = 1 -> log_rot `e^(a, w) = (a, w). + sin a != 0 -> 0 <= a <= pi -> `|w|_e = 1 -> log_rot `e^(a, w) = (a, w). Proof. move=> ? ? ?; congr pair; by [rewrite Aa.angle_eskew | rewrite Aa.vaxis_eskew]. Qed. @@ -1364,7 +1382,7 @@ case/boolP : (Aa.angle M == 0) => [/eqP H|a0]. case/boolP : (Aa.angle M == pi) => [/eqP H|api]. rewrite H eskew_pi ?norm_normalize // /Aa.vaxis H eqxx ?vaxis_euler_neq0 //. exact: Aa.SO_pi_reflection. -(* +(* have sina0 : sin (Aa.angle M) != 0. apply: contra a0 => /eqP/sin0_inv [->//|/eqP]; by rewrite (negbTE api). *) @@ -1372,9 +1390,9 @@ set w : 'rV_3 := normalize _. have [a /andP[a_gtNpi a_lepi] Rota] := SO_isRot MSO. have {}Rota : isRot a (normalize (vaxis_euler M)) (mx_lin1 M). rewrite (isRotZ a _ (vaxis_euler_neq0 MSO)) //. - by rewrite invr_gt0 norm_gt0 vaxis_euler_neq0. + by rewrite invr_gt0 enorm_gt0 vaxis_euler_neq0. have w0 : normalize (vaxis_euler M) != 0 by rewrite normalize_eq0 vaxis_euler_neq0. -have w1 : norm w = 1 by rewrite norm_normalize // Aa.vaxis_neq0. +have w1 : `|w|_e = 1 by rewrite norm_normalize // Aa.vaxis_neq0. case: (leP 0 a) => Ha. - have aB1 : 0 <= a <= pi by rewrite Ha a_lepi. move: (Aa.isRot_angle w0 aB1 Rota) => a_angle_of_rot. @@ -1388,8 +1406,8 @@ case: (leP 0 a) => Ha. have k0 : 0 < k. rewrite /k invr_gt0 pmulrn_lgt0 // lt_neqAle eq_sym sina0 /=. by apply: sin_ge0_pi. - have Hn : normalize (vaxis_euler M) = - ((sin a *+ 2) * k) *: (norm (Aa.vaxis M) *: w). + have Hn : normalize (vaxis_euler M) = + ((sin a *+ 2) * k) *: (`|Aa.vaxis M|_e *: w). rewrite -(norm_scale_normalize (normalize (vaxis_euler M))). rewrite norm_normalize ?vaxis_euler_neq0 // w'axial. rewrite scale1r {2}/k divff ?mulrn_eq0 // scale1r. @@ -1398,8 +1416,8 @@ case: (leP 0 a) => Ha. rewrite pmulr_rgt0 // pmulrn_lgt0 // lt_neqAle eq_sym sina0. by rewrite sin_ge0_pi. rewrite -a_angle_of_rot isRot_eskew //. - rewrite normalizeZ ?normalizeI // -?norm_eq0 ?w1 ?oner_neq0 //. - by rewrite norm_gt0 ?Aa.vaxis_neq0. + rewrite normalizeZ ?normalizeI // -?enorm_eq0 ?w1 ?oner_neq0 //. + by rewrite enorm_gt0 ?Aa.vaxis_neq0. have aB1 : - pi <= a <= 0 by rewrite (ltW a_gtNpi) ltW. move: (Aa.isRot_angleN w0 aB1 Rota) => a_angle_of_rot. have : M \in unitmx by rewrite orthogonal_unit // rotation_sub // -rotationV. @@ -1417,7 +1435,7 @@ have sa_gt0 : 0 < sin (Aa.angle M). by rewrite -oppr_gt0 -sinN sin_gt0_pi // oppr_cp0 Ha ltrNl. have se_neq0 : sin (Aa.angle M) != 0 by case: ltgtP sa_gt0. have k0 : 0 < k by rewrite /k invr_gt0 pmulrn_lgt0. -apply: (@same_isRot _ _ _ _ (- norm (Aa.vaxis M) *: w) ((sin (Aa.angle M) *+ 2) * k) w0 _ (- Aa.angle M)). +apply: (@same_isRot _ _ _ _ (- `|Aa.vaxis M|_e *: w) ((sin (Aa.angle M) *+ 2) * k) w0 _ (- Aa.angle M)). - by rewrite pmulr_rgt0 // pmulrn_lgt0. - rewrite -(norm_scale_normalize (normalize (vaxis_euler M))) //. rewrite norm_normalize ?vaxis_euler_neq0 // w'axial //. @@ -1426,8 +1444,8 @@ apply: (@same_isRot _ _ _ _ (- norm (Aa.vaxis M) *: w) ((sin (Aa.angle M) *+ 2) by rewrite tr_axial scalerN. - by rewrite -a_angle_of_rot //. rewrite isRotZN; first by rewrite opprK isRot_eskew // normalizeI. - by rewrite -norm_eq0 w1 oner_neq0. -by rewrite oppr_lt0 norm_gt0 // Aa.vaxis_neq0. + by rewrite -enorm_eq0 w1 oner_neq0. +by rewrite oppr_lt0 enorm_gt0 // Aa.vaxis_neq0. Qed. Lemma angle_axis_isRot (Q : 'M[T]_3) : axial Q != 0 -> @@ -1454,7 +1472,7 @@ rewrite {3}H isRotZ; last 2 first. rewrite invr_eq0 mulrn_eq0 /=. suff : 0 < sin (Aa.angle Q) by case: ltgtP. by apply: sin_gt0_pi. - by rewrite invr_gt0 norm_gt0. + by rewrite invr_gt0 enorm_gt0. exact: isRot_eskew_normalize. Qed. @@ -1467,7 +1485,7 @@ Let vector := 'rV[T]_3. Record angle_axis := AngleAxis { angle_axis_val : T * vector ; - _ : norm (angle_axis_val.2) == 1 }. + _ : `|angle_axis_val.2|_e == 1 }. HB.instance Definition _ := [isSub for angle_axis_val]. (*Canonical angle_axis_subType := [subType for angle_axis_val].*) @@ -1475,20 +1493,20 @@ HB.instance Definition _ := [isSub for angle_axis_val]. Definition aangle (a : angle_axis) := (val a).1. Definition aaxis (a : angle_axis) := (val a).2. -Lemma norm_axis a : norm (aaxis a) = 1. +Lemma enorm_axis a : `|aaxis a|_e = 1. Proof. by case: a => *; apply/eqP. Qed. -Fact norm_e1_subproof : norm (@delta_mx T _ 3 0 0) == 1. -Proof. by rewrite norm_delta_mx. Qed. +Fact enorm_e1_subproof : `|@delta_mx T _ 3 0 0|_e == 1. +Proof. by rewrite enorm_delta_mx. Qed. Definition angle_axis_of (a : T) (v : vector) := - insubd (@AngleAxis (a,_) norm_e1_subproof) (a, normalize v). + insubd (@AngleAxis (a,_) enorm_e1_subproof) (a, normalize v). Lemma aaxis_of (a : T) (v : vector) : v != 0 -> aaxis (angle_axis_of a v) = normalize v. Proof. move=> v_neq0 /=; rewrite /angle_axis_of /aaxis val_insubd /=. -by rewrite normZ normfV normr_norm mulVf ?norm_eq0 // eqxx. +by rewrite enormZ normfV normr_enorm mulVf ?enorm_eq0// eqxx. Qed. Lemma aangle_of (a : T) (v : vector) : aangle (angle_axis_of a v) = a. @@ -1520,35 +1538,35 @@ Hypothesis MO : M \is 'O[T]_3. Lemma sqr_Mi0E i : M i 1 ^+ 2 + M i 2%:R ^+ 2 = 1 - M i 0 ^+ 2. Proof. -move/norm_row_of_O : MO => /(_ i)/(congr1 (fun x => x ^+ 2)). +move/enorm_row_of_O : MO => /(_ i)/(congr1 (fun x => x ^+ 2)). rewrite -dotmulvv dotmulE sum3E !mxE -!expr2 expr1n => /eqP. by rewrite -addrA addrC eq_sym -subr_eq => /eqP <-. Qed. Lemma sqr_Mi1E i : M i 0 ^+ 2 + M i 2%:R ^+ 2 = 1 - M i 1 ^+ 2. Proof. -move/norm_row_of_O : MO => /(_ i)/(congr1 (fun x => x ^+ 2)). +move/enorm_row_of_O : MO => /(_ i)/(congr1 (fun x => x ^+ 2)). rewrite -dotmulvv dotmulE sum3E !mxE -!expr2 expr1n => /eqP. by rewrite addrAC eq_sym -subr_eq => /eqP <-. Qed. Lemma sqr_Mi2E i : M i 0 ^+ 2 + M i 1 ^+ 2 = 1 - M i 2%:R ^+ 2. Proof. -move/norm_row_of_O : MO => /(_ i)/(congr1 (fun x => x ^+ 2)). +move/enorm_row_of_O : MO => /(_ i)/(congr1 (fun x => x ^+ 2)). rewrite -dotmulvv dotmulE sum3E !mxE -!expr2 expr1n => /eqP. by rewrite eq_sym -subr_eq => /eqP <-. Qed. Lemma sqr_M2jE j : M 0 j ^+ 2 + M 1 j ^+ 2 = 1 - M 2%:R j ^+ 2. Proof. -move/norm_col_of_O : MO => /(_ j)/(congr1 (fun x => x ^+ 2)). +move/enorm_col_of_O : MO => /(_ j)/(congr1 (fun x => x ^+ 2)). rewrite -dotmulvv dotmulE sum3E !mxE -!expr2 expr1n => /eqP. by rewrite eq_sym -subr_eq => /eqP <-. Qed. Lemma sqr_M0jE j : M 1 j ^+ 2 + M 2%:R j ^+ 2 = 1 - M 0 j ^+ 2. Proof. -move/norm_col_of_O : MO => /(_ j)/(congr1 (fun x => x ^+ 2)). +move/enorm_col_of_O : MO => /(_ j)/(congr1 (fun x => x ^+ 2)). rewrite -dotmulvv dotmulE sum3E !mxE -!expr2 expr1n => /eqP. by rewrite -addrA addrC eq_sym -subr_eq => /eqP <-. Qed. @@ -1601,7 +1619,7 @@ Local Open Scope frame_scope. (* two orthogonal vectors belonging to the plan (y,z) projected on y and z *) Lemma exists_rotation_angle (F : frame T) (u v : 'rV[T]_3) : - norm u = 1 -> norm v = 1 -> u *d v = 0 -> u *v v = F|,0 -> + `|u|_e = 1 -> `|v|_e = 1 -> u *d v = 0 -> u *v v = F|,0 -> { w : T | [/\ - pi < w <= pi, u = cos w *: (F|,1) + sin w *: (F|,2%:R) & v = - sin w *: (F|,1) + cos w *: (F|,2%:R)] }. @@ -1626,7 +1644,7 @@ case/boolP : (u *d F|,2%:R == 0) => [/eqP|] u2. rewrite (orthogonal_expansion F u) (orthogonal_expansion F v). rewrite u2 u0 v0 v1 !(scale0r,addr0,add0r). have [/eqP u1 | /eqP u1] : {u *d F |, 1 == 1} + {u *d F|,1 == -1}. - move: normu => /(congr1 (fun x => x ^+ 2)); rewrite (sqr_norm_frame F u). + move: normu => /(congr1 (fun x => x ^+ 2)); rewrite (sqr_enorm_frame F u). rewrite sum3E u0 u2 expr0n add0r addr0 expr1n => /eqP. by rewrite sqrf_eq1 => /Bool.orb_true_elim. - have v2 : v *d F|,2%:R = 1. @@ -1635,7 +1653,7 @@ case/boolP : (u *d F|,2%:R == 0) => [/eqP|] u2. rewrite {1}(orthogonal_expansion F v) v0 v1 !(scale0r,add0r). rewrite (linearZr_LR _ F|,1)/=. rewrite (frame_jcrossk F) => /scaler_eq1; apply. - by rewrite -norm_eq0 noframe_norm oner_eq0. + by rewrite -enorm_eq0 noframe_norm oner_eq0. rewrite v2 u1 !scale1r; by left. - have v2 : v *d F|,2%:R = -1. move: uva0. @@ -1644,7 +1662,7 @@ case/boolP : (u *d F|,2%:R == 0) => [/eqP|] u2. rewrite (linearNl _ _ F|,1)/=. rewrite (linearZr_LR _ _ (v *d F|,2))/=. rewrite (frame_jcrossk F) -scaleNr => /scaler_eqN1; apply. - by rewrite -norm_eq0 noframe_norm oner_eq0. + by rewrite -enorm_eq0 noframe_norm oner_eq0. rewrite v2 u1 !scaleN1r; by right. have pi2B : - pi < (pi : T) / 2%:R <= pi. rewrite lter_pdivlMr ?ltr0n // ler_pdivrMr ?ltr0n //. @@ -1657,7 +1675,7 @@ have piN2B : - pi < - ((pi : T) / 2%:R) <= pi. case/boolP : (u *d F|,1 == 0) => [/eqP|] u1. have {u2}[/eqP u2|/eqP u2] : {u *d F|,2%:R == 1} + {u *d F|,2%:R == -1}. move: normu => /(congr1 (fun x => x ^+ 2)). - rewrite (sqr_norm_frame F u) sum3E u0 u1 expr0n !add0r expr1n => /eqP. + rewrite (sqr_enorm_frame F u) sum3E u0 u1 expr0n !add0r expr1n => /eqP. by rewrite sqrf_eq1 => /Bool.orb_true_elim. + have v1 : v *d F|,1%:R = -1. move: uva0. @@ -1666,10 +1684,10 @@ case/boolP : (u *d F|,1 == 0) => [/eqP|] u1. rewrite (linearDr _ F|,2)/=. rewrite (linearZr_LR _ _ (v *d F|,1)) /= (@lieC _ (vec3 T)) /= (frame_jcrossk F). rewrite (linearZr_LR _ _ (v *d F|,2)) /= (@liexx _ (vec3 T)) scaler0 addr0 scalerN -scaleNr => /scaler_eqN1; apply. - by rewrite -norm_eq0 noframe_norm oner_eq0. + by rewrite -enorm_eq0 noframe_norm oner_eq0. have v2 : v *d F|,2%:R = 0. move: normv => /(congr1 (fun x => x ^+ 2)). - rewrite expr1n (sqr_norm_frame F) sum3E v1 v0 expr0n add0r sqrrN expr1n => /eqP. + rewrite expr1n (sqr_enorm_frame F) sum3E v1 v0 expr0n add0r sqrrN expr1n => /eqP. by rewrite eq_sym addrC -subr_eq subrr eq_sym sqrf_eq0 => /eqP. exists (pi / 2%:R). rewrite cos_pihalf sin_pihalf !(scale0r,add0r,scale1r,scaleN1r,addr0). @@ -1685,10 +1703,10 @@ case/boolP : (u *d F|,1 == 0) => [/eqP|] u1. rewrite (linearZr_LR _ _ (v *d F|,2))/=. rewrite /= (@liexx _ (vec3 T)) scaler0 subr0. rewrite -scalerN (@lieC _ (vec3 T)) /= opprK (frame_jcrossk F) => /scaler_eq1; apply. - by rewrite -norm_eq0 noframe_norm oner_eq0. + by rewrite -enorm_eq0 noframe_norm oner_eq0. have v2 : v *d F|,2%:R = 0. move: normv => /(congr1 (fun x => x ^+ 2)). - rewrite expr1n (sqr_norm_frame F) sum3E v1 v0 expr0n add0r expr1n => /eqP. + rewrite expr1n (sqr_enorm_frame F) sum3E v1 v0 expr0n add0r expr1n => /eqP. by rewrite eq_sym addrC -subr_eq subrr eq_sym sqrf_eq0 => /eqP. exists (- (pi / 2%:R)). rewrite cosN sinN cos_pihalf sin_pihalf ?(scale0r,add0r,scale1r,scaleN1r,addr0,opprK). @@ -1703,10 +1721,10 @@ have f2D0 : F|,2%:R != 0 by apply: contra u2 => /eqP->; rewrite dotmulv0. have [w [wB Hw1 Hw2]] : {w : T | [/\ - pi < w <= pi, u *d F|,1 = cos w & (u *d F|,2%:R) = sin w]}. apply: sqrD1_cossin. - move/(congr1 (fun x => norm x)) : Hr2. + move/(congr1 (fun x => `|x|_e)) : Hr2. rewrite normu. move/(congr1 (fun x => x ^+ 2)). - rewrite expr1n normD !normZ ?noframe_norm !mulr1. + rewrite expr1n enormD !enormZ ?noframe_norm !mulr1. rewrite (_ : cos _ = 0); last first. case: (lerP 0 (u *d F|,2%:R)). rewrite le_eqVlt eq_sym (negbTE u2) /= => {}u2. @@ -1760,16 +1778,16 @@ have <- : v *d F|,1 = - sin w. rewrite -Hw2 2!dotmul_cos normu 2!noframe_norm mul1r normv mulr1. rewrite [in LHS]mul1r [in RHS]mul1r ?opprK H'. rewrite [in RHS]cos_vec_anglevN ?opprK; [by [] | | ]. - by rewrite -norm_eq0 normv oner_neq0. - by rewrite -norm_eq0 noframe_norm oner_neq0. + by rewrite -enorm_eq0 normv oner_neq0. + by rewrite -enorm_eq0 noframe_norm oner_neq0. have <- : v *d F|,2%:R = cos w. by rewrite -Hw1 2!dotmul_cos normu 2!noframe_norm mul1r normv mulr1 H. by []. Qed. Lemma euler_angles_zyx_RO (a1 a2 u v : 'rV[T]_3) w1 k k' : - norm u = 1 -> norm v = 1 -> u *d v = 0 -> - norm a1 = 1 -> norm a2 = 1 -> a1 *d a2 = 0 -> + `|u|_e = 1 -> `|v|_e = 1 -> u *d v = 0 -> + `|a1|_e = 1 -> `|a2|_e = 1 -> a1 *d a2 = 0 -> u = k *: a1 + k' *: a2 -> v = - k' *: a1 + k *: a2 -> cos w1 = a1 *d u -> @@ -1853,8 +1871,8 @@ transitivity (row_mx (col 0 R) (row_mx a2 a3) *m Rx w1). r2^T = cos w *: (a |, 1) + sin w *: (a |, 2%:R) & r3^T = - sin w *: (a |, 1) + cos w *: (a |, 2%:R)] }. apply: exists_rotation_angle. - by rewrite tr_col norm_row_of_O // rotation_sub // rotationV. - by rewrite tr_col norm_row_of_O // rotation_sub // rotationV. + by rewrite tr_col enorm_row_of_O// rotation_sub// rotationV. + by rewrite tr_col enorm_row_of_O// rotation_sub// rotationV. rewrite 2!tr_col. by move: RSO; rewrite -rotationV => /rotation_sub/orthogonalP ->. rewrite frame_of_SO_i -tr_col -/a1 Ha1 !tr_col. @@ -1877,8 +1895,8 @@ transitivity (row_mx (col 0 R) (row_mx a2 a3) *m Rx w1). by move: RSO; rewrite -rotationV => /rotation_sub/orthogonal3P/and6P[_ /eqP]. by move: RSO; rewrite -rotationV => /rotation_sub/orthogonal3P/and6P[_ _ /eqP]. move: RSO; by rewrite -rotationV => /rotation_sub/orthogonal3P/and6P[_ _ _ _ _ /eqP]. - by rewrite tr_col norm_row_of_O // rotation_sub // rotationV Rzy_is_SO. - by rewrite tr_col norm_row_of_O // rotation_sub // rotationV Rzy_is_SO. + by rewrite tr_col enorm_row_of_O// rotation_sub// rotationV Rzy_is_SO. + by rewrite tr_col enorm_row_of_O// rotation_sub// rotationV Rzy_is_SO. move: (Rzy_is_SO w3 w2). rewrite -rotationV => /rotation_sub/orthogonal3P/and6P[_ _ _ _ _ /eqP]. by rewrite !tr_col. @@ -1887,14 +1905,14 @@ transitivity (row_mx (col 0 R) (row_mx a2 a3) *m Rx w1). by rewrite -Ha1 row_mx_colE. Qed. -Lemma Rz_rotation_exists (u : 'rV[T]_3) : norm u = 1 -> +Lemma Rz_rotation_exists (u : 'rV[T]_3) : `|u|_e = 1 -> u != 'e_2%:R -> u != - 'e_2%:R -> let n : 'rV_3 := normalize ('e_2%:R *v u) in {phi | isRot phi 'e_2%:R (mx_lin1 (Rz phi)) & 'e_0 *m Rz phi = n}. Proof. move=> u1 H1 H2 n. exists (if 0 <= u``_0 then vec_angle n 'e_0 else - vec_angle n 'e_0). - by rewrite Rz_eskew isRot_eskew // ?normalizeI // ?norm_delta_mx. + by rewrite Rz_eskew isRot_eskew ?normalizeI ?enorm_delta_mx. rewrite {1}e0row /Rz mulmx_row3_col3 ?(scale0r,scale1r,addr0). rewrite [in RHS]/n crossmulE. rewrite (_ : 'e_2%:R 0 1 = 0) ?(mul0r,add0r); last by rewrite mxE. @@ -1902,9 +1920,9 @@ rewrite (_ : 'e_2%:R 0 0 = 0) ?(mul0r,subrr,subr0); last by rewrite mxE. rewrite (_ : 'e_2%:R 0 2%:R = 1) ?mul1r; last by rewrite mxE. have ? : 'e_2%:R *v u != 0. apply/colinearP; case. - by rewrite -norm_eq0 u1 // oner_eq0. + by rewrite -enorm_eq0 u1 // oner_eq0. case=> _ [k Hk]; have k1 : `|k| = 1. - move: Hk => /(congr1 (@norm _ _)); rewrite normZ u1 mulr1 norm_delta_mx. + move: Hk => /(congr1 (@enorm _ _)); rewrite enormZ u1 mulr1 enorm_delta_mx. by move->. case: (lerP k 0) => k0; move: k1 Hk. rewrite ler0_norm // -{2}(opprK k) => ->; rewrite scaleN1r. @@ -1912,13 +1930,13 @@ have ? : 'e_2%:R *v u != 0. by rewrite gtr0_norm // => ->; rewrite scale1r => /esym; apply/eqP. rewrite /normalize row3Z mulr0; congr row3. - transitivity (n *d 'e_0). - rewrite dotmul_cos norm_normalize ?mul1r ?norm_delta_mx ?mul1r //. + rewrite dotmul_cos norm_normalize ?mul1r ?enorm_delta_mx ?mul1r //. case: ifP => //; by rewrite cosN. by rewrite -coorE /n crossmulE /normalize row3Z !mxE /= ?(mulr0,mul0r,add0r,mul1r,subr0,oppr0). -- transitivity (if 0 <= u``_0 then norm (n *v 'e_0) else - norm (n *v 'e_0)). - rewrite norm_crossmul norm_normalize ?mul1r // norm_delta_mx mul1r. - rewrite ger0_norm // ?sin_vec_angle_ge0 // -?norm_eq0 ?norm_normalize ?oner_neq0 // - ?norm_delta_mx ?oner_neq0 //. +- transitivity (if 0 <= u``_0 then `|n *v 'e_0|_e else - `|n *v 'e_0|_e). + rewrite enorm_crossmul norm_normalize ?mul1r // enorm_delta_mx mul1r. + rewrite ger0_norm // ?sin_vec_angle_ge0 // -?enorm_eq0 ?norm_normalize ?oner_neq0 // + ?enorm_delta_mx ?oner_neq0 //. case: ifPn => //; by rewrite sinN. rewrite /n /normalize crossmulE. rewrite (_ : 'e_0%:R 0 2%:R = 0) ?(mulr0,subr0,add0r); last by rewrite mxE. @@ -1929,12 +1947,12 @@ rewrite /normalize row3Z mulr0; congr row3. rewrite (_ : 'e_2%:R 0 0 = 0) ?(mul0r,subrr,subr0); last by rewrite mxE. rewrite (_ : 'e_2%:R 0 2%:R = 1) ?(mul1r); last by rewrite mxE. rewrite !mxE mulr0 /=. - rewrite -{2 3 5 6}(oppr0) -row3N normN. + rewrite -{2 3 5 6}(oppr0) -row3N enormN. rewrite [in LHS]mulrC -{2 3 5 6}(mulr0 (u``_0)) -row3Z. - rewrite normZ mulrC norm_row3z ger0_norm ?invr_ge0 ?norm_ge0 //. + rewrite enormZ mulrC enorm_row3z ger0_norm ?invr_ge0 ?enorm_ge0//. case: ifPn => R20. - by rewrite ger0_norm. - - by rewrite ltr0_norm ?ltNge // mulrN opprK. + - by rewrite ltr0_norm ?ltNge// mulrN opprK. Qed. End euler_angles_existence. diff --git a/scara.v b/scara.v index 7dabcad8..ef544782 100644 --- a/scara.v +++ b/scara.v @@ -1,5 +1,5 @@ -(* coq-robot (c) 2017 AIST and INRIA. License: LGPL-2.1-or-later. *) -From mathcomp Require Import all_ssreflect ssralg ssrint ssrnum rat poly. +(* robot-rocq (c) 2026 AIST and INRIA. License: LGPL-2.1-or-later. *) +From mathcomp Require Import all_boot ssralg ssrint ssrnum rat poly. From mathcomp Require Import closed_field polyrcf matrix mxalgebra mxpoly zmodp. From mathcomp Require Import realalg complex fingroup perm. From mathcomp Require Import sesquilinear. @@ -8,18 +8,20 @@ Require Import ssr_ext euclidean skew vec_angle rot frame rigid screw. From mathcomp Require Import reals. Require Import extra_trigo. -(******************************************************************************) -(* SCARA Robot Manipulator *) +(**md**************************************************************************) +(* # SCARA Robot Manipulator *) (* *) (* This file addresses the forward kinematics problem for the SCARA robot *) (* manipulator in two ways: (1) it first provides the DH parameters, *) (* (2) using screw motions. *) (* *) +(* ``` *) (* B10,B21,B32,B43 == relative positions of the consecutive frames of the *) (* SCARA robot manipulator using DH parameters *) (* t1,t2,t3,t4 == twists of the SCARA robot manipulator *) (* g0 == position of the end-effector using twists *) (* g == orientation of the end-effector using twists *) +(* ``` *) (* *) (******************************************************************************) @@ -118,7 +120,7 @@ rewrite /t1 /rjoint_twist. rewrite (linearNl _ q1)/=. rewrite (linear0r _ w1)/=. rewrite oppr0 etwist_Rz; last first. - by rewrite -norm_eq0 normeE oner_eq0. + by rewrite -enorm_eq0 enormeE oner_eq0. by rewrite -Rz_eskew. Qed. @@ -126,11 +128,11 @@ Qed. Lemma point_axis_twist (d : R) : \pt( axis \T((- 'e_2%:R *v row3 d 0 0), 'e_2%:R) ) = row3 d 0 0. Proof. -rewrite {1}/axis ang_tcoorE (negbTE (norm1_neq0 (normeE _ _))) /=. -rewrite normeE expr1n invr1 scale1r lin_tcoorE. +rewrite {1}/axis ang_tcoorE (negbTE (norm1_neq0 (enormeE _ _))) /=. +rewrite enormeE expr1n invr1 scale1r lin_tcoorE. rewrite (linearNl _ ((row3 d)``_0))/=. rewrite (linearNr _ ('e_2))/=. -rewrite double_crossmul dotmulvv normeE expr1n scale1r /w2 /q2 e2row. +rewrite double_crossmul dotmulvv enormeE expr1n scale1r /w2 /q2 e2row. rewrite dotmulE sum3E !mxE /=. by Simp.r. Qed. @@ -138,8 +140,8 @@ Lemma S2_helper th d : `e$(th, \T(- w2 *v row3 d 0 0, w2)) = hom (Rz th) (row3 (d * (1 - cos th)) (- d * sin th) 0). Proof. -rewrite etwistE (negbTE (norm1_neq0 (normeE _ _))). -rewrite pitch_perp ?normeE // mulr0 scale0r add0r. +rewrite etwistE (negbTE (norm1_neq0 (enormeE _ _))). +rewrite pitch_perp ?enormeE// mulr0 scale0r add0r. rewrite point_axis_twist -Rz_eskew; congr hom. rewrite mulmxBr mulmx1 mulmx_row3_col3 !scale0r !addr0 row3Z row3N row3D. Simp.r. diff --git a/screw.v b/screw.v index 37304ea0..a0cdfd39 100644 --- a/screw.v +++ b/screw.v @@ -1,4 +1,4 @@ -(* coq-robot (c) 2017 AIST and INRIA. License: LGPL-2.1-or-later. *) +(* robot-rocq (c) 2026 AIST and INRIA. License: LGPL-2.1-or-later. *) From HB Require Import structures. From mathcomp Require Import all_boot order ssralg ssrint ssrnum rat poly. From mathcomp Require Import closed_field polyrcf matrix mxalgebra mxpoly zmodp. @@ -7,8 +7,8 @@ From mathcomp Require Import sesquilinear. From mathcomp Require Import interval reals trigo. Require Import ssr_ext euclidean skew vec_angle frame rot rigid extra_trigo. -(******************************************************************************) -(* Screw Motions *) +(**md**************************************************************************) +(* # Screw Motions *) (* *) (* This file develops the theory of screws and twists. It establishes in *) (* particular Chasles' theorem (given a rigid body motion, it shows *) @@ -16,6 +16,7 @@ Require Import ssr_ext euclidean skew vec_angle frame rot rigid extra_trigo. (* rigid body motion), Mozzi-Chasles' theorem (it shows the existence of a *) (* set of points that undergo just a translation---this is the screw axis). *) (* *) +(* ``` *) (* Module sqLieAlgebra == square matrices form a Lie algebra *) (* 'se3[R] == the set of twists *) (* wedge t == form a twist in 'se3[R] given twist (coordinates) *) @@ -35,6 +36,7 @@ Require Import ssr_ext euclidean skew vec_angle frame rot rigid extra_trigo. (* `e$(a, t) == the exponential of a twist t with angle a *) (* rjoint_twist w p == twist of a revolute joint *) (* pjoint_twist v == twist of a prismatic joint *) +(* ``` *) (* *) (******************************************************************************) @@ -54,7 +56,7 @@ Local Open Scope ring_scope. (* TODO: move? *) Lemma mulmx_tr_uvect (T : rcfType) (w : 'rV[T]_3) : - norm w = 1 -> (w^T *m w) ^+ 2 = w^T *m w. + `|w|_e = 1 -> (w^T *m w) ^+ 2 = w^T *m w. Proof. move=> w1; rewrite expr2 -mulmxE -mulmxA (mulmxA w) dotmulP dotmulvv w1 expr1n. by rewrite mul1mx. @@ -623,7 +625,7 @@ rewrite /wedge Twist.ang_of Twist.lin_of spin0. by rewrite -idmxE (@scalar_mx_block _ 3 1 1) (add_block_mx 1 0 0 1 0 _ v) !(addr0,add0r). Qed. -Lemma p41eq234 w v : norm w = 1 -> +Lemma p41eq234 w v : `|w|_e = 1 -> let g := rigid_trans w v in let h := w *d v in g^-1 *m wedge \T(v, w) *m g = wedge \T(h *: w, w). @@ -651,7 +653,7 @@ rewrite !mulrA divrr ?rigid_trans_unit // mul1r -mulrA. by rewrite divrr ?mulr1 // rigid_trans_unit. Qed. -Lemma p42eq2 w v : norm w = 1 -> +Lemma p42eq2 w v : `|w|_e = 1 -> let g := rigid_trans w v in let e' := g^-1 *m wedge \T(v, w) *m g in forall k, e' ^+ k.+2 = block_mx (\S( w ) ^+ k.+2) 0 0 0. @@ -671,7 +673,7 @@ rewrite exprS mulmxA spinE. by rewrite (linearZr_LR _ w)/= (@liexx _ (vec3 T)) scaler0 mul0mx. Qed. -Lemma emx2_twist w v a : norm w = 1 -> +Lemma emx2_twist w v a : `|w|_e = 1 -> let g := rigid_trans w v in let h := w *d v in emx (a *: wedge \T(v, w) ) 2 = g *m hom (emx (a *: \S( w)) 2) (h *: (a *: w)) *m g^-1. @@ -694,7 +696,7 @@ rewrite (linearZl_LR _ (v *v w))/= -scalerDr; congr (_ *: _). by rewrite double_crossmul dotmulvv w1 expr1n scale1r -/h addrCA subrr addr0. Qed. -Lemma p42eq3 w v a : norm w = 1 -> +Lemma p42eq3 w v a : `|w|_e = 1 -> let g := rigid_trans w v in let h := w *d v in let e' := g^-1 *m wedge \T(v, w) *m g in @@ -718,7 +720,7 @@ Definition hom_twist (t : twist T) (a : T) e : 'M[T]_4 := if w == 0 then hom 1 (a *: v) else - hom e ((norm w)^-2 *: ((w *v v) *m (1 - e) + (a *: v) *m (w^T *m w))). + hom e ((`|w|_e) ^- 2 *: ((w *v v) *m (1 - e) + (a *: v) *m (w^T *m w))). (* [murray] eqn 2.36, p.42 *) Definition emx_twist a t k : 'M_4 := @@ -736,9 +738,9 @@ case/boolP : (w == 0) => [/eqP ->|w0]. rewrite tcoorZ /= scaler0 emx_twist0E. by rewrite /emx_twist /hom_twist ang_tcoorE eqxx lin_tcoorE. set w' : 'rV_3 := a *: w. -rewrite -(norm_scale_normalize w) (_ : v = (norm w) *: ((norm w)^-1 *: v)); last first. - by rewrite scalerA divrr ?scale1r // unitfE norm_eq0. -rewrite -(tcoorZ (norm w) ((norm w)^-1 *: v) (normalize w)). +rewrite -(norm_scale_normalize w) (_ : v = `|w|_e *: ((`|w|_e)^-1 *: v)); last first. + by rewrite scalerA divrr ?scale1r // unitfE enorm_eq0. +rewrite -(tcoorZ `|w|_e ((`|w|_e)^-1 *: v) (normalize w)). rewrite scalerA p42eq235 p42eq3; last by rewrite norm_normalize. rewrite -mulmxE. rewrite {1}/rigid_trans mulmxE homM mul1r. @@ -760,19 +762,19 @@ rewrite (linearZl_LR _ w) /=. rewrite [in X in _ + _ + X = _]scalerN. rewrite [in X in _ + _ + X]scalerA. rewrite -[in LHS]scalemxAl -scalerDr -scalerBr; congr (_ *: _). - by rewrite -invrM ?unitfE ?norm_eq0. + by rewrite -invrM ?unitfE ?enorm_eq0. rewrite -/w' /= [in X in _ = X + _]mulmxBr mulmx1. rewrite -[in RHS]addrA [in RHS]addrC; congr (_ + _ + _). - rewrite lin_tcoorE (@lieC _ (vec3 T)) mulNmx. - by rewrite scalerA divrr ?scale1r // ?unitfE ?norm_eq0. + by rewrite scalerA divrr ?scale1r ?unitfE ?enorm_eq0. - rewrite lin_tcoorE. - rewrite (scalerA (norm w)) divrr ?scale1r ?unitfE ?norm_eq0 //. + rewrite (scalerA `|w|_e) divrr ?scale1r ?unitfE ?enorm_eq0//. rewrite -scalemxAl. rewrite mulmxA. rewrite dotmulP mul_scalar_mx dotmulC. by rewrite scalerA mulrC -scalerA. - rewrite (@lieC _ (vec3 T)) opprK; congr (_ *v _). - by rewrite lin_tcoorE scalerA divrr ?scale1r ?lin_of_twistE // unitfE norm_eq0. + by rewrite lin_tcoorE scalerA divrr ?scale1r ?lin_of_twistE // unitfE enorm_eq0. Qed. (* [murray] proposition 2.8, p. 41 *) @@ -803,16 +805,16 @@ Local Notation "'`e$(' a ',' t ')'" := (etwist a t) (format "'`e$(' a ',' t ')' Lemma etwistv0 (a : T) : `e$(a, \T(0, 0)) = hom 1 0. Proof. by rewrite /etwist ang_tcoorE /hom_twist ang_tcoorE eqxx lin_tcoorE scaler0. Qed. -Lemma etwist_is_SE (t : twist T) a : norm \w( t ) = 1 -> `e$(a, t) \is 'SE3[T]. +Lemma etwist_is_SE (t : twist T) a : `|\w( t )|_e = 1 -> `e$(a, t) \is 'SE3[T]. Proof. move=> w1. by rewrite /etwist /hom_twist (negbTE (norm1_neq0 w1)) hom_is_SE // eskew_is_SO. Qed. Definition etwist_is_onto_SE_mat (a : T) w := - (a * norm w ^+ 2)%:A - + ((1 - cos a) * norm w ^+2) *: \S(w) - + (a - sin a) *: \S(w)^+2. + (a * `|w|_e ^+ 2)%:A + + ((1 - cos a) * `|w|_e ^+ 2) *: \S(w) + + (a - sin a) *: \S(w) ^+ 2. (*******************STOP*****************************) Definition etwist_is_onto_SE_mat_inv (a : T) w := @@ -820,8 +822,8 @@ Definition etwist_is_onto_SE_mat_inv (a : T) w := - 2%:R^-1 *: \S(w) + (a^-1 - 2%:R^-1 * cot (a / 2%:R)) *: \S(w) ^+ 2. -Lemma etwist_is_onto_SE_matP a w - (aB : - pi < a <= pi) (a0 : a != 0) (w1 : norm w = 1) : +Lemma etwist_is_onto_SE_matP a w + (aB : - pi < a <= pi) (a0 : a != 0) (w1 : `|w|_e = 1) : etwist_is_onto_SE_mat_inv a w * etwist_is_onto_SE_mat a w = 1. Proof. rewrite /etwist_is_onto_SE_mat /etwist_is_onto_SE_mat_inv. @@ -901,11 +903,11 @@ Lemma etwist_is_onto_SE (f : 'M[T]_4) : f \is 'SE3[T] -> Proof. set p := trans_of_hom f. case/boolP: (rot_of_hom f == 1) => rotf fSE. -case/boolP : ((norm p) == 0) => p0. +case/boolP : (`|p|_e == 0) => p0. exists \T(p, 0), 1. rewrite /etwist /hom_twist ang_tcoorE eqxx lin_tcoorE. by rewrite scale1r (SE3E fSE) (eqP rotf). - exists \T((norm p)^-1 *: p, 0), (norm p). + exists \T((`|p|_e)^-1 *: p, 0), `|p|_e. rewrite /etwist /hom_twist ang_tcoorE eqxx /= lin_tcoorE. rewrite scalerA divff //. by rewrite scale1r (SE3E fSE) (eqP rotf). @@ -915,7 +917,7 @@ have a0 : a != 0. apply: contra rotf => /eqP. rewrite fexp_skew => ->; by rewrite emx30M. set A : 'M_3 := \S(w) *m (1 - rot_of_hom f) + a *: (w^T *m w). -suff [v Hv] : { v | p = (norm w)^-2 *: (v *m A) }. +suff [v Hv] : { v | p = (`|w|_e) ^- 2 *: (v *m A) }. exists \T(v, w), a. rewrite (SE3E fSE) /etwist /hom_twist ang_tcoorE. have /negbTE -> : w != 0 by rewrite normalize_eq0 vaxis_euler_neq0 // rot_of_hom_is_SO. @@ -942,9 +944,9 @@ have HA : A = etwist_is_onto_SE_mat a w. by rewrite scaleNr scalerN opprK scalerA. suff : { A' : 'M_3 | A' * A = 1 }. case => A' AA'. - exists ((norm w) ^+2 *: p *m A'). + exists ((`|w|_e) ^+ 2 *: p *m A'). rewrite -mulmxA mulmxE AA' mulmx1 scalerA. - rewrite mulrC divrr ?scale1r // unitfE expf_eq0 /= norm_eq0. + rewrite mulrC divrr ?scale1r // unitfE expf_eq0 /= enorm_eq0. apply: contra rotf; rewrite fexp_skew => /eqP ->. by rewrite spin0 emx3a0. (* NB: corresponds to [murray], exercise 9, p.75 *) @@ -989,11 +991,11 @@ Definition w : vector := 'e_2%:R. Let A_inv := etwist_is_onto_SE_mat_inv a w. -Definition v := ((norm w)^+2 *: P20) *m A_inv. +Definition v := ((`|w|_e) ^+ 2 *: P20) *m A_inv. Lemma vP : v = row3 ((a1 + a2) * sin a / (2%:R * (1 - cos a))) (- (a1 - a2) / 2%:R) 0 :> vector. Proof. -rewrite /v normeE expr1n scale1r /P20. +rewrite /v enormeE expr1n scale1r /P20. rewrite /A_inv /etwist_is_onto_SE_mat_inv. rewrite mulmxDr mulmxBr. rewrite mul_mx_scalar row3Z mulr0. @@ -1053,7 +1055,7 @@ Definition screw_motion s (p : point) : 'rV_3 := let p0 := \pt( l ) in let w := \vec( l ) in p0 + (p - p0) *m `e^(a, w) + (h * a) *: w. -Lemma screw_motionE s (p : point) (w1 : norm \vec( Screw.l s) = 1) : +Lemma screw_motionE s (p : point) (w1 : `| \vec( Screw.l s) |_e = 1) : let l := Screw.l s in let a := Screw.a s in let h := Screw.h s in let q := \pt( l ) in let w := \vec( l ) in screw_motion s p = EuclideanMotion.motion_point @@ -1114,7 +1116,7 @@ rewrite [in X in _ = _ *: (X + _)]mulmxBl. rewrite opprB -addrA. rewrite scalerDr. rewrite -[in X in _ = X + _]scalemxAl scalerA [in X in _ = X + _]mulrC divrr ?scale1r; last first. - by rewrite unitfE expf_eq0 /= norm_eq0. + by rewrite unitfE expf_eq0 /= enorm_eq0. congr (_ + _). rewrite -[in X in _ = _ *: (_ + X)]scalemxAl. rewrite mulmxDl. @@ -1125,7 +1127,7 @@ rewrite scalerDr. rewrite 2!scalerA. rewrite [in X in _ = X + _]mulrA. rewrite [in X in _ = X + _]mulrC. -rewrite -(mulrA (a * h)) divrr ?mulr1; last by rewrite unitfE expf_eq0 /= norm_eq0. +rewrite -(mulrA (a * h)) divrr ?mulr1; last by rewrite unitfE expf_eq0 /= enorm_eq0. rewrite mulrC -[LHS]addr0. congr (_ + _). rewrite mulmxBr mulmx1. @@ -1154,7 +1156,7 @@ Definition axis (t : twist T) : Line.t T := if w == 0 then Line.mk 0 v else - Line.mk ((norm w)^-2 *: (w *v v)) w. + Line.mk ((`|w|_e) ^- 2 *: (w *v v)) w. Lemma point_axis_nolin w : w != 0 -> \pt( axis \T(0, w) ) = 0. Proof. @@ -1165,7 +1167,7 @@ Qed. (* [murray] 2.42, p.47 *) Definition pitch (t : twist T) : T := let w := \w( t ) in let v := \v( t ) in - (norm w)^-2 *: v *d w. + (`|w|_e) ^- 2 *: v *d w. Lemma pitch_nolin (w : 'rV[T]_3) : pitch \T(0, w) = 0. Proof. by rewrite /pitch ang_tcoorE lin_tcoorE scaler0 dotmul0v. Qed. @@ -1174,7 +1176,7 @@ Definition rjoint_twist (w : vector) (q : point) := \T(- w *v q, w). Definition pjoint_twist (v : vector) := \T(v, 0). -Lemma pitch_perp (w u : 'rV[T]_3) : norm w = 1 -> pitch (rjoint_twist w u) = 0. +Lemma pitch_perp (w u : 'rV[T]_3) : `|w|_e = 1 -> pitch (rjoint_twist w u) = 0. Proof. move=> w1; rewrite /pitch ang_tcoorE lin_tcoorE w1 expr1n invr1 scale1r. rewrite (@lieC _ (vec3 T))/=. @@ -1184,34 +1186,34 @@ Qed. (* [murray] 2.44, p.48 *) Definition magnitude (t : twist T) : T := let w := \w( t ) in let v := \v( t ) in - if w == 0 then norm v else norm w. + if w == 0 then `|v|_e else `|w|_e. Lemma magnitudeZ (t : twist T) a : 0 < a -> magnitude ((a *: t) : 'M__) = a * magnitude t. Proof. move=> a_gt0. rewrite /magnitude. -case/boolP : (a == 0) => [/eqP ->|a0]. - by rewrite scale0r mul0r ang_tcoor0 eqxx lin_tcoor0 norm0. +have [->|a0] := eqVneq a 0. + by rewrite scale0r mul0r ang_tcoor0 eqxx lin_tcoor0 enorm0. rewrite ang_tcoorZ scaler_eq0 (negbTE a0) /=. case: ifPn => M0. - by rewrite lin_tcoorZ normZ gtr0_norm. -by rewrite normZ gtr0_norm. + by rewrite lin_tcoorZ enormZ gtr0_norm. +by rewrite enormZ gtr0_norm. Qed. (* unit twist: [murray] p.49 (p.48 also) *) Definition utwist (t : twist T) := (magnitude t == 1). Lemma utwistE (t : twist T) : utwist t = - (norm \w( t ) == 1) || ((norm \w( t ) == 0) && (norm \v( t ) == 1)). + (`| \w( t ) |_e == 1) || ((`| \w( t ) |_e == 0) && (`| \v( t ) |_e == 1)). Proof. apply/idP/idP. - rewrite /utwist /magnitude. - case: ifPn => [/eqP -> ->|w0 ->]; by rewrite norm_eq0 ?eqxx /= ?orbT. + case: ifPn => [/eqP -> ->|w0 ->]; by rewrite enorm_eq0 ?eqxx /= ?orbT. - case/orP => [w1|/andP[w0 v1]]. rewrite /utwist /magnitude; case: ifPn => [w0| //]. - by rewrite (eqP w0) norm0 eq_sym (negbTE (@oner_neq0 _)) in w1. - by rewrite /utwist /magnitude -{1}norm_eq0 w0. + by rewrite (eqP w0) enorm0 eq_sym (negbTE (@oner_neq0 _)) in w1. + by rewrite /utwist /magnitude -{1}enorm_eq0 w0. Qed. (* [murray] p. 48 @@ -1279,7 +1281,7 @@ congr hom. rewrite lin_tcoorE. rewrite -scalemxAl mulmxA dotmulP scalemxAl scalerDr -scalemxAl. rewrite (scalerA _ a) (mulrC _ a). -rewrite -(scalerA a (norm w ^+ 2)^-1). +rewrite -(scalerA a (`|w|_e ^+ 2)^-1). rewrite mul_scalar_mx (scalerA _ (v *d w) w) -(dotmulZv v _ w). rewrite (_ : _ *d _ = pitch \T(v, w)); last by rewrite /pitch lin_tcoorE ang_tcoorE. rewrite addrC. @@ -1320,7 +1322,7 @@ Let vaxis0 : Aa.vaxis Q != 0. Proof. by rewrite /Aa.vaxis (negbTE api) scaler_eq0 negb_or w0 andbT invr_eq0 mulrn_eq0. Qed. -Let w1 : norm w = 1. Proof. by rewrite norm_normalize. Qed. +Let w1 : `|w|_e = 1. Proof. by rewrite norm_normalize. Qed. (* [angeles] theorem 3.2.1, p.97: the displacements of all the points of the body have the same projection onto e *) @@ -1341,32 +1343,32 @@ Qed. Definition axialdisp p := axialcomp (displacement f p) w. -Lemma axialdispE p : axialdisp p = d0 *: ((norm w)^-2 *: w). +Lemma axialdispE p : axialdisp p = d0 *: ((`|w|_e) ^- 2 *: w). Proof. rewrite /axialdisp /axialcomp dotmulC dotmulvZ displacement_proj mulrC -scalerA. -by rewrite (scalerA (norm w)^-1) -expr2 exprVn. +by rewrite (scalerA (`|w|_e)^-1) -expr2 exprVn. Qed. Definition normdisp p := normalcomp (displacement f p) w. Lemma decomp_displacement p : - norm (displacement f p) ^+ 2 = norm (d0 *: (norm w ^- 2 *: w)) ^+2 + norm (normdisp p) ^+ 2. + `|displacement f p|_e ^+ 2 = `|d0 *: (`|w|_e ^- 2 *: w)|_e ^+2 + `|normdisp p|_e ^+ 2. Proof. -rewrite (axialnormalcomp (displacement f p) w) normD -dotmul_cos axialnormal // mul0rn addr0. +rewrite (axialnormalcomp (displacement f p) w) enormD -dotmul_cos axialnormal // mul0rn addr0. by rewrite -/(normdisp p) -/(axialdisp p) axialdispE. Qed. -Lemma MozziChasles_helper p : norm (displacement f p) = d0 -> normdisp p = 0. +Lemma MozziChasles_helper p : `|displacement f p|_e = d0 -> normdisp p = 0. Proof. move=> Hp. -have := lexx (norm (d0 *: w) ^+ 2). -rewrite {1}normZ w1 mulr1 sqr_normr -{1}Hp decomp_displacement -lerBDl. +have := lexx (`|d0 *: w|_e ^+ 2). +rewrite {1}enormZ w1 mulr1 sqr_normr -{1}Hp decomp_displacement -lerBDl. rewrite w1 expr1n invr1 scale1r. -by rewrite subrr le_eqVlt ltNge sqr_ge0 orbF sqrf_eq0 norm_eq0 => /eqP. +by rewrite subrr le_eqVlt ltNge sqr_ge0 orbF sqrf_eq0 enorm_eq0 => /eqP. Qed. (* [angeles] theorem 3.2.2, p.97 *) -Lemma MozziChasles p : norm (displacement f p) = d0 -> +Lemma MozziChasles p : `|displacement f p|_e = d0 -> colinear (displacement f p) w. Proof. move=> H. @@ -1443,8 +1445,8 @@ rewrite /Aa.vaxis. rewrite (negbTE api). by rewrite scaler_eq0 negb_or w0 andbT invr_eq0 mulrn_eq0. Qed. -Let w1 : norm w = 1. -Proof. rewrite norm_normalize //. Qed. +Let w1 : `|w|_e = 1. +Proof. by rewrite norm_normalize. Qed. Lemma wTwQN1 : (w^T *m w) *m (Q - 1)^T = 0. Proof. @@ -1580,7 +1582,7 @@ Qed. (* [angeles] Sect. 3.2.1 (the screw of a rigid-body motion) *) Lemma screw_axis_pointE p0 q : p0 *d w = 0 (* p0 is the closed point to the origin *) -> - norm (displacement f p0) = d0 f -> + `|displacement f p0|_e = d0 f -> p0 = screw_axis_point f q. Proof. move=> p0e0 fp0e0. diff --git a/skew.v b/skew.v index 5a577f43..affd9052 100644 --- a/skew.v +++ b/skew.v @@ -1,18 +1,19 @@ -(* coq-robot (c) 2017 AIST and INRIA. License: LGPL-2.1-or-later. *) +(* robot-rocq (c) 2026 AIST and INRIA. License: LGPL-2.1-or-later. *) From HB Require Import structures. -From mathcomp Require Import all_ssreflect ssralg ssrint ssrnum rat poly. +From mathcomp Require Import all_boot ssralg ssrint ssrnum rat poly. From mathcomp Require Import closed_field polyrcf matrix mxalgebra mxpoly zmodp. From mathcomp Require Import sesquilinear. From mathcomp Require Import realalg complex finset fingroup perm ring. Require Import ssr_ext euclidean vec_angle. From mathcomp Require Import reals. -(******************************************************************************) -(* Skew-symmetric matrices *) +(**md**************************************************************************) +(* # Skew-symmetric matrices *) (* *) (* This file develops the theory of skew-symmetric matrices to be used in *) (* particular to represent the exponential coordinates of rotation matrices. *) (* *) +(* ``` *) (* 'so[R]_n == the type of skew-symmetric matrices, i.e., matrices M such *) (* that M = -M^T *) (* \S(w) == the spin of vector w, i.e., the (row-vector convention) *) @@ -20,10 +21,13 @@ From mathcomp Require Import reals. (* symp A == symmetric part of matrix A *) (* antip A == antisymmetric part of matrix A *) (* spin_eigenvalues u == eigenvalues of \S(u) *) +(* ``` *) (* *) (* Cayley transform: *) +(* ``` *) (* cayley M == (1 - M)^-1 * (1 + M) *) (* uncayley M == (M - 1) * (M + 1)^-1 *) +(* ``` *) (* *) (******************************************************************************) @@ -533,7 +537,7 @@ Let vector := 'rV[R]_3. Implicit Types u : vector. Implicit Types M : 'M[R]_3. -Lemma sqr_spin u : \S( u ) ^+ 2 = u^T *m u - (norm u ^+ 2)%:A. +Lemma sqr_spin u : \S( u ) ^+ 2 = u^T *m u - (`|u|_e ^+ 2)%:A. Proof. apply (symP (sqr_spin_is_sym u)); last move=> i j. rewrite rpredD//= ?mul_tr_vec_sym//. @@ -556,18 +560,18 @@ case/boolP : (i == 0) => [/eqP-> _|/ifnot0P/orP[]/eqP->]. by rewrite -eqr_opp 2!opprB opprK eq_sym subr_eq -dotmulvv dotmulE sum3E -!expr2. Qed. -Lemma spin3 u : \S( u ) ^+ 3 = - (norm u) ^+ 2 *: \S( u ). +Lemma spin3 u : \S( u ) ^+ 3 = - `|u|_e ^+ 2 *: \S( u ). Proof. rewrite exprS sqr_spin mulrBr -mulmxE mulmxA spin_mul_tr mul0mx add0r. by rewrite scalemx1 mul_mx_scalar scaleNr. Qed. -Lemma exp_spin u n : \S( u ) ^+ n.+3 = - (norm u) ^+ 2 *: \S( u ) ^+ n.+1. +Lemma exp_spin u n : \S( u ) ^+ n.+3 = - `|u|_e ^+ 2 *: \S( u ) ^+ n.+1. Proof. -elim: n => [|n IH]; by [rewrite expr1 spin3|rewrite exprS IH -scalerAr -exprS]. +by elim: n => [|n IH]; [rewrite expr1 spin3|rewrite exprS IH -scalerAr -exprS]. Qed. -Lemma mxtrace_sqr_spin u : \tr (\S( u ) ^+ 2) = - (2%:R * (norm u) ^+ 2). +Lemma mxtrace_sqr_spin u : \tr (\S( u ) ^+ 2) = - (2%:R * `|u|_e ^+ 2). Proof. rewrite sqr_spin linearD /= mxtrace_tr_mul linearN /= linearZ /=; apply/eqP. by rewrite !mxtrace_scalar subr_eq addrC mulrC -mulrBl -natrB // mul1r. @@ -592,18 +596,18 @@ case: i => [] [] // [] // i _ /=. by rewrite !mxE; Simp.ord. Qed. -Lemma char_poly_spin u : char_poly \S( u ) = 'X^3 + norm u ^+2 *: 'X. +Lemma char_poly_spin u : char_poly \S( u ) = 'X^3 + `|u|_e ^+2 *: 'X. Proof. rewrite char_poly3 det_spin subr0 trace_anti ?spin_is_so //. rewrite scale0r subr0 expr0n add0r mulrN mxtrace_sqr_spin mulrN opprK. by rewrite mulrA div1r mulVr ?unitfE ?pnatr_eq0 // mul1r. Qed. -Definition spin_eigenvalues u : seq R[i] := [:: 0; 0 +i* norm u ; 0 -i* norm u]%C. +Definition spin_eigenvalues u : seq R[i] := [:: 0; 0 +i* `|u|_e ; 0 -i* `|u|_e]%C. Ltac eigenvalue_spin_eval_poly := rewrite /map_poly horner_poly size_polyDl; [ | - by rewrite size_polyXn size_scale ?size_polyX // sqrf_eq0 norm_eq0]; + by rewrite size_polyXn size_scale ?size_polyX // sqrf_eq0 enorm_eq0]; rewrite size_polyXn sum4E !(coefD,coefXn,coefZ,coefX,expr0,expr1) !(mulr0,mul0r,mul1r,add0r,addr0,mul1r). @@ -628,9 +632,10 @@ case: ifPn => [|Hk]. rewrite eqxx mulr1 mulrC (exprS _ 2) -mulrDr mulf_eq0 => /orP [/eqP ->|]. by rewrite inE eqxx. rewrite eq_sym addrC -subr_eq add0r -mulN1r -sqr_i => H. - have {H}: (norm u)*i%C ^+2 == k ^+2. - rewrite -(eqP H) eq_complex. simpc. by rewrite /= !(mulr0,add0r,mul0r,eqxx). - rewrite eqf_sqr => /orP [/eqP <-|]. + have {H}: `|u|_e *i%C ^+2 == k ^+2. + rewrite -(eqP H) eq_complex. simpc. + by rewrite /= !(mulr0,add0r,mul0r,eqxx). + rewrite eqf_sqr => /predU1P[<-|]. by rewrite !inE eqxx orbC. rewrite -eqr_oppLR => /eqP <-. rewrite !inE orbA; apply/orP; right. @@ -695,7 +700,7 @@ Qed. Lemma skew_det1BM n (M : 'M[R]_n.+1) : M \is 'so[R]_n.+1 -> \det (1 - M) != 0. Proof. move=> Mso; apply/det0P => -[v v0]; apply/eqP; rewrite mulmxBr mulmx1 subr_eq0. -apply: contra v0 => /eqP v1M; rewrite -norm_eq0 -sqrf_eq0 -dotmulvv {2}v1M. +apply: contra v0 => /eqP v1M; rewrite -enorm_eq0 -sqrf_eq0 -dotmulvv {2}v1M. by have /eqP := skew_dotmulmx v Mso; rewrite -eq_sym dotmulNv eqrNxx. Qed. @@ -703,50 +708,50 @@ Qed. Lemma skew_det1DM n (M : 'M[R]_n.+1) : M \is 'so[R]_n.+1 -> \det (1 + M) != 0. Proof. move=> Mso; apply/det0P => -[v v0]; apply/eqP; rewrite mulmxDr mulmx1 addr_eq0. -apply: contra v0 => /eqP v1M; rewrite -norm_eq0 -sqrf_eq0 -dotmulvv {2}v1M. +apply: contra v0 => /eqP v1M; rewrite -enorm_eq0 -sqrf_eq0 -dotmulvv {2}v1M. have /eqP := skew_dotmulmx v Mso. by rewrite -eq_sym dotmulNv eqrNxx dotmulvN eqr_oppLR oppr0. Qed. Lemma inv1BM u : (1 - \S(u)) * - (1 + (1 + (norm u)^+2)^-1 *: \S(u) + (1 + (norm u)^+2)^-1 *: \S(u)^+2) = 1. + (1 + (1 + `|u|_e ^+ 2)^-1 *: \S(u) + (1 + `|u|_e ^+ 2)^-1 *: \S(u)^+2) = 1. Proof. rewrite mulrDr 2!mulrBl 2!mul1r. apply/eqP; rewrite eq_sym addrC -subr_eq; apply/eqP. rewrite opprD addrA opprD addrA subrr add0r opprK addrC. rewrite mulrDr mulr1 (addrC \S(u)) scalerAr -addrA; congr (_ + _). rewrite mulrA -expr2 -scalerAr -exprSr spin3 -{1}(scale1r \S(u)). -rewrite -{1}(@divff _ (1 + norm u ^+ 2)) ?paddr_eq0 ?oner_eq0 ?sqr_ge0//. +rewrite -{1}(@divff _ (1 + `|u|_e ^+ 2)) ?paddr_eq0 ?oner_eq0 ?sqr_ge0//. rewrite mulrC -scalerA -scalerBr -scalerN scaleNr opprK; congr (_ *: _). by rewrite scalerDl scale1r addrAC subrr add0r. Qed. Lemma inv1BME u : (1 - \S(u))^-1 = - 1 + (1 + (norm u)^+2)^-1 *: \S(u) + (1 + (norm u)^+2)^-1 *: \S(u)^+2. + 1 + (1 + `|u|_e ^+ 2)^-1 *: \S(u) + (1 + `|u|_e ^+ 2)^-1 *: \S(u)^+2. Proof. rewrite -[LHS]mulmx1 -[X in _ *m X = _](inv1BM u) mulmxA mulVmx ?mul1mx//. by rewrite unitmxE unitfE skew_det1BM // spin_is_so. Qed. (* TODO: move? *) -Lemma det_sub1spin3E M : M \is 'so[R]_3 -> \det (1 - M) = 1 + norm (unspin M) ^+ 2. +Lemma det_sub1spin3E M : M \is 'so[R]_3 -> \det (1 - M) = 1 + `|unspin M|_e ^+ 2. Proof. move=> Mso; rewrite -{1}(unspinK Mso); set v := \S( _ ). rewrite det_mx33 [v]lock !mxE /=. Simp.r. rewrite -lock /v !spinij subr0. Simp.r. rewrite -!addrA; congr (_ + _); rewrite !addrA. -by rewrite mulrBr opprB addrA mulrDr addrA mulrCA subrK addrAC sqr_norm sum3E. +by rewrite mulrBr opprB addrA mulrDr addrA mulrCA subrK addrAC sqr_enorm sum3E. Qed. (* TODO: move? *) -Lemma det_add1spin3E M : M \is 'so[R]_3 -> \det (1 + M) = 1 + norm (unspin M) ^+ 2. +Lemma det_add1spin3E M : M \is 'so[R]_3 -> \det (1 + M) = 1 + `|unspin M|_e ^+ 2. Proof. move=> Mso; rewrite -{1}(unspinK Mso); set v := \S( _ ). rewrite det_mx33 [v]lock !mxE /=. Simp.r. rewrite -lock /v !spinij addr0. Simp.r. rewrite -!addrA; congr (_ + _); rewrite !addrA. -rewrite sqr_norm sum3E -!expr2 -!addrA; congr (_ + _). -rewrite mulrDr -expr2 (addrC _ (_^+2)) -!addrA addrC; congr (_ + _). +rewrite sqr_enorm sum3E -!expr2 -!addrA; congr (_ + _). +rewrite mulrDr -expr2 (addrC _ (_ ^+ 2)) -!addrA addrC; congr (_ + _). by rewrite mulrBr opprB -expr2 addrCA mulrCA subrr addr0. Qed. @@ -855,11 +860,11 @@ Definition cayley21 (a b c : R) := (b * c + a) *+ 2. Definition cayley22 (a b c : R) := 1 - a ^+ 2 - b ^+ 2 + c ^+ 2. Lemma sqr_norm_row3 (a b c : R) : - (norm (row3 a b c)) ^+ 2 = a ^+ 2 + b ^+ 2 + c ^+ 2. + `|row3 a b c|_e ^+ 2 = a ^+ 2 + b ^+ 2 + c ^+ 2. Proof. by rewrite -dotmulvv dotmulE sum3E !mxE/= -!expr2. Qed. (* result of the Cayley transform expressed with Rodrigues' parameters *) -Lemma cayleyE (a b c : R) : let r := euclidean.norm (row3 a b c) in +Lemma cayleyE (a b c : R) : let r := `|row3 a b c|_e in cayley \S((row3 a b c)) = (1 + r ^+ 2)^-1 *: (col_mx3 (row3 (cayley00 a b c) (cayley01 a b c) (cayley02 a b c)) (row3 (cayley10 a b c) (cayley11 a b c) (cayley12 a b c)) diff --git a/ssr_ext.v b/ssr_ext.v index 25e7aee1..81818fad 100644 --- a/ssr_ext.v +++ b/ssr_ext.v @@ -1,19 +1,21 @@ -(* coq-robot (c) 2017 AIST and INRIA. License: LGPL-2.1-or-later. *) -From Stdlib Require Import NsatzTactic. +(* coq-robot (c) 2025 AIST and INRIA. License: LGPL-2.1-or-later. *) +Require Import NsatzTactic. From mathcomp Require Import all_ssreflect ssralg ssrnum ssrint rat poly. From mathcomp Require Import closed_field polyrcf matrix mxalgebra mxpoly zmodp. From mathcomp Require Import perm path fingroup complex. -(******************************************************************************) -(* Minor additions to MathComp libraries *) +(**md**************************************************************************) +(* # Minor additions to MathComp libraries *) (* *) (* This file contains minor additions ssrbool, ssralg, ssrnum, and complex *) (* and more. *) (* *) +(* ``` *) (* u``_i == the ith component of the row vector u *) (* 'e_0, 'e_1, 'e_2 == the canonical vectors *) (* Section Nsatz_rcfType == type classes for the Coq nsatz tactic *) (* (https://coq.inria.fr/refman/addendum/nsatz.html) *) +(* ``` *) (* *) (******************************************************************************) @@ -21,9 +23,11 @@ Reserved Notation "''e_' i" (format "''e_' i", at level 8, i at level 2). Reserved Notation "u '``_' i" (at level 3, i at level 2, left associativity, format "u '``_' i"). -(* TODO: overrides forms.v *) Notation "u '``_' i" := (u (@GRing.zero _) i) : ring_scope. +(* NB: like Damien's LaSalle *) +Notation "p ..[ i ]" := (p (@GRing.zero _) i) (at level 10, only parsing). + Set Implicit Arguments. Unset Strict Implicit. Unset Printing Implicit Defensive. @@ -187,6 +191,12 @@ have -> : k = if i == k then i else if j == k then j else - (i + j). by move: i j k neq_ij; do 3![case=> [[|[|[|?]]] ?] //=]; constructor. Qed. +Lemma I3_cases (i : 'I_3) : [\/ i = 0, i = 1 | i = 2]. +Proof. +by move: i => [[|[|[|[|]]]]] // ?; [ + exact/Or31/val_inj| exact/Or32/val_inj| exact/Or33/val_inj]. +Qed. + Lemma odd_perm312 : perm3 1 2%:R = false :> bool. Proof. suff ->: perm3 1 2%:R = 1%g by rewrite odd_perm1. diff --git a/tilt_analysis.v b/tilt_analysis.v new file mode 100644 index 00000000..2ec25d90 --- /dev/null +++ b/tilt_analysis.v @@ -0,0 +1,748 @@ +From HB Require Import structures. +From mathcomp Require Import all_boot all_order all_algebra ring. +From mathcomp Require Import interval_inference. +From mathcomp Require Import boolp classical_sets functions filter reals. +From mathcomp Require Import topology ereal prodnormedzmodule normedtype. +From mathcomp Require Import sequences derive realfun landau measure. +From mathcomp Require Import lebesgue_integral. +Require Import ssr_ext derive_matrix. + +(**md**************************************************************************) +(* # Additions to the MathComp-Analysis library *) +(* *) +(******************************************************************************) + +Set Implicit Arguments. +Unset Strict Implicit. +Unset Printing Implicit Defensive. + +Import Order.TTheory GRing.Theory Num.Def Num.Theory. +Import numFieldNormedType.Exports. + +Local Open Scope ring_scope. +Local Open Scope classical_set_scope. + +(* PR to MCA *) +Section Rintegral. +Context d {T : measurableType d} {R : realType}. +Variable mu : {measure set T -> \bar R}. +Implicit Types (D : set T). + +Lemma Rintegral_cst D : d.-measurable D -> + forall r, \int[mu]_(_ in D) r = r * fine (mu D). +Proof. +move=> mD r; rewrite /Rintegral/= integral_cst//. +have := leey (mu D); rewrite le_eqVlt => /predU1P[->/=|muy]; last first. + by rewrite fineM// ge0_fin_numE. +rewrite mulr0 mulr_infty/=; have [_|r0|r0] := sgrP r. +- by rewrite mul0e. +- by rewrite mul1e. +- by rewrite mulN1e. +Qed. + +End Rintegral. + +Lemma within_continuousB {T : topologicalType} {K : numFieldType} + {V : pseudoMetricNormedZmodType K} (A : set T) (f g : T -> V) : + {within A, continuous f} -> {within A, continuous g} -> + {within A, continuous (f - g)}. +Proof. by move=> cf cg x; apply: cvgB; [exact: cf|exact: cg]. Qed. + + +Lemma within_continuous_comp {U V W : topologicalType} + (A : set V) (f : V -> U) (g : U -> W) : + {in f @` A, continuous g} -> + {within A, continuous f} -> + {within A, continuous (g \o f)}. +Proof. +move=> cg /subspace_sigL_continuousP cf; apply/subspace_sigL_continuousP. +rewrite /sigL -compA => /= x; apply: continuous_comp; first exact: cf. +by apply/cg/image_f; rewrite inE; exact/set_valP. +Qed. + +Lemma within_continuous_compN {R : realFieldType} {K : numDomainType} + {U : pseudoMetricNormedZmodType K} (f : R -> U) (a b : R) : + {within `[- b, - a], continuous f} -> {within `[a, b], continuous (f \o -%R)}. +Proof. +have [ab|ba _ |-> _] := ltgtP a b; last 2 first. + by rewrite set_itv_ge ?bnd_simp -?ltNge//; exact: continuous_subspace0. + by rewrite set_itv1; exact: continuous_subspace1. +move/continuous_within_itvP; rewrite ltrN2 => /(_ ab)[cf fb fa]. +apply/(continuous_within_itvP _ ab); split. +- move=> t tab. + apply: (@cvg_comp _ _ _ -%R f); first exact: oppr_continuous. + by apply: cf; rewrite oppr_itvoo !opprK. +- by rewrite -{1}(opprK a); apply/cvg_at_leftNP; exact: fa. +- by rewrite -{1}(opprK b); apply/cvg_at_rightNP; exact: fb. +Qed. + +(* TODO: PR to MCA *) +Lemma nbhs_ge {R : realFieldType} (t x : R) : + t < x -> \forall x0 \near nbhs x, t <= x0. +Proof. +move=> tx. +exists ((x - t) / 2). + by rewrite /= divr_gt0// subr_gt0. +move=> y/=. +have [xy|yx] := lerP x y. + rewrite ltrBlDl => H. + by rewrite (le_trans (ltW tx)). +rewrite ltrBlDl -ltrBlDr => /ltW; apply: le_trans. +rewrite -lerBlDr opprK. +by rewrite -lerBrDl ler_piMr ?invf_le1 ?ler1n// subr_ge0 ltW. +Qed. + +(* TODO: PR *) +Section vector_continuous. +Context {R : realFieldType} {n : nat}. +Let U := 'rV[R]_n. + +Lemma within_continuous_coord A (f : R -> U) : + {within A, continuous f} <-> + forall i, {within A, continuous (fun x => f x ord0 i)}. +Proof. +split=> [Af i|Af]. +- apply/subspace_continuousP => /= x Dx. + have /subspace_continuousP/(_ x Dx) Afx := Af. + apply: (cvg_comp f (fun z => z ord0 i) Afx). + exact: coord_continuous. +- apply/subspace_continuousP => /= x Ax; apply/cvgrPdist_le => /= e e0. + rewrite near_withinE. + near=> t => At. + rewrite /Num.norm/= mx_normrE; apply/(bigmax_le _ (ltW e0)) => /= -[i j] _ /=. + rewrite {i}(ord1 i) !mxE. + move: j At. + near: t. + apply: filter_forall => /= i. + have /subspace_continuousP/(_ x Ax) := Af i. + move/cvgrPdist_le => /(_ _ e0). + by rewrite near_withinE. +Unshelve. all: by end_near. Qed. + +End vector_continuous. + +(* PR to MCA *) +Section continuous_patch. +Context {R : realType} {n : nat} {U : normedModType R}. +Variables (a b c : R) (f : R -> U) (g : R -> U). +Hypothesis ab : a < b. +Hypothesis bc : b < c. +Hypothesis cont1 : {within `[a, b], continuous f}. +Hypothesis cont2 : {within `[b, c], continuous g}. +Hypothesis matchb : f b = g b. + +Lemma within_continuous_patch : {within `[a, c], continuous (patch g `[a, b] f)}. +Proof. +have -> : `[a, c] = `[a, b] `|` `[b, c]. + rewrite (@itv_bndbnd_setU _ _ _ (BRight b)) // ?bnd_simp//=; [|exact: ltW..]. + apply/seteqP; split => [x []|x []]. + by left. + by right; exact: subset_itv_oc_cc b0. + by left. + rewrite -setU1itv ?bnd_simp//; last exact: ltW. + case; last by right. + move=> ->; left => /=. + by rewrite bound_itvE ltW. +apply: (withinU_continuous (@itv_closed _ _ a b) (@itv_closed _ _ b c)). + apply: subspace_eq_continuous cont1. + by move=> /=r rab; rewrite /from_subspace /patch rab. +have eq2 : {in `[b, c], g =1 patch g `[a, b] f }. + move=> r rab. + rewrite /patch; case: ifPn => [xab | xabnot] => //. + suff -> : r = b by rewrite matchb. + apply: le_anti. + move: rab xab. + by rewrite !inE/=!in_itv/= => /andP [-> _] /andP [_ ->]. +exact: (subspace_eq_continuous eq2). +Qed. + +End continuous_patch. + +Lemma norm_rowmx {K : rcfType} {m n1 n2 : nat} + (A1 : 'M[K]_(m.+1, n1.+1)) (A2 : 'M[K]_(m.+1, n2.+1)) : + `|row_mx A1 A2| = Num.max `|A1| `|A2|. +Proof. +rewrite /Num.norm/= !mx_normrE. +apply/eqP; rewrite eq_le; apply/andP; split. +- apply: bigmax_le => /=. + rewrite le_max;apply /orP;left. + exact/le_trans/(le_bigmax _ _ (ord0,ord0)). + move=> [i j] _ /=. + rewrite le_max; apply/orP. + rewrite mxE. + case: (splitP j) => j1 h1. + by left; exact: (le_bigmax _ _ (i, j1)). + by right;exact: (le_bigmax _ _ (i, j1)). +rewrite ge_max; apply/andP; split. + apply: bigmax_le => /=. + apply: le_trans; last first. + exact: (le_bigmax _ _ (ord0, ord0)). + exact: normr_ge0. + move=> [i j] _. + rewrite -(row_mxEl _ A2). + exact: (le_bigmax _ _ (i, lshift n2.+1 j)). +apply: bigmax_le => /=. + apply: le_trans; last first. + exact: (le_bigmax _ _ (ord0, ord0)). + exact: normr_ge0. +move=> [i j] _. +rewrite -(row_mxEr A1). +exact: (le_bigmax _ _ (i, rshift n1.+1 j)). +Qed. + +Lemma mx_norm_mul {K : rcfType} {m n p} (A : 'M[K]_(m.+1, n.+1)) (B : 'M_(n.+1, p.+1)) : + `|A *m B| <= n.+1%:R * `| A| * `|B|. +Proof. +rewrite /Num.norm/= !mx_normrE. +apply: bigmax_le. + rewrite -mulrA mulr_ge0//. + by apply mulr_ge0; apply/le_trans/(le_bigmax _ _ (ord0, ord0)). +move=> /= [i j] _/=. +rewrite mxE. +rewrite (le_trans (ler_norm_sum _ _ _))//=. +have le_inside k : `|A i k * B k j| <= `|A| * `|B|. + rewrite normrM /Num.norm/= !mx_normrE/= ler_pM//=. + - exact: normr_ge0. + - exact: normr_ge0. + - exact: (le_bigmax _ _ (i, k)). + - exact: (le_bigmax _ _ (k, j)). +rewrite -mulrA. +rewrite (@le_trans _ _ (\sum_(k < n.+1) `|A| * `|B|))//. + by apply: ler_sum => k _; apply le_inside. +rewrite mulr_natl. +rewrite big_const_ord. +rewrite iter_addr_0. +by rewrite /Num.norm/= !mx_normrE. +Qed. + +(* NB: PR to PCA *) +Section pointwise_derivable. +Context {R : realFieldType} {V W : normedModType R} {m n : nat}. +Implicit Types M : V -> 'M[R]_(m, n). + +Definition derivable_mx M t v := + forall i j, derivable (fun x => M x i j) t v. + +Lemma derivable_mxP M t v : derivable_mx M t v <-> derivable M t v. +Proof. +split; rewrite /derivable_mx /derivable. +- move=> H. + apply/cvg_ex => /=. + pose l := \matrix_(i < m, j < n) sval (cid ((cvg_ex _).1 (H i j))). + exists l. + apply/cvgrPdist_le => /= e e0. + near=> x. + rewrite /Num.Def.normr/= mx_normrE. + apply: (bigmax_le _ (ltW e0)) => /= i _. + rewrite !mxE/=. + move: i. + near: x. + apply: filter_forall => /= i. + exact: ((@cvgrPdist_le _ _ _ _ (dnbhs_filter 0) _ _).1 + (svalP (cid ((cvg_ex _).1 (H i.1 i.2)))) _ e0). +- move=> /cvg_ex[/= l Hl] i j. + apply/cvg_ex; exists (l i j). + apply/cvgrPdist_le => /= e e0. + move/cvgrPdist_le : Hl => /(_ _ e0)[/= r r0] H. + near=> x. + apply: le_trans; last first. + apply: (H x). + rewrite /ball_/=. + rewrite sub0r normrN. + near: x. + exact: dnbhs0_lt. + near: x. + exact: nbhs_dnbhs_neq. + rewrite [leRHS]/Num.Def.normr/= mx_normrE. + apply: le_trans; last exact: le_bigmax. + by rewrite /= !mxE. +Unshelve. all: by end_near. Qed. + +End pointwise_derivable. + +(* NB: PR to MCA *) +Section pointwise_derive. +Local Open Scope classical_set_scope. +Context {R : realFieldType} {V W : normedModType R} . + +Lemma derive_mx {m n : nat} (M : V -> 'M[R]_(m, n)) t v : + derivable M t v -> + 'D_v M t = \matrix_(i < m, j < n) 'D_v (fun t => M t i j) t. +Proof. +move=> /cvg_ex[/= l Hl]; apply/cvg_lim => //=. +apply/cvgrPdist_le => /= e e0. +move/cvgrPdist_le : (Hl) => /(_ (e / 2)). +rewrite divr_gt0// => /(_ isT)[d /= d0 dle]. +near=> x. +rewrite [in leLHS]/Num.Def.normr/= mx_normrE. +apply/(bigmax_le _ (ltW e0)) => -[/= i j] _. +rewrite [in leLHS]mxE/= [X in _ + X]mxE -[X in X - _](subrK (l i j)). +rewrite -(addrA (_ - _)) (le_trans (ler_normD _ _))// (splitr e) lerD//. +- rewrite mxE. + suff : (h^-1 *: (M (h *: v + t) i j - M t i j)) @[h --> 0^'] --> l i j. + move/cvg_lim => /=; rewrite /derive /= => ->//. + by rewrite subrr normr0 divr_ge0// ltW. + apply/cvgrPdist_le => /= r r0. + move/cvgrPdist_le : Hl => /(_ r r0)[/= s s0] sr. + near=> y. + have : `|l - y^-1 *: (M (y *: v + t) - M t)| <= r. + rewrite sr//=; last by near: y; exact: nbhs_dnbhs_neq. + by rewrite sub0r normrN; near: y; exact: dnbhs0_lt. + apply: le_trans. + rewrite [in leRHS]/Num.Def.normr/= mx_normrE. + by under eq_bigr do rewrite !mxE; exact: (le_bigmax _ _ (i, j)). +- rewrite mxE. + have : `|l - x^-1 *: (M (x *: v + t) - M t)| <= e / 2. + apply: dle => //=; last by near: x; exact: nbhs_dnbhs_neq. + by rewrite sub0r normrN; near: x; exact: dnbhs0_lt. + apply: le_trans. + rewrite [in leRHS]/Num.Def.normr/= mx_normrE/=. + under eq_bigr do rewrite !mxE. + apply: le_trans; last exact: le_bigmax. + by rewrite !mxE. +Unshelve. all: by end_near. Qed. + +End pointwise_derive. + +Lemma differentiable_scalar_mx {R : numFieldType} n (r : R) : + differentiable (@scalar_mx _ n) r. +Proof. +apply/derivable1_diffP/cvg_ex => /=. +exists 1; apply/cvgrPdist_le => /= e e0. +near=> t. +rewrite scaler1 -raddfB/= addrK (scale_scalar_mx _ t^-1) mulVf. + by rewrite subrr normr0 ltW. +by near: t; exact: nbhs_dnbhs_neq. +Unshelve. all: by end_near. Qed. + +Lemma derivable_sqrt {K: realType} (u : K) : u > 0 -> derivable Num.sqrt u 1. +Proof. +move=> u0. +apply: ex_derive. +exact: (is_derive1_sqrt u0). +Qed. + +Lemma differentiable_rsubmx_comp {R : realFieldType} (V : normedModType R) {n1 n2} + (f : V -> 'rV[R]_(n1 + n2)) t : + (forall x, differentiable f x) -> + differentiable (fun x => rsubmx (f x)) t. +Proof. +move=> /= df1. +apply: differentiable_comp => //. +exact: differentiable_rsubmx. +Qed. + +Lemma differentiable_lsubmx_comp {R : realFieldType} (V : normedModType R) {n1 n2} + (f : V -> 'rV[R]_(n1 + n2)) t : + (forall x, differentiable f x) -> + differentiable (fun x => lsubmx (f x)) t. +Proof. +move=> /= df1. +apply: differentiable_comp => //. +exact: differentiable_lsubmx. +Qed. + +Lemma derivable_scalar_mx {R : realFieldType} n (f : 'rV[R]_n -> R) + (a : 'rV[R]_n) v : + derivable f a v -> + derivable (@scalar_mx _ 1 \o f) a v. +Proof. +move=> /cvg_ex[/= l fav]. +apply/cvg_ex => /=. +exists (\col_(i < 1) l). +apply/cvgrPdist_le => /= e e0. +move/cvgrPdist_le : fav => /(_ _ e0). +apply: filterS => x. +apply: le_trans. +rewrite [in leLHS]/Num.Def.normr/= !mx_normrE/=. +apply: bigmax_le => //= -[i j] _. +rewrite !mxE/=. +by rewrite !ord1 eqxx !mulr1n. +Qed. + +Local Open Scope classical_set_scope. + +(* TODO: rename, generalize to the subset relation *) +Lemma in_switch {R : numDomainType} (I : interval R) P : + {in [set` I], forall x, P x} <-> {in I, forall x, P x}. +Proof. +split => [h x xI| h x xI]; apply h. + by rewrite inE. +by rewrite inE in xI. +Qed. + +Lemma lsubmx_norm_le {K : rcfType} n1 n2 (x : 'rV[K]_(n1.+1 + n2.+1)) : + `|lsubmx x| <= `|x|. +Proof. +rewrite /Num.norm/= !mx_normrE; apply: bigmax_le. + exact/le_trans/(le_bigmax _ _ (ord0, ord0)). +move=> /= [i j] _ /=. +rewrite mxE. +exact: (le_bigmax _ _ (i, lshift n2.+1 j)). +Qed. + +Lemma rsubmx_norm_le {K : rcfType} n1 n2 (x : 'rV[K]_(n1.+1 + n2.+1)) : + `|rsubmx x| <= `|x|. +Proof. +rewrite /Num.norm/= !mx_normrE; apply: bigmax_le. + exact/le_trans/(le_bigmax _ _ (ord0,ord0)). +move=> /= [i j] _ /=. +rewrite mxE. +exact: (le_bigmax _ _ (i, rshift n1.+1 j)). +Qed. + +Lemma mx_norm1 {K : rcfType} {n} : `|1 : 'M[K]_n.+1| = 1. +Proof. +rewrite /Num.norm/= !mx_normrE. +apply/eqP; rewrite eq_le; apply/andP; split. +- apply: bigmax_le => //= i _. + rewrite mxE/=. + by case: eqP => /= _; rewrite ?(normr1, normr0). +- rewrite -normr1. + have -> : (1 : K) = ((1 : 'M[K]_n.+1) ord0 ord0) by rewrite mxE. + exact: (le_bigmax _ _ (ord0, ord0)). +Qed. + +Lemma mx_norm_delta_mx {K : rcfType} n (i : 'I_n.+1) : `| 'e_i : 'rV[K]__ | <= 1. +Proof. +rewrite /Num.norm /= mx_normrE; apply: bigmax_le => //= -[/= a b] _. +rewrite mxE /=. +case: eqP => /= _; last by rewrite normr0. +case: eqP => /= _; last by rewrite normr0. +by rewrite normr1. +Qed. + +Lemma mx_norm_sq_le {K : rcfType} {n} (A : 'M[K]_n.+1) : + `|A ^+ 2| <= n.+1%:R * `|A| ^+ 2. +Proof. by rewrite !expr2 mulrA; exact: mx_norm_mul. Qed. + +Local Open Scope classical_set_scope. +(* PR to MCA *) +Lemma EVT_max_rV (R : realType) n (f : 'rV[R]_n -> R) (A : set 'rV[R]_n) : + A !=set0 -> + compact A -> + {within A, continuous f} -> exists2 c, c \in A & + forall t, t \in A -> f t <= f c. +Proof. +move=> A0 compactA fcont; set imf := f @` A. +have imf_sup : has_sup imf. + split. + case: A0 => a Aa. + by exists (f a); apply/imageP. + have [M [Mreal imfltM]] : bounded_set (f @` A). + exact/compact_bounded/continuous_compact. + exists (M + 1) => y /imfltM yleM. + by rewrite (le_trans _ (yleM _ _)) ?ler_norm ?ltrDl. +have [|imf_ltsup] := pselect (exists2 c, c \in A & f c = sup imf). + move=> [c cab fceqsup]; exists c => // t tab; rewrite fceqsup. + apply/sup_upper_bound => //. + exact/imageP/set_mem. +have {}imf_ltsup t : t \in A -> f t < sup imf. + move=> tab; case: (ltrP (f t) (sup imf)) => // supleft. + rewrite falseE; apply: imf_ltsup; exists t => //; apply/eqP. + rewrite eq_le supleft andbT sup_upper_bound//. + exact/imageP/set_mem. +pose g t : R := (sup imf - f t)^-1. +have invf_continuous : {within A, continuous g}. + rewrite continuous_subspace_in => t tab; apply: cvgV => //=. + by rewrite subr_eq0 gt_eqF // imf_ltsup //; rewrite inE in tab. + by apply: cvgD; [exact: cst_continuous | apply: cvgN; exact: (fcont t)]. +have /ex_strict_bound_gt0 [k k_gt0 /= imVfltk] : bounded_set (g @` A). + by apply/compact_bounded/continuous_compact. +have [_ [t tab <-]] : exists2 y, imf y & sup imf - k^-1 < y. + by apply: sup_adherent => //; rewrite invr_gt0. +rewrite ltrBlDr -ltrBlDl. +suff : sup imf - f t > k^-1 by move=> /ltW; rewrite leNgt => /negbTE ->. +rewrite -[ltRHS]invrK ltf_pV2// ?qualifE/= ?invr_gt0 ?subr_gt0 ?imf_ltsup//; last first. + exact/mem_set. +by rewrite (le_lt_trans (ler_norm _) _) ?imVfltk//; exact: imageP. +Qed. + +(* PR to MCA *) +Lemma EVT_min_rV (R : realType) n (f : 'rV[R]_n -> R) (A : set 'rV[R]_n) : + A !=set0 -> + compact A -> + {within A, continuous f} -> exists2 c, c \in A & + forall t, t \in A -> f c <= f t. +Proof. +move=> A0 cA fcont. +have /(EVT_max_rV A0 cA) [c clr fcmax] : {within A, continuous (- f)}. + by move=> ?; apply: continuousN => ?; exact: fcont. +by exists c => // ? /fcmax; rewrite lerN2. +Qed. + +Section closure_neitv. +Context {R : realType}. +Implicit Type a b : R. + +Lemma closure_neitv_oo a b : a < b -> + closure `]a, b[%classic = `[a, b]%classic. +Proof. +move=> ab. +set c := (a + b) / 2%:R. +set d := (b - a) / 2%:R. +rewrite (_ : a = c - d); last by rewrite /c/d !mulrDl addrKA mulNr opprK -splitr. +rewrite (_ : b = c + d); last by rewrite addrC /c/d !mulrDl mulNr subrKA -splitr. +rewrite -ball_itv -closed_ball_itv ?closure_ballE//. +apply: divr_gt0 => //. +by rewrite subr_gt0. +Qed. + +End closure_neitv. + +(* TODO: move *) +Lemma open_disjoint_separated (X : topologicalType) (A B : set X) : + open A -> open B -> A `&` B = set0 -> separated A B. +Proof. +move=>Ao Bo ABdisj. +split. +apply /disjoints_subset. +rewrite (closure_id (~` B)).1; last by apply open_closedC. +by apply /closure_subset/disjoints_subset. +rewrite setIC;apply /disjoints_subset. +rewrite (closure_id (~` A)).1; last by apply open_closedC. +apply /closure_subset/disjoints_subset. +by rewrite setIC. +Qed. + +(* TODO: move *) +Lemma separated_closedUP {T : topologicalType} (A B : set T) : separated A B -> + closed (A `|` B) <-> closed A /\ closed B. +Proof. +move => ABsep. +split => [/closure_id h | [h1 h2]]; last by apply closedU. +rewrite closureU in h. +split;apply /closure_id/seteqP;split => [|x cx]; try by apply subset_closure. +have /orP[] : (x \in A) || (x \in B). + by rewrite -in_setU h inE/=;left. +by rewrite inE. +rewrite inE => xB. +have [/seteqP[+ _] _] := ABsep. +case /(_ x). +by split. +have /orP[] : (x \in A) || (x \in B). + by rewrite -in_setU h inE/=;right. +rewrite inE => xB. +have [_ /seteqP[+ _]] := ABsep. +case /(_ x). +by split. +by rewrite inE. +Qed. + +Lemma cst_oo_cc {R : realType} (f : R -> R) y (a b : R) : + y \in `[a, b]%R -> + {within `[a, b], continuous f} -> + {in `]a, b[%R, f =1 cst (f y)} -> + {in `[a, b]%R, f =1 cst (f y)}. +Proof. +have [ab|ba] := ltP a b; last first. + move=> yab _ H x. + rewrite in_itv/= => /andP[ax xb]. + have /eqP ? : a == x by rewrite eq_le ax (le_trans xb _). + subst x. + move: yab; rewrite in_itv/= => /andP[ay yb]. + have /eqP ? : a == y by rewrite eq_le ay (le_trans yb _). + by subst. +move=> yab cf H x. +rewrite in_itv/= => /andP[]. +rewrite le_eqVlt => /predU1P[<-{x} _|]. + move: yab; rewrite in_itv/= => /andP[]. + rewrite le_eqVlt => /predU1P[->//|ay yb]. + move/continuous_within_itvP : cf => /(_ ab)[_ fafa _]. + move/cvgrPdist_le in fafa. + rewrite /= in fafa. + apply/eqP. + rewrite -subr_eq0. + rewrite -normr_le0. + apply/ler_addgt0Pr => /= e e0. + rewrite add0r. + have := fafa _ e0 => -[d /= d0] H'. + near a^'+ => a0. + rewrite (_ : f y = f a0)//; last first. + apply/esym/H. + rewrite in_itv/=. + by apply/andP. + apply: H' => //=. + rewrite ltr0_norm ?subr_lt0// opprB. + rewrite ltrBlDl. + near: a0; apply: nbhs_right_lt. + by rewrite ltrDl. +move=> ax. +rewrite le_eqVlt => /predU1P[->|]; last first. + move=> xb. + apply: H => //. + by rewrite in_itv/= ax. +clear x ax. +move: yab. +rewrite in_itv/= => /andP[ay]. +rewrite le_eqVlt => /predU1P[<-//|yb]. +move/continuous_within_itvP : cf => /(_ ab)[_ _ fbfb]. +move/cvgrPdist_le in fbfb. +rewrite /= in fbfb. +apply/eqP. +rewrite -subr_eq0. +rewrite -normr_le0. +apply/ler_addgt0Pr => /= e e0. +rewrite add0r. +have := fbfb _ e0 => -[d /= d0] H'. +near b^'- => b0. +rewrite (_ : f y = f b0)//; last first. + apply/esym/H. + rewrite in_itv/=. + by apply/andP; split. +apply: H' => //=. +rewrite distrC. +rewrite ltr0_norm ?subr_lt0// opprB. +rewrite ltrBlDr. +rewrite -ltrBlDl. +near: b0; apply: nbhs_left_gt. +by rewrite ltrBlDl ltrDr. +Unshelve. all: by end_near. Qed. + +Lemma oo_is_derive_0_is_cst {R : realType} (f : R -> R) y (a b : R) : + y \in `]a, b[%R -> + {within `[a, b], continuous f} -> + (forall x, x \in `]a, b[%R -> is_derive x (1 : R) f 0) -> + {in `[a, b]%R, f =1 cst (f y)}. +Proof. +move=> yab cf Hd. +apply: cst_oo_cc => //. + exact: subset_itv_oo_cc yab. +move=> x xab. +wlog xLy : x y xab yab/ x <= y. + move=> H; case: (leP x y) => [/H |/ltW xy]. + exact. + by apply/esym/H => //. +rewrite -(subKr (f y) (f x)). +have : forall x0, x0 \in `]x, y[%R -> is_derive x0 1 f (0 x0). + move=> z zxy. + apply: Hd. + move: zxy. + apply: subset_itvSoo; rewrite bnd_simp. + by rewrite ltW// (itvP xab). + by rewrite ltW// (itvP yab). +move/MVT_segment => /(_ xLy)[]. + apply: continuous_subspaceW(* NB: should be , do a PRS*) cf. + apply: subset_itvScc; rewrite bnd_simp. + by rewrite ltW// (itvP xab). + by rewrite ltW// (itvP yab). +move=> r rxy. +rewrite mul0r => ->. +by rewrite subr0. +Qed. + +Lemma cc_is_derive_0_is_cst {R : realType} (f : R -> R) y (a b : R) : + y \in `[a, b]%R -> + {within `[a, b], continuous f} -> + (forall x, x \in `]a, b[%R -> is_derive x (1 : R) f 0) -> + {in `[a, b]%R, f =1 cst (f y)}. +Proof. +move => yab cont d x xab /=. +have : a <= b. + move: xab. + rewrite in_itv/= => /andP[]. + exact: le_trans. +rewrite le_eqVlt => /predU1P[ab|ab]. +suff [-> ->] : b = x /\ b = y by []. +split; apply/eqP; rewrite eq_le. +by rewrite (itvP xab) -ab (itvP xab). +by rewrite (itvP yab) -ab (itvP yab). +suff [-> ->] : f x = f ((a + b) / 2) /\ f y = f ((a + b)/2) by []. +have ab2 : (a + b)/2 \in `]a, b[%R by rewrite in_itv/= !midf_lt. +by split; exact/oo_is_derive_0_is_cst. +Qed. + +Lemma closed_ball_bounded {K : realType} {n} (x y : 'rV[K]_n) r : + 0 < r -> closed_ball x r y -> `|y| <= `|x| + r. +Proof. +move=> r0. +rewrite closed_ballE// /closed_ball_/= => dxy. +rewrite ler_distlCDr//. +by rewrite (le_trans (ler_dist_dist _ _)). +Qed. + +Lemma ball0_le0 (R : realDomainType) (V : pseudoMetricNormedZmodType R) (a : V) (r : R) : + ball a r = set0 -> r <= 0. +Proof. +rewrite -subset0 => ar0; rewrite leNgt; apply/negP => r0. +by have /(_ (ballxx _ r0)) := ar0 a. +Qed. + +Lemma closed_ballAE {K : realType} n (e : K) (x : 'rV[K]_n) : + 0 < e -> closed_ball x e = closed_ball_ (@mx_norm _ _ _) x e. +Proof. +by move=> e0; rewrite closed_ballE. +Qed. + +Local Close Scope classical_set_scope. + +Lemma maxE {K : realType} (x y : {nonneg K}) : + (Num.max x%:num y%:num) = (Num.max x y)%:num. +Proof. +rewrite /Num.max /maxr; apply/esym. +case: ifPn => // xy. + case: ifPn => //. + rewrite -leNgt => yx. + by apply/eqP; rewrite eq_le yx/= ltW. +case: ifPn => // yx. +apply/eqP; rewrite eq_le (ltW yx)/=. +by rewrite -leNgt in xy. +Qed. + +Section gradient. + +Definition jacobian1 {R : numFieldType} n (f : 'rV[R]_n -> R) + : 'rV_n -> 'cV_n := + jacobian (scalar_mx \o f). + +(* NB: not used *) +Definition partial {R : numFieldType} {n : nat} (f : 'rV[R]_n -> R) (a : 'rV[R]_n) i := + lim (h^-1 * (f (a + h *: 'e_i) - f a) @[h --> 0^'])%classic. + +Lemma partial_diff {R : realFieldType} n (f : 'rV[R]_n -> R) (a : 'rV[R]_n) + (i : 'I_n) : + derivable f a 'e_i -> + partial f a i = ('D_'e_i (@scalar_mx _ 1 \o f) a) 0 0. +Proof. +move=> fa1. +rewrite derive_mx ?mxE//=; last first. + exact: derivable_scalar_mx. +rewrite /partial. +under eq_fun do rewrite (addrC a). +by under [in RHS]eq_fun do rewrite !mxE/= !mulr1n. +Qed. + +(* NB: not used *) +Definition err_vec {R : pzRingType} n (i : 'I_n) : 'rV[R]_n := + \row_(j < n) (i == j)%:R. + +Lemma err_vecE {R : pzRingType} n (i : 'I_n) : + err_vec i = 'e_i :> 'rV[R]_n. +Proof. +apply/rowP => j. +by rewrite !mxE eqxx /= eq_sym. +Qed. + +Definition gradient_partial {R : numFieldType} n (f : 'rV[R]_n -> R) (a : 'rV[R]_n) := + \row_(i < n) partial f a i. + +Lemma gradient_partial_sum {R : numFieldType} n (f : 'rV[R]_n -> R) (a : 'rV[R]_n) : + gradient_partial f a = \sum_(i < n) partial f a i *: 'e_i. +Proof. +rewrite /gradient_partial [LHS]row_sum_delta. +by under eq_bigr do rewrite mxE. +Qed. + +Lemma gradient_partial_jacobian1 {R : realFieldType} n (f : 'rV[R]_n -> R) + (v : 'rV[R]_n) : differentiable f v -> + gradient_partial f v = (jacobian1 f v)^T. +Proof. +move=> fa; apply/rowP => i. +rewrite /gradient_partial mxE mxE /jacobian mxE -deriveE; last first. + apply: differentiable_comp => //. + exact: differentiable_scalar_mx. +rewrite partial_diff//. +exact/diff_derivable. +Qed. + +End gradient. diff --git a/tilt_lasalle.v b/tilt_lasalle.v new file mode 100644 index 00000000..f1cce5fa --- /dev/null +++ b/tilt_lasalle.v @@ -0,0 +1,654 @@ +From HB Require Import structures. +From mathcomp Require Import all_boot all_algebra ring. +From mathcomp Require Import interval_inference finmap. +From mathcomp Require Import boolp classical_sets functions reals order. +From mathcomp Require Import topology normedtype landau sequences derive realfun. +From mathcomp Require Import matrix_normedtype. +Require Import ssr_ext euclidean rigid frame skew derive_matrix. +Require Import tilt_mathcomp tilt_analysis tilt_robot. +Require Import lasalle (* to at least get the structure of filters on sets *). +Require Import ode tilt_stability tilt_lyapunov. + +(**md**************************************************************************) +(* # Formalization of [benallegue2023itac] (2/2) *) +(* *) +(* The main result of this file is to show that all solutions converge to one *) +(* of the two equilibrium points. *) +(* *) +(* Reference: *) +(* - [cohen2017itp] C. Cohen, D. Rouhling. A formal proof in Coq of LaSalle’s *) +(* invariance principle. ITP 2017 *) +(* - [benallegue2023itac] *) +(* https://hal.science/hal-04271257v1/file/benallegue2019tac_October_2022.pdf *) +(******************************************************************************) + +Set Implicit Arguments. +Unset Strict Implicit. +Unset Printing Implicit Defensive. + +Import Order.TTheory GRing.Theory Num.Def Num.Theory. +Import numFieldNormedType.Exports. +Local Open Scope ring_scope. + +(* finite intersection property *) +Lemma compact_decreasing_bigcap d {K : orderType d} (k0 : K) + (X : ptopologicalType) (B : K -> set X) (O : set X) : + hausdorff_space X -> + (forall i : K, (k0 <= i)%O -> compact (B i)) -> + (forall i j : K, (i <= j)%O -> B j `<=` B i) -> + open O -> + (\bigcap_(i in [set i | (k0 <= i)%O]) B i `<=` O) -> + exists i0, (k0 <= i0)%O /\ B i0 `<=` O. +Proof. +move => H comp decr openO subO. +set V := fun i => B i `&` ~` O. +have comp' i : (k0 <= i)%O -> compact (V i). + move=> i0. + apply: compact_closedI. + by apply comp. + by apply open_closedC. +have decr' i j : (i <= j)%O -> V j `<=` V i. + move=> ij. + rewrite /V. + by apply: setSI; exact: decr. +apply/not_existsP => hf. +suff /set0P : \bigcap_(i in [set t | k0 <= t]%O) V i !=set0. + rewrite bigcapIl; last by exists k0 => /=; exact: lexx. + by move/eqP/subsets_disjoint. +have cf : closed_fam_of (B k0) [set t | t >= k0]%O V. + exists V => t t0 //. + apply closedI. + apply compact_closed => //. + exact: comp. + exact: open_closedC. + rewrite /V setIA. + congr (_ `&` _). + rewrite setIC. + exact/esym/setIidl/decr. +have : compact (B k0) by apply comp. +rewrite compact_In0/=; apply => //. +move=> D Ds. +set m := \big[Order.max/k0]_(z <- D) z. +have M x : x \in D -> (x <= m)%O by move=> xD; exact: le_bigmax_seq. +suff Vm : V m `<=` \bigcap_(i in [set` D]) V i. + apply: (subset_nonempty Vm). + have := hf m. + apply: contra_notP. + move/nonemptyPn => Ve; split. + exact: bigmax_ge_id. + by apply subsets_disjoint. +apply sub_bigcap => i Di. +exact/decr'/M. +Qed. + +(* NB: should be possible to generalize without normal_space X *) +Lemma compact_connected_cluster {K : realType} + (X : ptopologicalType) (f : K -> X) (A : set X) : + hausdorff_space X -> + normal_space X -> + continuous f -> + compact A -> + (forall t, 0 <= t -> f t \in A) -> + connected (cluster (f t @[t --> +oo])). +Proof. +move => H Hn contf compactf imagef. +set B := fun t => closure (f @` `[t, +oo[). +have Bcon t : connected (B t). + apply: connected_closure. + apply: connected_continuous_connected. + apply /connected_intervalP/interval_is_interval. + by apply continuous_subspaceT. +have Bnonempty t : B t !=set0. + exists (f t); apply/subset_closure/set_mem/image_f. + by rewrite inE/= in_itv/= lexx. +have Bmon s t : s <= t -> B t `<=` B s. + move=> st; apply/closure_subset/image_subset. + by apply: subset_itvr; rewrite bnd_simp. +have Bcom t : 0 <= t -> compact (B t). + move=> t0; apply: (subclosed_compact _ compactf). + exact: closed_closure. + rewrite (closure_id A).1; last exact: compact_closed. + apply: closure_subset => _ [x tx] <-. + apply/set_mem/imagef. + by move: tx; rewrite /= in_itv/= andbT; exact: le_trans. +have -> : cluster (f t @[t --> +oo]) = \bigcap_(t in [set t | 0 <= t]) B t. + rewrite clusterE; apply/seteqP; split. + - apply: sub_bigcap => /= t _. + apply: bigcap_inf. + exists t; split; first exact: num_real. + by move=> x tx; exists x => //; rewrite /= in_itv/= ltW. + - apply: sub_bigcap => b /= [t0 [_ /= h]]. + apply: (subset_trans (bigcap_inf (i := Num.max 0 (t0 + 1)) _)) => //=. + by rewrite le_max lexx. + apply: closure_subset => _ /= [x xt] <-. + apply h. + move: xt; rewrite in_itv/= andbT; apply: lt_le_trans. + by rewrite lt_max ltrDl ltr01 orbT. +apply/connectedP => E [Enonempty Eu Esep]. +have /(separated_closedUP Esep) [E1c E2c] : closed (E false `|` E true). + rewrite -Eu; apply: closed_bigI => i P; apply: compact_closed => //. + exact: Bcom. +have /normal_openP := Hn. +move /(_ K (E false) (E true)) => [//|//|| V1 [V2 [? ? EfalseV1 EtrueV2 ?]]]. + exact: separated_disjoint. +have V1V2o : open (V1 `|` V2) by exact: openU. +have V1V2sep : separated V1 V2 by exact: open_disjoint_separated. +have BV1V2 : \bigcap_(t in [set t | 0 <= t]) B t `<=` V1 `|` V2. + by rewrite Eu; exact: setUSS. +case/compact_decreasing_bigcap : BV1V2 => // t0 [t0ge0 Bto] //. +suff: V1 `&` V2 !=set0 by apply nonemptyPn. +have [e1 E1] := Enonempty false. +have [e2 E2] := Enonempty true. +have EB : E false `|` E true `<=` B t0. + by rewrite - Eu; exact: bigcap_inf. +have [hbv|hbv] := connected_subset V1V2sep Bto (Bcon _). +- exists e2; split; last exact: EtrueV2. + by apply: hbv; apply: EB; right. +- exists e1; split; first exact: EfalseV1. + by apply: hbv; apply: EB; left. +Qed. + +Section sublevel. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n. + +Definition sublevel (V : U -> R) c := [set x : U | V x <= c]. + +Lemma sublevel_preimage (V : U -> R) c : sublevel V c = V @^-1` [set r | r <= c]. +Proof. by []. Qed. + +End sublevel. + +Section LaSalle_tilt. +Context {K : realType}. +Let U := 'rV[K]_6. +Variable sol : U -> K -> U. +Variables gamma alpha1 : K. +Hypothesis gamma_gt0 : 0 < gamma. +Hypothesis alpha1_gt0 : 0 < alpha1. +Let phi := Tilt.eqn alpha1 gamma. + +Hypothesis solP : forall y, y 0 \in Tilt.Upsilon1 -> + lasalle.is_sol phi y <-> y = sol (y 0). + +Hypothesis initp : forall p, sol p 0 = p. + +Let isSol p : p \in Tilt.Upsilon1 -> sol_is_deriv_c0y phi (sol p). +Proof. +move=> Kp. +apply/sol_is_deriv_c0yP. +have : lasalle.is_sol phi (sol p) by apply/solP; rewrite ?initp. +move=> [/= _ H] t t0. +split. + by apply: ex_derive; exact: H. +by rewrite derive1E; apply H. +Qed. + +Definition sublevelUpsilon1 (p : U) := + sublevel (Tilt.V1 alpha1 gamma) (Tilt.V1 alpha1 gamma p) `&` Tilt.Upsilon1. + +Lemma mem_sublevelUpsilon1 p : Tilt.Upsilon1 p -> + p \in sublevelUpsilon1 p. +Proof. by rewrite /sublevelUpsilon1 /sublevel/= inE/=. Qed. + +(* continuity in initial value: assumption needed for LaSalle *) +Hypothesis cont_sol : forall p t, {within sublevelUpsilon1 p, continuous sol^~ t}. + +Local Notation Left := (@lsubmx _ 1 3 3). +Local Notation Right := (@rsubmx _ 1 3 3). + +Lemma V1_bound_compact p : + compact (sublevel (Tilt.V1 alpha1 gamma) (Tilt.V1 alpha1 gamma p)). +Proof. +(* TODO: use something similar to compact_sphere *) +apply: bounded_closed_compact. +- rewrite /Tilt.V1/= /bounded_near. + near=> r. + move=> /= x. + rewrite /sublevel/= !addf_div; rewrite ?lt0r_neq0 ?mulr_gt0//. + rewrite ler_pdivrMr ?mulr_gt0// divrK; last first. + by rewrite unitfE lt0r_neq0 // ?mulr_gt0. + rewrite !(mulrC 2) !mulrA -!mulrDl ler_pM2r// => h. + set c := `| Left p |_e ^+ 2 * gamma + `| Right p |_e ^+ 2 * alpha1. + have c0 : 0 <= c. + by rewrite addr_ge0// mulr_ge0 ?sqr_ge0 ?ltW. + have hL : `| Left x |_e <= Num.sqrt (c / gamma). + rewrite -(sqr_sqrtr (enorm_ge0 (Left x))). + rewrite /GRing.exp/= -sqrtrM ?enorm_ge0//. + rewrite ler_sqrt ?divr_ge0 ?(@ltW _ _ _ gamma)//. + rewrite ler_pdivlMr//. + apply: le_trans h. + by rewrite lerDl mulr_ge0// ?sqr_ge0 ?ltW. + have hR : `| Right x |_e <= Num.sqrt (c / alpha1). + rewrite -(sqr_sqrtr (enorm_ge0 (Right x))). + rewrite /GRing.exp/= -sqrtrM ?enorm_ge0//. + rewrite ler_sqrt// ?divr_ge0 ?(@ltW _ _ _ alpha1)//. + rewrite ler_pdivlMr//. + apply: le_trans h. + by rewrite addrC lerDl mulr_ge0 // ?sqr_ge0 ?ltW. + have normb : `|x| <= `| Left x |_e + `|Right x|_e. + rewrite -[in leLHS](@hsubmxK _ 1 3 3 x) (norm_rowmx (Left x)) ge_max. + by rewrite !(le_trans (mxnorm_enorm_le _))//= ?lerDl ?lerDr ?enorm_ge0. + exact/(le_trans normb)/(le_trans (lerD hL hR)). +- rewrite sublevel_preimage. + apply: closed_comp. + move=> /= x xin. + exact: (differentiable_continuous (V1_diff _ _ _)). + exact: closed_le. +Unshelve. all: by end_near. Qed. + +Lemma compact_sublevelUpsilon1 p : compact (sublevelUpsilon1 p). +Proof. +apply: compact_closedI; first exact: V1_bound_compact. +rewrite Tilt.Upsilon1_preimage. +apply : closed_comp => // => x xp. +apply : continuous_comp; last exact: continuous_enorm. +apply: continuousB. + exact: cst_continuous. +exact: continuous_rsubmx. +Qed. + +Lemma invariant_sublevelUpsilon1 p : + lasalle.is_invariant sol (sublevelUpsilon1 p). +Proof. +rewrite /= /lasalle.is_invariant/=. +move => /= x. +rewrite /sublevelUpsilon1/= => -[Vx Kx] t t0. +split; last first. + apply/(@tilt_state_spaceS _ alpha1 gamma). + exists (sol x), (t + 1) => /=. (* use large enough time *) + split => //. + + rewrite initp. + exact/mem_set. + + apply sol_is_deriv_c0yco. + apply isSol => //. + by rewrite inE. + + exists t => //. + by rewrite /= in_itv/=t0/=ltrDl. +move/mem_set : (Kx) => /isSol /sol_is_deriv_c0yP solA. +rewrite /sublevel/=. +rewrite (le_trans _ Vx)//. +rewrite -[in leRHS](@initp x). +have : {in `[0, t + 1[, forall t : K, derivable (sol x) t 1}. + move=> t'. + rewrite in_itv/= => /andP[t0' _]. + by apply solA. +move/V_nincr => /= => /(_ (Tilt.V1 alpha1 gamma)). +apply. +- exact: V1_diff. +- move => t1 tt1. + apply: (@derive_along_V1_le0 _ _ _ _ _ (t + 1)) => //. + + by rewrite initp inE. + + apply: sol_is_deriv_c0yco => //. + apply/sol_is_deriv_c0yP. + by apply solA. + + move=> t2 /andP[t2' _]. + apply/derivable1_diffP. + apply solA. + by rewrite ltW. +- by rewrite ltrDl. +- by rewrite lexx. +Qed. + +Local Lemma sol_sublevelUpsilon1 p u : + u \in sublevelUpsilon1 p -> sol_is_deriv_c0y phi (sol u). +Proof. +rewrite inE/= => -[h1 h2]. +apply isSol => //. +by rewrite inE. +Qed. + +Lemma V1dot_point1_eq0 : V1dot Tilt.point1 = (0 : K). +Proof. +rewrite /V1dot /Tilt.point1 /=. +rewrite lsubmx_const rsubmx_const enorm0 expr0n /= oppr0 add0r !mul0mx sub0r oppr0. +by rewrite mxE. +Qed. + +Lemma V1dot_point2_eq0 : V1dot Tilt.point2 = (0 : K). +Proof. +rewrite /V1dot /Tilt.point2 /=. +rewrite row_mxKl row_mxKr. +rewrite enorm0 expr0n /= oppr0 add0r. +rewrite -!scalemxAl -scalerBr. +rewrite trmx0 mulmx0 subr0. +rewrite !scalemxAl. +rewrite norm_spin. +rewrite -!scalemxAl enormZ. +rewrite spinE. +suff -> : 'e_2 *v 'e_2 = (0 : 'rV[K]_3). + by rewrite enorm0 /GRing.exp /= !mulr0 oppr0. +by rewrite vece2 /= scale0r. +Qed. + +Local Lemma sol_continuous p : p \in Tilt.Upsilon1 -> continuous (sol p). +Proof. +move => sp t. +have [issol0 issol1]: lasalle.is_sol phi (sol p). + apply: (lasalle.sol_is_sol (sol := sol) (K:=Tilt.Upsilon1)) => //. + move => y Ky. + by apply /solP;rewrite inE. + move : sp. + by rewrite inE. +apply : differentiable_continuous. +apply /derivable1_diffP. +have [ht | ht] := ltP t 0; last by apply /ex_derive/issol1. +apply : (@near_eq_derivable _ _ _ (fun t => 2 *: sol p 0 - sol p (-t))) => //. + near do (rewrite -issol0//). + exact: lt_nbhsl. +apply/derivable1_diffP. +apply: differentiable_comp => //. +apply: differentiable_comp => //. +apply: differentiable_comp => //. +apply/derivable1_diffP. +apply/ex_derive/issol1. +by rewrite lerNr oppr0 ltW. +Unshelve. all: by end_near. Qed. + +Local Lemma limS_subset_V1dot0 p : + p \in Tilt.Upsilon1 -> + lasalle.limS sol (sublevelUpsilon1 p) `<=` + [set x : 'rV[K]_6 | V1dot x = 0] `&` Tilt.Upsilon1. +Proof. +move => ps. +have lasalle_sol (y : K -> 'rV_6) : + sublevelUpsilon1 p (y 0) -> lasalle.is_sol phi y <-> y = sol (y 0). + move=> Ky. + apply/solP. + rewrite inE. + by apply Ky. +have H : lasalle.limS sol (sublevelUpsilon1 p) `<=` + [set x | (Tilt.V1 alpha1 gamma \o sol x)^`()%classic 0 = 0] `&` + Tilt.Upsilon1. + rewrite subsetI; split. + - apply: (@lasalle.stable_limS _ _ _ _ (@compact_sublevelUpsilon1 p) _ _ + lasalle_sol _ (@invariant_sublevelUpsilon1 p) + (Tilt.V1 alpha1 gamma)) => //=. + + apply/continuous_subspaceT => x xK. + apply: differentiable_continuous. + exact: V1_diff. + + move=> /= p0 t K0 t0. + apply/derivable1_diffP. + apply: differentiable_comp. + apply/derivable1_diffP. + apply isSol => //; last first. + by rewrite in_itv/= andbT. + rewrite inE. + by have [_ +] := K0. + exact: V1_diff. + + move=> p0 K0. + have p0s : p0 \in Tilt.Upsilon1. + by move : K0; rewrite inE/= /inE/= => -[]. + rewrite derive1E -derive_along_derive. + * apply : derive_along_V1_le0_global => //. + by rewrite initp. + by apply isSol. + * rewrite initp. + exact: V1_diff. + + apply /derivable1_diffP. + apply isSol => //. + by rewrite in_itv/= lexx. + - move=>/=x [q qKsub xcl]. + suff [] : (sublevelUpsilon1 q) x by []. + rewrite (closure_id (sublevelUpsilon1 q)).1; last first. + apply compact_closed => //. + exact: compact_sublevelUpsilon1. + have qs (t : K) : 0 <= t -> state_space phi (sublevelUpsilon1 q) (sol q t). + move=> t0; exists (sol q), (t + 1); split. + + by rewrite initp; apply: mem_sublevelUpsilon1; case: qKsub. + + apply: sol_is_deriv_c0yco. + by apply isSol; rewrite inE; apply qKsub. + + exists t => //. + by rewrite/=in_itv/= t0 ltrDl ltr01. + have lim_sp : (sol q x @[x --> +oo]) (sublevelUpsilon1 q). + exists 0; split => // t t0 /=. + apply invariant_sublevelUpsilon1. + split => /=. + by rewrite /sublevel/=. + by case: qKsub. + by rewrite ltW. + by move: xcl; rewrite clusterE; exact. +apply: (subset_trans H) =>/= x [+ h1] /=. +rewrite /= derive1E -derive_along_derive. +- rewrite derive_along_V1_global //=. + by rewrite initp ?inE. + split => //. + apply isSol => //. + by apply/mem_set. + apply isSol => //. + by apply/mem_set. +- exact: V1_diff. +- apply/derivable1_diffP. + apply isSol => //; last first. + by rewrite in_itv/= lexx. + by rewrite inE. +Qed. + +Lemma limS_subset_points p : + p \in Tilt.Upsilon1 -> lasalle.limS sol (sublevelUpsilon1 p) `<=` Tilt.points. +Proof. +have -> : Tilt.points = [set x : 'rV[K]_6 | V1dot x = 0] `&` Tilt.Upsilon1. + apply/seteqP; split => x /=. + case => ->;split; [exact: V1dot_point1_eq0 | | exact: V1dot_point2_eq0 | ]. + have := @tilt_point1_in_state_space K. + by rewrite inE. + have := @tilt_point2_in_state_space K. + by rewrite inE. + move => [h1 h2']. + have h2 : x \in Tilt.Upsilon1 by rewrite inE. + move : h1. + have hi := initp x. + rewrite -hi => h1. + have sol' : sol_is_deriv_co (fun=> phi) 0 1 (sol x). + apply: sol_is_deriv_c0yco. + by apply isSol. + rewrite /Tilt.points/=. + apply: (V1dot_eq0_p1_or_p2 _ sol') => //. + rewrite hi. + exact/mem_set. + by rewrite bound_itvE ltr01. +by apply limS_subset_V1dot0. +Qed. + +Lemma cvg_to_set_points p : p \in Tilt.Upsilon1 -> + sol p t @[t --> +oo] --> (Tilt.points : set 'rV_6). +Proof. +move=> /set_mem ps. +have p0K : (forall p0 : 'rV_6, p0 \in sublevelUpsilon1 p -> sol p0 0 = p0). + move => q /set_mem[_ h]. + exact: initp. +apply: (cvg_trans (lasalle.cvg_to_limS (@compact_sublevelUpsilon1 p) + (@invariant_sublevelUpsilon1 p) _)). + by apply/set_mem/mem_sublevelUpsilon1. +move => /= S [eps eps0 Be]. +exists eps => //. +apply bigcup_sub => /= x H. +apply: (subset_trans _ Be). +have ps' : p \in Tilt.Upsilon1 by exact/mem_set. +have : Tilt.points x by apply: (limS_subset_points ps'). +move => h x' Bx'. +by exists x. +Qed. + +Lemma avoid_x (x : U) : (~` Tilt.points) x -> + exists S : set U, [/\ open S, Tilt.points `<=` S & ~ closure S x]. +Proof. +move => hx. +have cx : closed [set x]. + by apply accessible_closed_set1; apply hausdorff_accessible. +have cp : closed (@Tilt.points K). + rewrite /Tilt.points. + by apply accessible_finite_set_closed => //; apply hausdorff_accessible. +have /(@normal_openP K) Hn : normal_space U by apply: pseudometric_normal. +have [|V1 [V2 [V1o V2o V1c V2c Vdisj]]] := (Hn _ _ cx cp). + apply disjoints_subset. + by rewrite sub1set; apply/mem_set . +exists V2;split => //. +move => h. +have [_ +] := open_disjoint_separated V1o V2o Vdisj. +apply /nonemptyPn => /=. +rewrite not_notE. +exists x. +split => //. +by apply V1c. +Qed. + +Lemma cluster_contained_points p : p \in Tilt.Upsilon1 -> + cluster (sol p t @[t --> +oo]) `<=` Tilt.points. +Proof. +move => ps. +have /cvg_cluster cp12 := cvg_to_set_points ps. +apply: (subset_trans cp12). +rewrite clusterE. +move => /= x H. +suff : (~ (~` Tilt.points) x) by apply contrapT. +move => Hdist. +have [S [So Sc Sx]] := avoid_x Hdist. +have [e1 /= e10 /= P1] : \forall e \near 0^'+, ball Tilt.point1 e `<=` S. + apply: open_subball => //. + by apply Sc; left. +have [e2 /= e20 /= P2] : \forall e \near 0^'+, ball Tilt.point2 e `<=` S. + apply: open_subball => //. + by apply Sc; right. +set eps := Num.min (e1 / 2) (e2 / 2). +have eps0 : 0 < eps by rewrite lt_min !divr_gt0. +have B1 : ball Tilt.point1 eps `<=` S. + apply P1 => //. + rewrite /ball_/= sub0r normrN ger0_norm ?gt_min ?ltW // ltr_pdivrMr // ltr_pMr ?ltrDr //. + by apply/orP; left. +have B2 : ball Tilt.point2 eps `<=` S. + apply P2 => //. + rewrite /ball_/= sub0r normrN ger0_norm ?gt_min ?ltW // ?ltr_pdivrMr // ltr_pMr ?ltrDr //. + by apply/orP; right. +have nbh' : (nbhs Tilt.points S). + exists eps => //=. + rewrite /ball_set. + by apply: bigcup_sub => /= _ [-> | ->]. +by have := H _ nbh'. +Qed. + +Local Lemma connected2_subset (A : set U) : connected A -> A !=set0 -> + A `<=` Tilt.points -> A = [set Tilt.point1] \/ A = [set Tilt.point2]. +Proof. +move=>Ac Anonempty Asub. +have sep : separated [set (@Tilt.point1 K)] [set Tilt.point2]. + split. + - rewrite -(closure_id _).1; last first. + by apply accessible_closed_set1; apply hausdorff_accessible. + apply/disjoints_subset. + rewrite sub1set. + apply/mem_set => /=. + exact/eqP/Tilt.point1_neq2. + - rewrite setIC -(closure_id _).1; last first. + by apply accessible_closed_set1; apply hausdorff_accessible. + apply/disjoints_subset. + rewrite sub1set. + apply/mem_set => /=. + exact/nesym/eqP/Tilt.point1_neq2. +have [/subset_set1 [/nonemptyPn A0 | ] | /subset_set1 [/nonemptyPn A0 |] ] := + connected_subset sep Asub Ac => //. +by left. +by right. +Qed. + +Lemma cluster_nonempty p : p \in Tilt.Upsilon1 -> + cluster (sol p t @[t --> +oo]) !=set0. +Proof. +move => sp. +suff : (sublevelUpsilon1 p) `&` cluster (sol p t @[t --> +oo]) !=set0. + move => [x [_ cx]]. + by exists x. +apply (@compact_sublevelUpsilon1 p) => //. + by apply: fmap_proper_filter. +apply sub_image_at_infty => /=. +move => _ [t t0] <-. +apply invariant_sublevelUpsilon1 => //. +by apply/set_mem/mem_sublevelUpsilon1/set_mem. +Qed. + +Lemma p1_sublevelUpsilon1 p : sublevelUpsilon1 p Tilt.point1. +Proof. +split => /=; last by have /set_mem := @tilt_point1_in_state_space K. +rewrite /sublevel/= /Tilt.point1 /Tilt.V1. +rewrite lsubmx_const rsubmx_const/= !enorm0 !expr0n /= !mul0r add0r. +by rewrite addr_ge0// divr_ge0// ?sqr_ge0 ?mulr_ge0// ltW. +Qed. + +Lemma tilt_cvg_to_point1_or_point2 p : p \in Tilt.Upsilon1 -> + (sol p t @[t --> +oo] --> Tilt.point1) \/ + (sol p t @[t --> +oo] --> Tilt.point2). +Proof. +move => ps. +have cluster_con : connected (cluster (sol p t @[t --> +oo])). + apply: (compact_connected_cluster _ _ _ (@compact_sublevelUpsilon1 p) ) => //. + exact: pseudometric_normal. + exact: sol_continuous. + move=> t t0. + apply/mem_set. + apply: invariant_sublevelUpsilon1 => //. + exact/set_mem/mem_sublevelUpsilon1/set_mem. +have := connected2_subset cluster_con (cluster_nonempty ps) + (cluster_contained_points ps). +suff H (q : U): cluster (sol p t @[t --> +oo]) = [set q] -> + sol p t @[t --> +oo] --> q. + by move => [h | h]; [left|right]; apply H. +move => H. +have sublevelUpsilon1q : sublevelUpsilon1 p q. + suff: cluster (sol p t @[t --> +oo]) `<=` sublevelUpsilon1 p. + by apply; rewrite H. + rewrite clusterE. + apply: (@subset_trans _ (closure (sol p @` `[0, +oo[))). + apply: bigcap_inf => //=. + exists 0; split => //= x x0. + exists x =>//. + rewrite in_itv/=ltW//. + rewrite (closure_id (sublevelUpsilon1 p)).1; last first. + by apply compact_closed =>//; apply compact_sublevelUpsilon1. + apply closure_subset. + move => /= _ [t +] <-. + rewrite in_itv/= => /andP[t0 _]. + apply invariant_sublevelUpsilon1 => //. + exact/set_mem/mem_sublevelUpsilon1/set_mem. +have [M [Mr Mp]] : bounded_set (sublevelUpsilon1 p). + apply compact_bounded. + exact: compact_sublevelUpsilon1. +have [M0 | M0] := leP 0 M;last first. + suff : `|q| < 0 by rewrite normr_lt0. + have M02 : M < M / 2 by rewrite ltr_pdivlMr // gtr_nMr // ltrDl. + have /= w := Mp _ M02 _ sublevelUpsilon1q. + apply (le_lt_trans w). + by rewrite ltr_pdivrMr// mul0r. +set V := ball (p : U) (`|p| + (M + 1 + 1) : K). +have VsublevelUpsilon1 : sublevelUpsilon1 p `<=` V. + move => /= x Kx. + rewrite /V -ball_normE/ball_ /=. + by rewrite (le_lt_trans (ler_normB _ _))// ltrD2l ltr_pwDr// Mp// ltrDl. +have B1 : 0 < `|p| + (M + 1 + 1). + by rewrite ltr_wpDl// addr_gt0// ltr_wpDl. +have Vo : open V. + by rewrite /V; exact: ball_open. +have cV : compact (closure V). + rewrite closure_ballE closed_ballE//. + apply: bounded_closed_compact; last exact: closed_closed_ball_. + exists (`|p| + (`|p| + (M + 1 +1))). + rewrite /closed_ball_/=. + split => //= x xB y Hy. + rewrite -(subrKC p y). + apply: (le_trans (ler_normD _ _)). + rewrite distrC. + apply (le_trans (lerD (lexx _ ) Hy)). + by apply ltW. +apply: (compact_cluster_set1 _ cV ) => //. + rewrite nbhsE/=. + exists V; last by apply subset_closure. + split => //. + by apply VsublevelUpsilon1. +apply: (filterS (closure_subset VsublevelUpsilon1)). +exists 0; split => //= x /ltW x0. +rewrite -(closure_id (sublevelUpsilon1 p)).1;last first. + by apply compact_closed =>//; apply compact_sublevelUpsilon1. +apply invariant_sublevelUpsilon1 => //. +by apply/set_mem/mem_sublevelUpsilon1/set_mem. +Qed. + +End LaSalle_tilt. diff --git a/tilt_lyapunov.v b/tilt_lyapunov.v new file mode 100644 index 00000000..56967e71 --- /dev/null +++ b/tilt_lyapunov.v @@ -0,0 +1,1262 @@ +From HB Require Import structures. +From mathcomp Require Import all_boot all_algebra ring. +From mathcomp Require Import interval_inference. +From mathcomp Require Import boolp classical_sets functions reals order. +From mathcomp Require Import topology normedtype landau sequences derive realfun. +From mathcomp Require Import matrix_normedtype. +Require Import ssr_ext euclidean rigid frame skew derive_matrix. +Require Import tilt_mathcomp tilt_analysis tilt_robot. +Require Import ode tilt_stability. + +(**md**************************************************************************) +(* # Formalization of [benallegue2023itac] (1/2) *) +(* *) +(* This file starts with a formal description of the physical model. *) +(* The final result of this file is the proof that the equilibrium point 0 is *) +(* stable. *) +(* *) +(* ``` *) +(* S2 == unit sphere centered at 0 *) +(* Module PhysicalModel == This module contains a formalization of the *) +(* transformation of a system of measurements to *) +(* a differential equation that captures the error *) +(* dynamics. *) +(* Tilt.point{1.2} == equilibrium points *) +(* Tilt.Upsilon1 == state space *) +(* Tilt.eqn == equation (14) in [benallegue2023itac] *) +(* Tilt.V1 == Lyapunov function *) +(* u2 == 2 x 2 matrix to prove the Lyapunov function *) +(* ``` *) +(* *) +(* Reference: *) +(* - [benallegue2023itac] *) +(* https://hal.science/hal-04271257v1/file/benallegue2019tac_October_2022.pdf *) +(******************************************************************************) + +Set Implicit Arguments. +Unset Strict Implicit. +Unset Printing Implicit Defensive. + +Import Order.TTheory GRing.Theory Num.Def Num.Theory. +Import numFieldNormedType.Exports. + +Local Open Scope ring_scope. +Local Open Scope classical_set_scope. + +Definition S2 {R : realType} := [set x : 'rV[R]_3 | `|x|_e = 1]. + +Module PhysicalModel. +Section physicalmodel. +Variable R : realType. +Variable g0 : R. (* standard gravitational constant *) +Hypotheses g0_neq0 : g0 != 0. + +Variable M : R -> 'M[R]_3. (* orientation of frame L w.r.t. frame W *) +Hypothesis MisSO : forall t, M t \is 'SO[R]_3. + +Let w t := ang_vel M t. (* angular velocity *) + +(* tilt, eqn (8) *) +Definition x2 t : 'rV[R]_3 := 'e_2 *m M t. + +Lemma x2_S2 t : x2 t \in S2. +Proof. by rewrite /S2 /x2 inE/= orth_preserves_norm ?enormeE ?rotation_sub. Qed. + +(* what the accelerometer measures according to [benallegue2023itac] *) +Definition y_a x t := - x t *m \S(w t) + 'D_1 x t + g0 *: x2 t. + +(* proof that y_a is indeed the sum of linear and gravitational acceleration *) +Section y_aE. +Variable p : R -> 'rV[R]_3. +Let v := fun t : R => 'D_1 p t *m M t. + +Lemma y_aE t : (forall t, derivable M t 1) -> + (forall t, derivable p t 1) -> (forall t, derivable ('D_1 p) t 1) -> + ('D_1 ('D_1 p) t + g0 *: 'e_2) *m M t = y_a v t. +Proof. +move=> derivableR derivablep derivableDp. +rewrite mulmxDl. +rewrite /y_a/= /= /x2. +congr +%R; last by rewrite scalemxAl. +rewrite -ang_vel_mxE/=; last 2 first. + by move=> ?; rewrite rotation_sub. + exact: derivableR. +rewrite [in RHS]derive_mulmx => //. +rewrite derive1mx_ang_vel//; last by move=> ?; rewrite rotation_sub. +rewrite ang_vel_mxE//; last by move=> ?; rewrite rotation_sub. +rewrite addrCA. +rewrite -mulmxE. +rewrite -mulNmx. +rewrite [X in _ = _ X]addrC. +rewrite !mulNmx. +by rewrite -mulmxA /= addrN addr0. +Qed. + +End y_aE. + +Hypothesis derivableR : forall t, derivable M t 1. +Variable v : R -> 'rV[R]_3. (* linear velocity *) +Let x1 t := v t. + +(* section III.A of [benallegue2023itac] *) +Section state_dynamics. + +(* NB: not used *) +Lemma derive_ang_vel t (u : R -> 'rV[R]_3) (T : R -> 'M[R]_3) : + (forall t, derivable u t 1) -> (forall t, derivable T t 1) -> + (forall t, t \is 'SO[R]_3) -> + 'D_1 (fun t => u t *m T t) t = u t *m T t *m \S(ang_vel T t) + 'D_1 u t *m T t. +Proof. +move=> deru dert TisSO. +rewrite derive_mulmx => //. +rewrite addrC; congr +%R. +rewrite -ang_vel_mxE ; last 2 first. + by move => t0; rewrite rotation_sub. + exact: dert. +rewrite -mulmxA. +rewrite mulmxE. +by rewrite -derive1mx_ang_vel// => ?; rewrite rotation_sub. +Qed. + +(* eqn (10/11) *) +(* NB: we write x_i * S(w) whereas it is - S(w) * x_i in [benallegue2023itac], + row convention *) +Lemma derive_x1 t : 'D_1 x1 t = x1 t *m \S(w t) + y_a x1 t - g0 *: x2 t. +Proof. +rewrite /y_a/= -addrA addrK. +rewrite /x1. +rewrite addrCA addrA mulNmx /= /w. +by rewrite (addrC(-_)) subrr add0r. +Qed. + + (* eqn (11b) *) +Lemma derive_x2 t : 'D_1 x2 t = x2 t *m \S( w t ). +Proof. +rewrite /w -ang_vel_mxE//; last by move=> ?; rewrite rotation_sub. +have -> : 'D_1 (fun t0 => 'e_2 *m (M t0)) t = 'e_2 *m 'D_1 M t. + move=> n /=. + rewrite derive_mulmx//=. + by rewrite derive_cst mul0mx add0r. +rewrite derive1mx_ang_vel /=; last by move=> ?; rewrite rotation_sub. +by rewrite mulmxA. +Qed. + +End state_dynamics. + +Hypothesis v_derivable : forall t, derivable v t 1. + +(* section III.A in [benallegue2023itac] *) +Section two_steps_first_order_estimator. +Local Notation y_a := (y_a v). +Variables gamma alpha1 : R. + +Variable x1_hat : R -> 'rV[R]_3. (* estimator *) +Hypothesis derivable_x1_hat : forall t, derivable x1_hat t 1. + +Variable x2_hat : R -> 'rV[R]_3. (* estimator *) +Hypothesis x2_hat_S2 : x2_hat 0 \in S2. +Hypothesis x2_hat_derivable : forall t, derivable x2_hat t 1. +Hypothesis norm_x2_hat : forall t, `|x2_hat t|_e = 1. + +Let x2'_hat t := - (alpha1 / g0) *: (x1 t - x1_hat t). (* eqn (12b) *) + +Hypothesis eqn12a : forall t, + 'D_1 x1_hat t = x1_hat t *m \S(w t) + y_a t - g0 *: x2'_hat t. (* eqn (12a) *) + +Hypothesis eqn12c : forall t, + 'D_1 x2_hat t = x2_hat t *m \S(w t + gamma *: x2'_hat t *m \S(x2_hat t)). + (* eqn (12c) *) + +(* estimation error *) +Let error1 t := x2 t - x2'_hat t. (* p_1 in [benallegue2023ieeetac] *) +Let error2 t := x2 t - x2_hat t. (* \tilde{x_2} in [benallegue2023ieeetac] *) +(* projection from the local frame to the world frame(?) *) +Let error1_p t := error1 t *m (M t)^T (* z_p_1 in [benallegue2023ieeetac] *). +Let error2_p t := error2 t *m (M t)^T. + +Let error2E t : error2 t = error2_p t *m M t. +Proof. +by rewrite /error2 -mulmxA orthogonal_tr_mul ?rotation_sub// mulmx1. +Qed. + +Let derivable_x2 t : derivable x2 t 1. Proof. exact: derivable_mulmx. Qed. + +Let derivable_x2'_hat t : derivable x2'_hat t 1. +Proof. by apply: derivableZ => /=; exact: derivableB. Qed. + +Let derivable_error1 t : derivable error1 t 1. Proof. exact: derivableB. Qed. + +Let derivable_error2 t : derivable error2 t 1. Proof. exact: derivableB. Qed. + +(* eqn (13a) *) +Lemma derive_error1 t : + 'D_1 error1 t = error1 t *m \S(w t) - alpha1 *: error1 t. +Proof. +simpl in *. +rewrite deriveB//=. +rewrite deriveZ//=; last exact: derivableB. +rewrite scaleNr opprK. +rewrite deriveB//. +rewrite !derive_x2 // -/(x2 t) /=. +rewrite derive_x1//. +rewrite eqn12a. +transitivity ((x2 t + (alpha1 / g0) *: (x1 t - x1_hat t)) *m \S(w t) + - alpha1 *: error1 t). + transitivity (x2 t *m \S(w t) + (alpha1 / g0) *: (x1 t *m \S(w t) - + g0 *: x2 t - + (x1_hat t *m \S(w t) - + g0 *: x2'_hat t))). + congr (_ + _ *: _). + rewrite -2![in LHS]addrA -[in RHS]addrA. + congr +%R. + rewrite opprD [in LHS]addrCA. + rewrite opprK. + rewrite [in RHS]opprB. + rewrite [in RHS]addrCA [in RHS]addrC. + rewrite -[in RHS]addrA. + congr +%R. + rewrite opprD. + rewrite [LHS]addrA. + rewrite (addrC (y_a t)). + by rewrite subrK. + rewrite (_ : x1 t *m \S(w t) - g0 *: x2 t - + (x1_hat t *m \S(w t) - g0 *: x2'_hat t) = + (x1 t - x1_hat t) *m \S(w t) - + g0 *: (x2 t - x2'_hat t)); last first. + rewrite mulmxBl scalerDr scalerN opprB addrA [LHS]addrC 2!addrA. + rewrite -addrA; congr +%R. + by rewrite addrC. + by rewrite opprB addrC. + rewrite -/(error1 t). + rewrite scalerDr addrA scalemxAl -mulmxDl scalerN scalerA. + by rewrite divfK. +by rewrite {2}/error1 /x2'_hat scaleNr opprK. +Qed. + +(* eqn (13b) *) +(* we write x~_2 * S(w) instead of - S(w) * x~_2 in [benallegue2023itac] *) +Lemma derive_error2 t : + 'D_1 error2 t = error2 t *m \S(w t) + + gamma *: (error2 t - error1 t) *m \S(x2_hat t) ^+ 2. +Proof. +rewrite /error2. +rewrite [in LHS]deriveB//. +rewrite derive_x2//. +rewrite -/(x2 t) -/(w t) -/(error2 t). +rewrite eqn12c. +rewrite spinD. +rewrite -[in LHS]scalemxAl. +rewrite (spinZ gamma). +rewrite mulmxDr opprD [LHS]addrA. +rewrite [in LHS]addrC addrA (addrC _ (x2 t *m \S(w t))). +rewrite addrAC. +rewrite -mulmxBl -/(error2 t). +simpl in *. +rewrite -[in RHS]opprB. +rewrite scalerN mulNmx. +congr (_ - _). +rewrite -scalemxAr -[RHS]scalemxAl. +congr (_ *: _). +rewrite /error2 /error1. +rewrite opprB addrCA. +rewrite (addrC (x2 t)) addrK. +rewrite mulmxBl. +rewrite [X in _ = X + _](_ : _ = 0) ?add0r; last first. + rewrite mulmxA. + rewrite -(mulmxA(x2_hat t)) sqr_spin //. + rewrite mulmxDr !mulmxA. + rewrite dotmul1 // mul1mx. + by rewrite mulmxN mulmx1 subrr. +rewrite expr2 -mulmxE fact215 -mulmxE -spin_crossmul. +rewrite [in RHS]mulmxA [in RHS]spinE spinE spinE. +by rewrite [LHS](@lieC _ (vec3 R)). +Qed. + +Lemma x2_hatR t : x2_hat t *m (M t)^T = 'e_2 - error2_p t. +Proof. +rewrite /error2_p /error2 mulmxBl opprB addrCA. +rewrite [X in _ + X](_ : _ = 0) ?addr0//. +rewrite /x2 -mulmxA. +by rewrite orthogonal_mul_tr ?rotation_sub// mulmx1 subrr. +Qed. + +(* eqn (14a) *) +Lemma derive_error1_p t : 'D_1 error1_p t = - alpha1 *: error1_p t. +Proof. +rewrite /error1. +rewrite derive_mulmx//=; last by rewrite derivable_trmx. +rewrite derive_error1. +rewrite mulmxBl addrAC. +apply/eqP. +rewrite subr_eq. +rewrite [in eqbRHS]addrC scaleNr scalemxAl subrr /=. +rewrite derive_trmx//. +rewrite derive1mx_ang_vel //; last by move => t0; rewrite rotation_sub. +rewrite ang_vel_mxE //; last by move => t1 ; rewrite rotation_sub. +rewrite -/(w t) -mulmxA -mulmxDr trmx_mul tr_spin. +by rewrite mulNmx subrr mulmx0. +Qed. + +Definition eqn14b_rhs x1 x2 := gamma *: (x2 - x1) *m \S('e_2 - x2) ^+ 2. + +(* eqn (14b) *) +Lemma derive_error2_p t : 'D_1 error2_p t = eqn14b_rhs (error1_p t) (error2_p t). +Proof. +rewrite /eqn14b_rhs. +rewrite [LHS]derive_mulmx//=; last by rewrite derivable_trmx. +simpl in *. +rewrite derive_trmx//. +rewrite derive1mx_ang_vel//=; last by move=> ?; rewrite rotation_sub. +rewrite !ang_vel_mxE//; last by move=> ?; rewrite rotation_sub. +rewrite trmx_mul mulmxA -mulmxDl. +rewrite derive_error2 /=. +rewrite -/(w t) tr_spin mulmxN. +rewrite -!addrA addrC addrA subrK. +rewrite -scalemxAl. +rewrite -!scalemxAl. +congr (_ *: _). +rewrite -x2_hatR. +rewrite -spin_similarity ?rotationV//. +rewrite trmxK. +rewrite [in RHS]expr2 -mulmxE !mulmxA. +rewrite -!mulNmx opprB. +congr (_ *m _ *m _). +rewrite -[in RHS]mulmxA. +rewrite orthogonal_tr_mul ?rotation_sub// mulmx1. +congr (_ *m _). +rewrite -/(error2 _). +rewrite error2E. +rewrite mulmxDl. +congr (_ + _)%R. +by rewrite /error1 -mulmxA orthogonal_tr_mul ?rotation_sub// mulmx1. +Qed. + +End two_steps_first_order_estimator. + +End physicalmodel. +End PhysicalModel. + +Module Tilt. +Section tilt. +Context {R : realType}. +Variables alpha1 gamma : R. + +Local Notation Left := (@lsubmx _ 1 3 3). +Local Notation Right := (@rsubmx _ 1 3 3). + +Definition eqn_functional (f : R -> 'rV[R]_6) : R -> 'rV[R]_6 := + let error1_p_dot := Left \o f in + let error2_p_dot := Right \o f in + fun t => row_mx + (- alpha1 *: error1_p_dot t) + (PhysicalModel.eqn14b_rhs gamma (error1_p_dot t) (error2_p_dot t)). + +Definition eqn (dot_z1_z2 : 'rV[R]_6) : 'rV[R]_6 := + let dot_z1 := Left dot_z1_z2 in + let dot_z2 := Right dot_z1_z2 in + row_mx (- alpha1 *: dot_z1) + (PhysicalModel.eqn14b_rhs gamma dot_z1 dot_z2). + +Lemma eqnE (f : R -> 'rV[R]_6) t : eqn (f t) = eqn_functional f t. +Proof. by []. Qed. + +Definition Upsilon1 := [set x : 'rV[R]_6 | `| 'e_2 - Right x |_e = 1]. + +Lemma Upsilon1_preimage : + Upsilon1 = (fun x => `| 'e_2 - Right x |_e ) @^-1` [set (1 : R)]. +Proof. by []. Qed. + +Definition point1 : 'rV[R]_6 := 0. +Definition point2 : 'rV[R]_6 := @row_mx _ _ 3 _ 0 (2 *: 'e_2). + +Lemma point1_neq2 : point1 != point2. +Proof. +apply/eqP; rewrite /point1 /point2 => /eqP. +rewrite eq_sym (@row_mx_eq0 _ 1 3 3) eqxx/= => /eqP/rowP/(_ ord_max). +by rewrite !mxE eqxx/= mulr1; apply/eqP; rewrite pnatr_eq0. +Qed. + +Definition points := [set point1; point2]. + +Definition V1 (z1_z2 : 'rV[R]_6) : R := + let z1 := Left z1_z2 in + let z2 := Right z1_z2 in + `|z1|_e ^+ 2 / (2 * alpha1) + `|z2|_e ^+ 2 / (2 * gamma). + +End tilt. +End Tilt. + +(* properties of Tilt.eqn *) +Section tilt_eqn. +Context {R : realType}. +Variables alpha1 gamma : R. +Hypothesis gamma_gt0 : 0 < gamma. +Hypothesis alpha1_gt0 : 0 < alpha1. +Let phi := Tilt.eqn alpha1 gamma. + +Local Notation Left := (@lsubmx _ 1 3 3). +Local Notation Right := (@rsubmx _ 1 3 3). + +Lemma tilt_eqn_locally_lipschitz : locally_lipschitz phi. +Proof. +move=> /= x. +exists (PosNum ltr01). +near (pinfty_nbhs R) => k. +have k0 : 0 < k by []. +exists (PosNum k0) => /= => -[/= x0 x1] [x0B x1B]. +rewrite (opp_row_mx (n1:=3)) (add_row_mx (n1:=3)). +rewrite !scaleNr opprK/=. +rewrite addrC -scalerBr. +rewrite /PhysicalModel.eqn14b_rhs. +rewrite -!scalemxAl -scalerBr. +rewrite (norm_rowmx (m:=0) (n1:=2) (n2:=2)). +rewrite ge_max; apply/andP; split. +- rewrite mx_normZ. + rewrite -linearB/=. + rewrite ler_pM//. + rewrite distrC. + exact/le_trans/(@lsubmx_norm_le _ 2). +- rewrite mx_normZ. + set a := Right x0 - Left x0. + set b := Right x1 - Left x1. + set c := \S('e_2 - Right x0) ^+ 2. + set d := \S('e_2 - Right x1) ^+ 2. + have abound : `|a| <= 2 * (`|x| + 1). + rewrite (le_trans (ler_normB _ _ ))// mulrDl lerD// mul1r. + rewrite (le_trans (rsubmx_norm_le _))//. + exact: closed_ball_bounded. + rewrite (le_trans (lsubmx_norm_le _))//. + exact: closed_ball_bounded. + (* todo: find some bound and show *) + have sbound x' : closed_ball x 1 x' -> `|'e_2 - Right x'| <= 2+`|x|. + move=> cb. + rewrite (le_trans (ler_normB _ _))// [in leRHS](natrD _ 1 1) -addrA lerD//. + exact: mx_norm_delta_mx. + by rewrite (le_trans (rsubmx_norm_le _))// addrC closed_ball_bounded. + have dbound : `|d| <= 3 * (2 + `|x|) ^+ 2. + rewrite /d. + apply: (le_trans (spin_sq_norm_bound _)). + apply ler_pM => //. + suff h : `|'e_2 - Right x1| <= 2 + `|x|. + by apply ler_pM => //; apply normr_ge0. + by apply sbound. + rewrite -ler_pdivlMl; last by rewrite normr_gt0 lt0r_neq0. + rewrite -(subrKA (a *m d) (a *m c )) (le_trans (ler_normD _ _))//. + rewrite -[X in `|X| + _]mulmxBr. + rewrite -[X in _ + `|X|]mulmxBl. + rewrite (splitr `|gamma|^-1) mulrDl. + rewrite -invrM ?unitfE//; last first. + by rewrite gt_eqF// gtr0_norm. + rewrite lerD//. + + apply: (le_trans (mx_norm_mul _ _)). + have h0 := spin_sq_dist_bound ('e_2 - Right x0) ('e_2 - Right x1). + apply : (le_trans (ler_pM _ _ (le_refl _) h0)) => //. + have -> : 'e_2 - Right x0 - ('e_2 - Right x1) = Right x1 - Right x0. + by rewrite opprB addrC addrA subrK. + rewrite !mulrA. + apply ler_pM => //; last by rewrite distrC -linearB; exact: rsubmx_norm_le. + rewrite (mulrC 3) -!mulrA. + apply: (le_trans (ler_pM _ _ abound (lexx _))) => //. + rewrite !mulrA. + rewrite ler_pdivlMl; last first. + by rewrite mulr_gt0// gtr0_norm. + rewrite !mulrA. + suff h : `|'e_2 - Right x0| + `|'e_2 - Right x1| <= 2 * (2 + `|x|). + exact: (le_trans (ler_pM _ _ (le_refl _) h)). + by rewrite mulrDl mul1r lerD//; apply sbound. + + rewrite (le_trans (mx_norm_mul _ _))//. + rewrite opprB -addrA (addrC (-Left x0)) addrA (addrC (Left x1)) addrA -(addrA (Right x0 - _)). + rewrite mulrC. + apply (@le_trans _ _ (`| d| * (6 * `|x0 - x1|))). + apply ler_pM => //. + rewrite [in leRHS](natrM _ 3 2)// -mulrA ler_pM//. + rewrite (le_trans (ler_normD _ _))//. + rewrite mulrDl lerD// mul1r. + by rewrite -linearB; exact: rsubmx_norm_le. + by rewrite distrC -linearB/=; exact: lsubmx_norm_le. + rewrite (le_trans (ler_pM _ _ dbound (lexx _ )))//. + rewrite ler_pdivlMl; last by rewrite mulr_gt0// gtr0_norm. + by rewrite !mulrA ler_pM. +Unshelve. all: by end_near. Qed. + +Lemma tilt_state_spaceS : state_space phi Tilt.Upsilon1 `<=` Tilt.Upsilon1. +Proof. +move => p [y [D [y0_init1 deri]]]. +have [D0|D0] := leP 0 D; last first. + move=> -[t + x]. + rewrite in_itv/= => -/andP[x0 xD]. + have := lt_trans xD D0. + by rewrite ltNge x0. +rewrite /Tilt.Upsilon1. +have : {in `]0, D[%R, + (fun t => ('e_2 - Right (y t)) *d (('e_2 - Right (y t))))^`() =1 0}. + move => x xd /=. + transitivity ((fun t => -2 * (Right (y^`()%classic t) *d + ('e_2 - Right (y t)))) x). + rewrite !derive1E. + have ? : derivable y x 1. + apply deri. + by apply: subset_itvr xd; rewrite bnd_simp. + rewrite derive_mx//. + rewrite /dotmul. + under eq_fun do rewrite dotmulP /=. + rewrite dotmulP. + rewrite !mxE /= mulr1n. + under eq_fun do rewrite !mxE /= mulr1n. + rewrite !derive_dotmul/=; last 2 first. + apply: derivableB => //=; apply: derivable_rsubmx => //=. + by apply: derivableB => //=; exact: derivable_rsubmx. + rewrite /dotmul /=. + rewrite [in RHS]mulr2n [RHS]mulNr [in RHS]mulrDl. + rewrite !mul1r !dotmulP /= dotmulC [in RHS]dotmulC !linearD /=. + rewrite !mxE /= !mulr1n. + have -> : 'D_1 (fun x0 => 'e_2 - Right (y x0)) x = - Right ('D_1 y x). + rewrite deriveB /= ; last 2 first. + exact: derivable_cst. + exact: derivable_rsubmx. + rewrite derive_cst /= sub0r; congr (- _). + exact: derive_rsubmx. + rewrite -(_ : 'D_1 y x = + \matrix_(i, j) 'D_1 (fun t0 => y t0 i j) x); last first. + by apply/matrixP => a b; rewrite !mxE derive_mx//= ?mxE. + ring. + have Rsu t0 : t0 \in `[0, D[%R -> Right (y^`()%classic t0) = + (gamma *: (Right (y t0) - Left (y t0)) *m \S('e_2 - Right (y t0)) ^+ 2). + rewrite inE/=. + by move/deri => [_ ->]; rewrite row_mxKr. + rewrite /dotmul. + transitivity (-2 * (gamma *: (Right (y x) - + Left (y x)) *m \S('e_2 - Right (y x)) ^+ 2 *m + ('e_2 - Right (y x))^T) 0 0). + rewrite Rsu//. + by apply: subset_itvr xd; rewrite bnd_simp. + rewrite !mulmxA. + apply/eqP. + rewrite mulf_eq0 /= oppr_eq0 ?pnatr_eq0 /= -!mulmxA spin_mul_tr. + by rewrite !mulmx0 mxE. +move => h [t t0d ->]. +have norm_constant t0 : t0 \in `[0, D[%R -> + `|'e_2 - Right (y t0)|_e ^+ 2 = `|'e_2 - Right (y 0)|_e ^+ 2. + have : forall x0, x0 \in `]0, D[%R -> + is_derive x0 (1 : R) (fun x => `|'e_2 - Right (y x)|_e ^+ 2) 0. + move => x0 x0d. + have ? : derivable y x0 1. + apply deri. + by apply: subset_itvr x0d; rewrite bnd_simp. + apply: DeriveDef. + apply/derivable_enorm_squared => //=. + apply/derivableB => //=. + exact/derivable_rsubmx. + rewrite -derive1E. + have := h _ x0d. + under eq_fun do rewrite dotmulvv /=. + by apply. + move=> /= hd0 t0d'. + apply/esym. + have {}t0d'' : t0 \in `[0, t0]%R by rewrite bound_itvE/= (itvP t0d'). + have {}hd0 x0 : x0 \in `]0, t0[%R -> + is_derive x0 1 (fun x => `| 'e_2 - Right (y x) |_e ^+ 2) 0. + move=> x00t0. + apply: hd0. + apply: subset_itvl x00t0; rewrite bnd_simp. + by rewrite ltW// (itvP t0d'). + have {t0d'' hd0} := cc_is_derive_0_is_cst t0d'' _ hd0. + apply => //; last by rewrite bound_itvE (itvP t0d'). + apply: (@within_continuous_comp _ _ _ `[0, t0] y (fun x => `|'e_2 - Right x|_e ^+ 2)) => //=. + move=> z _. + apply: differentiable_continuous => //. + apply: differentiable_enorm_squared => /=. + exact: differentiableB. + rewrite /sol_is_deriv_co/= in deri. + have cont : {in `[0, t0]%R, continuous y}. + move=> t' t'0D. + apply/differentiable_continuous/derivable1_diffP. + apply deri. + apply: subset_itvl t'0D; rewrite bnd_simp. + by rewrite (itvP t0d'). + move/in_switch in cont. + move/continuous_in_subspaceT : cont. + apply: continuous_subspaceW. + by apply: subset_itvl; rewrite bnd_simp. +suff: `|'e_2 - Right (y t)|_e ^+ 2 = 1. + move=> /(congr1 Num.sqrt). + by rewrite sqrtr1 sqr_sqrtr// dotmulvv sqr_ge0. +rewrite norm_constant//. +move: y0_init1. +rewrite inE /Tilt.Upsilon1 /= => ->. +by rewrite expr2 mulr1. +Qed. + +Lemma tilt_point1_in_state_space : @Tilt.point1 R \in Tilt.Upsilon1. +Proof. +rewrite inE /Tilt.Upsilon1 /Tilt.point1/=. + by rewrite rsubmx_const /= subr0 enormeE. +Qed. + +Lemma equilibrium_point1 : is_equilibrium_point phi Tilt.point1. +Proof. +split. +- move=> t t0; exact: derivable_cst. + rewrite derive1E derive_cst /Tilt.point1; apply/eqP. + rewrite eq_sym (@row_mx_eq0 _ 1 3 3); apply/andP; split. + by rewrite scaler_eq0 oppr_eq0 gt_eqF//= lsubmx_const. + apply/eqP/rowP; move => i; apply/eqP. + rewrite /PhysicalModel.eqn14b_rhs. + set N := (X in _ *: X *m _); have : N = 0. + by rewrite /N /=; apply/rowP => j; rewrite !mxE subrr. + by move=> N0; rewrite N0 scaler0 mul0mx. +Qed. + +Lemma tilt_point2_in_state_space : @Tilt.point2 R \in Tilt.Upsilon1. +Proof. +rewrite inE /Tilt.Upsilon1 /Tilt.point2 /=. +rewrite row_mxKr. +rewrite -[X in X - _ ]scale1r. +rewrite -scalerBl enormZ enormeE mulr1 distrC. +rewrite [X in _ - X](_:1 = 1%:R) //. +by rewrite -natrB //= normr1. +Qed. + +Lemma equilibrium_point2 : is_equilibrium_point phi Tilt.point2. +Proof. +move=> D D0. +split. +exact: derivable_cst. +rewrite derive1E derive_cst; apply/eqP. +rewrite eq_sym (@row_mx_eq0 _ 1 3 3); apply/andP. +set N := (X in _ *: X == 0 /\ _). +have N0 : N = 0. + apply/rowP; move=> i; rewrite !mxE; case: splitP. + by move => j _; rewrite mxE. + move=> k /= i3k. + have := ltn_ord i. + by rewrite i3k -ltn_subRL subnn. +split. + by rewrite scaler_eq0 N0 eqxx orbT. +rewrite /PhysicalModel.eqn14b_rhs. +rewrite -scalemxAl scalemx_eq0 gt_eqF//=. +rewrite -[Left Tilt.point2]/N N0 subr0. +set M := (X in X *m _); rewrite -/M. +have ME : M = 2 *: 'e_2. + apply/rowP => i; rewrite !mxE eqxx/=. + case: splitP => [j ij|j]/=. + have := ltn_ord j. + by rewrite -ij. + move/eqP. + rewrite eqn_add2l => /eqP /ord_inj ->. + by rewrite !mxE eqxx/=. +rewrite ME -scalemxAl scalemx_eq0 pnatr_eq0/=. +rewrite [X in X *: _](_ : _ = 1 + 1)// scalerDl scale1r opprD addrA. +rewrite subrr sub0r spinN sqrrN expr2 -mulmxE mulmxA. +rewrite (_ : 'e_2 *m _ = 0) ?mul0mx//; apply: trmx_inj. +by rewrite trmx_mul trmx0 tr_spin mulNmx spin_mul_tr oppr0. +Qed. + +End tilt_eqn. + +Section u2. +Context {R : realType}. + +Definition u2 : 'M[R]_(2, 2) := \matrix_(i < 2, j < 2) [eta (fun=> 0) with + (0,0) |-> 1, + (0,1) |-> -2^-1, + (1,0) |-> -2^-1, + (1,1) |-> 1] (i, j). + +Lemma u2neq0 : u2 != 0. +Proof. by apply/matrix0Pn; exists 1, 1; rewrite mxE /= oner_neq0. Qed. + +Lemma u2_sym : u2 \is sym 2 R. +Proof. +rewrite /= symE. +apply/eqP/matrixP. +move => i j. +rewrite !mxE/=. +case: ifPn => [/eqP[->{i} ->{j}//]|]. +case: ifPn => [/eqP[->{i} ->{j}//]|]. +case: ifPn => [/eqP[->{i} ->{j}//]|]. +case: ifPn => [/eqP[->{i} ->{j}//]|]. +by move: i j => [[|[|//]]] /= ? [[|[|]]]. +Qed. + +Lemma tr_u2 : \tr u2 = 2. +Proof. by rewrite /u2/= /mxtrace /= sum2E/= !mxE/=. Qed. + +Lemma det_u2 : \det u2 = 3/4. +Proof. by rewrite /u2 det_mx22 /= !mxE /=; field. Qed. + +Lemma posdefmxu2 : posdefmx u2. +Proof. +split; first exact: u2_sym. +move=> a. +move/eigenvalueP => [u] /[swap] u0 H. +have a_eigen : eigenvalue u2 a. + apply/eigenvalueP. + exists u. rewrite /u2. + exact: H. + exact: u0. +have : root (char_poly u2) a. + rewrite -eigenvalue_root_char. + exact : a_eigen. +rewrite char_poly2 tr_u2 det_u2 rootE => a_root . +have char_poly_fact : 'X^2 - 2%:P * 'X + (3/4)%:P = + ('X - (1%:R / 2)%:P) * ('X - (3%:R / 2)%:P) :> {poly R}. + rewrite mulrBr mulrBl -expr2 -!addrA; congr +%R. + rewrite mulrBl opprB addrCA addrC; congr +%R. + by rewrite -[RHS]polyCM; congr (_%:P); field. + rewrite [in RHS]mulrC -opprD -mulrDr mulrC; congr (- (_ * _)). + by rewrite -polyCD; congr (_%:P); by field. +move: a_root. +rewrite char_poly_fact hornerM !hornerXsubC. +by rewrite mulf_eq0 => /orP[|]; rewrite subr_eq0 => /eqP ->; rewrite divr_gt0. +Qed. + +Lemma u2_quadratic_form_gt0 (v : 'rV_2) : + v != 0 -> 0 < (v *m u2 *m v^T) 0 0. +Proof. +move=> v0. +rewrite !(mxE,sum2E,mulr1)/= !mulrDl -!expr2. +rewrite [ltRHS](_ : _ = v``_0 ^+ 2 - v``_1 * v``_0 + v``_1 ^+ 2); last first. + rewrite -!addrA; congr +%R. + rewrite !addrA; congr +%R. + rewrite (mulrC _ v``_0) -mulrA -mulrDr. + rewrite mulrC -mulNr; congr *%R. + rewrite mulrC -mulrDr -mulr2n. + rewrite mulNr; congr (- _). + rewrite -(mulr_natl v``_1). + by rewrite mulrA mulVf// ?mul1r. +rewrite [ltRHS](_ : _ = (v``_0 - 2^-1 * v``_1) ^+ 2 + 3 / 4 * v``_1 ^+ 2); last first. + rewrite sqrrB -!addrA; congr +%R. + rewrite -mulNrn mulrCA -(mulr_natl (- _) 2) mulrN !mulrA divff ?mul1r//. + rewrite mulrC; congr +%R. + rewrite -mulrA -expr2 exprMn -mulrDl. + rewrite (expr2 2^-1). + rewrite -invfM -div1r -natrM -mulrDl. + by rewrite nat1r divff// mul1r. +rewrite ltNge le_eqVlt negb_or -leNgt addr_ge0 ?(sqr_ge0,mulr_ge0)// andbT. +rewrite paddr_eq0 ?(sqr_ge0,mulr_ge0)//. +apply/negP => /andP[]; rewrite sqrf_eq0 => /[swap]. +rewrite mulf_eq0/= sqrf_eq0 mulf_eq0 invr_eq0 !pnatr_eq0/= => /eqP v10. +rewrite v10 mulr0 subr0 => /eqP v00. +move/negP : v0; apply. +apply/eqP/rowP => -[[i|[j|//]]]; rewrite !mxE//. +by rewrite (_ : Ordinal _ = 0)//; exact/val_inj. +by rewrite (_ : Ordinal _ = 1)//; exact/val_inj. +Qed. + +End u2. + +Section V1. +Local Open Scope classical_set_scope. +Context {R : realType}. +Variables alpha1 gamma : R. +Hypothesis alpha1_gt0 : 0 < alpha1. +Hypothesis gamma_gt0 : 0 < gamma. + +Local Notation Left := (@lsubmx _ 1 3 3). +Local Notation Right := (@rsubmx _ 1 3 3). +Local Notation V1 := (Tilt.V1 alpha1 gamma). + +Lemma V1_diff (t : 'rV_6) : differentiable V1 t. +Proof. +apply/differentiableD => //=. + apply/differentiableM => //=. + exact/differentiable_enorm_squared/differentiable_lsubmx_comp. +apply/differentiableM => //=. +exact/differentiable_enorm_squared/differentiable_rsubmx_comp. +Qed. + +Lemma V1_is_Lyapunov_candidate : + is_Lyapunov_candidate V1 [set: 'rV_6] Tilt.point1. +Proof. +rewrite /V1 /Tilt.point1; split; first by rewrite inE. +- by rewrite lsubmx_const rsubmx_const enorm0 expr0n/= !mul0r add0r. +- move=> /= z_near _ z0. + have /orP[lz0|rz0] : (Left z_near != 0) || (Right z_near != 0). + rewrite -negb_and. + apply: contra z0 => /andP[/eqP l0 /eqP r0]. + rewrite -[eqbLHS](@hsubmxK _ _ 3 3) l0 r0. + apply/eqP/rowP; move => i; rewrite !mxE /=; case: splitP => ? ?; + by rewrite mxE. + + set rsub := Right z_near. + have : `|rsub|_e >= 0 by rewrite enorm_ge0. + set lsub := Left z_near. + move=> nor. + have normlsub : `|lsub|_e > 0 by rewrite enorm_gt0. + rewrite ltr_pwDl//. + by rewrite divr_gt0 ?exprn_gt0// mulr_gt0. + by rewrite divr_ge0 ?exprn_ge0// mulr_ge0// ltW. + + rewrite ltr_pwDr//. + by rewrite divr_gt0 ?exprn_gt0 ?mulr_gt0 ?enorm_gt0. + by rewrite divr_ge0 ?exprn_ge0 ?enorm_ge0 ?mulr_ge0// ltW. +Unshelve. all: by end_near. Qed. + +Definition V1dot (zp1_z2 : 'rV[R]_6) : R := + let zp1 := Left zp1_z2 in + let z2 := Right zp1_z2 in + - `|zp1|_e ^+ 2 + (z2 *m (\S('e_2 - z2))^+2 *m z2^T + - z2 *m (\S('e_2 - z2))^+2 *m zp1^T)``_0. + +End V1. + +Section tilt_eqn_Lyapunov. +Local Open Scope classical_set_scope. +Context {R : realType}. +Variables alpha1 gamma : R. +Hypotheses (alpha1_gt0 : 0 < alpha1) (gamma_gt0 : 0 < gamma). +Let phi := Tilt.eqn alpha1 gamma. +Implicit Types f : R -> 'rV[R]_6. + +Local Notation Left := (@lsubmx _ 1 3 3). +Local Notation Right := (@rsubmx _ 1 3 3). + +Lemma derive_zp1 (D : R) t f : + sol_is_deriv_co (fun=> phi) 0 D f -> + t \in `[0, D[ -> 'D_1 (Left \o f) t = - alpha1 *: Left (f t). +Proof. +move=> /= deri /[!inE]/= t0D. +have [derivable_f] := deri _ t0D. +move=> /(congr1 Left). +rewrite derive1E row_mxKl => <-. +by rewrite derive_lsubmx. +Qed. + +Lemma derive_z2 (D : R) z f : + sol_is_deriv_co (fun=> phi) 0 D f -> + z \in `[0, D[ -> 'D_1 (Right \o f) z = + gamma *: (Right (f z) - Left (f z)) *m \S('e_2 - Right (f z)) ^+ 2. +Proof. +move=> deriv /[!inE]/= z0D. +have [derivable_f +] := deriv _ z0D. +move => /(congr1 Right). +by rewrite derive1E row_mxKr => ?; rewrite derive_rsubmx. +Qed. + +Lemma is_sol_state_space_tilt (D : R) f t : + t \in `[0, D[%R -> + f 0 \in Tilt.Upsilon1 -> + sol_is_deriv_co (fun=> phi) 0 D f -> + Tilt.Upsilon1 (f t). +Proof. +move=> + f0 deriv_f. +rewrite in_itv/= => /andP[]. +rewrite le_eqVlt => /predU1P[<- D0|t0 tD]. + exact/set_mem. +apply: (@tilt_state_spaceS _ alpha1 gamma) => //=. +exists f, D; split => //=. +exists t => //. +by rewrite in_itv/= (ltW t0) tD. +Qed. + +Lemma norm_e2z2 (D : R) f (z : R) + (z2 := Right \o f) (zp1 := Left \o f) (u := 'e_2 - z2 z) : + z \in `[0, D[%R -> + f 0 \in Tilt.Upsilon1 -> + sol_is_deriv_co (fun=> phi) 0 D f -> `|u|_e = 1. +Proof. +move=> z0D sol0 sol_f. +suff: Tilt.Upsilon1 (row_mx (zp1 z) (z2 z)). + by rewrite /Tilt.Upsilon1/= row_mxKr. +rewrite /zp1 /z2 hsubmxK /=. +exact: (is_sol_state_space_tilt z0D). +Qed. + +Lemma angvel_sqr (D : R) (f : R -> 'rV_6) z + (z2 := fun r : R => Right (f r) : 'rV_3) + (w := (z2 z) *m \S('e_2)) (u := 'e_2 - z2 z) : + z \in `[0, D[%R -> + f 0 \in Tilt.Upsilon1 -> + sol_is_deriv_co (fun=> phi) 0 D f -> + (w *m \S(u)) *d (w *m \S(u)) = (w *d w) * (u *d u) - (w *d u) ^+ 2. +Proof. +move=> z0D sol0 dtraj. +rewrite /dotmul !trmx_mul !tr_spin !mulNmx mulmxN opprK mulmxN !dotmulP. +have key_ortho : (z2 z *m \S('e_2)) *d u = 0. + by rewrite dotmulC; exact/ortho_spin. +rewrite key_ortho expr2. +rewrite [in RHS]mxE. +rewrite [X in _ = - (w *m (\S('e_2) *m (z2 z)^T)) 0 0 * (u *d u)%:M 0 0 + - 0%:M 0 0 * X]mxE. +rewrite mulr1n mulr0 subr0/=. +rewrite /u -/w /dotmul. +have Hw_ortho : (w *d u) = 0 by rewrite /u dotmulC ortho_spin. +rewrite !mulmxA dotmulP dotmulvv (norm_e2z2 z0D)// expr2 mulr1. +rewrite [X in _ = - (w *m \S('e_2) *m (z2 z)^T) 0 0 * X]mxE /= mulr1n /=. +rewrite [X in _ = - (w *m \S('e_2) *m (z2 z)^T) 0 0 * X]mxE /= mulr1. +have wu0 : w *m u^T *m u = 0 by rewrite dotmulP Hw_ortho mul_scalar_mx scale0r. +rewrite -[in LHS](mulmxA w) sqr_spin; last by rewrite -/u (norm_e2z2 z0D). +rewrite [in LHS]mulmxBr mulmxA wu0 sub0r. +by rewrite 2!mulNmx mulmx1 mxE. +Qed. + +Lemma neg_spin (D : R) (f : R -> 'rV_6) z : + z \in `[0, D[%R -> + f 0 \in Tilt.Upsilon1 -> + sol_is_deriv_co (fun=> phi) 0 D f -> + `|Right (f z) *m \S('e_2) *m - \S('e_2 - Right (f z))|_e = + `|Right (f z) *m \S('e_2)|_e. +Proof. +move=> z0D f0 dtraj. +rewrite mulmxN enormN. +pose zp1 := fun r => Left (f r). +pose z2 := fun r => Right (f r). +set w := (z2 z) *m \S('e_2). +have Upsilon1_traj : Tilt.Upsilon1 (f z) by apply/(is_sol_state_space_tilt z0D). +rewrite /enorm. +rewrite !dotmulvv [RHS]sqrtr_sqr sqrtr_sqr. +have Hnorm_sq : `|w *m \S('e_2 - Right (f z))|_e ^+ 2 = `|w|_e ^+ 2. + rewrite -!dotmulvv (angvel_sqr z0D)// !dotmulvv (norm_e2z2 z0D)//=. + rewrite -!dotmulvv expr2 !mul1r mulr1. + have -> : w *d ('e_2 - Right (f z)) = 0 by rewrite dotmulC ortho_spin. + by rewrite expr2 mul0r subr0. +rewrite !normr_enorm. +by move/sqr_inj : Hnorm_sq => ->//; rewrite ?nnegrE ?enorm_ge0. +Qed. + +Let c1 := 2^-1 / alpha1. +Let c2 := 2^-1 / gamma. + +Lemma V1dotE z (D : R) (f : R -> 'rV_6) + (zp1 := Left \o f) (z2 := Right \o f) : + sol_is_deriv_co (fun=> phi) 0 D f -> + z \in `[0, D[ -> + V1dot (f z) = + c1 *: (2 *: 'D_1 zp1 z *m (Left (f z))^T) 0 0 + + c2 *: (2 *: 'D_1 z2 z *m (Right (f z))^T) 0 0. +Proof. +move=> fP zd. +rewrite -scalemxAl mxE (scalerA c1 2) mulrAC mulVf ?pnatr_eq0// div1r. +rewrite -scalemxAl [in X in _ + X]mxE (scalerA c2 2) mulrAC. +rewrite mulVf// div1r. +rewrite (derive_zp1 fP)// -scalemxAl mxE. +rewrite [X in X + _](mulrA (alpha1^-1) (- alpha1)). +rewrite mulrN mulVf ?gt_eqF// mulN1r. +rewrite (derive_z2 fP)// -scalemxAl mulmxA -scalemxAl [in X in _ + X]mxE. +rewrite scalerA mulVf ?gt_eqF// scale1r. +rewrite norm_squared /V1dot. +congr +%R. +rewrite -2![in LHS]mulmxA -mulmxBr -mulmxBr -linearB/=. +rewrite -[X in (X *m (_ *m _)) 0 0 = _]trmxK. +rewrite -[X in (_ *m (X *m _)) 0 0 = _]trmxK. +rewrite mulmxA -trmx_mul -trmx_mul [LHS]mxE. +rewrite -(mulmxA (Right (f z) - (Left (f z)))) mulmxE -expr2. +rewrite tr_sqr_spin. +by rewrite mulmxA. +Qed. + +Lemma derive_along_V1 (D : R) t (f : R -> 'rV_6) : + t \in `]0, D[ -> + sol_is_deriv_co (fun=> phi) 0 D f -> + (forall t, t \in `]0, D[ -> differentiable f t) -> + 'D~(f) (Tilt.V1 alpha1 gamma) t = V1dot (f t). +Proof. +move=> t0D tilt_eqnx dif1. +rewrite /Tilt.V1 derive_alongD; last 3 first. + apply/differentiableM => //=. + exact/differentiable_enorm_squared/differentiable_lsubmx_comp. + apply/differentiableM => //=. + exact/differentiable_enorm_squared/differentiable_rsubmx_comp. + exact: dif1. +under [X in derive_along X _ _ + _]eq_fun do rewrite mulrC. +under [X in _ + derive_along X _ _]eq_fun do rewrite mulrC. +rewrite derive_alongMl => //; last 2 first. + exact/differentiable_enorm_squared/differentiable_lsubmx_comp. + exact: dif1. +rewrite derive_alongMl => //; last 2 first. + exact/differentiable_enorm_squared/differentiable_rsubmx_comp. + exact: dif1. +rewrite -fctE /= !derive_along_enorm_squared//=. +- rewrite (V1dotE tilt_eqnx); last first. + by move: t0D; rewrite !inE; apply: subset_itvr; rewrite bnd_simp. + by rewrite /c1 /c2 !invfM. +- exact: dif1. +- exact/differentiable_lsubmx_comp. +- exact: dif1. +Qed. + +Definition u1 (f : R -> 'rV[R]_6) t + (zp1 := Left \o f) (z2 := Right \o f) + (w := z2 t *m \S('e_2)) : 'rV[R]_2 := + \row_(i < 2) [eta (fun=> 0) with 0 |-> `|zp1 t|_e, 1 |-> `|w|_e] i. + +Lemma V1dot_ub (D : R) (f : R -> 'rV[R]_6) + (zp1 := Left \o f) (z2 := Right \o f) : + f 0 \in Tilt.Upsilon1 -> + sol_is_deriv_co (fun=> phi) 0 D f -> + forall t, t \in `[0, D[%R -> + V1dot (f t) <= (- (u1 f t) *m u2 *m (u1 f t)^T) 0 0. +Proof. +move=> f0 fP z z0D. +set w := z2 z *m \S('e_2). +rewrite /V1dot. +rewrite mxE norm_spin mxE addrA expr2 mulmxA. +have -> : z2 z *m \S('e_2 - z2 z) = z2 z *m \S('e_2). + by rewrite spinD spinN -tr_spin !mulmxDr !mul_tr_spin !addr0. +rewrite -dotmulNv addrC -mulmxN -expr2. +have cauchy : ((w *m - \S('e_2 - z2 z) *d (zp1 z))%:M : 'rV_1) 0 0 <= + `|w *m - \S('e_2 - z2 z)|_e * `|zp1 z|_e. + rewrite mxE /= mulr1n (le_trans (ler_norm _)) //. + rewrite -ler_sqr // ; last first. + by rewrite nnegrE // mulr_ge0 ?enorm_ge0. + by rewrite exprMn sqr_normr (le_trans (CauchySchwarz_rV _ _)) // !dotmulvv. +apply: (@le_trans _ _ (`|w *m - \S('e_2 - z2 z)|_e * `|zp1 z|_e + + (- `|zp1 z|_e ^+ 2 - `|w|_e ^+ 2))). + rewrite lerD2r (le_trans _ cauchy)//. + by rewrite mxE eqxx mulr1n. +rewrite (neg_spin z0D)// /u1 /u2. +rewrite mxE. +rewrite !sum2E/= ![in leRHS]mxE !sum2E/= ![in leRHS]mxE /=. +rewrite !mulr1 mulrN mulNr opprK mulrDl mulNr -expr2. +rewrite [in leLHS] addrCA -!addrA lerD2l mulrDl (mulNr `|w|_e). +rewrite -expr2 !addrA lerD2r !(mulrN , mulNr) opprK -mulrA. +rewrite [in leRHS](mulrC (_ / 2)) (mulrC 2^-1) -mulrDr -splitr. +by rewrite [leRHS]mulrC. +Qed. + +Lemma V1dot_eq0_p1_or_p2 (D : R) (f : R -> 'rV[R]_6) t : + f 0 \in Tilt.Upsilon1 -> + sol_is_deriv_co (fun=> phi) 0 D f -> + t \in `[0, D[%R -> + V1dot (f t) = 0 -> + f t = Tilt.point1 \/ f t = Tilt.point2. +Proof. +move => f0 fP t0d V1df. +have h : u1 f t = 0. + case: (u1 f t =P 0) => [-> // |/eqP hf]. + have := V1dot_ub f0 fP t0d. + have := u2_quadratic_form_gt0 hf. + rewrite V1df !mulNmx !mxE oppr_ge0. + move => h1 h2. + have := lt_le_trans h1 h2. + by rewrite ltxx. +have L0 : Left (f t) = 0. + apply/eqP; rewrite -enorm_eq0; apply /eqP. + have := congr1 (fun v : 'rV_2 => v ord0 ord0) h. + by rewrite !mxE/=. +have R0 : (Right (f t)) *m \S('e_2) = 0. + apply/eqP; rewrite -enorm_eq0; apply/eqP. + have := congr1 (fun v : 'rV_2 => v ord0 ord_max) h. + by rewrite !mxE/=. +rewrite -(hsubmxK (n1:=3) (f t)). +rewrite L0. +suff [-> | -> ] : Right (f t) = 0 \/ Right (f t) = (2 *: 'e_2). + left;apply /matrixP => i j;rewrite mxE. + case: splitP => // k _;by rewrite !mxE. + right;apply /matrixP => i j;rewrite mxE. + by case: splitP => // k _. +have := is_sol_state_space_tilt t0d f0 fP. +rewrite /Tilt.Upsilon1/=. +have /sub_rVP [k ->] : (Right (f t) <= ('e_2 : 'rV_3))%MS. + apply: (@submx_trans _ _ _ _ _ _ (kermx \S('e_2))). + by apply /sub_kermxP. + rewrite submxElt kernel_spin //. + by apply /negP;rewrite -enorm_eq0 enormeE;apply /negP. +rewrite -{1}(scale1r 'e_2)/= -scalerBl enormZ enormeE mulr1. +rewrite -{2}normr1. +move /eqP => hk. +rewrite eqr_norm2 in hk. +case /orP : hk. +by rewrite subr_eq addrC -subr_eq subrr => /eqP <-;rewrite scale0r;left. +by rewrite subr_eq addrC -subr_eq opprK => /eqP <-;right. +Qed. + +Lemma derive_along_V1_le0 (D : R) (f : R -> 'rV_6) : + f 0 \in Tilt.Upsilon1 -> + sol_is_deriv_co (fun=> phi) 0 D f -> + (forall t, t \in `]0, D[%R -> differentiable f t) -> + forall t, t \in `]0, D[%R -> + 'D~(f) (Tilt.V1 alpha1 gamma) t <= 0. +Proof. +move=> sol0 solP diff t t0. +have {}t0 : t \in `]0, D[ by rewrite inE. +rewrite (derive_along_V1 t0)//; last first. + move=> t1 t10D. + apply: diff => //. + by rewrite inE/= in t10D. +have /(V1dot_ub sol0 solP) : t \in `[0, D[%R. + rewrite inE in t0. + by apply: subset_itvr t0; rewrite bnd_simp. +move/le_trans; apply. +have Hquad : let u1 := \row_i [eta fun=> 0 + with 0 |-> `|(Left \o f) t|_e, + 1 |-> `|(Right \o f) t *m \S('e_2)|_e] + i in 0 <= (u1 *m u2 *m u1^T) 0 0. + set u1 := \row_i [eta fun=> 0 + with 0 |-> `|(Left \o f) t|_e, + 1 |-> `|(Right \o f) t *m \S('e_2)|_e] + i. + rewrite /=. + case: (u1 =P 0) => [->|/eqP u1_neq0]. + by rewrite !mul0mx mxE. + by rewrite ltW// u2_quadratic_form_gt0. +by rewrite -oppr_ge0 !mulNmx mxE opprK Hquad. +Qed. + +End tilt_eqn_Lyapunov. + +Section tilt_eqn_Lyapunov_global. +Local Open Scope classical_set_scope. +Context {R : realType}. +Variables alpha1 gamma : R. +Hypotheses (alpha1_gt0 : 0 < alpha1) (gamma_gt0 : 0 < gamma). +Let phi := Tilt.eqn alpha1 gamma. + +Let c1 := 2^-1 / alpha1. +Let c2 := 2^-1 / gamma. + +Local Notation Left := (@lsubmx _ 1 3 3). +Local Notation Right := (@rsubmx _ 1 3 3). + +(* todo: copy paste *) +Lemma derive_zp10 (sol : R -> 'rV_6) : + sol_is_deriv_c0y phi sol -> + 'D_1 (Left \o sol) 0 = - alpha1 *: Left (sol 0). +Proof. +move/sol_is_deriv_c0yP. +move/(_ _ (lexx 0)) => [d0 +]. +move=> /(congr1 Left). +rewrite derive1E row_mxKl => <-. +by rewrite derive_lsubmx. +Qed. + +Lemma derive_z20 (sol : R -> 'rV_6) : + sol_is_deriv_c0y phi sol -> + 'D_1 (Right \o sol) 0 = + gamma *: (Right (sol 0) - Left (sol 0)) *m \S('e_2 - Right (sol 0)) ^+ 2. +Proof. +move/sol_is_deriv_c0yP. +move /(_ _ (lexx 0)) => [d0 +]. +move => /(congr1 Right). +rewrite derive1E. +by rewrite row_mxKr => ?; rewrite derive_rsubmx. +Qed. + +Lemma V1dotE0 (sol : R -> 'rV_6) (zp1 := Left \o sol) (z2 := Right \o sol) : + sol_is_deriv_c0y phi sol -> + V1dot (sol 0) = + c1 *: (2 *: 'D_1 zp1 0 *m (Left (sol 0))^T) 0 0 + + c2 *: (2 *: 'D_1 z2 0 *m (Right (sol 0))^T) 0 0. +Proof. +move => h. +rewrite -scalemxAl mxE (scalerA c1 2) mulrAC mulVf ?pnatr_eq0// div1r. +rewrite -scalemxAl [in X in _ + X]mxE (scalerA c2 2) mulrAC. +rewrite mulVf// div1r. +rewrite derive_zp10 // -scalemxAl mxE [X in X + _](mulrA (alpha1^-1) (- alpha1)). +rewrite mulrN mulVf ?gt_eqF// mulN1r. +rewrite derive_z20 // -scalemxAl mulmxA -scalemxAl [in X in _ + X]mxE. +rewrite scalerA mulVf ?gt_eqF// scale1r. +rewrite norm_squared /V1dot. +congr +%R. +rewrite -2![in LHS]mulmxA -mulmxBr -mulmxBr -linearB/=. +rewrite -[X in (X *m (_ *m _)) 0 0 = _]trmxK. +rewrite -[X in (_ *m (X *m _)) 0 0 = _]trmxK. +rewrite mulmxA -trmx_mul -trmx_mul [LHS]mxE. +rewrite -(mulmxA (Right (sol 0) - (Left (sol 0)))) mulmxE -expr2. +rewrite tr_sqr_spin. +by rewrite mulmxA. +Qed. + +Lemma derive_along_V1_global t (sol : R -> 'rV_6) : + 0 <= t -> + sol_is_deriv_c0y phi sol -> + 'D~(sol) (Tilt.V1 alpha1 gamma) t = V1dot (sol t). +Proof. +move=> t0 tilt_eqnx. +have dif1 : forall t : R, 0 <= t -> differentiable sol t. + move => /= t' t'0. + apply/derivable1_diffP. + move/sol_is_deriv_c0yP in tilt_eqnx. + by apply tilt_eqnx. +rewrite /Tilt.V1 derive_alongD; last 3 first. + apply/differentiableM => //=. + exact/differentiable_enorm_squared/differentiable_lsubmx_comp. + apply/differentiableM => //=. + exact/differentiable_enorm_squared/differentiable_rsubmx_comp. + exact: dif1. +under [X in derive_along X _ _ + _]eq_fun do rewrite mulrC. +under [X in _ + derive_along X _ _]eq_fun do rewrite mulrC. +rewrite derive_alongMl//; last first. + exact: dif1. + exact/differentiable_enorm_squared/differentiable_lsubmx_comp. +rewrite derive_alongMl => //; last first. + exact: dif1. + exact/differentiable_enorm_squared/differentiable_rsubmx_comp. +rewrite -fctE /= !derive_along_enorm_squared//=; last 3 first. + exact: dif1. + exact/differentiable_lsubmx_comp. + exact: dif1. +move: t0; rewrite le_eqVlt => /predU1P[<-//|t0]. + by rewrite V1dotE0// !invfM. +rewrite (V1dotE alpha1_gt0 gamma_gt0 (@sol_is_deriv_c0yco _ _ _ _ tilt_eqnx (t + 1))) //. + by rewrite !invfM. +by rewrite inE/= in_itv/= (ltW t0) ltrDl; apply /andP. +Qed. + +Lemma derive_along_V1_le0_global (sol : R -> 'rV[R]_6) : + sol 0 \in Tilt.Upsilon1 -> + sol_is_deriv_c0y phi sol -> + forall t : R, 0 <= t -> + 'D~(sol) (Tilt.V1 alpha1 gamma) t <= 0. +Proof. +move=> sol0 solves. +have diff : forall (t : R), 0 <= t -> differentiable sol t. + move => /= t' t0'. + apply/derivable1_diffP. + move/sol_is_deriv_c0yP in solves. + by apply solves. +move => t t0. +rewrite derive_along_V1_global//. +have t0D : t \in `[0, t + 1[%R. + by rewrite in_itv/=t0 ltrDl ltr01. +have Hub := V1dot_ub sol0 (@sol_is_deriv_c0yco _ _ _ _ solves (t + 1)) t0D. +apply: (le_trans Hub). +have Hquad : let u1 := \row_i [eta fun=> 0 + with 0 |-> `|(Left \o sol) t|_e, + 1 |-> `|(Right \o sol) t *m \S('e_2)|_e] + i in 0 <= (u1 *m u2 *m u1^T) 0 0. + set u1 := \row_i [eta fun=> 0 + with 0 |-> `|(Left \o sol) t|_e, + 1 |-> `|(Right \o sol) t *m \S('e_2)|_e] + i. + rewrite /=. + case: (u1 =P 0) => [->|/eqP u1_neq0]. + by rewrite !mul0mx mxE. + by rewrite ltW// u2_quadratic_form_gt0. +by rewrite -oppr_ge0 !mulNmx mxE opprK Hquad. +Qed. + +End tilt_eqn_Lyapunov_global. + +Section equilibrium_zero_stable. +Context {R : realType}. +Variables gamma alpha1 : R. +Hypotheses (gamma_gt0 : 0 < gamma) (alpha1_gt0 : 0 < alpha1). +Let phi := Tilt.eqn alpha1 gamma. +Variable Init : set 'rV[R]_6. + +Lemma equilibrium_zero_stable : + Tilt.point1 \in Init -> open Init -> Init `<=` Tilt.Upsilon1 -> + is_stable_at phi Init Tilt.point1. +Proof. +move=> Init0 openInit Init_in_state. +apply: (@Lyapunov_stability R _ phi Init openInit (Tilt.V1 alpha1 gamma)). +- exact: V1_diff. +- move=> D /= f f0 sol_f t t0. + apply: (@derive_along_V1_le0 _ _ _ _ _ D f) => //. + + rewrite inE. + apply: Init_in_state. + exact/set_mem. + + move=> /= t1 t10D. + apply/derivable1_diffP. + apply sol_f. + by apply: subset_itvr t10D; rewrite bnd_simp. +- have := V1_is_Lyapunov_candidate alpha1_gt0 gamma_gt0. + rewrite /is_Lyapunov_candidate /Tilt.point1 => H. + rewrite /Tilt.V1 lsubmx_const rsubmx_const; split => //. + + by rewrite !expr2 !enorm0 !mulr0 !mul0r add0r. + + move=> z zInit z_neq0. + case: H => // _ _. + by apply => //; rewrite in_setT. +Qed. + +End equilibrium_zero_stable. diff --git a/tilt_mathcomp.v b/tilt_mathcomp.v new file mode 100644 index 00000000..ff7855a9 --- /dev/null +++ b/tilt_mathcomp.v @@ -0,0 +1,29 @@ +From mathcomp Require Import all_boot all_order all_algebra ring. +Require Import ssr_ext euclidean rigid frame skew. + +(**md**************************************************************************) +(* # Additions to the MathComp library *) +(* *) +(******************************************************************************) + +Set Implicit Arguments. +Unset Strict Implicit. +Unset Printing Implicit Defensive. + +Import Order.TTheory GRing.Theory Num.Def Num.Theory. +Local Open Scope ring_scope. + +Lemma sqr_inj {R : rcfType} : {in Num.nneg &, injective (fun x : R => x ^+ 2)}. +Proof. +by move=> x y x0 y0 /(congr1 (@Num.sqrt R)); rewrite !sqrtr_sqr! ger0_norm. +Qed. + +Lemma gerN {R : numDomainType} (x : R) : 0 <= x -> - x <= x. +Proof. by move=> x0; rewrite ge0_cp. Qed. + +Definition And31 (P1 P2 P3 : Prop) (a : [/\ P1, P2 & P3]) := + let: And3 p1 p2 p3 := a in p1. +Definition And32 (P1 P2 P3 : Prop) (a : [/\ P1, P2 & P3]) := + let: And3 p1 p2 p3 := a in p2. +Definition And33 (P1 P2 P3 : Prop) (a : [/\ P1, P2 & P3]) := + let: And3 p1 p2 p3 := a in p3. diff --git a/tilt_robot.v b/tilt_robot.v new file mode 100644 index 00000000..87258bfb --- /dev/null +++ b/tilt_robot.v @@ -0,0 +1,453 @@ +From HB Require Import structures. +From mathcomp Require Import all_boot all_order all_algebra ring. +From mathcomp Require Import interval_inference. +From mathcomp Require Import boolp classical_sets functions reals. +From mathcomp Require Import topology normedtype derive realfun. +Require Import ssr_ext euclidean rigid frame skew derive_matrix tilt_analysis. + +(**md**************************************************************************) +(* # Additions to the RobotRocq library *) +(* *) +(******************************************************************************) + +Set Implicit Arguments. +Unset Strict Implicit. +Unset Printing Implicit Defensive. + +Import Order.TTheory GRing.Theory Num.Def Num.Theory. +Import numFieldNormedType.Exports. +Local Open Scope ring_scope. + +(* see Appendix VII.A of + https://hal.science/hal-04271257v1/file/benallegue2019tac_October_2022.pdf *) +Section basic_facts. +Variable K : realType. + +Lemma fact212 (v w : 'rV[K]_3) : \S(v) * \S(w) = w^T *m v - (v *m w^T)``_0 *: 1. +Proof. +apply/matrix3P/and9P; split; apply/eqP; rewrite !(mxE,sum3E,spinij,sum1E); Simp.r. + ring. +by rewrite mulrC. +by rewrite mulrC. +by rewrite mulrC. +by rewrite !opprD; ring. +by rewrite mulrC. +by rewrite mulrC. +by rewrite mulrC. +by rewrite !opprD; ring. +Qed. + +Lemma fact213 (v w : 'rV[K]_3) : \S(v) * \S(w) * \S(v) = - (v *m w^T) ``_0 *: \S(v). +Proof. +rewrite fact212 mulrBl -mulmxE -mulmxA; have: v *m \S(v) = 0. + apply: trmx_inj. + by rewrite trmx_mul tr_spin mulNmx spin_mul_tr trmx0 oppr0. +move => ->. +by rewrite mulmx0 sub0r -mul_scalar_mx -mulNmx; congr (_ *m _); rewrite scalemx1 rmorphN. +Qed. + +Lemma fact215 ( v w : 'rV[K]_3) : \S(w *m \S(v)) = \S(w) * \S(v) - \S(v) * \S(w). +Proof. +by rewrite spinE spin_crossmul. +Qed. + +Lemma fact216 (v w : 'rV[K]_3): \S(w *m \S(v)) = v^T *m w - w^T *m v. +Proof. +by rewrite fact215 !fact212 -!/(_ *d _) dotmulC opprB addrA subrK. +Qed. +Lemma fact217 (v : 'rV[K]_3): \S(v) ^+ 3 = - (`|v|_e ^+2) *: \S(v). + exact: spin3. +Qed. + +Lemma fact214 (M : 'M[K]_3) (v_ : seq 'rV[K]_3) : M \is 'SO[K]_3 -> + M^T * (\prod_(i <- v_) \S( i )) * M = (\prod_(i <- v_) \S(i *m M)). +Proof. +move=> MSO. +elim/big_ind2 : _ => //. + by rewrite -!mulmxE mulmx1 rotation_tr_mul. +- move => a b c d H1 H2. + rewrite -H1 // -H2 // -!mulmxE -!rotation_inv // !mulmxA -[M^-1 *m b *m M *m M^-1]mulmxA. + rewrite mulmxV; last first. + rewrite unitmxE. + apply: orthogonal_unit. + exact: rotation_sub. + by rewrite -[M^-1 *m b *m 1%:M *m d]mulmxA mul1mx. +- move => i true. + exact: spin_similarity. +Qed. + +End basic_facts. + +(* spin and matrix/norm properties *) + +Lemma tr_sqr_spin {R : realFieldType} (u : 'rV[R]_3) : + (\S(u) ^+ 2)^T = \S(u) ^+ 2. +Proof. by apply/esym/eqP; rewrite -symE; exact: sqr_spin_is_sym. Qed. + +Lemma mul_tr_spin {R : comNzRingType} (u : 'rV[R]_3) : u *m \S(u)^T = 0. +Proof. by apply: trmx_inj; rewrite trmx_mul trmxK spin_mul_tr trmx0. Qed. + +Lemma norm_spin {R : rcfType} (u : 'rV[R]_3) (v : 'rV[R]_3) : + (u *m \S(v - u) ^+ 2 *m (u)^T) 0 0 = - `|u *m \S(v)|_e ^+ 2. +Proof. +rewrite spinD spinN -tr_spin mulmxA !mulmxDr mulmxDl !mul_tr_spin !addr0. +rewrite -dotmulvv /dotmul trmx_mul. +rewrite mxE [X in _ + X = _](_ : _ = 0) ?addr0; last first. + by rewrite tr_spin -mulmxA mulNmx spin_mul_tr mulmxN mulmx0 oppr0 mxE. +by rewrite tr_spin mulNmx mulmxN [in RHS]mxE opprK mulmxA. +Qed. + +Lemma sqr_spin {R : rcfType} (u : 'rV[R]_3) (norm_u1 : `|u|_e = 1) : + \S(u) *m \S(u) = u^T *m u - 1%:M. +Proof. +have sqrspin : \S(u) ^+ 2 = u^T *m u - (`|u|_e ^+ 2)%:A by rewrite sqr_spin. +rewrite expr2 norm_u1 expr2 mulr1 in sqrspin. +rewrite mulmxE sqrspin. + apply/matrixP => i j ; rewrite mxE /= [in RHS]mxE /=. + congr (_+_); rewrite mxE mxE /= mul1r. + by rewrite [in RHS]mxE [in RHS]mxE /= -mulNrn mxE -mulNrn. +Qed. + +Lemma CauchySchwarz_rV {R : rcfType} {n : nat} (a b : 'rV[R]_n) : + (a *d b) ^+ 2 <= (a *d a) * (b *d b). +Proof. +suffices: 0 <= (b *d b) * (a *d a) - (a *d b) ^+ 2. + rewrite subr_ge0. + by rewrite mulrC. +rewrite subr_ge0 expr2 mulrC !dotmulvv /= -expr2. +have [->|hb] := eqVneq b 0. + rewrite dotmulv0 expr0n. + rewrite enorm0. + by rewrite expr0n mul0r. +pose t := (a *d b) / (`|b|_e ^+ 2). +have h : 0 <= `|a - t *: b|_e ^+ 2. + by rewrite exprn_ge0// enorm_ge0. +rewrite -(dotmulvv (a - t *: b)) in h. +rewrite dotmulBl dotmulBr dotmulvv in h. +rewrite dotmulvZ in h. +rewrite -dotmulvv in h. +rewrite /t in h. +have h1 : 0 <= a *d a - (a *d b) ^+ 2 / `|b|_e ^+ 2. + move: h. + rewrite dotmulBr dotmulvZ. + rewrite (dotmulC ((a *d b / `|b|_e ^+ 2) *: b) a). + rewrite dotmulvZ dotmulC dotmulvv /t expr2 -!expr2 dotmulZv dotmulvv. + rewrite divfK /=; last first. + by rewrite sqrf_eq0 enorm_eq0. + by rewrite subrr subr0 !expr2 mulrAC. +have h2 : 0 <= `|b|_e ^+ 2 * (a *d a) - (a *d b) ^+ 2. + have pos: 0 < `|b|_e ^+ 2. + by rewrite exprn_gt0// enorm_gt0. + suff: `|b|_e ^+ 2 * (a *d a - (a *d b) ^+ 2 / `|b|_e ^+ 2) = + `|b|_e ^+ 2 * (a *d a) - (a *d b) ^+ 2. + move=> eq_step. + rewrite -eq_step. + by apply: mulr_ge0; [rewrite ltW | exact h1]. + rewrite mulrBr. + congr (_ - _)%R. + by rewrite mulrCA divff ?mulr1// sqrf_eq0 enorm_eq0. +rewrite -subr_ge0 mulrC. +by rewrite dotmulvv mulrC in h2. +Qed. + +(* not used *) +Lemma Young_inequality_rV {R : rcfType} {n : nat} (a b : 'rV[R]_n) : + (a *d b) <= (2^-1 * (`|a|_e) ^+ 2) + (2^-1 * `|b|_e ^+ 2). +Proof. +have normage0 : 0 <= `|a|_e ^+ 2 by rewrite sqr_ge0. +have normbge0 : 0 <= `|b|_e ^+ 2 by rewrite sqr_ge0. +rewrite -!dotmulvv. +have: 0 <= `|a - b|_e ^+ 2 by rewrite sqr_ge0. +rewrite -dotmulvv dotmulD !dotmulvv. +move => h. +rewrite -mulr_natl in h. +have h2 : 2 * (a *d b) <= `|a|_e ^+ 2 + `|- b|_e ^+ 2. + rewrite -subr_ge0. + rewrite dotmulvN mulrN in h. + by rewrite addrAC. +rewrite -ler_pdivlMl// in h2. +rewrite -mulrDr. +by rewrite enormN in h2. +Qed. + +Lemma dotmulspin1 {R : numFieldType} (u : 'rV[R]_3) (v : 'rV[R]_3) : + (u *m \S(v)) *d v = 0. +Proof. +apply/eqP. +rewrite dotmulC dotmul_trmx -normalvv normal_sym mul_tr_spin normalvv. +by rewrite dotmulv0. +Qed. + +Lemma dotmulspin2 {R : numFieldType} (u : 'rV[R]_3) (v : 'rV[R]_3) : + (u *m \S(v)) *d u = 0. +Proof. +apply/eqP. +rewrite -normalvv normal_sym spinE -normalmN (@lieC _ (vec3 R)) /= opprK. +by rewrite crossmul_normal. +Qed. + +Lemma ortho_spin {R : numFieldType} (u : 'rV[R]_3) (v : 'rV[R]_3) : + (u - v) *d (v *m \S(u))= 0. +Proof. by rewrite dotmulBl dotmulC dotmulspin1 dotmulC dotmulspin2 subr0. Qed. + +Lemma norm_squared {R : rcfType} n (u : 'rV[R]_n) : + (u *m u^T) 0 0 = `|u|_e ^+ 2. +Proof. by rewrite -dotmulvv /dotmul. Qed. + +Global Instance is_diff_rsubmx {R : realFieldType} {V : normedModType R} {n1 n2} + (f df : V -> 'rV[R]_(n1 + n2)) t : + is_diff t f df -> + is_diff t (fun x => rsubmx (f x)) (fun x => rsubmx (df x)). +Proof. +case=> diff_f dfE. +apply: DiffDef. + by apply: differentiable_comp => //; exact: differentiable_rsubmx. +apply/funext => v. +rewrite -dfE. +rewrite -[LHS]deriveE; last first. + by apply: differentiable_comp => //; exact: differentiable_rsubmx. +rewrite -[in RHS]deriveE; last first. + by []. +rewrite derive_rsubmx//. +by apply: diff_derivable. +Qed. + +(*Global Instance is_diff_lsubmx {R : realFieldType} {V : normedModType R} {n1 n2} + (f df : V -> 'rV[R]_(n1 + n2)) t : + is_diff t f df -> + is_diff t (fun x => lsubmx (f x)) (fun x => lsubmx (df x)). +Proof. +case=> diff_f dfE. +apply: DiffDef. + by apply: differentiable_comp => //; exact: differentiable_lsubmx0. +apply/funext => v. +rewrite -dfE. +rewrite -[LHS]deriveE; last first. + by apply: differentiable_comp => //; exact: differentiable_lsubmx0. +rewrite -[in RHS]deriveE; last first. + by []. +rewrite derive_lsubmx//. +Abort.*) + +Lemma derivable_row_mx {R : realFieldType} {n1 n2 : nat} + (f : R -> 'rV[R]_n1) (g : R -> 'rV[R]_n2) t v : + (forall x, derivable f x v) -> (forall x, derivable g x v) -> + derivable (fun x : R => row_mx (f x) (g x)) t v. +Proof. +move=> /= fv gv; apply/derivable_mxP => i j. +rewrite (ord1 i)/=. +have /cvg_ex[/= l Hl]:= fv t. +have /cvg_ex[/= k Hk]:= gv t. +apply/cvg_ex => /=; exists (row_mx l k)``_j. +apply/cvgrPdist_le => /= e e0. +move/cvgrPdist_le : Hl => /(_ _ e0) Hl. +move/cvgrPdist_le : Hk => /(_ _ e0) Hk. +move: Hl Hk; apply: filterS2 => x Hl Hk. +rewrite !mxE. +case: fintype.splitP => j1 jj1. + apply: le_trans Hl. + rewrite [in leRHS]/Num.Def.normr/= mx_normrE. + apply: le_trans; last first. + exact: (le_bigmax _ _ (ord0, j1)). + by rewrite !mxE/=. +apply: le_trans Hk. +rewrite [in leRHS]/Num.Def.normr/= mx_normrE. +apply: le_trans; last first. + exact: (le_bigmax _ _ (ord0, j1)). +by rewrite !mxE/=. +Qed. + +Lemma derive_row_mx {R : realFieldType} {n1 n2 : nat} + (f : R -> 'rV[R]_n1) (g : R -> 'rV[R]_n2) t v : + (forall x : R, derivable f x v) -> + (forall x : R, derivable g x v) -> + 'D_v (fun x => row_mx (f x) (g x)) t = row_mx ('D_v f t) ('D_v g t). +Proof. +move=> fv gv. +apply/matrixP => i j. +rewrite [in LHS]derive_mx ?mxE//=; last first. + by apply: derivable_row_mx; [exact: fv|exact: gv]. +do 2 rewrite derive_mx ?mxE//=. +case: fintype.split_ordP => /= j1 jj1; rewrite !mxE; congr ('D_v _ t). + apply/funext => x; rewrite !mxE. + case: fintype.split_ordP => k jE. + congr (f x i _). + move: jE. + by rewrite jj1 => /(congr1 val) => /= /val_inj. + move: jE. + rewrite jj1 => /(congr1 val)/=. + have /[swap] -> := ltn_ord j1. + by rewrite ltnNge/= leq_addr. +apply/funext => x; rewrite !mxE. +case: fintype.split_ordP => k jE. + move: jE. + rewrite jj1 => /(congr1 val)/=. + have /[swap] <- := ltn_ord k. + by rewrite ltnNge/= leq_addr. +congr (g x i _). +move: jE. +rewrite jj1 => /(congr1 val) => /= /eqP. +by rewrite eqn_add2l => /eqP /val_inj. +Qed. + +Lemma char_poly2 (R : numFieldType) (M : 'M[R]_2) : + char_poly M = 'X^2 - (\tr M)%:P * 'X + (\det M)%:P. +Proof. +set P := (RHS). +apply/polyP => -[|[|[|i]]]; last first. +- have := (rwP (leq_sizeP (char_poly M) i.+3)).2. + rewrite size_char_poly => /(_ erefl) /(_ i.+3) => ->//. + rewrite (rwP (leq_sizeP P i.+3)).2//. + rewrite /P -addrA size_polyDl ?size_polyXn//. + rewrite -mulNr size_MXaddC; case: ifPn => // _. + by rewrite ltnS -polyCN size_polyC; case: (_ == _). +- rewrite /P -[in RHS]addrA [RHS]coefD coefXn/= coefD -mulrN coefCM coefC/= coefN coefX/= oppr0 mulr0 !addr0. + rewrite /char_poly det_mx22//. + rewrite /char_poly_mx !mxE/= mulr1n mulr0n sub0r mulNr opprK sub0r mulrN. + rewrite coefD coefN coefCM coefC/= mulr0 subr0. + by rewrite coefM sum3E !coefE/= !(subr0,mul0r,mulr0,addr0,mulr1,add0r). +- rewrite char_poly_trace//. + by rewrite /P -addrA addrCA !coefD coefN coefCM coefX/= mulr1 coefC/= addr0 coefXn addr0. +- rewrite char_poly_det sqrrN expr1n mul1r. + by rewrite /P !coefD coefC/= coefN coefCM coefX mulr0 subr0 coefXn/= add0r. +Qed. + +Lemma differentiable_enorm {K : realType} m n (f : 'rV[K]_m -> 'rV_n) + (g : K -> 'rV[K]_m) t : + differentiable f (g t) -> f (g t) != 0 -> + differentiable (fun x => `|f x|_e) (g t) . +Proof. +move=> fgt fgt0; rewrite /enorm -fctE. +apply: differentiable_comp. + exact: differentiable_dotmul. +apply/derivable1_diffP/derivable_sqrt. +by rewrite dotmulvv expr2 mulr_gt0 //= !enorm_gt0. +Qed. + +Lemma mxnorm_enorm_le {K : realType} {n} (x : 'rV[K]_n) : `|x| <= `|x|_e. +Proof. +rewrite /Num.norm/=mx_normrE. +apply/bigmax_leP; split. + exact: enorm_ge0. +move=> /= [i j] _ /=. +rewrite {i}ord1. +rewrite -sqrtr_sqr. +rewrite /enorm dotmulvv sqr_enorm. +rewrite ler_sqrt; last by apply sumr_ge0 => k _;apply sqr_ge0. +rewrite (bigD1 j) //=. +rewrite lerDl. +by apply sumr_ge0 => k _;apply sqr_ge0. +Qed. + +Lemma continuous_enorm {K : realType} {n : nat} : + continuous (fun u : 'rV[K]_n => `|u|_e). +Proof. +move=> /= x. +rewrite /enorm/=. +apply/continuous_comp=>/=. + apply: differentiable_continuous. + under eq_fun do rewrite dotmulvv sqr_enorm. + rewrite /=. + have <- : \sum_(i < n) (fun x0 : 'rV[K]_n => x0``_i ^+ 2) = + (fun x0 : 'rV[K]_n => \sum_(i < n) x0``_i ^+ 2). + apply funext => x0 /=. + exact: (big_morph (fun f : 'rV[K]_n -> K => f x0)). + apply: differentiable_sum. + move => i. + have -> : (fun x0 : 'rV[K]_n => x0``_i ^+ 2) = + (fun x0 : 'rV_n => x0``_i ) ^+2 by []. + apply: differentiableX. + exact: differentiable_coord. +exact: sqrt_continuous. +Qed. + +Lemma derivable_enorm_squared {K : realType} n (f : K -> 'rV[K]_n) (x0 : K) : + derivable f x0 1 -> + derivable (fun x => `|f x|_e ^+ 2) x0 1. +Proof. +move => dif1. +apply/diff_derivable. +rewrite /=. +under eq_fun do rewrite -dotmulvv dotmulE. +have -> : (fun x : K => \sum_k (f x)``_k * (f x)``_k) = + \sum_k (fun x => (f x)``_k * (f x)``_k ). + apply/funext => x => //=. + by rewrite fct_sumE. +apply/differentiable_sum => k => //=. +apply/differentiableM => //=. + apply/derivable1_diffP. + by apply/derivable_coord => //. +apply/derivable1_diffP. +by apply/derivable_coord => //. +Qed. + +Lemma derive_enorm_squared {K : realType} n (u : K -> 'rV[K]_n) (t : K) : + derivable u t 1 -> + 'D_1 (fun x => `|u x|_e ^+ 2) t = 2 * ('D_1 u t *d u t). +Proof. +move=> ut1. +under eq_fun do rewrite -dotmulvv. +rewrite derive_dotmul// dotmulC. +by field. +Qed. + +Lemma differentiable_enorm_squared {R : rcfType} m n + (f : 'rV[R]_m -> 'rV[R]_n) (v : 'rV[R]_m) : + differentiable f v -> + differentiable (fun x => `|f x|_e ^+ 2) v. +Proof. +move=> dif1. +under eq_fun do rewrite -dotmulvv. +exact: differentiable_dotmul. +Qed. + +Lemma spin_le_norm {K : rcfType} (x : 'rV[K]_3) : `|\S(x)| <= `|x|. +Proof. +rewrite {1}/Num.norm/= !mx_normrE. +apply: bigmax_le; first exact: normr_ge0. +move=> /= [i j] _/=. +by have [->|->|->] := I3_cases i; have [->|->|->] := I3_cases j; + rewrite ?(spinij,normr0,normrN)// /Num.norm/= mx_normrE; + exact: (le_bigmax _ _ (0, _)). +Qed. + +Lemma spin_sq_norm_bound {K : rcfType} (x : 'rV[K]_3) : `|\S(x) ^+ 2| <= 3 * `|x|^+2. +Proof. +rewrite (le_trans (mx_norm_sq_le _))// ler_pM//. +suff h : `|\S(x)| <= `|x| by apply: ler_pM. +exact: spin_le_norm. +Qed. + +Lemma spin_sq_dist_bound {K : rcfType} (x y: 'rV[K]_3) : + `|\S(x)^+2 - \S(y)^+2| <= 3 * (`|x| +`|y|) * `|x-y|. +Proof. +have -> : \S(x) ^+ 2 - \S(y) ^+ 2 = \S(x) *m (\S(x) - \S(y)) + (\S(x) - \S(y)) *m \S(y). + by rewrite mulmxBr mulmxBl addrA subrK. +rewrite mulrDr mulrDl. +apply: (le_trans (ler_normD _ _)). +rewrite -spinN -spinD. +apply: lerD. + apply: (le_trans (mx_norm_mul _ _)). + apply : ler_pM => //. + apply : ler_pM => //. + exact: spin_le_norm. + exact: spin_le_norm. +rewrite -mulrA (mulrC `|y|) mulrA. +rewrite (le_trans (mx_norm_mul _ _))//. +rewrite ler_pM//. + by rewrite ler_pM// spin_le_norm. +exact: spin_le_norm. +Qed. + +Lemma enorm_mxnorm {K : rcfType} {n} (x : 'rV[K]_n.+1) : + `|x|_e ^+ 2 <= n.+1%:R * `|x| ^ 2. +Proof. +rewrite sqr_enorm /=. +apply : (@le_trans _ _ (\sum_(i0 < n.+1) `|x| ^+ 2)). + apply: ler_sum => k _. + rewrite -sqr_normr. + suff h : `|x ord0 k| <= `|x| by exact: ler_pM. + rewrite {2}/Num.norm/= !mx_normrE /=. + exact: (le_bigmax _ _ (ord0, k)). +by rewrite big_const_ord mulr_natl iter_addr_0. +Qed. diff --git a/tilt_stability.v b/tilt_stability.v new file mode 100644 index 00000000..e750dc30 --- /dev/null +++ b/tilt_stability.v @@ -0,0 +1,712 @@ +From HB Require Import structures. +From mathcomp Require Import all_boot all_order all_algebra ring. +From mathcomp Require Import interval_inference. +From mathcomp Require Import boolp classical_sets functions filter reals. +From mathcomp Require Import topology prodnormedzmodule normedtype landau. +From mathcomp Require Import sequences derive realfun. +Require Import ssr_ext euclidean rigid frame skew derive_matrix. +Require Import tilt_mathcomp tilt_analysis tilt_robot ode. + +(**md**************************************************************************) +(* # Elements of stability theory *) +(* *) +(* This file provides elements of stability theory including a proof of *) +(* Lyapunov's stability theorem. *) +(* *) +(* ``` *) +(* posdefmx M == M is definite positive *) +(* is_Lyapunov_candidate V D x := x is in D, V x = 0, and V is positive *) +(* everywhere in D except at x *) +(* 'D~(f) V == derivative of V along the solution f *) +(* is_equilibrium_point phi Init x := x is in Init and cst x satisfies *) +(* sol_is_deriv_co phi *) +(* state_space phi Init == the set points attainable by a solution *) +(* of the autonomous ODE phi starting from *) +(* Init *) +(* is_stable_at f V x == Lyapunov stability *) +(* is_global_time_stable_at f V x == TODO *) +(* ``` *) +(* *) +(* Reference: *) +(* - Hassan K. Khalil, Nonlinear systems, 2002 *) +(******************************************************************************) + +Reserved Notation "''D~(' f ) V" (at level 10, f, V at next level, + format "''D~(' f ) V"). + +Set Implicit Arguments. +Unset Strict Implicit. +Unset Printing Implicit Defensive. + +Import Order.TTheory GRing.Theory Num.Def Num.Theory. +Import numFieldNormedType.Exports. + +Local Open Scope ring_scope. + +Definition posdefmx {R : realType} m (M : 'M[R]_m) : Prop := + M \is sym m R /\ forall a, eigenvalue M a -> a > 0. + +Local Open Scope classical_set_scope. + +Section locdef. +Context {R : realType} {U : normedModType R}. +Implicit Types V : U -> R. + +Definition is_Lyapunov_candidate V (A : set U) (x : U) := + [/\ x \in A, V x = 0 & forall z, z \in A -> z != x -> V z > 0]. + +Definition locnegdef V (x : U) := V x = 0 /\ \forall z \near x^', V z < 0. + +(* locally negative semidefinite *) +Definition locnegsemidef V (x : U) := V x = 0 /\ \forall z \near x^', V z <= 0. + +End locdef. + +(* derivation along the solution f, see Khalil p.114 *) +(* NB: we are not representing the initial state at t = 0 of the solution f *) +Definition derive_along {R : numFieldType} {n} (U := 'rV[R]_n) (V : U -> R) + (f : R -> U) t := + (jacobian1 V (f t))^T *d 'D_1 f t. + +Notation "''D~(' f ) V" := (derive_along V f). + +Section derive_along. +Context {R : realType} {n : nat}. +Variable f : R -> 'rV[R]_n. + +Lemma derive_along_derive (U := 'rV[R]_n) (V : U -> R) (t : R) : + differentiable V (f t) -> differentiable f t -> + 'D~(f) V t = 'D_1 (V \o f) t. +Proof. +move=> difV difsol. +rewrite /derive_along/=. +rewrite /jacobian1. +rewrite /jacobian. +rewrite /dotmul. +rewrite -trmx_mul. +rewrite mul_rV_lin1. +rewrite mxE. +rewrite -deriveE=> /=; last first. + apply: differentiable_comp => //. + exact/differentiable_scalar_mx. +rewrite derive_mx /=; last first. + apply: derivable_scalar_mx => //. + exact: diff_derivable. +rewrite mxE. +rewrite [in RHS]deriveE/=; last first. + exact: differentiable_comp. +rewrite [in RHS]diff_comp//=. +do 2 (rewrite -[in RHS]deriveE; last by []). +by under eq_fun do rewrite mxE /= mulr1n /=. +Qed. + +Lemma derive_alongMl (V : 'rV_n -> R) (k : R) t : + differentiable V (f t) -> differentiable f t -> + 'D~(f) (k *: V) t = k *: 'D~(f) V t. +Proof. +move=> dfx dpx. +rewrite derive_along_derive; last 2 first. + exact: differentiable_comp. + by []. +rewrite deriveZ/=; last first. + apply: diff_derivable => /=. + rewrite -fctE. + exact: differentiable_comp. +congr (_ *: _). +by rewrite derive_along_derive. +Qed. + +Lemma derive_alongD (V1 V2 : 'rV_n -> R) t : + differentiable V1 (f t) -> differentiable V2 (f t) -> + differentiable f t -> + 'D~(f) (V1 + V2) t = 'D~(f) V1 t + 'D~(f) V2 t. +Proof. +move=> dfV1 dfV2 dfsol. +rewrite derive_along_derive; last 2 first. + exact: differentiableD. + by []. +rewrite deriveD/=; last 2 first. + apply: diff_derivable => //. + rewrite -fctE. + exact: differentiable_comp. + apply: diff_derivable => //. + rewrite -fctE. + exact: differentiable_comp. +rewrite derive_along_derive; [|by []..]. +by rewrite derive_along_derive. +Qed. + +Lemma derivative_derive_along_eq0 (V : 'rV_n -> R) (t : R) : + differentiable V (f t) -> + 'D_1 f t = 0 -> 'D~(f) V t = 0. +Proof. +move=> df dsol0. +rewrite /derive_along /jacobian1 /dotmul dotmulP /dotmul -trmx_mul. +by rewrite dsol0 mul0mx !mxE. +Qed. + +Lemma derive_along_enorm_squared m (V : 'rV[R]_n -> 'rV[R]_m) (t : R) : + differentiable V (f t) -> + differentiable f t -> + 'D~(f) (fun y => `|V y|_e ^+ 2) t = + (2 *: 'D_1 (V \o f) t *m (V (f t))^T) 0 0. +Proof. +move=> difff diffphi. +rewrite derive_along_derive//; last exact: differentiable_enorm_squared. +rewrite fctE derive_enorm_squared //=; last first. + by apply: diff_derivable=> //=; exact: differentiable_comp. +by rewrite mulrDl mul1r scalerDl scale1r mulmxDl [in RHS]mxE. +Qed. + +End derive_along. + +(* NB: not used, can be shown to be equivalent to derive_along *) +Definition derive_along_partial {R : realType} n (V : 'rV[R]_n -> R) + (a : R -> 'rV[R]_n) (t : R) : R := + \sum_(i < n) (partial V (a t) i * ('D_1 a t) ``_ i). + +Section ode. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n. +Variable phi : U -> U. + +Lemma sol_is_deriv_c0oP (D : R) (f : R -> U) (e : {posnum R}) : + is_sol_oo (fun=> phi) (f (- e%:num)) (- e%:num) D f -> + sol_is_deriv_co (fun=> phi) 0 D f. +Proof. +move=> [_ H cf] t t0D; apply H; rewrite inE/=; apply: subset_itv t0D => //. +by rewrite bnd_simp. +Qed. + +(* "global" solution *) +Definition sol_is_deriv_c0y (f : R -> U) := + sol_is_deriv_cbnd (fun=> phi) 0 (BInfty R false) f. + +(* TODO: generalize this lemma *) +Lemma sol_is_deriv_c0yP (f : R -> U) : sol_is_deriv_c0y f <-> + forall t, t >= 0 -> derivable f t 1 /\ f^`() t = phi (f t). +Proof. +split=> H t t0oo; apply: H. + by rewrite in_itv/= andbT. +by move: t0oo; rewrite in_itv/= andbT. +Qed. + +Lemma sol_is_deriv_c0yco f : sol_is_deriv_c0y f -> + forall D, sol_is_deriv_co (fun=> phi) 0 D f. +Proof. +move=> + D t t0D. +apply. +by move: t0D; rewrite !in_itv/= => /andP[->]. +Qed. + +End ode. + +Section state_space. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n. +Variable phi : U -> U. + +Definition state_space (Init : set U) : set U := + [set x | exists f D, [/\ f 0 \in Init, sol_is_deriv_co (fun=> phi) 0 D f & + exists2 t, t \in `[0, D[%R & x = f t]]. + +End state_space. + +Section equilibrium_point. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n. +Variable phi : U -> U. + +Definition is_equilibrium_point (x : U) := + sol_is_deriv_cy (fun=> phi) 0 (cst x). + +(* Lemma equilibrium_point_in_state_space (Init : set U) : *) +(* is_equilibrium_point Init `<=` state_space phi Init. *) +(* Proof. *) +(* move=> x solf; exists (cst x), 1; split => //=. *) +(* apply: sol_is_deriv_cy_co. *) +(* by exists 0 => //; rewrite bound_itvE. *) +(* Qed. *) + +Definition equilibrium_points Init := [set p | Init p /\ is_equilibrium_point p]. + +Lemma equilibrium_points_subset (A B : set U) : A `<=` B -> + equilibrium_points A `<=` equilibrium_points B. +Proof. +move=> AB x. +rewrite /equilibrium_points/= /is_equilibrium_point. +move => [Ax H]. +split => //. +by apply AB. +Qed. + +End equilibrium_point. + +Section stability. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n. +Variable phi : U -> U. +Variable Init : set U. + +Definition is_stable_at (x : U) := + forall eps, eps > 0 -> exists2 d, d > 0 & + forall f D, f 0 \in Init -> sol_is_deriv_co (fun=> phi) 0 D f -> + `| f 0 - x | < d -> forall t, t \in `[0, D[%R -> `| f t - x | < eps. + +(* assuming solution exists for all time *) +Definition is_global_time_stable_at (x : U) := + forall eps, eps > 0 -> exists2 d, d > 0 & + forall f, f 0 \in Init -> sol_is_deriv_c0y phi f -> + `| f 0 - x | < d -> forall t, 0 <= t -> `| f t - x | < eps. + +Lemma stable_global_time : is_stable_at `<=` is_global_time_stable_at. +Proof. +move=> x H e /H [d d0 stable]. +exists d => // z0 z0Init zglob zd /= t t0. +apply: (stable _ (t + 1)) => //. + exact: sol_is_deriv_c0yco. +by rewrite in_itv/= t0/= ltrDl. +Qed. + +Definition is_asymptotically_stable_at (x : U) (f : R -> U) : Prop := + exists2 d, d > 0 & `| f 0 - x | < d -> f t @[t --> +oo] --> x. + +End stability. + +Section about_Lyapunov_function. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n.+1. +Variable phi : U -> U. +Variable D : R. +Variable f : R -> U. +Hypothesis derivable_f : {in `[0, D[%R, forall t, derivable f t 1}. + +Variable V : U -> R. +Hypothesis Vdiff : forall t : U, differentiable V t. +Hypothesis DV_le0 : forall t, t \in `]0, D[%R -> 'D~(f) V t <= 0. + +Lemma V_nincr a b : b < D -> 0 <= a <= b -> V (f b) <= V (f a). +Proof. +move=> bD /andP[a_ge0 ab]. +apply: (@ler0_derive1_le_cc _ (V \o f) 0 b) => //=. +- move=> y yb. + apply/diff_derivable/differentiable_comp; last exact: differentiable_comp. + rewrite -derivable1_diffP; apply: derivable_f. + by apply: subset_itv yb; rewrite bnd_simp// ltW. +- move=> y yb. + rewrite derive1E -derive_along_derive//. + + apply: DV_le0. + by apply: subset_itvl yb; rewrite bnd_simp ltW. + + rewrite -derivable1_diffP; apply: derivable_f. + by apply: subset_itv yb; rewrite bnd_simp// ltW. +- (* `[0, b] *) + have [b0|] := ltP 0 b; last first. + move=> b0. + have -> : b = 0 by apply/eqP; rewrite eq_le b0 (le_trans a_ge0). + rewrite set_itv1. + exact: continuous_subspace1. + apply/continuous_within_itvP => //; split. + + move=> z z0b. + apply: continuous_comp; last exact: differentiable_continuous. + apply: differentiable_continuous => //. + rewrite -derivable1_diffP; apply: derivable_f. + by apply: subset_itv z0b; rewrite bnd_simp// ltW. + + have d0 : 0 < D by exact/lt_trans/bD. + have cont : {in `[0, D[%R, continuous f}. + move=> t t0D. + apply: differentiable_continuous. + exact/derivable1_diffP/derivable_f. + apply: cvg_comp. + apply: cvg_at_right_filter. + apply: cont. + by rewrite bound_itvE. + exact: (differentiable_continuous (Vdiff (f 0))). + + apply: cvg_at_left_filter. + apply: differentiable_continuous => //. + apply: differentiable_comp. + rewrite -derivable1_diffP; apply: derivable_f. + by rewrite in_itv/= (ltW b0)// bDelta. + exact: Vdiff. +- by rewrite bound_itvE (le_trans a_ge0). +- by rewrite in_itv/= ab andbT. +Qed. + +End about_Lyapunov_function. + +(* TODO: move *) +Section sphere. +Context {R : realType} {n : nat}. +Local Open Scope classical_set_scope. + +Definition sphere r := [set x : 'rV[R]_n | `|x| = r]. + +Lemma sphere_nonempty r : n != 0 -> 0 < r -> sphere r !=set0. +Proof. +move=> n0 r_gt0. +rewrite /sphere. +exists (const_mx r). +rewrite /sphere /= /normr/=. +(* TODO: need lemma? *) +rewrite mx_normrE/=. +apply/eqP; rewrite eq_le; apply/andP; split. + apply: bigmax_le. + exact: ltW. + by move=> i _; rewrite mxE gtr0_norm. +under eq_bigr do rewrite mxE gtr0_norm//. +apply/le_bigmax => /=. +destruct n as [|n'] => //. +exact: (ord0, ord0). +Qed. + +Lemma compact_sphere r : compact (sphere r). +Proof. +apply: bounded_closed_compact. + suff : \forall M \near +oo, forall p, sphere r p -> + forall i, `|p ord0 i| < M. + rewrite /bounded_set. + apply: filter_app; near=> M0. + move=> Kbnd /= p /Kbnd ltpM0. + rewrite /normr/= mx_normrE. + apply/bigmax_leP; split => //= i _. + by rewrite ord1; exact/ltW/ltpM0. + near=> M => v. + rewrite /sphere /= => vr i. + rewrite (@le_lt_trans _ _ r)//. + rewrite -vr [leRHS]/normr/= mx_normE. + under eq_bigr do rewrite ord1. + rewrite -(pair_big xpredT xpredT (fun _ j => `|v ord0 j|%:nng))//=. + rewrite big_ord_recr/= big_ord0. + rewrite max_r; last exact/bigmax_ge_id. + rewrite (bigD1 i)//= -maxE le_max. + by apply/orP; left. + clear v vr i. + by near: M; apply: nbhs_pinfty_gt; rewrite num_real. +pose d := fun x : 'rV[R]_n => `|x| : R. +have contd : continuous d by move=> /= z; exact: norm_continuous. +rewrite [X in closed X](_ : _ = d @^-1` [set r]); last first. + by apply/seteqP; split. +by apply continuous_closedP. +Unshelve. all: by end_near. Qed. + +End sphere. + +Section Lyapunov_stability. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n.+1. +Variable phi : U -> U. +Variable Init : set U. +Hypothesis openInit : open Init. + +Let B r := closed_ball_ (fun x => `|x|) (0 : 'rV[R]_n.+1) r. + +Let BE s : 0 < s -> B s = closed_ball 0 s. +Proof. by move=> r0; rewrite /B -closed_ballE. Qed. + +Variable V : U -> R. +Hypothesis Vdiff : forall t : U, differentiable V t. +Hypothesis DV_le0 : forall D f, f 0 \in Init -> + sol_is_deriv_co (fun=> phi) 0 D f -> + forall t, t \in `]0, D[%R -> 'D~(f) V t <= 0. + +(* khalil theorem 4.1 *) +Theorem Lyapunov_stability0 : + is_Lyapunov_candidate V Init 0 -> is_stable_at phi Init 0. +Proof. +move=> VInitx /= eps eps0/=. +move: VInitx => [/= xInit Vx0 InitxV]. +have [r [r_gt0 r_eps BrD]] : exists r : R, [/\ 0 < r, r <= eps & B r `<=` Init]. + move: xInit; rewrite inE => /(open_subball openInit)[r0/= r0_gt0] q. + pose r := Num.min (r0 / 2) eps. + have r_gt0 : 0 < r by rewrite /r lt_min eps0 divr_gt0. + exists (r / 2); split. + - by rewrite divr_gt0. + - by rewrite /r ler_pdivrMr// ge_min ler_pMr// ler1n orbT. + - move=> v Brv; apply: (q r) => //. + rewrite /ball/= sub0r normrN gtr0_norm// gt_min. + by rewrite gtr_pMr ?invf_lt1 ?ltr1n. + move: Brv; rewrite BE ?divr_gt0//. + exact: subset_closure_half(*TODO: naming seems off, report*). +rewrite {xInit}. +have alpha_min : {x : 'rV[R]_n.+1 | x \in sphere r /\ + forall y, y \in sphere r -> V x <= V y}. + have : {within sphere r, continuous V}. + apply: continuous_subspaceT => /= v. + by apply/differentiable_continuous; exact/Vdiff. + move/(EVT_min_rV (sphere_nonempty _ r_gt0) (@compact_sphere _ _ r)). + by move=> /(_ isT)/cid2[c sphere_r_c sphere_r_V]; exists c. +pose alpha := V (sval alpha_min). +have alpha_gt0 : 0 < alpha. + have sphere_pos y : y \in sphere r -> 0 < V y. + move=> yr; apply: InitxV; last first. + rewrite gtr0_norm_neq0//. + by move: yr; rewrite inE /sphere/= => ->. + apply/mem_set/BrD. + move: yr; rewrite inE /sphere/= => <-. + by rewrite /B /closed_ball_/= sub0r normrN. + rewrite /alpha sphere_pos// /sphere inE/=. + by have [+ _] := svalP alpha_min; rewrite inE. +rewrite {InitxV}. +have [beta /andP[beta_gt0 beta_alpha]] : exists beta, 0 < beta < alpha. + by exists (alpha / 2); rewrite divr_gt0//= ltr_pdivrMr//= ltr_pMr// ltr1n. +set Omega_beta := [set x : 'rV[R]_n.+1 | B r x /\ V x <= beta]. +have Omega_beta_Br : Omega_beta `<=` (B r)°. + move=> y [Bry Vybeta]. + rewrite BE// interior_closed_ballE => //=. + have yr : `|y| <= r by move: Bry; rewrite /B /closed_ball_/= sub0r normrN. + have [{}yr|ry|{}yr] := ltgtP `|y| r. + - by rewrite mx_norm_ball /ball_/= sub0r normrN. + - by have := le_lt_trans yr ry; rewrite ltxx. + - have alphaVy : alpha <= V y. + by rewrite /alpha; case: (svalP alpha_min) => [_]; apply; rewrite inE. + by have := lt_le_trans beta_alpha (le_trans alphaVy Vybeta); rewrite ltxx. +(* any trajectory starting in Omega_beta at t = 0 + stays in Omega_beta for all t >= 0 *) +have Df_Omega_beta D f : f 0 \in Init -> sol_is_deriv_co (fun=> phi) 0 D f -> + f 0 \in Omega_beta -> forall t, t \in `[0, D[%R -> f t \in Omega_beta. + move=> f0 solf f0_Omega. + have /= V_nincr_consequence t : t \in `]0, D[%R -> forall u, 0 <= u <= t -> + 'D~(f) V u <= 0 -> V (f t) <= V (f 0) <= beta. + move=> /= t0D u ut Vle0l; apply/andP; split. + - move: f0_Omega; rewrite inE /Omega_beta/= => -[Brphi0 Vphi0beta]. + apply: (@V_nincr _ _ D f). + + by move=> t' t'0D; apply solf. + + by move=> t'; exact: Vdiff. + + exact: DV_le0. + + by rewrite (itvP t0D). + + by rewrite lexx/= (itvP t0D). + - by move: f0_Omega; rewrite inE => -[]. + move=> t t0D. + have [->//|t0] := eqVneq t 0. + have {t0}t0D : t \in `]0, D[%R. + by rewrite in_itv/= lt_neqAle eq_sym t0/= 2!(itvP t0D). + rewrite inE; split; last first. + have : 'D~(f) V t <= 0 by exact: (DV_le0 _ solf). + have := @V_nincr_consequence t t0D t. + rewrite lexx (itvP t0D)/= => /(_ isT) => /[apply]. + by move=> /andP[/le_trans] => /[apply]. + move: f0_Omega; rewrite inE /Omega_beta/= /B /closed_ball_/=. + rewrite !sub0r !normrN => -[f0r Vf0beta]. + rewrite leNgt; apply/negP => rft. + have [t1 /andP[t1_ge0 t1t] phit1r] : exists2 t0, 0 <= t0 <= t & `|f t0| = r. + have t0 : 0 <= t by rewrite (itvP t0D). + have norm_phi_cont : {within `[0, t]%classic, continuous (normr \o f)}. + apply/(@within_continuous_comp _ _ _ `[0, t] f (@normr _ _)) => //. + by move=> z _; exact: norm_continuous. + have : {in `[0, D[, continuous f}. + move=> t'; rewrite inE => t'0D. + by apply/differentiable_continuous/derivable1_diffP; apply solf. + move/continuous_in_subspaceT. + apply: continuous_subspaceW. + by apply: subset_itvl; rewrite bnd_simp (itvP t0D). + have : Num.min `|f 0| `|f t| <= r <= Num.max `|f 0| `|f t|. + by rewrite ge_min f0r/= le_max (ltW rft) orbT. + move=> /(IVT t0 norm_phi_cont)[c cI norm_phi_c]. + by exists c => //; move/itvP: cI => ->. + have alphaVphit1 : alpha <= V (f t1). + rewrite {alpha_gt0 beta_alpha} /alpha; case: alpha_min => /=. + by move=> y [_ +]; apply; rewrite inE. + have : beta < V (f t1). + by rewrite (lt_le_trans _ alphaVphit1)//; case/andP: beta_alpha. + apply/negP; rewrite -leNgt. + move: t1_ge0; rewrite le_eqVlt => /predU1P[<-//|t10]. + have := @V_nincr_consequence t1. + have tD : t < D by rewrite (itvP t0D). + rewrite in_itv/= t10/= (le_lt_trans t1t tD) => /(_ isT). + move=> /(_ t1); rewrite (ltW t10) lexx => /(_ isT). + have : 'D~(f) V t1 <= 0. + apply: (@DV_le0 _ _ _ solf) => //. + by rewrite in_itv/= t10/= (le_lt_trans _ tD). + move=> /[swap] /[apply]. + by move=> /andP[/le_trans] => /[apply]. +have _ : compact Omega_beta. + apply: bounded_closed_compact; rewrite /Omega_beta. + - rewrite /bounded_set /= /globally. + exists r; split => //= t rt v. + rewrite /B /closed_ball_/= sub0r normrN. + by move=> [/le_trans vr _]; rewrite vr// ltW. + - apply: closedI => /=. + by rewrite BE//; exact: closed_ball_closed. + rewrite [X in closed X](_ : _ = V @^-1` [set x | x <= beta]); last first. + by apply/seteqP; split. + apply: closed_comp => //= v _. + apply: continuous_comp; first by []. + exact: differentiable_continuous. +have [d0 d0_gt0 Vbeta] : exists2 d, d > 0 & forall x, `|x| <= d -> V x < beta. + have [d d_gt0 xdV] : exists2 d, 0 < d & + forall y, `|y - 0| < d -> `|V y - V 0| < beta. + have /cvgrPdist_lt /(_ _ beta_gt0) : + V x @[x --> nbhs (0 : 'rV_n.+1) ] --> V 0. + exact/differentiable_continuous/Vdiff. + rewrite nearE /= => /nbhs_ballP[d /= d_pos xdV]. + exists d => // y. + move: xdV; rewrite mx_norm_ball /ball_ /= distrC => /[apply]. + by rewrite distrC. + exists (d / 2); first exact: divr_gt0. + move=> v vd; have /(xdV v) : `|v - 0| < d. + by rewrite subr0 (le_lt_trans vd)// ltr_pdivrMr // ltr_pMr // ltr1n. + by rewrite Vx0 subr0; apply: le_lt_trans; rewrite ler_normlW. +pose delta := Num.min d0 r. +have delta_gt0 : 0 < delta by rewrite /delta lt_min d0_gt0 r_gt0. +have deltaV y : `|y| <= delta -> V y < beta. + move=> /= ydelta. + have : `|y| <= d0 by rewrite (le_trans ydelta)// /delta ge_min lexx. + exact: Vbeta. +have B_delta_Omega_beta : B delta `<=` Omega_beta. + rewrite /Omega_beta => /= v. + rewrite /B /closed_ball_/= sub0r normrN => vdelta. + split; last exact/ltW/deltaV. + by rewrite (le_trans vdelta)// /delta ge_min lexx orbT. +exists delta => //. +move=> f D' f0 solf f0xD t0 t0_ge0. +rewrite subr0. +have : f 0 \in Omega_beta. + rewrite inE; apply: B_delta_Omega_beta. + rewrite /B /closed_ball_/= sub0r normrN; apply/ltW. + by rewrite subr0 in f0xD. +rewrite inE => -[+ Vf0beta]. +rewrite /B /closed_ball_/= sub0r normrN => f0r. +have : (B r)° (f t0). + apply: Omega_beta_Br; apply/set_mem. + apply: (Df_Omega_beta D') => //. + rewrite inE; split; first by rewrite /B /closed_ball_/= sub0r normrN. + have : B delta (f 0). + rewrite /closed_ball_; apply: ltW; rewrite sub0r normrN. + by rewrite subr0 in f0xD. + by move/B_delta_Omega_beta => []. +rewrite BE//= interior_closed_ballE//=. +by rewrite mx_norm_ball /ball_/= sub0r normrN => /lt_le_trans; exact. +Unshelve. all: by end_near. Qed. + +End Lyapunov_stability. + +Section is_equilibrium_point_change_of_variables. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n.+1. +Variable phi : U -> U. +Variable Init : set U. + +Lemma sol_is_deriv_co_substitution D f x : + sol_is_deriv_co (fun=> phi) 0 D f -> + sol_is_deriv_co (fun _ y => phi (y + x)) 0 D (f \- cst x). +Proof. +rewrite /sol_is_deriv_co => /= H t t0D; split. + apply: derivableB => //. + by apply H. +rewrite subrK derive1E deriveB//; last by apply H. +by rewrite derive_cst subr0 -derive1E; apply H. +Qed. + +Lemma is_stable_at_substitution x : + is_stable_at (fun y => phi (y + x)) [set y - x | y in Init] 0 -> + is_stable_at phi Init x. +Proof. +move=> H. +rewrite /is_stable_at => /= e e0. +have [/= d d0 {}H] := H _ e0. +exists d => // f D f0Init solf f0xd t t0. +rewrite -[_ - _]subr0. +rewrite -[f t - x]/((f \- cst x) t). +apply: (H _ D) => //. +- exact/image_f. +- exact: sol_is_deriv_co_substitution. +- by rewrite /= subr0. +Qed. + +Lemma is_equilibrium_point_substitutionP x : + is_equilibrium_point (fun y => phi (y + x)) 0 <-> + is_equilibrium_point phi x. +Proof. +split. +- move=> issol t t0; split. + exact: derivable_cst. + have := issol 0. + rewrite in_itv/= lexx => /(_ isT)[_]. + rewrite add0r => <-. + by rewrite !derive1_cst. +- move=> issol t t0; split. + exact: derivable_cst. + have [] := issol _ t0. + rewrite !derive1_cst //=. + by rewrite add0r => _ ->. +Qed. + +Lemma is_Lyapunov_candidate_substitution V x : + is_Lyapunov_candidate V Init x -> + is_Lyapunov_candidate (fun y => V (y + x)) [set y - x | y in Init] 0. +Proof. +move=> [xInit Vx0/= InitV]. +split. +- rewrite inE/=. + exists x; rewrite ?subrr//. + by rewrite inE in xInit. +- by rewrite add0r. +- move=> /= z. + rewrite inE/= => -[x0 x0Init <-{z}]. + rewrite subr_eq0 => x0x. + apply: InitV => //. + by rewrite subrK inE. + by rewrite subrK. +Qed. + +End is_equilibrium_point_change_of_variables. + +Section Lyapunov_stability. +Context {R : realType} {n : nat}. +Let U := 'rV[R]_n.+1. +Variable phi : U -> U. +Variable Init : set U. +Hypothesis openInit : open Init. + +Variable V : U -> R. +Hypothesis Vdiff : forall t : U, differentiable V t. +Hypothesis V'_le0 : forall D (f : R -> U), + f 0 \in Init -> + sol_is_deriv_co (fun=> phi) 0 D f -> + forall t, t \in `]0, D[%R -> 'D~(f) V t <= 0. + +Theorem Lyapunov_stability : + is_Lyapunov_candidate V Init `<=` is_stable_at phi Init. +Proof. +move=> x VInitx. +apply: is_stable_at_substitution. +apply: (@Lyapunov_stability0 _ _ _ _ _ (fun y => V (y + x))). +- rewrite [X in open X](_ : _ = (fun y => y + x) @^-1` Init); last first. + apply/seteqP; split. + by move=> /= z [v vInit <-]; rewrite subrK. + by move=> /= z zxInit; exists (z + x) => //; rewrite addrK. + apply: open_comp => // z _. + rewrite /continuous_at. + apply: (@cvgD _ 'rV_n.+1) => //=. + by apply: filter_filter; exact: mx_nbhs_filter. (* TODO: should be automatic! *) + by apply: cvg_cst; apply: filter_filter; exact: mx_nbhs_filter. +- by move=> t; exact: differentiable_comp. +- move=> /= D sol sol0 sol0Init /= t t0D. + rewrite [leLHS](_ : _ = ('D~((fun y => y + x) \o sol) V) t); last first. + rewrite derive_along_derive; last 2 first. + exact: differentiable_comp. + apply/derivable1_diffP. + apply sol0Init. + by apply: subset_itvr t0D; rewrite bnd_simp. + have -> : (fun y => V (y + x)) \o sol = V \o (+%R^~ x \o sol). + exact/funext. + rewrite derive_along_derive; last 2 first. + exact: differentiable_comp. + apply: differentiable_comp => //. + apply/derivable1_diffP. + apply sol0Init. + by apply: subset_itvr t0D; rewrite bnd_simp. + by []. + apply: (@V'_le0 D); last by assumption. + - rewrite inE/=. + move: sol0; rewrite inE/= => -[x0 x0Init <-]. + by rewrite subrK. + - move=> /= z z0D; split. + apply/derivable1_diffP/differentiable_comp => //. + by apply/derivable1_diffP; apply sol0Init. + rewrite derive1E deriveD//; last by apply sol0Init. + rewrite derive_cst addr0 -derive1E. + by apply sol0Init. +exact: is_Lyapunov_candidate_substitution. +Qed. + +End Lyapunov_stability. diff --git a/vec_angle.v b/vec_angle.v index 38773e6e..fe0452cf 100644 --- a/vec_angle.v +++ b/vec_angle.v @@ -1,5 +1,5 @@ (* coq-robot (c) 2017 AIST and INRIA. License: LGPL-2.1-or-later. *) -From mathcomp Require Import all_ssreflect ssralg ssrint ssrnum rat poly. +From mathcomp Require Import all_boot all_order ssralg ssrint ssrnum rat poly. From mathcomp Require Import closed_field polyrcf matrix mxalgebra mxpoly zmodp. From mathcomp Require Import sesquilinear. From mathcomp Require Import realalg complex fingroup perm reals interval trigo. @@ -46,8 +46,8 @@ Import Order.TTheory GRing.Theory Num.Def Num.Theory. Local Open Scope ring_scope. -Lemma norm_le1 [T : rcfType] (u : 'rV[T]_2) : - norm u <= 1 -> (- 1 <= u``_ 0 <= 1) /\ (- 1 <= u``_1 <= 1). +Lemma enorm_le1 [T : rcfType] (u : 'rV[T]_2) : + `| u |_e <= 1 -> (- 1 <= u``_ 0 <= 1) /\ (- 1 <= u``_1 <= 1). Proof. move=> nuL1; rewrite -!ler_norml. rewrite -!(expr_le1 (_ : 0 < 2)%N (normr_ge0 _)) //. @@ -56,22 +56,22 @@ suff sL1 : `|u``_0| ^+ 2 + `|u``_1| ^+ 2 <= 1. by rewrite -[X in X <= _]addr0 lerD // sqr_ge0. by rewrite -[X in X <= _]add0r lerD // sqr_ge0. rewrite !sqr_normr //. -suff : norm u ^+ 2 <= 1 by rewrite sqr_norm sum2E. -by apply: exprn_ile1 (norm_ge0 _) _. +suff : `| u |_e ^+ 2 <= 1 by rewrite sqr_enorm sum2E. +by apply: exprn_ile1 (enorm_ge0 _) _. Qed. -Lemma norm1_cossin (T : realType) (v : 'rV[T]_2) : - norm v = 1 -> {a | v``_0 = cos a /\ v``_1 = sin a}. +Lemma enorm1_cossin (T : realType) (v : 'rV[T]_2) : + `| v |_e = 1 -> {a | v``_0 = cos a /\ v``_1 = sin a}. Proof. move=> nvE. exists (if 0 <= v``_1 then acos v``_0 else -acos v``_0). -have /norm_le1[v0B v1B] : norm v <= 1 by rewrite nvE. +have /enorm_le1[v0B v1B] : `| v |_e <= 1 by rewrite nvE. have [v0_ge0|v0_gt0] := leP 0%R (v``_1). rewrite acosK ?in_itv //= sin_acos ?in_itv //=. - rewrite -(expr1n T 2) -nvE sqr_norm sum2E [_ + _^+2] addrC addrK. + rewrite -(expr1n T 2) -nvE sqr_enorm sum2E [_ + _^+2] addrC addrK. by rewrite sqrtr_sqr ger0_norm. rewrite cosN sinN acosK ?in_itv //= sin_acos ?in_itv //=. -rewrite -(expr1n T 2) -nvE sqr_norm sum2E [_ + _^+2] addrC addrK. +rewrite -(expr1n T 2) -nvE sqr_enorm sum2E [_ + _^+2]addrC addrK. by rewrite sqrtr_sqr ltr0_norm ?opprK. Qed. @@ -81,7 +81,7 @@ Implicit Types u v : 'rV[T]_3. Definition vec_angle v w : T := if v == 0 then 0 else - if w == 0 then 0 else acos (v *d w / (norm v * norm w)). + if w == 0 then 0 else acos (v *d w / (`| v |_e * `| w |_e)). Lemma vec_anglev0 v : vec_angle v 0 = 0. Proof. by rewrite /vec_angle eqxx if_same. Qed. @@ -93,14 +93,14 @@ Definition vec_angle0 := (vec_anglev0, vec_angle0v). Lemma vec_angleC v w : vec_angle v w = vec_angle w v. Proof. -by rewrite /vec_angle dotmulC [norm _ * _]mulrC; do 2 case: eqP. +by rewrite /vec_angle dotmulC [`| _ |_e * _]mulrC; do 2 case: eqP. Qed. Lemma vec_anglevZ u v k : 0 < k -> vec_angle u (k *: v) = vec_angle u v. Proof. move=> k_gt0; rewrite /vec_angle; case: eqP => // /eqP u0. rewrite scaler_eq0 (negPf (lt0r_neq0 _)) //=. -rewrite dotmulvZ normZ gtr0_norm // mulrCA -mulf_div divff ?mul1r //. +rewrite dotmulvZ enormZ gtr0_norm // mulrCA -mulf_div divff ?mul1r//. by rewrite lt0r_neq0. Qed. @@ -111,7 +111,7 @@ Lemma vec_anglevZN u v k : k < 0 -> vec_angle u (k *: v) = vec_angle u (- v). Proof. move=> k_lt0; rewrite /vec_angle; case: eqP => // /eqP u0. rewrite scaler_eq0 (negPf (ltr0_neq0 _)) //= oppr_eq0. -rewrite dotmulvZ normZ ltr0_norm // normN dotmulvN mulrCA -mulf_div. +rewrite dotmulvZ enormZ ltr0_norm// enormN dotmulvN mulrCA -mulf_div. rewrite invrN mulrN divff ?(mulN1r, mulNr) //. by rewrite ltr0_neq0. Qed. @@ -123,24 +123,24 @@ Lemma vec_anglevv u : u != 0 -> vec_angle u u = 0. Proof. move=> u0. rewrite /vec_angle /= (negPf u0) dotmulvv -expr2 divff ?acos1 //. -by rewrite expf_eq0 //= norm_eq0. +by rewrite expf_eq0 //= enorm_eq0. Qed. Lemma dotmul_div_N11 v w : - v != 0 -> w != 0 -> v *d w / (norm v * norm w) \in `[(-1), 1]. + v != 0 -> w != 0 -> v *d w / (`| v |_e * `| w |_e) \in `[(-1), 1]. Proof. move=> u0 v0. rewrite in_itv /= -ler_norml -(expr_le1 (_ : 0 < 2)%N) //. rewrite sqr_normr expr_div_n ler_pdivrMr ?mul1r. -rewrite -subr_ge0 -norm_crossmul' ?exprn_ge0 ?norm_ge0 //. -by rewrite exprn_gt0 // mulr_gt0 // norm_gt0. +rewrite -subr_ge0 -enorm_crossmul' ?exprn_ge0 ?enorm_ge0//. +by rewrite exprn_gt0// mulr_gt0// enorm_gt0. Qed. Lemma cos_vec_angleNv v w : v != 0 -> w != 0 -> cos (vec_angle (- v) w) = - cos (vec_angle v w). Proof. move=> u0 v0. -rewrite /vec_angle oppr_eq0 (negPf u0) (negPf v0) normN dotmulNv mulNr. +rewrite /vec_angle oppr_eq0 (negPf u0) (negPf v0) enormN dotmulNv mulNr. have H := dotmul_div_N11 u0 v0. by rewrite !acosK ?oppr_itvcc ?opprK. Qed. @@ -164,21 +164,21 @@ Proof. rewrite /vec_angle oppr_eq0; case: eqP => [//|/eqP uD0]. case: eqP => [//|/eqP vD0]. have H := dotmul_div_N11 uD0 vD0; rewrite in_itv in H. -rewrite normN dotmulvN mulNr !sin_acos ?sqrrN //. +rewrite enormN dotmulvN mulNr !sin_acos ?sqrrN//. by rewrite lerNr opprK lerNl andbC. Qed. Lemma sin_vec_angleNv u v : sin (vec_angle (- u) v) = sin (vec_angle u v). Proof. by rewrite vec_angleC [in RHS]vec_angleC [in LHS]sin_vec_anglevN. Qed. -Lemma dotmul_cos u v : u *d v = norm u * norm v * cos (vec_angle u v). +Lemma dotmul_cos u v : u *d v = `| u |_e * `| v |_e * cos (vec_angle u v). Proof. wlog /andP[u0 v0] : u v / (u != 0) && (v != 0). - case/boolP : (u == 0) => [/eqP ->{u}|u0]; first by rewrite dotmul0v norm0 !mul0r. - case/boolP : (v == 0) => [/eqP ->{v}|v0]; first by rewrite dotmulv0 norm0 !(mulr0,mul0r). - apply; by rewrite u0. -rewrite /vec_angle (negPf u0) (negPf v0) acosK; last by apply: dotmul_div_N11. -by rewrite mulrC divfK // mulf_eq0 negb_or !norm_eq0 u0. + have [->|u0] := eqVneq u 0; first by rewrite dotmul0v enorm0 !mul0r. + have [->|v0] := eqVneq v 0; first by rewrite dotmulv0 enorm0 !(mulr0,mul0r). + by apply; rewrite u0. +rewrite /vec_angle (negPf u0) (negPf v0) acosK; last exact: dotmul_div_N11. +by rewrite mulrC divfK // mulf_eq0 negb_or !enorm_eq0 u0. Qed. Lemma dotmul0_vec_angle u v : u != 0 -> v != 0 -> @@ -189,13 +189,13 @@ by rewrite /vec_angle (negPf u0) (negPf v0) uv0 mul0r acos0 sin_pihalf normr1. Qed. Lemma triine u v : - (norm u * norm v * cos (vec_angle u v)) *+ 2 <= norm u ^+ 2 + norm v ^+ 2. + (`| u |_e * `| v |_e * cos (vec_angle u v)) *+ 2 <= `| u |_e ^+ 2 + `| v |_e ^+ 2. Proof. -move/eqP: (sqrrD (norm u) (norm v)); rewrite addrAC -subr_eq => /eqP <-. -rewrite lerBrDr -mulrnDl -{2}(mulr1 (norm u * norm v)) -mulrDr. -apply (@le_trans _ _ (norm u * norm v * 2%:R *+ 2)). +move/eqP: (sqrrD `|u|_e `|v|_e); rewrite addrAC -subr_eq => /eqP <-. +rewrite lerBrDr -mulrnDl -{2}(mulr1 (`|u|_e * `|v|_e)) -mulrDr. +apply (@le_trans _ _ (`|u|_e * `|v|_e * 2%:R *+ 2)). rewrite lerMn2r /=; apply ler_pM => //. - by apply mulr_ge0; apply norm_ge0. + by apply mulr_ge0; apply: enorm_ge0. rewrite -lerBlDr add0r; move: (cos_max (vec_angle u v)). by rewrite ler_norml => /andP[]. rewrite -lerBrDr {2}(_ : 1 = 1%:R) // -natrB //. @@ -204,43 +204,45 @@ rewrite sqrrD mulr2n addrAC; apply: lerD; last by rewrite mulr_natr. by rewrite -subr_ge0 addrAC mulr_natr -sqrrB sqr_ge0. Qed. -Lemma normB u v : norm (u - v) ^+ 2 = - norm u ^+ 2 + norm u * norm v * cos (vec_angle u v) *- 2 + norm v ^+ 2. +(* TODO: move? *) +Lemma enormB u v : `|u - v|_e ^+ 2 = + `|u|_e ^+ 2 + `|u|_e * `|v|_e * cos (vec_angle u v) *- 2 + `|v|_e ^+ 2. Proof. -rewrite /norm dotmulD {1}dotmulvv sqr_sqrtr; last first. +rewrite /enorm dotmulD {1}dotmulvv sqr_sqrtr; last first. rewrite !dotmulvN !dotmulNv opprK dotmulvv dotmul_cos. by rewrite addrAC mulNrn subr_ge0 triine. -rewrite sqr_sqrtr ?le0dotmul // !dotmulvv !sqrtr_sqr normN dotmulvN dotmul_cos. -by rewrite ger0_norm ?norm_ge0 // ger0_norm ?norm_ge0 // mulNrn. +rewrite sqr_sqrtr ?le0dotmul // !dotmulvv !sqrtr_sqr enormN dotmulvN dotmul_cos. +by rewrite ger0_norm ?enorm_ge0// ger0_norm ?enorm_ge0// mulNrn. Qed. -Lemma normD u v : norm (u + v) ^+ 2 = - norm u ^+ 2 + norm u * norm v * cos (vec_angle u v) *+ 2 + norm v ^+ 2. +(* TODO: move? *) +Lemma enormD u v : `|u + v|_e ^+ 2 = + `|u|_e ^+ 2 + `|u|_e * `|v|_e * cos (vec_angle u v) *+ 2 + `|v|_e ^+ 2. Proof. rewrite {1}(_ : v = - - v); last by rewrite opprK. -rewrite normB normN. -case/boolP: (u == 0) => [/eqP ->|u0]. - by rewrite !(norm0,expr0n,add0r,vec_angle0,mul0r,mul0rn,oppr0). -case/boolP: (v == 0) => [/eqP ->|v0]. - by rewrite norm0 mulr0 oppr0 vec_angle0 cos0 mul0r mul0rn subr0 addr0. +rewrite enormB enormN. +have [->|u0] := eqVneq u 0. + by rewrite !(enorm0,expr0n,add0r,vec_angle0,mul0r,mul0rn,oppr0). +have [->|v0] := eqVneq v 0. + by rewrite enorm0 mulr0 oppr0 vec_angle0 cos0 mul0r mul0rn subr0 addr0. by rewrite [in LHS]cos_vec_anglevN // mulrN mulNrn opprK. Qed. Lemma cosine_law' a b c : - norm (b - c) ^+ 2 = norm (c - a) ^+ 2 + norm (b - a) ^+ 2 - - norm (c - a) * norm (b - a) * cos (vec_angle (b - a) (c - a)) *+ 2. + `|b - c|_e ^+ 2 = `|c - a|_e ^+ 2 + `|b - a|_e ^+ 2 - + `|c - a|_e * `|b - a|_e * cos (vec_angle (b - a) (c - a)) *+ 2. Proof. rewrite -[in LHS]dotmulvv (_ : b - c = b - a - (c - a)); last first. by rewrite -!addrA opprB (addrC (- a)) (addrC a) addrK. rewrite dotmulD dotmulvv [in X in _ + _ + X = _]dotmulvN dotmulNv opprK. -rewrite dotmulvv dotmulvN addrAC (addrC (norm (b - a) ^+ _)); congr (_ + _). -by rewrite dotmul_cos mulNrn (mulrC (norm (b - a))). +rewrite dotmulvv dotmulvN addrAC (addrC (`|b - a|_e ^+ _)); congr (_ + _). +by rewrite dotmul_cos mulNrn (mulrC `|b - a|_e). Qed. -Lemma cosine_law a b c : norm (c - a) != 0 -> norm (b - a) != 0 -> +Lemma cosine_law a b c : `|c - a|_e != 0 -> `|b - a|_e != 0 -> cos (vec_angle (b - a) (c - a)) = - (norm (b - c) ^+ 2 - norm (c - a) ^+ 2 - norm (b - a) ^+ 2) / - (norm (c - a) * norm (b - a) *- 2). + (`|b - c|_e ^+ 2 - `|c - a|_e ^+ 2 - `|b - a|_e ^+ 2) / + (`|c - a|_e * `|b - a|_e *- 2). Proof. move=> H0 H1. rewrite (cosine_law' a b c) -2!addrA addrCA -opprD subrr addr0. @@ -253,51 +255,51 @@ rewrite -mulrA mulf_eq0 pnatr_eq0/=. by rewrite mulf_eq0 negb_or H0 H1. Qed. -Lemma norm_crossmul u v : - norm (u *v v) = norm u * norm v * `| sin (vec_angle u v) |. +Lemma enorm_crossmul u v : + `|u *v v|_e = `|u|_e * `|v|_e * `| sin (vec_angle u v) |. Proof. -suff /eqP : (norm (u *v v))^+2 = (norm u * norm v * `| sin (vec_angle u v) |)^+2. - rewrite -eqr_sqrt ?sqr_ge0 // 2!sqrtr_sqr ger0_norm; last by rewrite norm_ge0. +suff /eqP : `|u *v v|_e ^+ 2 = (`|u|_e * `|v|_e * `| sin (vec_angle u v) |)^+2. + rewrite -eqr_sqrt ?sqr_ge0 // 2!sqrtr_sqr ger0_norm; last by rewrite enorm_ge0. rewrite ger0_norm; first by move/eqP. - by rewrite -mulrA mulr_ge0 // ?norm_ge0 // mulr_ge0 // ? norm_ge0. -rewrite norm_crossmul' dotmul_cos !exprMn. + by rewrite -mulrA mulr_ge0 ?enorm_ge0 // mulr_ge0 // enorm_ge0. +rewrite enorm_crossmul' dotmul_cos !exprMn. apply/eqP; rewrite subr_eq -mulrDr. rewrite real_normK //; first by rewrite addrC cos2Dsin2 mulr1. by rewrite realE; case: ltgtP. Qed. -Lemma norm_dotmul_crossmul u v : u != 0 -> v != 0 -> - (`|u *d v +i* norm (u *v v)| = (norm u * norm v)%:C)%C. +Lemma enorm_dotmul_crossmul u v : u != 0 -> v != 0 -> + (`|u *d v +i* `|u *v v|_e| = (`|u|_e * `|v|_e)%:C)%C. Proof. move=> u0 v0 . -rewrite {1}dotmul_cos {1}norm_crossmul normc_def. +rewrite {1}dotmul_cos {1}enorm_crossmul normc_def. rewrite exprMn (@exprMn _ 2 _ `| sin _ |) -mulrDr. rewrite sqrtrM ?sqr_ge0 // sqr_normr cos2Dsin2 sqrtr1 mulr1. -rewrite sqrtr_sqr normrM; by do 2 rewrite ger0_norm ?norm_ge0 //. +by rewrite sqrtr_sqr normrM; do 2 rewrite ger0_norm ?enorm_ge0//. Qed. Lemma vec_angle0_inv u v : u != 0 -> v != 0 -> - vec_angle u v = 0 -> u = (norm u / norm v) *: v. + vec_angle u v = 0 -> u = (`|u|_e / `|v|_e) *: v. Proof. move=> uD0 vD0 uv0. -apply/eqP; rewrite -subr_eq0 -norm_eq0. -rewrite -(@eqrXn2 _ 2) // ?norm_ge0 // expr0n /= normB. -rewrite vec_anglevZ; last by rewrite divr_gt0 // norm_gt0. -rewrite uv0 cos0 mulr1 !normZ ger0_norm; last first. - by rewrite divr_ge0 // norm_ge0. -by rewrite divfK ?norm_eq0 // -expr2 addrAC -mulr2n subrr. +apply/eqP; rewrite -subr_eq0 -enorm_eq0. +rewrite -(@eqrXn2 _ 2) ?enorm_ge0// expr0n /= enormB. +rewrite vec_anglevZ; last by rewrite divr_gt0// enorm_gt0. +rewrite uv0 cos0 mulr1 !enormZ ger0_norm; last first. + by rewrite divr_ge0// enorm_ge0. +by rewrite divfK ?enorm_eq0// -expr2 addrAC -mulr2n subrr. Qed. Lemma vec_anglepi_inv u v : u != 0 -> v != 0 -> - vec_angle u v = pi -> u = - (norm u / norm v) *: v. + vec_angle u v = pi -> u = - (`|u|_e / `|v|_e) *: v. Proof. move=> uD0 vD0 uvpi. -apply/eqP; rewrite -subr_eq0 -norm_eq0 scaleNr opprK. -rewrite -(@eqrXn2 _ 2) // ?norm_ge0 // expr0n /= normD. -rewrite vec_anglevZ; last by rewrite divr_gt0 // norm_gt0. -rewrite uvpi cospi mulrN1 !normZ ger0_norm; last first. - by rewrite divr_ge0 // norm_ge0. -rewrite mulNrn divfK ?norm_eq0 //. +apply/eqP; rewrite -subr_eq0 -enorm_eq0 scaleNr opprK. +rewrite -(@eqrXn2 _ 2) ?enorm_ge0// expr0n /= enormD. +rewrite vec_anglevZ; last by rewrite divr_gt0// enorm_gt0. +rewrite uvpi cospi mulrN1 !enormZ ger0_norm; last first. + by rewrite divr_ge0// enorm_ge0. +rewrite mulNrn divfK ?enorm_eq0//. by rewrite addrC addrA -expr2 -mulr2n subrr. Qed. @@ -309,31 +311,31 @@ have := dotmul_div_N11 uD0 vD0; rewrite in_itv /= => uv_bound. by rewrite acos_ge0 // acos_lepi. Qed. -Lemma dotmul1_inv u v : norm u = 1 -> norm v = 1 -> u *d v = 1 -> u = v. +Lemma dotmul1_inv u v : `|u|_e = 1 -> `|v|_e = 1 -> u *d v = 1 -> u = v. Proof. move=> u1 v1; rewrite dotmul_cos u1 v1 2!mul1r => Huv. -suff: u = (norm u / norm v) *: v. +suff: u = (`|u|_e / `|v|_e) *: v. rewrite u1 v1 ?divff ?(scale1r, oner_neq0) //. -apply: vec_angle0_inv; first by rewrite -norm_eq0 u1 oner_neq0. - by rewrite -norm_eq0 v1 oner_neq0. +apply: vec_angle0_inv; first by rewrite -enorm_eq0 u1 oner_neq0. + by rewrite -enorm_eq0 v1 oner_neq0. apply: cos_inj; rewrite ?in_itv /=; last by rewrite cos0. by apply: vec_angle_bound. by rewrite lexx pi_ge0. Qed. -Lemma dotmulN1_inv u v : norm u = 1 -> norm v = 1 -> u *d v = - 1 -> u = - v. +Lemma dotmulN1_inv u v : `|u|_e = 1 -> `|v|_e = 1 -> u *d v = - 1 -> u = - v. Proof. move=> u1 v1 Huv. -by apply: dotmul1_inv; rewrite ?normN // dotmulvN Huv opprK. +by apply: dotmul1_inv; rewrite ?enormN// dotmulvN Huv opprK. Qed. Lemma cos_vec_angle a b : a != 0 -> b != 0 -> - `| cos (vec_angle a b) | = Num.sqrt (1 - (norm (a *v b) / (norm a * norm b)) ^+ 2). + `| cos (vec_angle a b) | = Num.sqrt (1 - (`|a *v b|_e / (`|a|_e * `|b|_e)) ^+ 2). Proof. move=> Ha Hb. -rewrite norm_crossmul mulrAC divrr // ?mul1r. +rewrite enorm_crossmul mulrAC divrr // ?mul1r. by rewrite sqr_normr -cos2sin2 sqrtr_sqr. -by rewrite unitfE mulf_neq0 // norm_eq0. +by rewrite unitfE mulf_neq0// enorm_eq0. Qed. Lemma orth_preserves_vec_angle M : M \is 'O[T]_3 -> @@ -343,8 +345,8 @@ move=> MO v w. have [->|/eqP vD0]:= v =P 0; first by rewrite mul0mx !vec_angle0. have [->|/eqP wD0]:= w =P 0; first by rewrite mul0mx !vec_angle0. apply: cos_inj; try by apply: vec_angle_bound. -have /mulfI : norm v * norm w != 0. - by rewrite mulf_eq0 !norm_eq0 negb_or vD0 wD0. +have /mulfI : `|v|_e * `|w|_e != 0. + by rewrite mulf_eq0 !enorm_eq0 negb_or vD0 wD0. apply; rewrite -[RHS]dotmul_cos. have /orth_preserves_dotmul/(_ v w)<- := MO. by rewrite [RHS]dotmul_cos !orth_preserves_norm. @@ -515,13 +517,13 @@ Lemma axialcomp0v e : axialcomp 0 e = 0. Proof. by rewrite /axialcomp dotmulv0 scale0r. Qed. Lemma axialcompv0 v : axialcomp v 0 = 0. -Proof. by rewrite /axialcomp /normalize norm0 invr0 ?(scale0r,dotmul0v). Qed. +Proof. by rewrite /axialcomp /normalize enorm0 invr0 ?(scale0r,dotmul0v). Qed. -Lemma axialcompE v e : axialcomp v e = (norm e) ^- 2 *: (v *m e^T *m e). +Lemma axialcompE v e : axialcomp v e = `|e|_e ^- 2 *: (v *m e^T *m e). Proof. -have [/eqP ->|?] := boolP (e == 0); first by rewrite axialcompv0 mulmx0 scaler0. +have [->|?] := eqVneq e 0; first by rewrite axialcompv0 mulmx0 scaler0. rewrite /axialcomp dotmulZv scalerA mulrAC dotmulP mul_scalar_mx dotmulC. -by rewrite -invrM ?unitfE ?norm_eq0 // -expr2 scalerA. +by rewrite -invrM ?unitfE ?enorm_eq0// -expr2 scalerA. Qed. Lemma axialcompvN v e : axialcomp v (- e) = axialcomp v e. @@ -532,9 +534,9 @@ Proof. by rewrite /axialcomp dotmulvN scaleNr. Qed. Lemma axialcompZ k e : axialcomp (k *: e) e = k *: e. Proof. -rewrite /axialcomp dotmulvZ dotmulC dotmul_normalize_norm. +rewrite /axialcomp dotmulvZ dotmulC dotmul_normalize_enorm. have [/eqP u0|u0] := boolP (e == 0); first by rewrite u0 normalize0 2!scaler0. -by rewrite scalerA -mulrA divrr ?unitfE ?norm_eq0 // mulr1. +by rewrite scalerA -mulrA divrr ?unitfE ?enorm_eq0// mulr1. Qed. Lemma axialcomp_dotmul v e : e *d v = 0 -> axialcomp v e = 0. @@ -559,15 +561,15 @@ rewrite (linearZl_LR _ e)/= (@liexx _ (vec3 T)). by rewrite scaler0 (linear0l _ (_ *v v)). Qed. -Lemma norm_axialcomp v e : e *d v < 0 -> - norm (axialcomp v e) = - (normalize e *d v). +Lemma enorm_axialcomp v e : e *d v < 0 -> + `|axialcomp v e|_e = - (normalize e *d v). Proof. move=> H. have ? : e != 0 by apply: contraTN H => /eqP ->; rewrite dotmul0v ltxx. -rewrite /axialcomp scalerA normZ ltr0_norm; last first. - rewrite pmulr_llt0 ?invr_gt0 ?norm_gt0 //. - by rewrite /normalize dotmulZv pmulr_rlt0 // invr_gt0 norm_gt0. -by rewrite mulNr -(mulrA _ _ (norm e)) mulVr ?mulr1 ?unitfE ?norm_eq0. +rewrite /axialcomp scalerA enormZ ltr0_norm; last first. + rewrite pmulr_llt0 ?invr_gt0 ?enorm_gt0 //. + by rewrite /normalize dotmulZv pmulr_rlt0 // invr_gt0 enorm_gt0. +by rewrite mulNr -(mulrA _ _ `|e|_e) mulVr ?mulr1 ?unitfE ?enorm_eq0. Qed. Lemma axialcomp_mulO Q p e : Q \is 'O[T]_3 -> e *m Q = e -> @@ -585,8 +587,8 @@ Lemma vec_angle_axialcomp v e : 0 < e *d v -> Proof. move=> H. have ? : e != 0 by apply: contraTN H => /eqP ->; rewrite dotmul0v ltxx. -rewrite /axialcomp scalerA vec_anglevZ // divr_gt0 // ?norm_gt0 //. -by rewrite /normalize dotmulZv mulr_gt0 // invr_gt0 norm_gt0. +rewrite /axialcomp scalerA vec_anglevZ // divr_gt0 ?enorm_gt0//. +by rewrite /normalize dotmulZv mulr_gt0 // invr_gt0 enorm_gt0. Qed. Definition normalcomp v e := v - axialcomp v e. @@ -594,7 +596,7 @@ Definition normalcomp v e := v - axialcomp v e. Lemma axialnormalcomp v e : v = axialcomp v e + normalcomp v e. Proof. by rewrite /axialcomp /normalcomp addrC subrK. Qed. -Lemma normalcompE v e : normalcomp v e = v *m (1 - norm e ^-2 *: (e^T *m e)). +Lemma normalcompE v e : normalcomp v e = v *m (1 - `|e|_e ^-2 *: (e^T *m e)). Proof. by rewrite /normalcomp axialcompE -mulmxA scalemxAr -{1}(mulmx1 v) -mulmxBr. Qed. @@ -618,7 +620,7 @@ Lemma normalcompB v1 v2 : normalcomp (v1 - v2) v2 = normalcomp v1 v2. Proof. apply/esym/eqP. rewrite /normalcomp subr_eq /axialcomp -scaleNr -!addrA -scalerDl -dotmulvN. -rewrite -dotmulDr opprB subrK dotmulC dotmul_normalize_norm. +rewrite -dotmulDr opprB subrK dotmulC dotmul_normalize_enorm. by rewrite norm_scale_normalize addrA subrK. Qed. @@ -644,10 +646,10 @@ Qed. Lemma dotmul_normalcomp v e : normalcomp v e *d e = 0. Proof. -case/boolP : (e == 0) => [/eqP ->|?]; first by rewrite dotmulv0. +have [->|?] := eqVneq e 0; first by rewrite dotmulv0. rewrite /normalcomp dotmulBl !dotmulZv dotmulvv (exprD _ 1 1) expr1. -rewrite (mulrA (_^-1)) mulVr ?unitfE ?norm_eq0 // mul1r mulrAC. -by rewrite mulVr ?unitfE ?norm_eq0 // mul1r dotmulC subrr. +rewrite (mulrA (_^-1)) mulVr ?unitfE ?enorm_eq0// mul1r mulrAC. +by rewrite mulVr ?unitfE ?enorm_eq0// mul1r dotmulC subrr. Qed. Lemma axialnormal v e : axialcomp v e *d normalcomp v e = 0. @@ -673,7 +675,7 @@ rewrite -scalemxAr -scalemxAl; congr (_ *: _). by rewrite -{1}uQu trmx_mul !mulmxA orthogonal_mul_tr // mul1mx -mulmxA uQu. Qed. -Lemma normalcomp_mul_tr e (e1 : norm e = 1) : normalcomp 'e_0 e *m e^T == 0. +Lemma normalcomp_mul_tr e (e1 : `|e|_e = 1) : normalcomp 'e_0 e *m e^T == 0. Proof. rewrite /normalcomp mulmxBl -scalemxAl -scalemxAl dotmul1 // dotmulC /dotmul. by rewrite e1 invr1 scalemx1 scalemx1 normalizeI // {1}dotmulP subrr. @@ -685,11 +687,11 @@ Lemma dotmul_orthogonalize v e : e *d orthogonalize v e = 0. Proof. rewrite /normalcomp /normalize dotmulBr !(dotmulZv, dotmulvZ). rewrite mulrACA -invfM -expr2 dotmulvv mulrCA. -have [->|u_neq0] := eqVneq e 0; first by rewrite norm0 invr0 dotmul0v !mul0r subrr. +have [->|u_neq0] := eqVneq e 0; first by rewrite enorm0 invr0 dotmul0v !mul0r subrr. rewrite norm_normalize // expr1n invr1 mul1r. rewrite (mulrC _ (e *d _)). rewrite -mulrA (mulrA (_^-1)) -expr2 -exprMn mulVr ?expr1n ?mulr1 ?subrr //. -by rewrite unitfE norm_eq0. +by rewrite unitfE enorm_eq0. Qed. End axial_normal_decomposition. @@ -764,32 +766,32 @@ Lemma cos0sin1 [R : realType] [x : R] : cos x = 0 -> `|sin x| = 1. Proof. by move/eqP; rewrite -norm_sin_eq1 => /eqP. Qed. Lemma triangle_sin_vector_helper v1 v2 : ~~ colinear v1 v2 -> - norm v1 ^+ 2 * sin (vec_angle v1 v2) ^+ 2 = norm (normalcomp v1 v2) ^+ 2. + `|v1|_e ^+ 2 * sin (vec_angle v1 v2) ^+ 2 = `|normalcomp v1 v2|_e ^+ 2. Proof. move=> H. have v10 : v1 != 0 by apply: contra H => /eqP ->; rewrite colinear0. have v20 : v2 != 0 by apply: contra H => /eqP ->; rewrite colinear_sym colinear0. -rewrite /normalcomp [in RHS]normB. +rewrite /normalcomp [in RHS]enormB. case/boolP : (0 < v2 *d v1) => [v2v1|]. - rewrite normZ gtr0_norm; last first. - by rewrite dotmulZv mulr_gt0 // invr_gt0 norm_gt0. + rewrite enormZ gtr0_norm; last first. + by rewrite dotmulZv mulr_gt0 // invr_gt0 enorm_gt0. rewrite norm_normalize // mulr1 vec_angle_axialcomp //. rewrite dotmul_cos norm_normalize // mul1r vec_angleZv; last first. - by rewrite invr_gt0 norm_gt0. + by rewrite invr_gt0 enorm_gt0. rewrite [in RHS]mulrA (vec_angleC v1) -expr2 -mulrA -expr2 exprMn. by rewrite mulr2n opprD addrA subrK sin2cos2 mulrBr mulr1. rewrite -leNgt le_eqVlt => /orP[|v2v1]. - rewrite {1}dotmul_cos -mulrA mulf_eq0 norm_eq0 (negbTE v20) /=. - rewrite mulf_eq0 norm_eq0 (negbTE v10) /= => /eqP Hcos. + rewrite {1}dotmul_cos -mulrA mulf_eq0 enorm_eq0 (negbTE v20) /=. + rewrite mulf_eq0 enorm_eq0 (negbTE v10) /= => /eqP Hcos. rewrite axialcomp_dotmul; last by rewrite dotmul_cos Hcos mulr0. - rewrite norm0 mulr0 mul0r expr0n mul0rn addr0 subr0. + rewrite enorm0 mulr0 mul0r expr0n mul0rn addr0 subr0. by rewrite -(sqr_normr (sin _)) vec_angleC cos0sin1 ?expr1n ?mulr1. rewrite vec_anglevZN //; last first. - by rewrite /normalize dotmulZv pmulr_rlt0 // invr_gt0 norm_gt0. + by rewrite /normalize dotmulZv pmulr_rlt0 // invr_gt0 enorm_gt0. rewrite cos_vec_anglevN // ?normalize_eq0 //. -rewrite norm_axialcomp // !(mulrN,mulNr,opprK,sqrrN). -rewrite vec_anglevZ // ?invr_gt0 ?norm_gt0 //. -rewrite dotmul_cos norm_normalize // mul1r vec_angleZv ?invr_gt0 ?norm_gt0 //. +rewrite enorm_axialcomp // !(mulrN,mulNr,opprK,sqrrN). +rewrite vec_anglevZ // ?invr_gt0 ?enorm_gt0//. +rewrite dotmul_cos norm_normalize // mul1r vec_angleZv ?invr_gt0 ?enorm_gt0//. rewrite (vec_angleC v2) -!mulrA -expr2 exprMn addrAC -addrA -mulrA -mulrnAr. rewrite -mulrBr mulr2n opprD addrA subrr sub0r. rewrite mulrA -expr2 mulrN mulrA -expr2. @@ -797,27 +799,27 @@ by rewrite sin2cos2 mulrBr mulr1. Qed. Lemma triangle_sin_vector v1 v2 : ~~ colinear v1 v2 -> - sin (vec_angle v1 v2) = norm (normalcomp v1 v2) / norm v1. + sin (vec_angle v1 v2) = `|normalcomp v1 v2|_e / `|v1|_e. Proof. move=> H. have v10 : v1 != 0 by apply: contra H => /eqP ->; rewrite colinear0. have v20 : v2 != 0 by apply: contra H => /eqP ->; rewrite colinear_sym colinear0. apply/eqP. -rewrite -(@eqrXn2 _ 2) // ?divr_ge0 // ?norm_ge0 // ?sin_vec_angle_ge0 //. +rewrite -(@eqrXn2 _ 2) // ?divr_ge0 ?enorm_ge0// ?sin_vec_angle_ge0 //. rewrite exprMn -triangle_sin_vector_helper // mulrAC exprVn divrr ?mul1r //. -by rewrite unitfE sqrf_eq0 norm_eq0. +by rewrite unitfE sqrf_eq0 enorm_eq0. Qed. Lemma triangle_sin_point (p1 p2 p : 'rV[T]_3) : ~~ tricolinear p1 p2 p -> let v1 := p1 - p in let v2 := p2 - p in - sin (vec_angle v1 v2) = norm (normalcomp v1 v2) / norm v1. + sin (vec_angle v1 v2) = `|normalcomp v1 v2|_e / `|v1|_e. Proof. move=> H v1 v2; apply triangle_sin_vector; apply: contra H. by rewrite tricolinear_perm 2!tricolinear_rot /tricolinear /v1 /v2 colinear_sym. Qed. Lemma law_of_sines_vector v1 v2 : ~~ colinear v1 v2 -> - sin (vec_angle v1 v2) / norm (v2 - v1) = sin (vec_angle (v2 - v1) v2) / norm v1. + sin (vec_angle v1 v2) / `|v2 - v1|_e = sin (vec_angle (v2 - v1) v2) / `|v1|_e. Proof. move=> H. move: (triangle_sin_vector H) => /= H1. @@ -826,16 +828,16 @@ have H' : ~~ colinear v2 (v2 - v1). rewrite colinear_sym; apply: contra H => H. move: (colinear_refl v2); rewrite -colinearNv => /(colinearD H). by rewrite addrAC subrr add0r colinearNv. -have H2 : sin (vec_angle v2 (v2 - v1)) = norm (normalcomp (v2 - v1) v2) / norm (v2 - v1). +have H2 : sin (vec_angle v2 (v2 - v1)) = `|normalcomp (v2 - v1) v2|_e / `|v2 - v1|_e. rewrite vec_angleC; apply triangle_sin_vector; by rewrite colinear_sym. rewrite [in RHS]vec_angleC [in RHS]H2. -by rewrite -normalcompB mulrAC -(opprB v2) normalcompNv normN. +by rewrite -normalcompB mulrAC -(opprB v2) normalcompNv enormN. Qed. Lemma law_of_sines_point (p1 p2 p : 'rV[T]_3) : ~~ tricolinear p1 p2 p -> let v1 := p1 - p in let v2 := p2 - p in - sin (vec_angle v1 v2) / norm (p2 - p1) = - sin (vec_angle (p2 - p1) (p2 - p)) / norm (p1 - p). + sin (vec_angle v1 v2) / `|p2 - p1|_e = + sin (vec_angle (p2 - p1) (p2 - p)) / `|p1 - p|_e. Proof. move=> H v1 v2. rewrite (_ : p2 - p1 = v2 - v1); last by rewrite /v1 /v2 opprB addrA subrK. @@ -1065,7 +1067,7 @@ Variable T : rcfType. Let point := 'rV[T]_3. Definition distance_point_line (p : point) l : T := - norm ((p - \pt( l )) *v \vec( l )) / norm \vec( l ). + `|(p - \pt( l )) *v \vec( l )|_e / `|\vec( l )|_e. Definition distance_between_lines (l1 l2 : Line.t T) : T := if intersects l1 l2 then @@ -1074,6 +1076,6 @@ Definition distance_between_lines (l1 l2 : Line.t T) : T := distance_point_line \pt( l1 ) l2 else (* skew lines *) let n := \vec( l1 ) *v \vec( l2 ) in - `| (\pt( l2 ) - \pt( l1 )) *d n | / norm n. + `| (\pt( l2 ) - \pt( l1 )) *d n | / `|n|_e. End distance_line.