The head wobbler example randomly moves the head to demonstrate using the head pan.
Contents
Introduction
Sawyer's head can rotate left-to-right in pan mode. The pan motion swings Sawyer's 'face' (a.k.a. screen) to a settable angle.
The head wobbler example is intended to be a simple demo whose code can be examined to learn how to use the head and demonstrate the use of the intera_interface Head class.
If you would like to follow along with the actual source code for the example on GitHub, it can be found through this link for head wobbler example.
Usage
From an RSDK Shell, run the head_wobbler.py demo from the intera_examples package:
$ rosrun intera_examples head_wobbler.py
Sawyer's head will begin panning left and right to random angles.
Code Walkthrough
Now, let's break down the code.
import argparse
import random
import rospy
import intera_interface
from intera_interface import CHECK_VERSION
This imports the intera interface for accessing the head class.
class Wobbler(object):
def __init__(self):
"""
'Wobbles' the head
"""
self._done = False
self._head = intera_interface.Head()
The _head
is an object of the Head class within the interface_interface. This creates a subscriber to the topic robot/head/head_state
and publishers to the topics robot/head/command_head_pan
. The object _head
, would be used to control the head panning.
# verify robot is enabled
print("Getting robot state... ")
self._rs = intera_interface.RobotEnable(CHECK_VERSION)
self._init_state = self._rs.state().enabled
print("Enabling robot... ")
self._rs.enable()
print("Running. Ctrl-c to quit")
intera_interface.RobotEnable(CHECK_VERSION)
checks if the sdk version updated in the settings is compatible with the sdk version loaded on the param server of the Robot and creates an object _rs
of the RobotEnable
class. The next line sets the _init_state
of the robot to its current state. The enable()
performs the actual enabling of the robot. It is important to note that the robot should be in enabled state before attempting to move its joints.
def clean_shutdown(self):
"""
Exits example cleanly by moving head to neutral position and
maintaining start state
"""
print("\nExiting example...")
if self._done:
self.set_neutral()
if not self._init_state and self._rs.state().enabled:
print("Disabling robot...")
self._rs.disable()
This function performs a clean shutdown of the program. The _done
variable gets updated once the head finishes its wobbling. Then, the head is moved to its neutral position and checks if the _init_state
was in disabled state and the current state is enabled. If so, it resets the robot to the disable state.
def set_neutral(self):
"""
Sets the head back into a neutral pose
"""
self._head.set_pan(0.0)
The set_pan
function moves the head to the desired joint position. It employs a PID position controller to move the head joint to that position. In order to move the head to the neutral position, the pan is set to 0.
def wobble(self):
self.set_neutral()
"""
Performs the wobbling
"""
command_rate = rospy.Rate(1)
control_rate = rospy.Rate(100)
start = rospy.get_time()
This is where the actual wobbling happens. Before the robot starts to wobble its head, it moves its head to the neutral position.
while not rospy.is_shutdown() and (rospy.get_time() - start < 10.0):
angle = random.uniform(-2.0, 0.95)
This retrieves a random floating point number between -2.0 and 0.95. These random angles are generated for 10 seconds.
while (not rospy.is_shutdown() and
not (abs(self._head.pan() - angle) <=
intera_interface.HEAD_PAN_ANGLE_TOLERANCE)):
This ensures that it loops till the current head pan position and the random angle generated above is within the HEAD_PAN_ANGLE_TOLERANCE
.
self._head.set_pan(angle, speed=0.3, timeout=0)
control_rate.sleep()
command_rate.sleep()
This publishes the corresponding position and the speed to the robot/head/command_head_pan
.
self._done = True
rospy.signal_shutdown("Example finished.")
Once the wobbling is completed, the _done
variable is updated as True and a shutdown signal is sent.
def main():
"""RSDK Head Example: Wobbler
Nods the head and pans side-to-side towards random angles.
Demonstrates the use of the intera_interface.Head class.
"""
arg_fmt = argparse.RawDescriptionHelpFormatter
parser = argparse.ArgumentParser(formatter_class=arg_fmt,
description=main.__doc__)
parser.parse_args(rospy.myargv()[1:])
print("Initializing node... ")
rospy.init_node("rsdk_head_wobbler")
wobbler = Wobbler()
An object of the Wobbler
class is generated and this initializes the head interface, checks for the appropriate version and enables the robot.
rospy.on_shutdown(wobbler.clean_shutdown)
print("Wobbling... ")
wobbler.wobble()
print("Done.")
if __name__ == '__main__':
main()
Panning happens when the wobble()
function is called.
Was this article helpful?
That’s Great!
Thank you for your feedback
Sorry! We couldn't be helpful
Thank you for your feedback
Feedback sent
We appreciate your effort and will try to fix the article