arci_ros2/
plugin.rs

1use crate::{
2    Node, Ros2CmdVelMoveBase, Ros2CmdVelMoveBaseConfig, Ros2ControlClient, Ros2ControlConfig,
3    Ros2LaserScan2D, Ros2LaserScan2DConfig, Ros2LocalizationClient, Ros2LocalizationClientConfig,
4    Ros2Navigation, Ros2NavigationConfig,
5};
6
7openrr_plugin::export_plugin!(Ros2Plugin {});
8
9struct Ros2Plugin {}
10
11impl openrr_plugin::Plugin for Ros2Plugin {
12    fn new_joint_trajectory_client(
13        &self,
14        args: String,
15    ) -> Result<Option<Box<dyn arci::JointTrajectoryClient>>, arci::Error> {
16        let config: Ros2ControlConfig = toml::from_str(&args).map_err(anyhow::Error::from)?;
17        let node = Node::new("plugin_ros2_control_node", "arci_ros2")?;
18        let all_client = Ros2ControlClient::new(node, &config.action_name)?;
19        if config.joint_names.is_empty() {
20            Ok(Some(Box::new(all_client)))
21        } else {
22            Ok(Some(Box::new(arci::PartialJointTrajectoryClient::new(
23                config.joint_names,
24                all_client,
25            )?)))
26        }
27    }
28
29    fn new_move_base(&self, args: String) -> Result<Option<Box<dyn arci::MoveBase>>, arci::Error> {
30        let config: Ros2CmdVelMoveBaseConfig =
31            toml::from_str(&args).map_err(anyhow::Error::from)?;
32        let node = Node::new("plugin_cmd_vel_node", "arci_ros2")?;
33        Ok(Some(Box::new(Ros2CmdVelMoveBase::new(
34            node,
35            &config.cmd_vel_topic,
36            &config.odom_topic,
37        ))))
38    }
39
40    fn new_navigation(
41        &self,
42        args: String,
43    ) -> Result<Option<Box<dyn arci::Navigation>>, arci::Error> {
44        let config: Ros2NavigationConfig = toml::from_str(&args).map_err(anyhow::Error::from)?;
45        let node = Node::new("plugin_nav2_node", "arci_ros2")?;
46        Ok(Some(Box::new(Ros2Navigation::new(
47            node,
48            &config.action_name,
49        ))))
50    }
51
52    fn new_localization(
53        &self,
54        args: String,
55    ) -> Result<Option<Box<dyn arci::Localization>>, arci::Error> {
56        let config: Ros2LocalizationClientConfig =
57            toml::from_str(&args).map_err(anyhow::Error::from)?;
58        let node = Node::new("plugin_ros2_localization_node", "arci_ros2")?;
59        Ok(Some(Box::new(Ros2LocalizationClient::new(
60            node,
61            config.request_final_nomotion_update_hack,
62            &config.nomotion_update_service_name,
63            &config.amcl_pose_topic_name,
64        )?)))
65    }
66
67    fn new_laser_scan2_d(
68        &self,
69        args: String,
70    ) -> Result<Option<Box<dyn arci::LaserScan2D>>, arci::Error> {
71        let config: Ros2LaserScan2DConfig = toml::from_str(&args).map_err(anyhow::Error::from)?;
72        let node = Node::new("plugin_ros2_laser_scan_node", "arci_ros2")?;
73        Ok(Some(Box::new(Ros2LaserScan2D::new(node, &config.topic)?)))
74    }
75}