Skip to content

Commit e4370b0

Browse files
authored
add end-effector info to PlanningGroup msg (#84)
1 parent afb30a4 commit e4370b0

File tree

3 files changed

+16
-2
lines changed

3 files changed

+16
-2
lines changed

moveit_studio_msgs/moveit_studio_agent_msgs/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@ find_package(std_msgs REQUIRED)
1818
set(msg_files
1919
"msg/AgentInfo.msg"
2020
"msg/ClientInfo.msg"
21+
"msg/EndEffector.msg"
2122
"msg/Event.msg"
2223
"msg/FaultStatus.msg"
2324
"msg/Json.msg"
Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
# The name of the end-effector, as defined in the SRDF.
2+
string name
3+
4+
# The name of the group that contains the links and joints that make up the end-effector.
5+
string group
6+
7+
# The name of the parent group this end-effector is attached to.
8+
string parent_group
9+
10+
# The name of the link in the parent group this end-effector is attached to.
11+
string parent_link
Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,7 @@
11
# Name of the planning group, as defined in the SRDF.
22
string name
33

4-
# Indicates if an IK solver is defined for this group
5-
# and thus, if it can be used by servo
4+
# Indicates if an IK solver is defined for this group.
65
bool has_ik_solver
76

87
# Base frame of the planning group.
@@ -12,3 +11,6 @@ string base_frame
1211
# Tip frames of the planning group.
1312
# Only filled in if the group has a kinematics solver.
1413
string[] tip_frames
14+
15+
# The end-effectors connected to this planning group.
16+
EndEffector[] end_effectors

0 commit comments

Comments
 (0)