ros_state.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import rospy
3 from flexbe_core.proxy import ProxyPublisher, ProxySubscriberCached
4 
5 from flexbe_core.core.state import State
6 
7 
8 class RosState(State):
9  """
10  A state to interface with ROS.
11  """
12 
13  def __init__(self, *args, **kwargs):
14  super(RosState, self).__init__(*args, **kwargs)
15  self._rate = rospy.Rate(10)
16  self._is_controlled = False
17 
18  self._pub = ProxyPublisher()
19  self._sub = ProxySubscriberCached()
20 
21  def sleep(self):
22  self._rate.sleep()
23 
24  @property
25  def sleep_duration(self):
26  return self._rate.remaining().to_sec()
27 
28  def set_rate(self, rate):
29  """
30  Set the execution rate of this state,
31  i.e., the rate with which the execute method is being called.
32 
33  Note: The rate is best-effort,
34  a rospy.Rate does not guarantee real-time properties.
35 
36  @type label: float
37  @param label: The desired rate in Hz.
38  """
39  self._rate = rospy.Rate(rate)
40 
42  self._is_controlled = True
43 
45  self._is_controlled = False
46 
47  @property
48  def is_breakpoint(self):
49  return self.path in rospy.get_param('/flexbe/breakpoints', [])
flexbe_core.core.ros_state.RosState._sub
_sub
Definition: ros_state.py:19
flexbe_core.core.ros_state.RosState._is_controlled
_is_controlled
Definition: ros_state.py:16
flexbe_core.core.ros_state.RosState._rate
_rate
Definition: ros_state.py:15
flexbe_core.core.ros_state.RosState._enable_ros_control
def _enable_ros_control(self)
Definition: ros_state.py:41
flexbe_core.core.ros_state.RosState.is_breakpoint
def is_breakpoint(self)
Definition: ros_state.py:48
flexbe_core.core.ros_state.RosState.sleep
def sleep(self)
Definition: ros_state.py:21
flexbe_core.core.state
Definition: state.py:1
flexbe_core.core.ros_state.RosState.sleep_duration
def sleep_duration(self)
Definition: ros_state.py:25
flexbe_core.core.state.State
Definition: state.py:13
flexbe_core.core.ros_state.RosState.__init__
def __init__(self, *args, **kwargs)
Definition: ros_state.py:13
flexbe_core.proxy
Definition: proxy/__init__.py:1
flexbe_core.core.state.State.path
def path(self)
Definition: state.py:69
flexbe_core.core.ros_state.RosState._disable_ros_control
def _disable_ros_control(self)
Definition: ros_state.py:44
flexbe_core.core.ros_state.RosState
Definition: ros_state.py:8
flexbe_core.core.ros_state.RosState._pub
_pub
Definition: ros_state.py:18
flexbe_core.core.ros_state.RosState.set_rate
def set_rate(self, rate)
Definition: ros_state.py:28


flexbe_core
Author(s): Philipp Schillinger
autogenerated on Fri Jul 21 2023 02:26:05