tilt_head.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Copyright (c) 2015 Fetch Robotics Inc.
4 # Copyright (c) 2013-2014 Unbounded Robotics Inc.
5 # All right reserved.
6 #
7 # Redistribution and use in source and binary forms, with or without
8 # modification, are permitted provided that the following conditions are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above copyright
13 # notice, this list of conditions and the following disclaimer in the
14 # documentation and/or other materials provided with the distribution.
15 # * Neither the name of Unbounded Robotics Inc. nor the names of its
16 # contributors may be used to endorse or promote products derived
17 # from this software without specific prior written permission.
18 #
19 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
20 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
21 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22 # DISCLAIMED. IN NO EVENT SHALL UNBOUNDED ROBOTICS INC. BE LIABLE FOR ANY DIRECT, INDIRECT,
23 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
24 # LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
25 # OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
26 # LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
27 # OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
28 # ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29 
30 #
31 # Tilt head for navigation obstacle avoidance.
32 #
33 
34 from threading import Lock
35 
36 import rospy
37 import actionlib
38 
39 from tf.listener import TransformListener
40 from tf.transformations import quaternion_matrix
41 
42 from actionlib_msgs.msg import GoalStatus, GoalStatusArray
43 from control_msgs.msg import PointHeadAction, PointHeadGoal
44 from geometry_msgs.msg import PointStamped
45 from nav_msgs.msg import Path
46 
48 
49  def __init__(self):
50  self.has_goal = False
51 
52  # pose and lock
53  self.x = 1.0
54  self.y = 0.0
55  self.mutex = Lock()
56 
57  self.listener = TransformListener()
58 
59  self.client = actionlib.SimpleActionClient("head_controller/point_head", PointHeadAction)
60  self.client.wait_for_server()
61 
62  self.plan_sub = rospy.Subscriber("move_base/TrajectoryPlannerROS/local_plan", Path, self.planCallback)
63  self.stat_sub = rospy.Subscriber("move_base/status", GoalStatusArray, self.statCallback)
64 
65  def statCallback(self, msg):
66  goal = False
67  for status in msg.status_list:
68  if status.status == GoalStatus.ACTIVE:
69  goal = True
70  break
71  self.has_goal = goal
72 
73  def planCallback(self, msg):
74  # get the goal
75  pose_stamped = msg.poses[-1]
76  pose = pose_stamped.pose
77 
78  # look ahead one meter
79  R = quaternion_matrix([pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w])
80  point = [1, 0, 0, 1]
81  M = R*point
82 
83  p = PointStamped()
84  p.header.frame_id = pose_stamped.header.frame_id
85  p.header.stamp = rospy.Time(0)
86  p.point.x += pose_stamped.pose.position.x + M[0,0]
87  p.point.y += pose_stamped.pose.position.y + M[1,0]
88  p.point.z += pose_stamped.pose.position.z + M[2,0]
89 
90  # transform to base_link
91  p = self.listener.transformPoint("base_link", p)
92 
93  # update
94  with self.mutex:
95  if p.point.x < 0.65:
96  self.x = 0.65
97  else:
98  self.x = p.point.x
99  if p.point.y > 0.5:
100  self.y = 0.5
101  elif p.point.y < -0.5:
102  self.y = -0.5
103  else:
104  self.y = p.point.y
105 
106  def loop(self):
107  while not rospy.is_shutdown():
108  if self.has_goal:
109  goal = PointHeadGoal()
110  goal.target.header.stamp = rospy.Time.now()
111  goal.target.header.frame_id = "base_link"
112  with self.mutex:
113  goal.target.point.x = self.x
114  goal.target.point.y = self.y
115  self.x = 1
116  self.y = 0
117  goal.target.point.z = 0.0
118  goal.min_duration = rospy.Duration(1.0)
119 
120  self.client.send_goal(goal)
121  self.client.wait_for_result()
122 
123  with self.mutex:
124  goal.target.point.x = self.x
125  goal.target.point.y = self.y
126  self.x = 1
127  self.y = 0
128  goal.target.point.z = 0.75
129 
130  self.client.send_goal(goal)
131  self.client.wait_for_result()
132  else:
133  rospy.sleep(1.0)
134 
135 if __name__=="__main__":
136  rospy.init_node("tilt_head_node")
138  h.loop()
def statCallback(self, msg)
Definition: tilt_head.py:65
def planCallback(self, msg)
Definition: tilt_head.py:73


fetch_navigation
Author(s): Michael Ferguson
autogenerated on Mon Feb 28 2022 22:24:05