Skip to content

Commit

Permalink
Fix excessive cpu consumption (#92)
Browse files Browse the repository at this point in the history
* Fix excessive cpu consumption

* Reorder imports

---------

Co-authored-by: Isaac Acevedo <[email protected]>
  • Loading branch information
Zaakhi and Isaac Acevedo authored Nov 6, 2024
1 parent 0e6efd9 commit 6ff23a3
Showing 1 changed file with 10 additions and 28 deletions.
38 changes: 10 additions & 28 deletions joy_teleop/joy_teleop/incrementer_server.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,15 +40,13 @@
# * Jeremie Deray (artivis)
# * Borong Yuan

import time

from control_msgs.msg import JointTrajectoryControllerState as JTCS
import rclpy
from rclpy.action import ActionServer
from rclpy.callback_groups import ReentrantCallbackGroup
from rclpy.duration import Duration
from rclpy.executors import MultiThreadedExecutor
from rclpy.node import Node
from rclpy.wait_for_message import wait_for_message
from teleop_tools_msgs.action import Increment as TTIA
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint

Expand All @@ -58,42 +56,28 @@ class IncrementerServer(Node):
def __init__(self):
super().__init__('incrementer_server', namespace='joint_trajectory_controller')

cb_group = ReentrantCallbackGroup()

self._has_new_message = False

self._as = ActionServer(self, TTIA, 'increment',
self._as_cb, callback_group=cb_group)
self._as_cb)

self._command_pub = self.create_publisher(
JointTrajectory, 'joint_trajectory', 1)

self._state_sub = self.create_subscription(
JTCS, 'controller_state', self._state_cb, 1, callback_group=cb_group)

self._goal = JointTrajectory()
self.get_logger().info('Connected to {}'.format(self.get_namespace()))
self.get_logger().info(f'Connected to {self.get_namespace()}')

def _as_cb(self, goal):
self.increment_by(goal.request.increment_by)
goal.succeed()
return TTIA.Result()

def _state_cb(self, state):
self._state = state
self._has_new_message = True

# TODO(artivis) change after
# https://github.com/ros2/rclcpp/issues/520
# has landed
def _wait_for_new_message(self):
self._has_new_message = False
while not self._has_new_message:
time.sleep(0.01)
return self._state
def _wait_for_state_message(self):
msg_ok = False
while not msg_ok:
msg_ok, state = wait_for_message(JTCS, self, 'controller_state')
return state

def increment_by(self, increment):
state = self._wait_for_new_message()
state = self._wait_for_state_message()
self._goal.joint_names = state.joint_names
self._value = state.feedback.positions
self._value = [x + y for x, y in zip(self._value, increment)]
Expand All @@ -109,11 +93,9 @@ def main():
rclpy.init()

node = IncrementerServer()
executor = MultiThreadedExecutor()
executor.add_node(node)

try:
executor.spin()
rclpy.spin(node)
except KeyboardInterrupt:
pass

Expand Down

0 comments on commit 6ff23a3

Please sign in to comment.