def on_start_button_clicked(self):
     self._ui.start_button.setEnabled(False)
     self._ui.stop_button.setEnabled(True)
     if not self._scan_to_angle:
         self._scan_to_angle = ScanToAngle('/scan',self._laser_scan_angle_topic_name)
     if not self._motion:
         self._motion = DriftEstimation(self._laser_scan_angle_topic_name, self._gyro_scan_angle_topic_name, self._error_scan_angle_topic_name, self._cmd_vel_topic_name,self._gyro_topic_name)
         self._motion.init(self._ui.angular_speed_spinbox.value())
     rospy.sleep(0.5)
     self._plot_widget.data_plot.reset()
     self._plot_widget._start_time = rospy.get_time()
     self._plot_widget.enable_timer(True)
     try:
         self._plot_widget.remove_topic(self._error_scan_angle_topic_name+'/scan_angle')
         self._plot_widget_live.remove_topic(self._laser_scan_angle_topic_name+'/scan_angle')
         self._plot_widget_live.remove_topic(self._gyro_scan_angle_topic_name+'/scan_angle')
         self._plot_widget_live.remove_topic(self._cmd_vel_topic_name+'/angular/z')
     except KeyError:
         pass
     self._plot_widget_live.add_topic(self._cmd_vel_topic_name+'/angular/z')
     self._plot_widget_live.add_topic(self._laser_scan_angle_topic_name+'/scan_angle')
     self._plot_widget_live.add_topic(self._gyro_scan_angle_topic_name+'/scan_angle')
     self._plot_widget.add_topic(self._error_scan_angle_topic_name+'/scan_angle')
     self._motion_thread = WorkerThread(self._motion.execute, None)
     self._motion_thread.start()
#!/usr/bin/env python
#
# License: BSD
#   https://raw.github.com/yujinrobot/kobuki/hydro-devel/kobuki_testsuite/LICENSE
#
##############################################################################
# Imports
##############################################################################

import roslib
roslib.load_manifest('kobuki_testsuite')
import rospy
from kobuki_testsuite import ScanToAngle

##############################################################################
# Main
##############################################################################
'''
  Hold the kinect up in front of a wall. This will calculate the relative
  heading angle it makes with the wall.
'''
if __name__ == '__main__':
    rospy.init_node('scan_to_angle')
    s = ScanToAngle('/scan', '/scan_angle')
    rospy.spin()