openrr_client/
robot_client.rs

1use std::{
2    collections::HashMap,
3    path::{Path, PathBuf},
4    sync::Arc,
5    time::Duration,
6};
7
8use arci::{
9    BaseVelocity, Error as ArciError, JointTrajectoryClient, JointTrajectoryClientsContainer,
10    Localization, MoveBase, Navigation, Speaker, WaitFuture,
11};
12use k::{nalgebra::Isometry2, Chain, Isometry3};
13use openrr_planner::{
14    collision::parse_colon_separated_pairs, JointPathPlannerConfig, SelfCollisionChecker,
15    SelfCollisionCheckerConfig,
16};
17use schemars::JsonSchema;
18use serde::{Deserialize, Serialize};
19use tracing::debug;
20
21use crate::{
22    create_collision_avoidance_client, create_collision_check_client, create_ik_solver_with_chain,
23    CollisionAvoidanceClient, CollisionCheckClient, Error, IkClient, IkSolverConfig,
24    IkSolverWithChain,
25};
26
27type ArcCollisionAvoidanceClient = Arc<CollisionAvoidanceClient<Arc<dyn JointTrajectoryClient>>>;
28type ArcIkClient = Arc<IkClient<Arc<dyn JointTrajectoryClient>>>;
29pub type ArcRobotClient =
30    RobotClient<Arc<dyn Localization>, Arc<dyn MoveBase>, Arc<dyn Navigation>>;
31pub type BoxRobotClient =
32    RobotClient<Box<dyn Localization>, Box<dyn MoveBase>, Box<dyn Navigation>>;
33
34type ArcJointTrajectoryClient = Arc<dyn JointTrajectoryClient>;
35
36pub struct RobotClient<L, M, N>
37where
38    L: Localization,
39    M: MoveBase,
40    N: Navigation,
41{
42    full_chain_for_collision_checker: Option<Arc<Chain<f64>>>,
43    raw_joint_trajectory_clients: HashMap<String, Arc<dyn JointTrajectoryClient>>,
44    all_joint_trajectory_clients: HashMap<String, Arc<dyn JointTrajectoryClient>>,
45    collision_avoidance_clients: HashMap<String, ArcCollisionAvoidanceClient>,
46    collision_check_clients:
47        HashMap<String, Arc<CollisionCheckClient<Arc<dyn JointTrajectoryClient>>>>,
48    ik_clients: HashMap<String, ArcIkClient>,
49    self_collision_checkers: HashMap<String, Arc<SelfCollisionChecker<f64>>>,
50    ik_solvers: HashMap<String, Arc<IkSolverWithChain>>,
51    speakers: HashMap<String, Arc<dyn Speaker>>,
52    localization: Option<L>,
53    move_base: Option<M>,
54    navigation: Option<N>,
55    joints_poses: HashMap<String, HashMap<String, Vec<f64>>>,
56}
57
58impl<L, M, N> RobotClient<L, M, N>
59where
60    L: Localization,
61    M: MoveBase,
62    N: Navigation,
63{
64    pub fn new(
65        config: OpenrrClientsConfig,
66        raw_joint_trajectory_clients: HashMap<String, Arc<dyn JointTrajectoryClient>>,
67        speakers: HashMap<String, Arc<dyn Speaker>>,
68        localization: Option<L>,
69        move_base: Option<M>,
70        navigation: Option<N>,
71    ) -> Result<Self, Error> {
72        debug!("{config:?}");
73
74        let mut all_joint_trajectory_clients = HashMap::new();
75        for (name, client) in &raw_joint_trajectory_clients {
76            all_joint_trajectory_clients.insert(name.to_owned(), client.clone());
77        }
78        for container_config in &config.joint_trajectory_clients_container_configs {
79            let mut clients = vec![];
80            for name in &container_config.clients_names {
81                clients.push(raw_joint_trajectory_clients[name].clone())
82            }
83            all_joint_trajectory_clients.insert(
84                container_config.name.to_owned(),
85                Arc::new(JointTrajectoryClientsContainer::new(clients)),
86            );
87        }
88
89        let (
90            full_chain_for_collision_checker,
91            collision_avoidance_clients,
92            collision_check_clients,
93            ik_clients,
94            self_collision_checkers,
95            ik_solvers,
96        ) = if let Some(urdf_full_path) = config.urdf_full_path() {
97            debug!("Loading {urdf_full_path:?}");
98            let full_chain_for_collision_checker = Arc::new(Chain::from_urdf_file(urdf_full_path)?);
99
100            let collision_avoidance_clients = create_collision_avoidance_clients(
101                urdf_full_path,
102                &config.self_collision_check_pairs,
103                &config.collision_avoidance_clients_configs,
104                &all_joint_trajectory_clients,
105                full_chain_for_collision_checker.clone(),
106            );
107
108            for (name, client) in &collision_avoidance_clients {
109                all_joint_trajectory_clients.insert(name.to_owned(), client.clone());
110            }
111
112            let collision_check_clients = create_collision_check_clients(
113                urdf_full_path,
114                &config.self_collision_check_pairs,
115                &config.collision_check_clients_configs,
116                &all_joint_trajectory_clients,
117                full_chain_for_collision_checker.clone(),
118            );
119
120            let mut self_collision_checkers = HashMap::new();
121
122            for (name, client) in &collision_check_clients {
123                self_collision_checkers.insert(name.to_owned(), client.collision_checker.clone());
124                all_joint_trajectory_clients.insert(name.to_owned(), client.clone());
125            }
126
127            let mut ik_solvers = HashMap::new();
128            for (k, c) in &config.ik_solvers_configs {
129                ik_solvers.insert(
130                    k.to_owned(),
131                    Arc::new(create_ik_solver_with_chain(
132                        &full_chain_for_collision_checker,
133                        c,
134                    )),
135                );
136            }
137
138            let ik_clients = create_ik_clients(
139                &config.ik_clients_configs,
140                &all_joint_trajectory_clients,
141                &ik_solvers,
142            );
143
144            for (name, client) in &ik_clients {
145                all_joint_trajectory_clients.insert(name.to_owned(), client.clone());
146            }
147            (
148                Some(full_chain_for_collision_checker),
149                collision_avoidance_clients,
150                collision_check_clients,
151                ik_clients,
152                self_collision_checkers,
153                ik_solvers,
154            )
155        } else {
156            (
157                None,
158                HashMap::new(),
159                HashMap::new(),
160                HashMap::new(),
161                HashMap::new(),
162                HashMap::new(),
163            )
164        };
165        let mut joints_poses: HashMap<String, HashMap<String, Vec<f64>>> = HashMap::new();
166        for joints_pose in &config.joints_poses {
167            joints_poses
168                .entry(joints_pose.client_name.clone())
169                .or_default()
170                .insert(
171                    joints_pose.pose_name.to_owned(),
172                    joints_pose.positions.to_owned(),
173                );
174        }
175        Ok(Self {
176            full_chain_for_collision_checker,
177            raw_joint_trajectory_clients,
178            all_joint_trajectory_clients,
179            collision_avoidance_clients,
180            collision_check_clients,
181            ik_clients,
182            self_collision_checkers,
183            ik_solvers,
184            speakers,
185            localization,
186            move_base,
187            navigation,
188            joints_poses,
189        })
190    }
191
192    /// Set the current joint positions to the robot kinematic model.
193    ///
194    /// Returns Error::FullChainNotFound when self.full_chain_for_collision_checker is None.
195    pub fn set_raw_clients_joint_positions_to_full_chain_for_collision_checker(
196        &self,
197    ) -> Result<(), Error> {
198        if self.full_chain_for_collision_checker.is_none() {
199            debug!("There are no full_chain_for_collision_checker");
200            return Err(Error::FullChainNotFound(
201                "set_raw_clients_joint_positions_to_full_chain_for_collision_checker is called"
202                    .to_owned(),
203            ));
204        }
205        for client in self.raw_joint_trajectory_clients.values() {
206            let positions = client.current_joint_positions()?;
207            let joint_names = client.joint_names();
208            if positions.len() != joint_names.len() {
209                return Err(Error::MismatchedLength(positions.len(), joint_names.len()));
210            }
211            for (index, joint_name) in joint_names.iter().enumerate() {
212                if let Some(joint) = self
213                    .full_chain_for_collision_checker
214                    .as_ref()
215                    .expect("full_chain_for_collision_checker not found")
216                    .find(joint_name)
217                {
218                    joint.set_joint_position_clamped(positions[index])
219                } else {
220                    return Err(ArciError::NoJoint(joint_name.to_owned()).into());
221                }
222            }
223        }
224        self.full_chain_for_collision_checker
225            .as_ref()
226            .expect("full_chain_for_collision_checker not found")
227            .update_transforms();
228        Ok(())
229    }
230
231    pub fn is_raw_joint_trajectory_client(&self, name: &str) -> bool {
232        self.raw_joint_trajectory_clients.contains_key(name)
233    }
234
235    pub fn is_joint_trajectory_client(&self, name: &str) -> bool {
236        self.all_joint_trajectory_clients.contains_key(name)
237    }
238
239    pub fn is_collision_avoidance_client(&self, name: &str) -> bool {
240        self.collision_avoidance_clients.contains_key(name)
241    }
242
243    pub fn is_collision_check_client(&self, name: &str) -> bool {
244        self.collision_check_clients.contains_key(name)
245    }
246
247    pub fn is_ik_client(&self, name: &str) -> bool {
248        self.ik_clients.contains_key(name)
249    }
250
251    fn joint_trajectory_client(
252        &self,
253        name: &str,
254    ) -> Result<&Arc<dyn JointTrajectoryClient>, Error> {
255        if self.is_joint_trajectory_client(name) {
256            Ok(&self.all_joint_trajectory_clients[name])
257        } else {
258            Err(Error::NoJointTrajectoryClient(name.to_owned()))
259        }
260    }
261
262    fn ik_client(&self, name: &str) -> Result<&ArcIkClient, Error> {
263        if self.is_ik_client(name) {
264            Ok(&self.ik_clients[name])
265        } else {
266            Err(Error::NoIkClient(name.to_owned()))
267        }
268    }
269
270    pub fn joint_trajectory_clients(&self) -> &HashMap<String, Arc<dyn JointTrajectoryClient>> {
271        &self.all_joint_trajectory_clients
272    }
273
274    pub fn self_collision_checkers(&self) -> &HashMap<String, Arc<SelfCollisionChecker<f64>>> {
275        &self.self_collision_checkers
276    }
277
278    pub fn ik_solvers(&self) -> &HashMap<String, Arc<IkSolverWithChain>> {
279        &self.ik_solvers
280    }
281
282    pub fn collision_avoidance_clients(&self) -> &HashMap<String, ArcCollisionAvoidanceClient> {
283        &self.collision_avoidance_clients
284    }
285
286    pub fn ik_clients(&self) -> &HashMap<String, ArcIkClient> {
287        &self.ik_clients
288    }
289
290    pub fn send_joint_positions(
291        &self,
292        name: &str,
293        positions: &[f64],
294        duration_sec: f64,
295    ) -> Result<WaitFuture, Error> {
296        if self.full_chain_for_collision_checker.is_some() {
297            self.set_raw_clients_joint_positions_to_full_chain_for_collision_checker()?;
298        }
299        if self.is_ik_client(name) {
300            Ok(self.ik_client(name)?.client.send_joint_positions(
301                positions.to_owned(),
302                Duration::from_secs_f64(duration_sec),
303            )?)
304        } else {
305            Ok(self.joint_trajectory_client(name)?.send_joint_positions(
306                positions.to_owned(),
307                Duration::from_secs_f64(duration_sec),
308            )?)
309        }
310    }
311
312    pub fn current_joint_positions(&self, name: &str) -> Result<Vec<f64>, Error> {
313        if self.is_ik_client(name) {
314            self.set_raw_clients_joint_positions_to_full_chain_for_collision_checker()?;
315            Ok(self.ik_client(name)?.current_joint_positions()?)
316        } else {
317            Ok(self
318                .joint_trajectory_client(name)?
319                .current_joint_positions()?)
320        }
321    }
322
323    /// Returns the joint names which is handled by the joint trajectory client with `name`
324    pub fn joint_names(&self, name: &str) -> Result<Vec<String>, Error> {
325        Ok(self.joint_trajectory_client(name)?.joint_names())
326    }
327
328    pub fn send_joints_pose(
329        &self,
330        name: &str,
331        pose_name: &str,
332        duration_sec: f64,
333    ) -> Result<WaitFuture, Error> {
334        if self.joints_poses.contains_key(name) && self.joints_poses[name].contains_key(pose_name) {
335            Ok(self.send_joint_positions(
336                name,
337                &self.joints_poses[name][pose_name],
338                duration_sec,
339            )?)
340        } else {
341            Err(Error::NoJointsPose(name.to_owned(), pose_name.to_owned()))
342        }
343    }
344
345    pub fn current_end_transform(&self, name: &str) -> Result<Isometry3<f64>, Error> {
346        self.set_raw_clients_joint_positions_to_full_chain_for_collision_checker()?;
347        Ok(self.ik_client(name)?.current_end_transform()?)
348    }
349
350    pub fn transform(&self, name: &str, pose: &Isometry3<f64>) -> Result<Isometry3<f64>, Error> {
351        self.set_raw_clients_joint_positions_to_full_chain_for_collision_checker()?;
352        Ok(self.ik_client(name)?.transform(pose)?)
353    }
354
355    pub fn move_ik(
356        &self,
357        name: &str,
358        target_pose: &Isometry3<f64>,
359        duration_sec: f64,
360    ) -> Result<WaitFuture, Error> {
361        self.set_raw_clients_joint_positions_to_full_chain_for_collision_checker()?;
362        Ok(self.ik_client(name)?.move_ik(target_pose, duration_sec)?)
363    }
364
365    pub fn move_ik_with_interpolation(
366        &self,
367        name: &str,
368        target_pose: &Isometry3<f64>,
369        duration_sec: f64,
370        max_resolution: f64,
371        min_number_of_points: i32,
372    ) -> Result<WaitFuture, Error> {
373        self.set_raw_clients_joint_positions_to_full_chain_for_collision_checker()?;
374        Ok(self.ik_client(name)?.move_ik_with_interpolation(
375            target_pose,
376            duration_sec,
377            max_resolution,
378            min_number_of_points,
379        )?)
380    }
381
382    pub fn send_joint_positions_with_pose_interpolation(
383        &self,
384        name: &str,
385        positions: &[f64],
386        duration_sec: f64,
387        max_resolution: f64,
388        min_number_of_points: i32,
389    ) -> Result<WaitFuture, Error> {
390        self.set_raw_clients_joint_positions_to_full_chain_for_collision_checker()?;
391        let target_pose = {
392            let ik_client = self.ik_client(name)?;
393            ik_client.set_joint_positions_clamped(positions);
394            ik_client.ik_solver_with_chain.end_transform()
395        };
396        self.move_ik_with_interpolation(
397            name,
398            &target_pose,
399            duration_sec,
400            max_resolution,
401            min_number_of_points,
402        )
403    }
404
405    pub fn raw_joint_trajectory_clients_names(&self) -> Vec<String> {
406        self.raw_joint_trajectory_clients
407            .keys()
408            .map(|k| k.to_owned())
409            .collect::<Vec<String>>()
410    }
411
412    pub fn joint_trajectory_clients_names(&self) -> Vec<String> {
413        self.all_joint_trajectory_clients
414            .keys()
415            .map(|k| k.to_owned())
416            .collect::<Vec<String>>()
417    }
418
419    pub fn collision_avoidance_clients_names(&self) -> Vec<String> {
420        self.collision_avoidance_clients
421            .keys()
422            .map(|k| k.to_owned())
423            .collect::<Vec<String>>()
424    }
425
426    pub fn collision_check_clients_names(&self) -> Vec<String> {
427        self.collision_check_clients
428            .keys()
429            .map(|k| k.to_owned())
430            .collect::<Vec<String>>()
431    }
432
433    pub fn ik_clients_names(&self) -> Vec<String> {
434        self.ik_clients
435            .keys()
436            .map(|k| k.to_owned())
437            .collect::<Vec<String>>()
438    }
439
440    pub fn full_chain_for_collision_checker(&self) -> &Option<Arc<Chain<f64>>> {
441        &self.full_chain_for_collision_checker
442    }
443
444    pub fn speakers(&self) -> &HashMap<String, Arc<dyn Speaker>> {
445        &self.speakers
446    }
447
448    pub fn speak(&self, name: &str, message: &str) -> Result<WaitFuture, Error> {
449        match self.speakers.get(name) {
450            Some(speaker) => Ok(speaker.speak(message)?),
451            _ => Err(anyhow::format_err!("Speaker \"{name}\" is not found.").into()),
452        }
453    }
454}
455
456impl<L, M, N> Localization for RobotClient<L, M, N>
457where
458    L: Localization,
459    M: MoveBase,
460    N: Navigation,
461{
462    fn current_pose(&self, frame_id: &str) -> Result<Isometry2<f64>, ArciError> {
463        self.localization.as_ref().unwrap().current_pose(frame_id)
464    }
465}
466
467impl<L, M, N> Navigation for RobotClient<L, M, N>
468where
469    L: Localization,
470    M: MoveBase,
471    N: Navigation,
472{
473    fn send_goal_pose(
474        &self,
475        goal: Isometry2<f64>,
476        frame_id: &str,
477        timeout: std::time::Duration,
478    ) -> Result<WaitFuture, ArciError> {
479        self.navigation
480            .as_ref()
481            .unwrap()
482            .send_goal_pose(goal, frame_id, timeout)
483    }
484
485    fn cancel(&self) -> Result<(), ArciError> {
486        self.navigation.as_ref().unwrap().cancel()
487    }
488}
489
490impl<L, M, N> MoveBase for RobotClient<L, M, N>
491where
492    L: Localization,
493    M: MoveBase,
494    N: Navigation,
495{
496    fn send_velocity(&self, velocity: &BaseVelocity) -> Result<(), ArciError> {
497        self.move_base.as_ref().unwrap().send_velocity(velocity)
498    }
499
500    fn current_velocity(&self) -> Result<BaseVelocity, ArciError> {
501        self.move_base.as_ref().unwrap().current_velocity()
502    }
503}
504
505#[derive(Debug, Serialize, Deserialize, Clone, JsonSchema)]
506#[serde(deny_unknown_fields)]
507pub struct JointTrajectoryClientsContainerConfig {
508    pub name: String,
509    pub clients_names: Vec<String>,
510}
511
512#[derive(Debug, Serialize, Deserialize, Clone, Default, JsonSchema)]
513#[serde(deny_unknown_fields)]
514pub struct OpenrrClientsConfig {
515    pub urdf_path: Option<String>,
516    urdf_full_path: Option<PathBuf>,
517    #[serde(default)]
518    pub self_collision_check_pairs: Vec<String>,
519
520    #[serde(default)]
521    // https://github.com/alexcrichton/toml-rs/issues/258
522    #[serde(skip_serializing_if = "Vec::is_empty")]
523    pub joint_trajectory_clients_container_configs: Vec<JointTrajectoryClientsContainerConfig>,
524    #[serde(default)]
525    // https://github.com/alexcrichton/toml-rs/issues/258
526    #[serde(skip_serializing_if = "Vec::is_empty")]
527    pub collision_avoidance_clients_configs: Vec<CollisionAvoidanceClientConfig>,
528    #[serde(default)]
529    // https://github.com/alexcrichton/toml-rs/issues/258
530    #[serde(skip_serializing_if = "Vec::is_empty")]
531    pub collision_check_clients_configs: Vec<CollisionCheckClientConfig>,
532    #[serde(default)]
533    // https://github.com/alexcrichton/toml-rs/issues/258
534    #[serde(skip_serializing_if = "Vec::is_empty")]
535    pub ik_clients_configs: Vec<IkClientConfig>,
536    #[serde(default)]
537    pub ik_solvers_configs: HashMap<String, IkSolverConfig>,
538
539    #[serde(default)]
540    // https://github.com/alexcrichton/toml-rs/issues/258
541    #[serde(skip_serializing_if = "Vec::is_empty")]
542    pub joints_poses: Vec<JointsPose>,
543}
544
545/// Make relative path into absolute path from base file (not base dir).
546///
547/// # Example
548/// ```
549/// use std::path::PathBuf;
550/// let abs_path = openrr_client::resolve_relative_path("/home/a/base_file.toml", "../another_file.mp3").unwrap();
551/// assert_eq!(abs_path, PathBuf::from("/home/a/../another_file.mp3"));
552/// ```
553pub fn resolve_relative_path<B: AsRef<Path>, P: AsRef<Path>>(
554    base_path: B,
555    path: P,
556) -> Result<PathBuf, Error> {
557    Ok(base_path
558        .as_ref()
559        .parent()
560        .ok_or_else(|| Error::NoParentDirectory(base_path.as_ref().to_owned()))?
561        .join(path))
562}
563
564impl OpenrrClientsConfig {
565    pub fn resolve_path<P: AsRef<Path>>(&mut self, path: P) -> Result<(), Error> {
566        if let Some(urdf_path) = self.urdf_path.as_ref() {
567            // TODO: pass Some(config_file_dir)
568            let urdf_path = openrr_config::evaluate(urdf_path, None)?;
569            self.urdf_full_path = Some(resolve_relative_path(path, urdf_path)?);
570        } else {
571            return Err(Error::NoUrdfPath);
572        }
573        Ok(())
574    }
575
576    pub fn urdf_full_path(&self) -> Option<&Path> {
577        self.urdf_full_path.as_deref()
578    }
579}
580
581#[derive(Debug, Serialize, Deserialize, Clone, JsonSchema)]
582#[serde(deny_unknown_fields)]
583pub struct JointsPose {
584    pub pose_name: String,
585    pub client_name: String,
586    pub positions: Vec<f64>,
587}
588
589#[derive(Clone, Serialize, Deserialize, Debug, JsonSchema)]
590#[serde(deny_unknown_fields)]
591pub struct IkClientConfig {
592    pub name: String,
593    pub client_name: String,
594    pub solver_name: String,
595}
596
597pub fn create_ik_clients(
598    configs: &[IkClientConfig],
599    name_to_joint_trajectory_client: &HashMap<String, ArcJointTrajectoryClient>,
600    name_to_ik_solvers: &HashMap<String, Arc<IkSolverWithChain>>,
601) -> HashMap<String, Arc<IkClient<ArcJointTrajectoryClient>>> {
602    let mut clients = HashMap::new();
603    for config in configs {
604        clients.insert(
605            config.name.clone(),
606            Arc::new(IkClient::new(
607                name_to_joint_trajectory_client[&config.client_name].clone(),
608                name_to_ik_solvers[&config.solver_name].clone(),
609            )),
610        );
611    }
612    clients
613}
614
615#[derive(Clone, Serialize, Deserialize, Debug, JsonSchema)]
616#[serde(deny_unknown_fields)]
617pub struct CollisionAvoidanceClientConfig {
618    pub name: String,
619    pub client_name: String,
620    #[serde(default)]
621    pub joint_path_planner_config: JointPathPlannerConfig,
622}
623
624pub fn create_collision_avoidance_clients<P: AsRef<Path>>(
625    urdf_path: P,
626    self_collision_check_pairs: &[String],
627    configs: &[CollisionAvoidanceClientConfig],
628    name_to_joint_trajectory_client: &HashMap<String, Arc<dyn JointTrajectoryClient>>,
629    full_chain: Arc<k::Chain<f64>>,
630) -> HashMap<String, Arc<CollisionAvoidanceClient<Arc<dyn JointTrajectoryClient>>>> {
631    let mut clients = HashMap::new();
632    for config in configs {
633        clients.insert(
634            config.name.clone(),
635            Arc::new(create_collision_avoidance_client(
636                &urdf_path,
637                parse_colon_separated_pairs(self_collision_check_pairs).unwrap(),
638                &config.joint_path_planner_config,
639                name_to_joint_trajectory_client[&config.client_name].clone(),
640                full_chain.clone(),
641            )),
642        );
643    }
644    clients
645}
646
647#[derive(Clone, Serialize, Deserialize, Debug, JsonSchema)]
648#[serde(deny_unknown_fields)]
649pub struct CollisionCheckClientConfig {
650    pub name: String,
651    pub client_name: String,
652    #[serde(default)]
653    pub self_collision_checker_config: SelfCollisionCheckerConfig,
654}
655
656pub fn create_collision_check_clients<P: AsRef<Path>>(
657    urdf_path: P,
658    self_collision_check_pairs: &[String],
659    configs: &[CollisionCheckClientConfig],
660    name_to_joint_trajectory_client: &HashMap<String, Arc<dyn JointTrajectoryClient>>,
661    full_chain: Arc<k::Chain<f64>>,
662) -> HashMap<String, Arc<CollisionCheckClient<Arc<dyn JointTrajectoryClient>>>> {
663    let mut clients = HashMap::new();
664    for config in configs {
665        clients.insert(
666            config.name.clone(),
667            Arc::new(create_collision_check_client(
668                &urdf_path,
669                self_collision_check_pairs,
670                &config.self_collision_checker_config,
671                name_to_joint_trajectory_client[&config.client_name].clone(),
672                full_chain.clone(),
673            )),
674        );
675    }
676    clients
677}