diff --git a/moveit_studio_msgs/moveit_studio_agent_msgs/CMakeLists.txt b/moveit_studio_msgs/moveit_studio_agent_msgs/CMakeLists.txt index 94de010..3591872 100644 --- a/moveit_studio_msgs/moveit_studio_agent_msgs/CMakeLists.txt +++ b/moveit_studio_msgs/moveit_studio_agent_msgs/CMakeLists.txt @@ -24,6 +24,7 @@ set(msg_files "msg/LicenseInfo.msg" "msg/Log.msg" "msg/PlanningGroup.msg" + "msg/RobotJointState.msg" "msg/Waypoint.msg" ) diff --git a/moveit_studio_msgs/moveit_studio_agent_msgs/msg/RobotJointState.msg b/moveit_studio_msgs/moveit_studio_agent_msgs/msg/RobotJointState.msg new file mode 100644 index 0000000..dfc1c8e --- /dev/null +++ b/moveit_studio_msgs/moveit_studio_agent_msgs/msg/RobotJointState.msg @@ -0,0 +1,5 @@ +# Contains the joint positions of single-dof joints (i.e. REVOLUTE, PRISMATIC) +sensor_msgs/JointState joint_state + +# Contains the joint positions of multi-dof joints (i.e. PLANAR, FLOATING). +sensor_msgs/MultiDOFJointState multi_dof_joint_state diff --git a/moveit_studio_msgs/moveit_studio_agent_msgs/srv/RetrieveJointState.srv b/moveit_studio_msgs/moveit_studio_agent_msgs/srv/RetrieveJointState.srv index 802c418..dec60f5 100644 --- a/moveit_studio_msgs/moveit_studio_agent_msgs/srv/RetrieveJointState.srv +++ b/moveit_studio_msgs/moveit_studio_agent_msgs/srv/RetrieveJointState.srv @@ -6,4 +6,4 @@ builtin_interfaces/Duration timeout --- bool success -sensor_msgs/JointState joint_state +moveit_studio_agent_msgs/RobotJointState robot_joint_state diff --git a/moveit_studio_msgs/moveit_studio_agent_msgs/srv/StoreJointState.srv b/moveit_studio_msgs/moveit_studio_agent_msgs/srv/StoreJointState.srv index 0f6ff87..2b8e8e9 100644 --- a/moveit_studio_msgs/moveit_studio_agent_msgs/srv/StoreJointState.srv +++ b/moveit_studio_msgs/moveit_studio_agent_msgs/srv/StoreJointState.srv @@ -1,6 +1,7 @@ # Service to store a joint state in the Parameter Manager sensor_msgs/JointState joint_state +sensor_msgs/MultiDOFJointState multi_dof_joint_state ---