RobotInterface. More...
Public Member Functions | |
def | __init__ |
def | cmd_vel |
def | cmd_vel |
def | shutdown |
Static Public Attributes | |
float | cmd_vel_publishing_interval = 0.1 |
tuple | image_received = Signal(sensor_msgs.CompressedImage, name="image_received") |
Private Member Functions | |
def | _publish_cmd_vel |
def | _ros_subscriber_image_callback |
Private Attributes | |
_cmd_vel | |
_cmd_vel_publisher | |
_cmd_vel_publisher_timer | |
_compressed_image_subscriber | |
_lock | |
Static Private Attributes | |
list | __slots__ |
RobotInterface.
Definition at line 21 of file video_teleop_interface.py.
def rocon_qt_library.interfaces.video_teleop_interface.VideoTeleopInterface.__init__ | ( | self, | |
image_received_slot, | |||
cmd_vel_topic_name = 'cmd_vel' , |
|||
compressed_image_topic_name = 'compressed_image' |
|||
) |
Initialise the robot interface with slot connections back to whatever qt views are attached and the ros topic names to be used. :param slot image_received_slot: slot to connect to the ``image_received`` signal. :param str cmd_vel_topic_name: topic name for the command velocity publisher. :param str compressed_image_topic_name: topic name for the compressed image subscriber.
Definition at line 34 of file video_teleop_interface.py.
def rocon_qt_library.interfaces.video_teleop_interface.VideoTeleopInterface._publish_cmd_vel | ( | self, | |
unused_event | |||
) | [private] |
Convert the command into an appropriate one for the cmd_vel topic and publish.
Definition at line 70 of file video_teleop_interface.py.
def rocon_qt_library.interfaces.video_teleop_interface.VideoTeleopInterface._ros_subscriber_image_callback | ( | self, | |
msg | |||
) | [private] |
Update the teleop image :param sensor_msgs.CompressedImage msg: an image stream feed from the robot
Definition at line 61 of file video_teleop_interface.py.
Returns this cmd_vel in a 2-tuple appropriate for 2d teleop'ing robots, i.e. (linear, angular). :returns: the last configured cmd_vel as a 2-tuple. :rtype: (float, float)
Definition at line 95 of file video_teleop_interface.py.
def rocon_qt_library.interfaces.video_teleop_interface.VideoTeleopInterface.cmd_vel | ( | self, | |
value | |||
) |
Convenient setter from a 2-tuple. The 2-tuple takes the form (linear, angular) with units in (m/s, rad/s). Usage: .. code-block:: python teleop_interaface.cmd_vel = (1.0, 0.35) # linear x, angular z values)
Definition at line 106 of file video_teleop_interface.py.
There is a problem in rospy here which spams you with a warning when the cmd_vel is unregistered. This is just noise I believe (it shouldn't be printing anything). The publisher gets unregistered properly. Should be safe to ignore (lots of work to actually follow up).
Definition at line 79 of file video_teleop_interface.py.
list rocon_qt_library::interfaces::video_teleop_interface.VideoTeleopInterface::__slots__ [static, private] |
[ '_cmd_vel', # geometry_msgs.Twist '_cmd_vel_publisher_timer', '_cmd_vel_publisher', '_compressed_image_subscriber', '_lock' ]
Definition at line 25 of file video_teleop_interface.py.
Definition at line 41 of file video_teleop_interface.py.
rocon_qt_library::interfaces::video_teleop_interface.VideoTeleopInterface::_cmd_vel_publisher [private] |
Definition at line 41 of file video_teleop_interface.py.
rocon_qt_library::interfaces::video_teleop_interface.VideoTeleopInterface::_cmd_vel_publisher_timer [private] |
Definition at line 41 of file video_teleop_interface.py.
Definition at line 41 of file video_teleop_interface.py.
Definition at line 41 of file video_teleop_interface.py.
float rocon_qt_library::interfaces::video_teleop_interface.VideoTeleopInterface::cmd_vel_publishing_interval = 0.1 [static] |
Definition at line 23 of file video_teleop_interface.py.
tuple rocon_qt_library::interfaces::video_teleop_interface.VideoTeleopInterface::image_received = Signal(sensor_msgs.CompressedImage, name="image_received") [static] |
Definition at line 32 of file video_teleop_interface.py.