pheeno_robot.py
Go to the documentation of this file.
1 """
2 Pheeno Robot Python Class files for coding
3 
4 Notes
5 -----
6 Contains files directly related to Pheeno Robot movement, sensors, etc. This
7 object class can be used in other python scripts to give one direct control
8 of the Pheeno without needing to write extra attributes, callbacks, etc.
9 
10 Written by: Zahi Kakish (zmk5)
11 License: BSD 3-Clause
12 
13 """
14 import random
15 import rospy
16 from geometry_msgs.msg import Twist
17 from geometry_msgs.msg import Vector3
18 from std_msgs.msg import Float32
19 from std_msgs.msg import Int16
20 
21 
22 class PheenoRobot(object):
23  """
24  PheenoRobot Class
25 
26  Provides a easier way of generating all the necessary attributes, ROS
27  publishers and subscribers, and useful methods for running a Pheeno robot.
28  Just instantiate the class to a variable within a script and all the
29  necessary ROS calls are generated automatically. Many of the attributes
30  of the Pheeno are hidden from users (except velocity ones) and require
31  getters to get them.
32 
33  Parameters
34  ----------
35  robot_id : str
36  ID number of the pheeno.
37  linear : int/float
38  Initial linear velocity of the robot.
39  angular : int/float
40  Initial angular velocity of the robot.
41  obstacle_velocity : int/float
42  Velocity for obstacle avoidance. In terms of angular velocity, may be
43  faster or slower than the current value of angular velocity.
44 
45  Attributes
46  ----------
47  pheeno_id : str
48  The ID of the pheeno that is used as the namespace for pheeno ROS
49  publishers and subscribers.
50  linear_velocity : float (default 0)
51  The linear velocity of the robot.
52  angular_velocity : float (default 0)
53  The angular velocity of the robot.
54  obstacle_velocity : float (default 0.5)
55  If a robot approaces an obstacle, this is the angular velocity used for
56  obstacle avoidance.
57 
58  Methods
59  -------
60  get_ir_data
61  Returns the IR data for a specific sensor. If the "all" option is
62  used, then all the data is returned as a list.
63  Options: "center", "back", "right", "left", "cr", "cl", "all"
64  get_encoder_data
65  Returns encoder data for a specific encoder. If the "all" option is
66  used, then all the data is returned as a list.
67  Options: "LL", "LR", "RL", "RR", "all"
68  get_magnetometer_data
69  Returns magnetometer data for a specific coordinate. If the "all" option
70  is used, then all the data is returned as a list.
71  Options: "x", "y", "z", "all"
72  get_gyroscope_data
73  Returns gyroscope data for a specific coordinate. If "all" option is
74  used, then all the data is returned as a list.
75  Options: "x", "y", "z", "all"
76  get_accelerometer_data
77  Returns accelerometer data for a specific coordinate. If "all" option
78  is used, then all the data is returned as a list.
79  Options: "x", "y", "z", "all"
80  avoid_obstacle
81  Obstacle avoidance algorithm based on IR sensors. Call when wanting to
82  plan motion while still trying to avoid obstacles.
83  is_obstacle_detected
84  Bool return if any IR sensor has been tripped.
85  is_ir_sensor_triggered
86  Bool return if a SPECIFIC IR sensor has been tripped.
87 
88  Examples
89  --------
90  >>> # If you have more than 10 robots add a `0` to the first
91  >>> # 9 numbers.
92  >>> pheeno = PheenoRobot("01", linear_vel=0.8, angular_vel=0)
93 
94  """
95  def __init__(self, robot_id, linear_velocity=0, angular_velocity=0,
96  obstacle_velocity=0.5):
97  if robot_id == "":
98  self.pheeno_id = robot_id
99 
100  else:
101  self.pheeno_id = "/pheeno_" + str(robot_id)
102 
103  self._velocity = {"linear": float(linear_velocity),
104  "angular": float(angular_velocity),
105  "obstacle": float(obstacle_velocity)}
106 
107  # Sensor Values
108  self._sensor_data = {"ir": {"center": 0.0,
109  "back": 0.0,
110  "right": 0.0,
111  "left": 0.0,
112  "cr": 0.0,
113  "cl": 0.0},
114  "odom": {"position": 0.0,
115  "orient": 0.0,
116  "linear": 0.0,
117  "angular": 0.0},
118  "encoder": {"LL": 0,
119  "LR": 0,
120  "RL": 0,
121  "RR": 0},
122  "magnetometer": {"x": 0.0,
123  "y": 0.0,
124  "z": 0.0},
125  "gyroscope": {"x": 0.0,
126  "y": 0.0,
127  "z": 0.0},
128  "accelerometer": {"x": 0.0,
129  "y": 0.0,
130  "z": 0.0}}
131 
132  # cmd_vel Publisher
133  self._pub = rospy.Publisher(self.pheeno_id + "/cmd_vel",
134  Twist,
135  queue_size=100)
136 
137  # IR Sensor Subscribers
138  rospy.Subscriber(self.pheeno_id + "/scan_center", Float32,
139  self.__callback_ir_sensor, callback_args="center")
140  rospy.Subscriber(self.pheeno_id + "/scan_back", Float32,
141  self.__callback_ir_sensor, callback_args="back")
142  rospy.Subscriber(self.pheeno_id + "/scan_right", Float32,
143  self.__callback_ir_sensor, callback_args="right")
144  rospy.Subscriber(self.pheeno_id + "/scan_left", Float32,
145  self.__callback_ir_sensor, callback_args="left")
146  rospy.Subscriber(self.pheeno_id + "/scan_cr", Float32,
147  self.__callback_ir_sensor, callback_args="cr")
148  rospy.Subscriber(self.pheeno_id + "/scan_cl", Float32,
149  self.__callback_ir_sensor, callback_args="cl")
150 
151  # Encoder Subscribers
152  rospy.Subscriber(self.pheeno_id + "/encoder_LL", Int16,
153  self.__callback_encoder, callback_args="LL")
154  rospy.Subscriber(self.pheeno_id + "/encoder_LR", Int16,
155  self.__callback_encoder, callback_args="LR")
156  rospy.Subscriber(self.pheeno_id + "/encoder_RL", Int16,
157  self.__callback_encoder, callback_args="RL")
158  rospy.Subscriber(self.pheeno_id + "/encoder_RR", Int16,
159  self.__callback_encoder, callback_args="RR")
160 
161  # Magnetometer, Gyroscope, Accelerometer Subscriber
162  rospy.Subscriber(self.pheeno_id + "/magnetometer", Vector3,
164  rospy.Subscriber(self.pheeno_id + "/gyroscope", Vector3,
166  rospy.Subscriber(self.pheeno_id + "/accelerometer", Vector3,
168 
169  def __callback_ir_sensor(self, msg, location):
170  """ Callback for IR sensors subscriber """
171  self._sensor_data["ir"][location] = msg.data
172 
173  def __callback_encoder(self, msg, location):
174  """ Callback for Encoder sensors subscriber """
175  self._sensor_data["encoder"][location] = msg.data
176 
177  def __callback_magnetometer(self, msg):
178  """ Callback for Magnetometer sensor subscriber """
179  self._sensor_data["magnetometer"]["x"] = msg.x
180  self._sensor_data["magnetometer"]["y"] = msg.y
181  self._sensor_data["magnetometer"]["z"] = msg.z
182 
183  def __callback_gyroscope(self, msg):
184  """ Callback for Gyroscope sensor subscriber """
185  self._sensor_data["gyroscope"]["x"] = msg.x
186  self._sensor_data["gyroscope"]["y"] = msg.y
187  self._sensor_data["gyroscope"]["z"] = msg.z
188 
189  def __callback_accelerometer(self, msg):
190  """ Callback for Accelerometer sensor subscriber """
191  self._sensor_data["accelerometer"]["x"] = msg.x
192  self._sensor_data["accelerometer"]["y"] = msg.y
193  self._sensor_data["accelerometer"]["z"] = msg.z
194 
195  @property
196  def linear_velocity(self):
197  """ Linear velocity property """
198  return self._velocity["linear"]
199 
200  @linear_velocity.setter
201  def linear_velocity(self, value):
202  """ Linear velocity setter property """
203  if -1.0 < value < 1.0:
204  self._velocity["linear"] = value
205 
206  else:
207  raise ValueError("Motor values must be between -1 and 1.")
208 
209  @property
210  def angular_velocity(self):
211  """ Angular velocity property """
212  return self._velocity["angular"]
213 
214  @angular_velocity.setter
215  def angular_velocity(self, value):
216  """ Angular velocity setter property """
217  if -1.0 < value < 1.0:
218  self._velocity["angular"] = value
219 
220  else:
221  raise ValueError("Motor values must be between -1 and 1.")
222 
223  @property
224  def obstacle_velocity(self):
225  """ Obstacle velocity property """
226  return self._velocity["obstacle"]
227 
228  @obstacle_velocity.setter
229  def obstacle_velocity(self, value):
230  """ Obstacle velocity setter property """
231  if 0 < value < 1.0:
232  self._velocity["obstacle"] = value
233 
234  else:
235  raise ValueError("Obstacle velocity should be an positive and between (0 < v < 1)")
236 
237  def get_ir_data(self, key):
238  """ Getter for IR Sensor data """
239  if key == "all":
240  values = []
241  for sensor in ["center", "back", "right", "left", "cr", "cl"]:
242  values.append(self._sensor_data["ir"][sensor])
243 
244  return values
245 
246  return self._sensor_data["ir"][key]
247 
248  def get_encoder_data(self, key):
249  """ Getter for Encoder data """
250  if key == "all":
251  values = []
252  for sensor in ["LL", "LR", "RL", "RR"]:
253  values.append(self._sensor_data["encoder"][sensor])
254 
255  return values
256 
257  return self._sensor_data["encoder"][key]
258 
259  def get_magnetometer_data(self, key):
260  """ Getter for Magnetometer data """
261  if key == "all":
262  values = []
263  for sensor in ["x", "y", "z"]:
264  values.append(self._sensor_data["magnetometer"][sensor])
265 
266  return values
267 
268  return self._sensor_data["magnetometer"][key]
269 
270  def get_gyroscope_data(self, key):
271  """ Getter for Gyroscope data """
272  if key == "all":
273  values = []
274  for sensor in ["x", "y", "z"]:
275  values.append(self._sensor_data["gyroscope"][sensor])
276 
277  return values
278 
279  return self._sensor_data["gyroscope"][key]
280 
281  def get_accelerometer_data(self, key):
282  """ Getter for Accelerometer data """
283  if key == "all":
284  values = []
285  for sensor in ["x", "y", "z"]:
286  values.append(self._sensor_data["accelerometer"][sensor])
287 
288  return values
289 
290  return self._sensor_data["accelerometer"][key]
291 
292  def publish_cmd_vel(self, twist_msg):
293  """ Publish an movement velocity on the `cmd_vel` topic """
294  self._pub.publish(twist_msg)
295 
296  def avoid_obstacle(self, limit, linear_vel, angular_vel):
297  """
298  Obstacle avoidance algorithm
299 
300  Given a desired linear and angular velocity, the algorithm will set
301  those values as the robots linear and angular velocity if no obstacle
302  is in the way. If there is, the linear velocity of the robot is set to
303  zero, and the angular velocity is set of a positive or negative version
304  of the obstacle velocity robot attribute depending on certain
305  conditions.
306 
307  Arguments
308  ---------
309  limit : int/float
310  The ir sensor limit.
311  linear_vel : float
312  The desired linear velocity a user would like to set if there are
313  no obstacles in the way.
314  angular_vel : float
315  The desired angular velocity a user would like to set if there are
316  no obstacles in the way.
317 
318  Examples
319  -------
320  For a robot moving along a linear path, the method may be called as such:
321  >>> ir_limit = 15 # in cm
322  >>> desired_linear = 0.7
323  >>> desired_angular = 0 # b/c we don't want it to turn
324  >>> pheeno.avoid_obstacle(ir_limit, desired_linear, desired_angular)
325 
326  If no obstacle is in the path of the robot, the attributes
327  `linear_velocity` and `angular_velocity` are set to 0.7 and 0,
328  respectively. If not, the values are set based on the internal logic of
329  the algorithm. Assign these values to the proper places in a
330  `geometry_msg.Twist()` msg and call the `publish_cmd_vel(twist_msg)`
331  method to enact the changes.
332 
333 
334  """
335  if self.is_obstacle_detected(limit):
336  if self.is_ir_sensor_triggered("center", limit):
337  if (self._sensor_data["ir"]["right"] < 10 and
338  self._sensor_data["ir"]["left"] < 10):
339  angular = self.random_turn() * self._velocity["obstacle"]
340 
341  if self._sensor_data["ir"]["right"] < self._sensor_data["ir"]["left"]:
342  angular = -1 * self._velocity["obstacle"] # Turn Left
343 
344  else:
345  angular = self._velocity["obstacle"] # Turn Right
346 
347  elif (self.is_ir_sensor_triggered("cl", limit) and
348  self.is_ir_sensor_triggered("cr", limit)):
349  angular = self.random_turn() * self._velocity["obstacle"]
350 
351  # If individual IR sensors are triggered.
352  else:
353  angular = self._velocity["obstacle"]
354 
355  # Set linear velocity to 0, so only angular velocity will occur.
356  linear = 0
357 
358  # If no obstacle detected, use the default terms.
359  else:
360  angular = angular_vel
361  linear = linear_vel
362 
363  # Set new velocities
364  self._velocity["linear"] = linear
365  self._velocity["angular"] = angular
366 
367  def is_obstacle_detected(self, limit):
368  """ Returns bool if an obstacle is in the way of any IR sensor """
369  for key in self._sensor_data["ir"]:
370  if self._sensor_data["ir"][key] <= limit:
371  return True
372 
373  return False
374 
375  def is_ir_sensor_triggered(self, key, limit):
376  """ Returns bool if the specific IR sensor is triggered """
377  if self._sensor_data["ir"][key] <= limit:
378  return True
379 
380  return False
381 
382  @staticmethod
383  def random_turn():
384  """ Given a velocity, generate a random turn direction """
385  if random.random() < 0.5:
386  rospy.loginfo("Turning Left")
387  return -1.0
388 
389  rospy.loginfo("Turning Right")
390  return 1.0
def publish_cmd_vel(self, twist_msg)
def __callback_ir_sensor(self, msg, location)
def avoid_obstacle(self, limit, linear_vel, angular_vel)
def is_ir_sensor_triggered(self, key, limit)
def __callback_encoder(self, msg, location)
def __init__(self, robot_id, linear_velocity=0, angular_velocity=0, obstacle_velocity=0.5)
Definition: pheeno_robot.py:96


pheeno_ros
Author(s): Zahi Kakish, Sean Wilson
autogenerated on Mon Jun 10 2019 14:10:48