arci_ros/
cmd_vel_move_base.rs1use arci::*;
2use schemars::JsonSchema;
3use serde::{Deserialize, Serialize};
4
5use crate::{msg, rosrust_utils::wait_subscriber};
6
7pub struct RosCmdVelMoveBase {
8 vel_publisher: rosrust::Publisher<msg::geometry_msgs::Twist>,
9}
10
11impl RosCmdVelMoveBase {
12 pub fn new(cmd_topic_name: &str) -> Self {
13 let vel_publisher = rosrust::publish(cmd_topic_name, 1).unwrap();
14 wait_subscriber(&vel_publisher);
15 Self { vel_publisher }
16 }
17}
18
19impl MoveBase for RosCmdVelMoveBase {
20 fn send_velocity(&self, velocity: &BaseVelocity) -> Result<(), Error> {
21 self.vel_publisher
22 .send((*velocity).into())
23 .map_err(|e| arci::Error::Connection {
24 message: format!("rosrust publish error: {e:?}"),
25 })
26 }
27
28 fn current_velocity(&self) -> Result<BaseVelocity, Error> {
29 Err(Error::Other(anyhow::Error::msg("not implemented yet")))
30 }
31}
32
33#[derive(Debug, Serialize, Deserialize, Clone, JsonSchema)]
34#[serde(deny_unknown_fields)]
35pub struct RosCmdVelMoveBaseConfig {
36 pub topic: String,
37}