start_laser.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 ### copy from pr2_move_base/scripts/pr2_move_base.py
3 import roslib; roslib.load_manifest('pr2_move_base')
4 import rospy
5 
6 from pr2_msgs.msg import LaserTrajCmd
7 from pr2_msgs.srv import SetLaserTrajCmd
8 import dynamic_reconfigure.client
9 
10 def set_tilt_profile(position, time_from_start):
11  cmd = LaserTrajCmd()
12  cmd.profile = 'blended_linear'
13  cmd.position = position
14  cmd.time_from_start = [rospy.Time.from_sec(x) for x in time_from_start]
15  cmd.max_velocity = 10
16  cmd.max_acceleration = 30
17  try:
18  tilt_profile_client.call(cmd)
19  except rospy.ServiceException, e:
20  rospy.logerr("Couldn't set the profile on the laser. Exception %s" % e)
21  return False
22  return True
23 
25  #TODO: remove hack to get things working in gazebo
26  try:
27  rospy.wait_for_service('tilt_hokuyo_node/set_parameters', 10.0)
28  except rospy.exceptions.ROSException, e:
29  rospy.logerr("Couldn't set parameters %s" % e)
30  return
31  #end TODO
32 
33  client = dynamic_reconfigure.client.Client('tilt_hokuyo_node')
34  global old_config
35  old_config = client.get_configuration(2.0)
36  new_config = {'skip': 0, 'intensity': 0, 'min_ang': -1.57, 'max_ang': 1.57, 'calibrate_time': 1, 'cluster': 1, 'time_offset': 0.0}
37  rospy.loginfo('Setting laser to the navigation configuration: %s' % new_config)
38  client.update_configuration(new_config)
39 
40 if __name__ == '__main__':
41  name = 'setting_laser'
42  rospy.init_node(name)
43 
44  #create a client to the tilt laser
45  rospy.wait_for_service('laser_tilt_controller/set_traj_cmd')
46  tilt_profile_client = rospy.ServiceProxy('laser_tilt_controller/set_traj_cmd', SetLaserTrajCmd)
47 
48  ## set_tilt_profile([1.05, -.7, 1.05], [0.0, 1.8, 2.0125 + .3]) ## original
49  set_tilt_profile([1.05, -.7, 1.05], [0.0, 2.4, 2.4 + .2125 + .3])
def set_tilt_profile(position, time_from_start)
Definition: start_laser.py:10
def configure_laser()
Definition: start_laser.py:24


pr2eus_tutorials
Author(s): Kei Okada
autogenerated on Fri Mar 5 2021 04:00:53