Skip to main content

dynamics_joint/
continuous.rs

1//! Continuous joint, constraining two objects to rotate around a given axis, without limits.
2//!
3//! This can be seen as a revolute joint without limits.
4//! On top of that, the parametrization of the configuration is different:
5//! instead of using an angle $\theta \in [-\pi, \pi]$, continuous joints use
6//! unit circle parametrization $(\cos(\theta), \sin(\theta))$.
7
8use dynamics_spatial::{
9    configuration::Configuration,
10    force::SpatialForce,
11    motion::{SpatialMotion, SpatialRotation},
12    se3::SE3,
13    vector3d::Vector3D,
14};
15use rand::Rng;
16
17use crate::{
18    joint::{JointModel, JointType, JointWrapper},
19    joint_data::{JointData, JointDataWrapper, JointError},
20    limits::JointLimits,
21};
22
23/// Model of a continuous joint.
24///
25/// This joint constraints two objects to rotate around a given axis, without limits.
26#[derive(Clone, Debug)]
27pub struct JointModelContinuous {
28    /// The axis of rotation expressed in the local frame of the joint.
29    pub axis: Vector3D,
30    /// The joint limits.
31    pub limits: JointLimits,
32}
33
34impl JointModelContinuous {
35    /// Creates a new `JointModelContinuous` with the given axis of rotation and unbounded limits.
36    ///
37    /// # Arguments
38    ///
39    /// * `axis` - The axis of rotation expressed in the local frame of the joint.
40    ///
41    /// # Returns
42    /// A new `JointModelContinuous` object.
43    #[must_use]
44    pub fn new(axis: Vector3D) -> Self {
45        let mut limits = JointLimits::new_unbounded(2);
46        limits.min_configuration[0] = -1.01;
47        limits.max_configuration[0] = 1.01;
48        limits.min_configuration[1] = -1.01;
49        limits.max_configuration[1] = 1.01;
50
51        JointModelContinuous { axis, limits }
52    }
53
54    /// Creates a new continuous joint model with `x` as axis of rotation.
55    ///
56    /// # Returns
57    /// A new `JointModelContinuous` object.
58    #[must_use]
59    pub fn new_rux() -> Self {
60        Self::new(Vector3D::x())
61    }
62
63    /// Creates a new continuous joint model with `y` as axis of rotation.
64    ///
65    /// # Returns
66    /// A new `JointModelContinuous` object.
67    #[must_use]
68    pub fn new_ruy() -> Self {
69        Self::new(Vector3D::y())
70    }
71
72    /// Creates a new continuous joint model with `z` as axis of rotation.
73    ///
74    /// # Returns
75    /// A new `JointModelContinuous` object.
76    #[must_use]
77    pub fn new_ruz() -> Self {
78        Self::new(Vector3D::z())
79    }
80}
81
82impl JointModel for JointModelContinuous {
83    fn get_joint_type(&self) -> JointType {
84        JointType::Continuous
85    }
86
87    fn nq(&self) -> usize {
88        2
89    }
90
91    fn nv(&self) -> usize {
92        1
93    }
94
95    fn neutral(&self) -> Configuration {
96        Configuration::from_row_slice(&[1.0, 0.0])
97    }
98
99    fn get_axis(&self) -> Vec<SpatialMotion> {
100        vec![SpatialMotion::from_rotational_axis(&self.axis)]
101    }
102
103    fn create_joint_data(&self) -> crate::joint_data::JointDataWrapper {
104        JointDataWrapper::continuous(JointDataContinuous::new(self))
105    }
106
107    fn random_configuration(&self, rng: &mut rand::rngs::ThreadRng) -> Configuration {
108        let angle: f64 = rng.random_range(0.0..(2.0 * std::f64::consts::PI));
109        Configuration::from_row_slice(&[angle.cos(), angle.sin()])
110    }
111
112    fn subspace(&self, v: &Configuration) -> SpatialMotion {
113        assert_eq!(
114            v.len(),
115            1,
116            "Continuous joint model expects a single velocity value."
117        );
118        v[0] * SpatialMotion::from_rotational_axis(&self.axis)
119    }
120
121    fn subspace_dual(&self, f: &SpatialForce) -> Configuration {
122        Configuration::from_row_slice(&[f.rotation().dot(&self.axis)])
123    }
124
125    fn bias(&self) -> SpatialMotion {
126        SpatialMotion::zero()
127    }
128}
129
130/// Data structure containing the mutable properties of a continuous joint.
131#[derive(Debug, Clone)]
132pub struct JointDataContinuous {
133    /// The joint configuration vector (cosine and sine of the angle).
134    pub joint_q: Configuration,
135    /// The joint velocity vector (angular velocity).
136    pub joint_v: Configuration,
137    /// The placement of the joint in the local frame.
138    pub placement: SE3,
139    /// The joint velocity as a spatial motion.
140    pub joint_velocity: SpatialMotion,
141}
142
143impl Default for JointDataContinuous {
144    fn default() -> Self {
145        JointDataContinuous {
146            joint_q: Configuration::from_row_slice(&[1.0, 0.0]),
147            joint_v: Configuration::from_row_slice(&[0.0]),
148            placement: SE3::identity(),
149            joint_velocity: SpatialMotion::zero(),
150        }
151    }
152}
153
154impl JointDataContinuous {
155    /// Creates a new `JointDataContinuous` object.
156    ///
157    /// # Arguments
158    ///
159    /// * `model` - The continuous joint model.
160    ///
161    /// # Returns
162    /// A new `JointDataContinuous` object.
163    #[must_use]
164    pub fn new(_joint_model: &JointModelContinuous) -> Self {
165        JointDataContinuous::default()
166    }
167
168    /// Returns the cosine of the joint angle.
169    #[must_use]
170    pub fn cos(&self) -> f64 {
171        self.joint_q[0]
172    }
173
174    /// Returns the sine of the joint angle.
175    #[must_use]
176    pub fn sin(&self) -> f64 {
177        self.joint_q[1]
178    }
179}
180
181impl JointData for JointDataContinuous {
182    fn get_joint_q(&self) -> &Configuration {
183        &self.joint_q
184    }
185
186    fn get_joint_v(&self) -> &Configuration {
187        &self.joint_v
188    }
189
190    fn update(
191        &mut self,
192        joint_model: &JointWrapper,
193        joint_q: &Configuration,
194        joint_v: Option<&Configuration>,
195    ) -> Result<(), JointError> {
196        // TODO: optimize this method to avoid computing the angle
197
198        assert_eq!(
199            joint_q.len(),
200            2,
201            "Continuous joint model expects two values (cosine and sine)."
202        );
203        if let Some(joint_v) = joint_v {
204            assert_eq!(
205                joint_v.len(),
206                1,
207                "Continuous joint model expects a single velocity value."
208            );
209        }
210
211        // store q and v
212        self.joint_q = joint_q.clone();
213        if let Some(joint_v) = joint_v {
214            self.joint_v = joint_v.clone();
215            self.joint_velocity = self.joint_v[0] * joint_model.get_axis()[0].clone();
216        }
217
218        // compute angle from cosine and sine
219        let angle = self.sin().atan2(self.cos());
220
221        // get axis
222        let axis = match joint_model.get_axis().len() {
223            1 => &joint_model.get_axis()[0],
224            _ => return Err(JointError::MissingAttributeError("axis".to_string())),
225        };
226
227        // compute placement
228        let rot = SpatialRotation::from_axis_angle(&axis.rotation(), angle);
229        self.placement = rot.to_se3(&Vector3D::zeros());
230
231        Ok(())
232    }
233
234    fn get_joint_placement(&self) -> SE3 {
235        self.placement
236    }
237
238    fn get_joint_velocity(&self) -> &SpatialMotion {
239        &self.joint_velocity
240    }
241}