Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update according to changes to Python-ROS 2 API #82

Merged
merged 6 commits into from
Feb 1, 2025
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -99,11 +99,11 @@ def __init__(

class DeclareInterbotixXSLoCoBotRobotDescriptionLaunchArgument(DeclareLaunchArgument):
"""Generate a URDF of a LoCoBot through a modified DeclareLaunchArgument object."""
lukeschmitt-tr marked this conversation as resolved.
Show resolved Hide resolved

def __init__(
self,
*,
default_value: Optional[SomeSubstitutionsType] = Command([
'sh -c "',
FindExecutable(name='xacro'), ' ',
PathJoinSubstitution([
FindPackageShare('interbotix_xslocobot_descriptions'),
Expand All @@ -122,6 +122,9 @@ def __init__(
'use_lidar:=', LaunchConfiguration('use_lidar'), ' ',
'external_urdf_loc:=', LaunchConfiguration('external_urdf_loc'), ' ',
'hardware_type:=', LaunchConfiguration('hardware_type'), ' ',
# Stripping comments from the URDF is necessary for gazebo_ros2_control to parse the
# robot_description parameter override
'| ', FindExecutable(name='perl'), ' -0777 -pe \'s/<!--.*?-->//gs\'"'
]),
**kwargs
) -> None:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,13 +33,13 @@
Python.
"""

from builtin_interfaces.msg import Duration
from geometry_msgs.msg import Pose
from interbotix_xs_modules.xs_robot.core import InterbotixRobotXSCore
from interbotix_xs_modules.xs_robot.mobile_base import InterbotixMobileBaseInterface
from irobot_create_msgs.msg import AudioNote, AudioNoteVector
from irobot_create_msgs.srv import ResetPose
from rclpy.constants import S_TO_NS
from rclpy.duration import Duration
from std_msgs.msg import Header


Expand Down Expand Up @@ -78,28 +78,28 @@ def __init__(
nav_timeout_sec=nav_timeout_sec,
use_nav=use_nav,
)
self.pub_base_sound = self.core.create_publisher(
self.pub_base_sound = self.core.get_node().create_publisher(
msg_type=AudioNoteVector,
topic='mobile_base/cmd_audio',
qos_profile=1
)
self.client_reset_pose = self.core.create_client(
self.client_reset_pose = self.core.get_node().create_client(
srv_type=ResetPose,
srv_name='mobile_base/reset_pose',
)

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

def reset_odom(self) -> None:
"""Reset odometry to zero."""
future_reset_odom = self.client_reset_pose.call_async(ResetPose.Request(pose=Pose()))
self.core.robot_spin_once_until_future_complete(future_reset_odom)
self.core.get_node().wait_until_future_complete(future_reset_odom)
self.play_sound(
sound=AudioNoteVector(
header=Header(
frame_id=f'{self.robot_name}/base_link',
stamp=self.core.get_clock().now().to_msg()
stamp=self.core.get_node().get_clock().now().to_msg()
),
notes=[AudioNote(frequency=6000, max_runtime=Duration(seconds=1.0))],
append=False,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,15 +33,13 @@
"""

from enum import Enum
from threading import Thread
import time

from interbotix_common_modules.common_robot.robot import InterbotixRobotNode
from interbotix_xs_modules.xs_robot.arm import InterbotixArmXSInterface
from interbotix_xs_modules.xs_robot.core import InterbotixRobotXSCore
from interbotix_xs_modules.xs_robot.gripper import InterbotixGripperXSInterface
from interbotix_xs_modules.xs_robot.turret import InterbotixTurretXSInterface
import rclpy
lukeschmitt-tr marked this conversation as resolved.
Show resolved Hide resolved
from rclpy.executors import MultiThreadedExecutor
from rclpy.logging import LoggingSeverity


Expand Down Expand Up @@ -70,9 +68,9 @@ def __init__(
topic_dxl_joint_states: str = 'dynamixel/joint_states',
topic_base_joint_states: str = 'mobile_base/joint_states',
use_nav: bool = False,
logging_level: LoggingSeverity = LoggingSeverity.INFO,
logging_level: LoggingSeverity = LoggingSeverity.DEBUG,
lukeschmitt-tr marked this conversation as resolved.
Show resolved Hide resolved
node_name: str = 'robot_manipulation',
start_on_init: bool = True,
node: InterbotixRobotNode = None,
args=None,
):
"""
Expand Down Expand Up @@ -105,17 +103,17 @@ def __init__(
ERROR, or FATAL. defaults to INFO
:param node_name: (optional) name to give to the core started by this class, defaults to
'robot_manipulation'
:param start_on_init: (optional) set to `True` to start running the spin thread after the
object is built; set to `False` if intending to sub-class this. If set to `False`,
either call the `start()` method later on, or add the core to an executor in another
thread.
:param node: (optional) `rclpy.Node` or derived class to base this robot's ROS-related
components on. If nothing is given, this robot will create its own node. defaults to
`None`.
"""
self.core = InterbotixRobotXSCore(
robot_model=robot_model,
robot_name=robot_name,
topic_joint_states=topic_dxl_joint_states,
logging_level=logging_level,
node_name=node_name,
node=node,
args=args
)
self.camera = InterbotixTurretXSInterface(
Expand Down Expand Up @@ -162,23 +160,6 @@ def __init__(
init_node=False
)

if start_on_init:
self.start()

def start(self) -> None:
"""Start a background thread that builds and spins an executor."""
self._execution_thread = Thread(target=self.run)
self._execution_thread.start()

def run(self) -> None:
"""Thread target."""
self.ex = MultiThreadedExecutor()
self.ex.add_node(self.core)
self.ex.spin()

def shutdown(self) -> None:
"""Destroy the node and shut down all threads and processes."""
self.core.destroy_node()
rclpy.shutdown()
self._execution_thread.join()
time.sleep(0.5)
def get_node(self) -> InterbotixRobotNode:
"""Return the core robot node for this robot."""
return self.core.robot_node
Original file line number Diff line number Diff line change
Expand Up @@ -83,34 +83,34 @@ def __init__(

cb_group_mobile_base = ReentrantCallbackGroup()

self.pub_base_twist = self.core.create_publisher(
self.pub_base_twist = self.core.get_node().create_publisher(
msg_type=Twist,
topic=topic_cmd_vel,
qos_profile=1,
callback_group=cb_group_mobile_base,
)
self.sub_base_states = self.core.create_subscription(
self.sub_base_states = self.core.get_node().create_subscription(
msg_type=JointState,
topic=topic_base_joint_states,
callback=self._base_states_cb,
qos_profile=1,
callback_group=cb_group_mobile_base,
)
self.sub_base_odom = self.core.create_subscription(
self.sub_base_odom = self.core.get_node().create_subscription(
msg_type=Odometry,
topic='/mobile_base/odom',
callback=self._base_odom_cb,
qos_profile=1,
callback_group=cb_group_mobile_base,
)
self.client_base_nav_to_pose = ActionClient(
node=self.core,
node=self.core.get_node(),
action_type=NavigateToPose,
action_name='navigate_to_pose',
callback_group=cb_group_mobile_base,
)

self.core.get_logger().info('Initialized InterbotixMobileBaseInterface!')
self.core.get_node().loginfo('Initialized InterbotixMobileBaseInterface!')

def command_velocity_xyaw(
self,
Expand Down Expand Up @@ -200,7 +200,7 @@ def command_pose(
:details: note that if 'blocking' is `False`, the function will always return `True`
"""
if not self.use_nav:
self.core.get_logger().error('`use_nav` set to `False`. Will not execute navigation.')
self.core.get_node().logerror('`use_nav` set to `False`. Will not execute navigation.')
return False
goal = NavigateToPose.Goal(
pose=self._stamp_pose(pose=goal_pose, frame_id=frame_id),
Expand All @@ -212,11 +212,11 @@ def command_pose(
feedback_callback=self._nav_to_pose_feedback_cb,
)

self.core.robot_spin_once_until_future_complete(future_send_nav_to_pose_goal)
self.core.get_node().wait_until_future_complete(future_send_nav_to_pose_goal)
self.goal_handle = future_send_nav_to_pose_goal.result()

if not self.goal_handle.accepted:
self.core.get_logger().error(
self.core.get_node().logerror(
f'Navigation goal [{goal_pose.position.x}, {goal_pose.position.y}] was rejected.'
)
return False
Expand All @@ -225,12 +225,12 @@ def command_pose(
while not self.is_nav_complete():
fb = self.get_nav_to_pose_feedback()
if Duration.from_msg(fb.navigation_time > Duration(seconds=self.nav_timeout_sec)):
self.core.get_logger().error(
self.core.get_node().logerror(
f'Navigation time ({fb.navigation_time}) exceeds timeout '
f'({self.nav_timeout_sec}). Cancelling navigation goal.'
)
future_cancel_nav_to_pose_goal = self.goal_handle.cancel_goal_async()
self.core.robot_spin_once_until_future_complete(
self.core.get_node().wait_until_future_complete(
future=future_cancel_nav_to_pose_goal
)
return False
Expand Down Expand Up @@ -290,11 +290,11 @@ def is_nav_complete(self):
"""
if not self.future_nav:
return True
self.core.robot_spin_once_until_future_complete(future=self.future_nav, timeout_sec=0.1)
self.core.get_node().wait_until_future_complete(future=self.future_nav, timeout_sec=0.1)
if self.future_nav.result():
self.nav_status = self.future_nav.result().status
if self.nav_status != GoalStatus.STATUS_SUCCEEDED:
self.core.get_logger().error(f"Navigation failed with status '{self.nav_status}'.")
self.core.get_node().logerror(f"Navigation failed with status '{self.nav_status}'.")
lukeschmitt-tr marked this conversation as resolved.
Show resolved Hide resolved
return True
else:
return False
Expand Down
Loading