$search

Public Member Functions | |
| def | __init__ |
| def | can_transform |
| def | can_transform_full |
| def | lookup_transform |
| def | lookup_transform_full |
| def | wait_for_server |
Public Attributes | |
| check_frequency | |
| client | |
| timeout_padding | |
Private Member Functions | |
| def | __is_done |
| def | __process_goal |
| def | __process_result |
Definition at line 47 of file buffer_client.py.
| def tf2_ros::buffer_client::BufferClient::__init__ | ( | self, | ||
| ns, | ||||
check_frequency = 10.0, |
||||
timeout_padding = rospy.Duration.from_sec(2.0) | ||||
| ) |
Definition at line 48 of file buffer_client.py.
| def tf2_ros::buffer_client::BufferClient::__is_done | ( | self, | ||
| state | ||||
| ) | [private] |
Definition at line 98 of file buffer_client.py.
| def tf2_ros::buffer_client::BufferClient::__process_goal | ( | self, | ||
| goal | ||||
| ) | [private] |
Definition at line 105 of file buffer_client.py.
| def tf2_ros::buffer_client::BufferClient::__process_result | ( | self, | ||
| result | ||||
| ) | [private] |
Definition at line 125 of file buffer_client.py.
| def tf2_ros::buffer_client::BufferClient::can_transform | ( | self, | ||
| target_frame, | ||||
| source_frame, | ||||
| time, | ||||
timeout = rospy.Duration(0.0) | ||||
| ) |
Definition at line 82 of file buffer_client.py.
| def tf2_ros::buffer_client::BufferClient::can_transform_full | ( | self, | ||
| target_frame, | ||||
| target_time, | ||||
| source_frame, | ||||
| source_time, | ||||
| fixed_frame, | ||||
timeout = rospy.Duration(0.0) | ||||
| ) |
Definition at line 91 of file buffer_client.py.
| def tf2_ros::buffer_client::BufferClient::lookup_transform | ( | self, | ||
| target_frame, | ||||
| source_frame, | ||||
| time, | ||||
timeout = rospy.Duration(0.0) | ||||
| ) |
Definition at line 58 of file buffer_client.py.
| def tf2_ros::buffer_client::BufferClient::lookup_transform_full | ( | self, | ||
| target_frame, | ||||
| target_time, | ||||
| source_frame, | ||||
| source_time, | ||||
| fixed_frame, | ||||
timeout = rospy.Duration(0.0) | ||||
| ) |
Definition at line 69 of file buffer_client.py.
| def tf2_ros::buffer_client::BufferClient::wait_for_server | ( | self, | ||
timeout = rospy.Duration() | ||||
| ) |
Definition at line 54 of file buffer_client.py.
Definition at line 51 of file buffer_client.py.
Definition at line 50 of file buffer_client.py.
Definition at line 52 of file buffer_client.py.