ros2_interfaces_rolling/moveit_msgs/msg/
robot_state.rs1use serde::{Deserialize, Serialize};
2
3#[derive(Debug, Clone, PartialEq, Serialize, Deserialize)]
4pub struct RobotState {
5 pub joint_state: crate::sensor_msgs::msg::JointState,
6 pub multi_dof_joint_state: crate::sensor_msgs::msg::MultiDOFJointState,
7 pub attached_collision_objects: Vec<crate::moveit_msgs::msg::AttachedCollisionObject>,
8 pub is_diff: bool,
9}
10
11impl Default for RobotState {
12 fn default() -> Self {
13 RobotState {
14 joint_state: crate::sensor_msgs::msg::JointState::default(),
15 multi_dof_joint_state: crate::sensor_msgs::msg::MultiDOFJointState::default(),
16 attached_collision_objects: Vec::new(),
17 is_diff: false,
18 }
19 }
20}
21
22impl ros2_client::Message for RobotState {}