3 import roslib; roslib.load_manifest(
'pr2_move_base')
6 from pr2_msgs.msg
import LaserTrajCmd
7 from pr2_msgs.srv
import SetLaserTrajCmd
8 import dynamic_reconfigure.client
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]
16 cmd.max_acceleration = 30
18 tilt_profile_client.call(cmd)
19 except rospy.ServiceException
as e:
20 rospy.logerr(
"Couldn't set the profile on the laser. Exception %s" % e)
27 rospy.wait_for_service(
'tilt_hokuyo_node/set_parameters', 10.0)
28 except rospy.exceptions.ROSException
as e:
29 rospy.logerr(
"Couldn't set parameters %s" % e)
33 client = dynamic_reconfigure.client.Client(
'tilt_hokuyo_node')
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)
40 if __name__ ==
'__main__':
41 name =
'setting_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)
def set_tilt_profile(position, time_from_start)