Skip to content

Commit bc091eb

Browse files
authored
Merge branch 'main' into fix-publish
2 parents bc0dea4 + d3c3258 commit bc091eb

File tree

7 files changed

+34
-6
lines changed

7 files changed

+34
-6
lines changed

CHANGELOG.rst

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@ Unreleased
1313
**Added**
1414

1515
* Added support for attached and non-attached collision mesh visualization to the ``Robot Visualize`` GH component.
16+
* Added a prefix to all GH components.
1617

1718
**Changed**
1819

@@ -21,6 +22,7 @@ Unreleased
2122
**Fixed**
2223

2324
* Fixed DH params for analytical IK solver of UR3e and UR10e.
25+
* Fixed Kinetic support on IK, FK, and motion planning calls.
2426
* Fixed ``Publish to topic`` Grasshopper component when the ``ros_client`` has been replaced (eg. disconnected and reconnected).
2527

2628
**Deprecated**

src/compas_fab/backends/ros/backend_features/move_it_forward_kinematics.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -87,6 +87,7 @@ def forward_kinematics_async(self, callback, errback,
8787
name=configuration.joint_names, position=configuration.joint_values, header=header)
8888
robot_state = RobotState(
8989
joint_state, MultiDOFJointState(header=header))
90+
robot_state.filter_fields_for_distro(self.ros_client.ros_distro)
9091

9192
def convert_to_frame(response):
9293
callback(response.pose_stamped[0].pose.frame)

src/compas_fab/backends/ros/backend_features/move_it_inverse_kinematics.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -109,6 +109,7 @@ def inverse_kinematics_async(self, callback, errback,
109109
name=start_configuration.joint_names, position=start_configuration.joint_values, header=header)
110110
start_state = RobotState(
111111
joint_state, MultiDOFJointState(header=header))
112+
start_state.filter_fields_for_distro(self.ros_client.ros_distro)
112113

113114
if options.get('attached_collision_meshes'):
114115
for acm in options['attached_collision_meshes']:

src/compas_fab/backends/ros/backend_features/move_it_plan_cartesian_motion.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -109,6 +109,7 @@ def plan_cartesian_motion_async(self, callback, errback,
109109
name=start_configuration.joint_names,
110110
position=start_configuration.joint_values)
111111
start_state = RobotState(joint_state, MultiDOFJointState(header=header), is_diff=True)
112+
start_state.filter_fields_for_distro(self.ros_client.ros_distro)
112113

113114
if options.get('attached_collision_meshes'):
114115
for acm in options['attached_collision_meshes']:

src/compas_fab/backends/ros/backend_features/move_it_plan_motion.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -114,6 +114,7 @@ def plan_motion_async(self, callback, errback,
114114
position=start_configuration.joint_values)
115115
start_state = RobotState(
116116
joint_state, MultiDOFJointState(header=header), is_diff=True)
117+
start_state.filter_fields_for_distro(self.ros_client.ros_distro)
117118

118119
if options.get('attached_collision_meshes'):
119120
for acm in options['attached_collision_meshes']:

src/compas_fab/backends/ros/messages/moveit_msgs.py

Lines changed: 18 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -189,6 +189,14 @@ def from_msg(cls, msg):
189189
item) for item in msg['attached_collision_objects']]
190190
return cls(joint_state, multi_dof_joint_state, attached_collision_objects, msg['is_diff'])
191191

192+
def filter_fields_for_distro(self, ros_distro):
193+
"""To maintain backwards compatibility with older ROS distros,
194+
we need to make sure newly added fields are removed from the request."""
195+
# Remove the field `pose` for distros older than NOETIC
196+
if ros_distro in (RosDistro.KINETIC, RosDistro.MELODIC):
197+
for aco in self.attached_collision_objects:
198+
del aco.object.pose
199+
192200

193201
class PositionIKRequest(ROSmsg):
194202
"""https://docs.ros.org/kinetic/api/moveit_msgs/html/msg/PositionIKRequest.html
@@ -539,6 +547,14 @@ def from_msg(cls, msg):
539547

540548
return cls(collision_objects, octomap)
541549

550+
def filter_fields_for_distro(self, ros_distro):
551+
"""To maintain backwards compatibility with older ROS distros,
552+
we need to make sure newly added fields are removed from the request."""
553+
# Remove the field `pose` for distros older than NOETIC
554+
if ros_distro in (RosDistro.KINETIC, RosDistro.MELODIC):
555+
for co in self.collision_objects:
556+
del co.pose
557+
542558

543559
class PlanningScene(ROSmsg):
544560
"""https://docs.ros.org/melodic/api/moveit_msgs/html/msg/PlanningScene.html
@@ -568,11 +584,8 @@ def filter_fields_for_distro(self, ros_distro):
568584
"""To maintain backwards compatibility with older ROS distros,
569585
we need to make sure newly added fields are removed from the request."""
570586
# Remove the field `pose` for distros older than NOETIC
571-
if ros_distro in (RosDistro.KINETIC, RosDistro.MELODIC):
572-
for aco in self.robot_state.attached_collision_objects:
573-
del aco.object.pose
574-
for co in self.world.collision_objects:
575-
del co.pose
587+
self.robot_state.filter_fields_for_distro(ros_distro)
588+
self.world.filter_fields_for_distro(ros_distro)
576589

577590
@classmethod
578591
def from_msg(cls, msg):

tasks.py

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -234,7 +234,16 @@ def build_ghuser_components(ctx, gh_io_folder=None, ironpython=None):
234234
if not ironpython:
235235
ironpython = 'ipy'
236236

237-
ctx.run('{} {} {} {} --ghio "{}"'.format(ironpython, os.path.join(action_dir, 'componentize.py'), source_dir, target_dir, os.path.abspath(gh_io_folder)))
237+
ctx.run(
238+
'{} {} {} {} --ghio "{}" --prefix "{}"'.format(
239+
ironpython,
240+
os.path.join(action_dir, 'componentize.py'),
241+
source_dir,
242+
target_dir,
243+
os.path.abspath(gh_io_folder),
244+
"(COMPAS-FAB) "
245+
)
246+
)
238247

239248

240249
@task(help={

0 commit comments

Comments
 (0)