Skip to content

Commit 28bd7aa

Browse files
asajlukeschmitt-tr
andauthored
Update according to changes to Python-ROS 2 API (#82)
* strip comments from locobot urdf * Update according to changes to Python-ROS 2 API * Apply suggestions from code review * Apply suggestions from code review * Apply suggestions from code review * Update interbotix_xs_toolbox/interbotix_xs_modules/interbotix_xs_modules/xs_launch/xs_launch.py --------- Co-authored-by: lukeschmitt-tr <85308904+lukeschmitt-tr@users.noreply.github.com>
1 parent dbe4d7d commit 28bd7aa

File tree

5 files changed

+63
-71
lines changed

5 files changed

+63
-71
lines changed

interbotix_xs_toolbox/interbotix_xs_modules/interbotix_xs_modules/xs_launch/xs_launch.py

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -104,6 +104,7 @@ def __init__(
104104
self,
105105
*,
106106
default_value: Optional[SomeSubstitutionsType] = Command([
107+
'sh -c "',
107108
FindExecutable(name='xacro'), ' ',
108109
PathJoinSubstitution([
109110
FindPackageShare('interbotix_xslocobot_descriptions'),
@@ -122,6 +123,9 @@ def __init__(
122123
'use_lidar:=', LaunchConfiguration('use_lidar'), ' ',
123124
'external_urdf_loc:=', LaunchConfiguration('external_urdf_loc'), ' ',
124125
'hardware_type:=', LaunchConfiguration('hardware_type'), ' ',
126+
# Stripping comments from the URDF is necessary for gazebo_ros2_control to parse the
127+
# robot_description parameter override
128+
'| ', FindExecutable(name='perl'), ' -0777 -pe \'s/<!--.*?-->//gs\'"'
125129
]),
126130
**kwargs
127131
) -> None:

interbotix_xs_toolbox/interbotix_xs_modules/interbotix_xs_modules/xs_robot/create3.py

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -33,13 +33,13 @@
3333
Python.
3434
"""
3535

36-
from builtin_interfaces.msg import Duration
3736
from geometry_msgs.msg import Pose
3837
from interbotix_xs_modules.xs_robot.core import InterbotixRobotXSCore
3938
from interbotix_xs_modules.xs_robot.mobile_base import InterbotixMobileBaseInterface
4039
from irobot_create_msgs.msg import AudioNote, AudioNoteVector
4140
from irobot_create_msgs.srv import ResetPose
4241
from rclpy.constants import S_TO_NS
42+
from rclpy.duration import Duration
4343
from std_msgs.msg import Header
4444

4545

@@ -78,28 +78,28 @@ def __init__(
7878
nav_timeout_sec=nav_timeout_sec,
7979
use_nav=use_nav,
8080
)
81-
self.pub_base_sound = self.core.create_publisher(
81+
self.pub_base_sound = self.core.get_node().create_publisher(
8282
msg_type=AudioNoteVector,
8383
topic='mobile_base/cmd_audio',
8484
qos_profile=1
8585
)
86-
self.client_reset_pose = self.core.create_client(
86+
self.client_reset_pose = self.core.get_node().create_client(
8787
srv_type=ResetPose,
8888
srv_name='mobile_base/reset_pose',
8989
)
9090

91-
self.core.get_clock().sleep_for(Duration(nanosec=int(0.5*S_TO_NS)))
92-
self.core.get_logger().info('Initialized InterbotixCreate3Interface!')
91+
self.core.get_node().get_clock().sleep_for(Duration(nanoseconds=int(0.5*S_TO_NS)))
92+
self.core.get_node().loginfo('Initialized InterbotixCreate3Interface!')
9393

9494
def reset_odom(self) -> None:
9595
"""Reset odometry to zero."""
9696
future_reset_odom = self.client_reset_pose.call_async(ResetPose.Request(pose=Pose()))
97-
self.core.robot_spin_once_until_future_complete(future_reset_odom)
97+
self.core.get_node().wait_until_future_complete(future_reset_odom)
9898
self.play_sound(
9999
sound=AudioNoteVector(
100100
header=Header(
101101
frame_id=f'{self.robot_name}/base_link',
102-
stamp=self.core.get_clock().now().to_msg()
102+
stamp=self.core.get_node().get_clock().now().to_msg()
103103
),
104104
notes=[AudioNote(frequency=6000, max_runtime=Duration(seconds=1.0))],
105105
append=False,

interbotix_xs_toolbox/interbotix_xs_modules/interbotix_xs_modules/xs_robot/locobot.py

Lines changed: 9 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -33,15 +33,12 @@
3333
"""
3434

3535
from enum import Enum
36-
from threading import Thread
37-
import time
3836

37+
from interbotix_common_modules.common_robot.robot import InterbotixRobotNode
3938
from interbotix_xs_modules.xs_robot.arm import InterbotixArmXSInterface
4039
from interbotix_xs_modules.xs_robot.core import InterbotixRobotXSCore
4140
from interbotix_xs_modules.xs_robot.gripper import InterbotixGripperXSInterface
4241
from interbotix_xs_modules.xs_robot.turret import InterbotixTurretXSInterface
43-
import rclpy
44-
from rclpy.executors import MultiThreadedExecutor
4542
from rclpy.logging import LoggingSeverity
4643

4744

@@ -72,7 +69,7 @@ def __init__(
7269
use_nav: bool = False,
7370
logging_level: LoggingSeverity = LoggingSeverity.INFO,
7471
node_name: str = 'robot_manipulation',
75-
start_on_init: bool = True,
72+
node: InterbotixRobotNode = None,
7673
args=None,
7774
):
7875
"""
@@ -105,17 +102,17 @@ def __init__(
105102
ERROR, or FATAL. defaults to INFO
106103
:param node_name: (optional) name to give to the core started by this class, defaults to
107104
'robot_manipulation'
108-
:param start_on_init: (optional) set to `True` to start running the spin thread after the
109-
object is built; set to `False` if intending to sub-class this. If set to `False`,
110-
either call the `start()` method later on, or add the core to an executor in another
111-
thread.
105+
:param node: (optional) `rclpy.Node` or derived class to base this robot's ROS-related
106+
components on. If nothing is given, this robot will create its own node. defaults to
107+
`None`.
112108
"""
113109
self.core = InterbotixRobotXSCore(
114110
robot_model=robot_model,
115111
robot_name=robot_name,
116112
topic_joint_states=topic_dxl_joint_states,
117113
logging_level=logging_level,
118114
node_name=node_name,
115+
node=node,
119116
args=args
120117
)
121118
self.camera = InterbotixTurretXSInterface(
@@ -162,23 +159,6 @@ def __init__(
162159
init_node=False
163160
)
164161

165-
if start_on_init:
166-
self.start()
167-
168-
def start(self) -> None:
169-
"""Start a background thread that builds and spins an executor."""
170-
self._execution_thread = Thread(target=self.run)
171-
self._execution_thread.start()
172-
173-
def run(self) -> None:
174-
"""Thread target."""
175-
self.ex = MultiThreadedExecutor()
176-
self.ex.add_node(self.core)
177-
self.ex.spin()
178-
179-
def shutdown(self) -> None:
180-
"""Destroy the node and shut down all threads and processes."""
181-
self.core.destroy_node()
182-
rclpy.shutdown()
183-
self._execution_thread.join()
184-
time.sleep(0.5)
162+
def get_node(self) -> InterbotixRobotNode:
163+
"""Return the core robot node for this robot."""
164+
return self.core.robot_node

interbotix_xs_toolbox/interbotix_xs_modules/interbotix_xs_modules/xs_robot/mobile_base.py

Lines changed: 14 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -83,34 +83,34 @@ def __init__(
8383

8484
cb_group_mobile_base = ReentrantCallbackGroup()
8585

86-
self.pub_base_twist = self.core.create_publisher(
86+
self.pub_base_twist = self.core.get_node().create_publisher(
8787
msg_type=Twist,
8888
topic=topic_cmd_vel,
8989
qos_profile=1,
9090
callback_group=cb_group_mobile_base,
9191
)
92-
self.sub_base_states = self.core.create_subscription(
92+
self.sub_base_states = self.core.get_node().create_subscription(
9393
msg_type=JointState,
9494
topic=topic_base_joint_states,
9595
callback=self._base_states_cb,
9696
qos_profile=1,
9797
callback_group=cb_group_mobile_base,
9898
)
99-
self.sub_base_odom = self.core.create_subscription(
99+
self.sub_base_odom = self.core.get_node().create_subscription(
100100
msg_type=Odometry,
101101
topic='/mobile_base/odom',
102102
callback=self._base_odom_cb,
103103
qos_profile=1,
104104
callback_group=cb_group_mobile_base,
105105
)
106106
self.client_base_nav_to_pose = ActionClient(
107-
node=self.core,
107+
node=self.core.get_node(),
108108
action_type=NavigateToPose,
109109
action_name='navigate_to_pose',
110110
callback_group=cb_group_mobile_base,
111111
)
112112

113-
self.core.get_logger().info('Initialized InterbotixMobileBaseInterface!')
113+
self.core.get_node().loginfo('Initialized InterbotixMobileBaseInterface!')
114114

115115
def command_velocity_xyaw(
116116
self,
@@ -200,7 +200,7 @@ def command_pose(
200200
:details: note that if 'blocking' is `False`, the function will always return `True`
201201
"""
202202
if not self.use_nav:
203-
self.core.get_logger().error('`use_nav` set to `False`. Will not execute navigation.')
203+
self.core.get_node().logerror('`use_nav` set to `False`. Will not execute navigation.')
204204
return False
205205
goal = NavigateToPose.Goal(
206206
pose=self._stamp_pose(pose=goal_pose, frame_id=frame_id),
@@ -212,11 +212,11 @@ def command_pose(
212212
feedback_callback=self._nav_to_pose_feedback_cb,
213213
)
214214

215-
self.core.robot_spin_once_until_future_complete(future_send_nav_to_pose_goal)
215+
self.core.get_node().wait_until_future_complete(future_send_nav_to_pose_goal)
216216
self.goal_handle = future_send_nav_to_pose_goal.result()
217217

218218
if not self.goal_handle.accepted:
219-
self.core.get_logger().error(
219+
self.core.get_node().logerror(
220220
f'Navigation goal [{goal_pose.position.x}, {goal_pose.position.y}] was rejected.'
221221
)
222222
return False
@@ -225,12 +225,12 @@ def command_pose(
225225
while not self.is_nav_complete():
226226
fb = self.get_nav_to_pose_feedback()
227227
if Duration.from_msg(fb.navigation_time > Duration(seconds=self.nav_timeout_sec)):
228-
self.core.get_logger().error(
228+
self.core.get_node().logerror(
229229
f'Navigation time ({fb.navigation_time}) exceeds timeout '
230230
f'({self.nav_timeout_sec}). Cancelling navigation goal.'
231231
)
232232
future_cancel_nav_to_pose_goal = self.goal_handle.cancel_goal_async()
233-
self.core.robot_spin_once_until_future_complete(
233+
self.core.get_node().wait_until_future_complete(
234234
future=future_cancel_nav_to_pose_goal
235235
)
236236
return False
@@ -290,11 +290,13 @@ def is_nav_complete(self):
290290
"""
291291
if not self.future_nav:
292292
return True
293-
self.core.robot_spin_once_until_future_complete(future=self.future_nav, timeout_sec=0.1)
293+
self.core.get_node().wait_until_future_complete(future=self.future_nav, timeout_sec=0.1)
294294
if self.future_nav.result():
295295
self.nav_status = self.future_nav.result().status
296296
if self.nav_status != GoalStatus.STATUS_SUCCEEDED:
297-
self.core.get_logger().error(f"Navigation failed with status '{self.nav_status}'.")
297+
self.core.get_node().logerror(
298+
f"Navigation failed with status '{self.nav_status}'."
299+
)
298300
return True
299301
else:
300302
return False

0 commit comments

Comments
 (0)