Skip to content
Open
Show file tree
Hide file tree
Changes from all 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
1 change: 1 addition & 0 deletions setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
license='Apache-2.0',
entry_points={
'console_scripts': [
'joint_states_relay = sr_ros2_python_utils.js_publisher:main'
],
},
)
27 changes: 27 additions & 0 deletions sr_ros2_python_utils/js_publisher.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import JointState

class JointStatesRelay(Node):
def __init__(self):
super().__init__('joint_states_relay')
self.subscription = self.create_subscription(
JointState,
'/ros1_joint_states',
self.joint_states_callback,
10
)
self.publisher = self.create_publisher(JointState, '/joint_states', 10)

def joint_states_callback(self, msg):
self.publisher.publish(msg)

def main(args=None):
rclpy.init(args=args)
node = JointStatesRelay()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()

if __name__ == '__main__':
main()
2 changes: 1 addition & 1 deletion sr_ros2_python_utils/transforms.py
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ def _quaternion_multiply(q0:ArrayLike, q1:ArrayLike) -> ArrayLike:


class TCPTransforms:
def __init__(self, node:Node, tcp_link_name:str='tcp_link', tool_link_name:str='tcp_gripper') -> None:
def __init__(self, node:Node, tcp_link_name:str='tcp_link', tool_link_name:str='tcp_link') -> None:
"""
TCP transformation helper class

Expand Down