2 Pheeno Robot Python Class files for coding 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. 10 Written by: Zahi Kakish (zmk5) 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
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 36 ID number of the pheeno. 38 Initial linear velocity of the robot. 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. 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 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" 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" 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" 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" 81 Obstacle avoidance algorithm based on IR sensors. Call when wanting to 82 plan motion while still trying to avoid obstacles. 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. 90 >>> # If you have more than 10 robots add a `0` to the first 92 >>> pheeno = PheenoRobot("01", linear_vel=0.8, angular_vel=0) 95 def __init__(self, robot_id, linear_velocity=0, angular_velocity=0,
96 obstacle_velocity=0.5):
101 self.
pheeno_id =
"/pheeno_" + str(robot_id)
104 "angular": float(angular_velocity),
105 "obstacle": float(obstacle_velocity)}
114 "odom": {
"position": 0.0,
122 "magnetometer": {
"x": 0.0,
125 "gyroscope": {
"x": 0.0,
128 "accelerometer": {
"x": 0.0,
138 rospy.Subscriber(self.
pheeno_id +
"/scan_center", Float32,
140 rospy.Subscriber(self.
pheeno_id +
"/scan_back", Float32,
142 rospy.Subscriber(self.
pheeno_id +
"/scan_right", Float32,
144 rospy.Subscriber(self.
pheeno_id +
"/scan_left", Float32,
146 rospy.Subscriber(self.
pheeno_id +
"/scan_cr", Float32,
148 rospy.Subscriber(self.
pheeno_id +
"/scan_cl", Float32,
152 rospy.Subscriber(self.
pheeno_id +
"/encoder_LL", Int16,
154 rospy.Subscriber(self.
pheeno_id +
"/encoder_LR", Int16,
156 rospy.Subscriber(self.
pheeno_id +
"/encoder_RL", Int16,
158 rospy.Subscriber(self.
pheeno_id +
"/encoder_RR", Int16,
162 rospy.Subscriber(self.
pheeno_id +
"/magnetometer", Vector3,
164 rospy.Subscriber(self.
pheeno_id +
"/gyroscope", Vector3,
166 rospy.Subscriber(self.
pheeno_id +
"/accelerometer", Vector3,
170 """ Callback for IR sensors subscriber """ 174 """ Callback for Encoder sensors subscriber """ 178 """ Callback for Magnetometer sensor subscriber """ 184 """ Callback for Gyroscope sensor subscriber """ 190 """ Callback for Accelerometer sensor subscriber """ 197 """ Linear velocity property """ 200 @linear_velocity.setter
202 """ Linear velocity setter property """ 203 if -1.0 < value < 1.0:
207 raise ValueError(
"Motor values must be between -1 and 1.")
211 """ Angular velocity property """ 214 @angular_velocity.setter
216 """ Angular velocity setter property """ 217 if -1.0 < value < 1.0:
221 raise ValueError(
"Motor values must be between -1 and 1.")
225 """ Obstacle velocity property """ 228 @obstacle_velocity.setter
230 """ Obstacle velocity setter property """ 235 raise ValueError(
"Obstacle velocity should be an positive and between (0 < v < 1)")
238 """ Getter for IR Sensor data """ 241 for sensor
in [
"center",
"back",
"right",
"left",
"cr",
"cl"]:
249 """ Getter for Encoder data """ 252 for sensor
in [
"LL",
"LR",
"RL",
"RR"]:
260 """ Getter for Magnetometer data """ 263 for sensor
in [
"x",
"y",
"z"]:
264 values.append(self.
_sensor_data[
"magnetometer"][sensor])
271 """ Getter for Gyroscope data """ 274 for sensor
in [
"x",
"y",
"z"]:
282 """ Getter for Accelerometer data """ 285 for sensor
in [
"x",
"y",
"z"]:
286 values.append(self.
_sensor_data[
"accelerometer"][sensor])
293 """ Publish an movement velocity on the `cmd_vel` topic """ 294 self._pub.publish(twist_msg)
298 Obstacle avoidance algorithm 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 312 The desired linear velocity a user would like to set if there are 313 no obstacles in the way. 315 The desired angular velocity a user would like to set if there are 316 no obstacles in the way. 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) 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. 342 angular = -1 * self.
_velocity[
"obstacle"]
360 angular = angular_vel
368 """ Returns bool if an obstacle is in the way of any IR sensor """ 376 """ Returns bool if the specific IR sensor is triggered """ 384 """ Given a velocity, generate a random turn direction """ 385 if random.random() < 0.5:
386 rospy.loginfo(
"Turning Left")
389 rospy.loginfo(
"Turning Right")
def __callback_gyroscope(self, msg)
def __callback_magnetometer(self, msg)
def get_gyroscope_data(self, key)
def get_accelerometer_data(self, key)
def angular_velocity(self)
def publish_cmd_vel(self, twist_msg)
def __callback_ir_sensor(self, msg, location)
def obstacle_velocity(self)
def avoid_obstacle(self, limit, linear_vel, angular_vel)
def linear_velocity(self)
def get_ir_data(self, key)
def is_ir_sensor_triggered(self, key, limit)
def __callback_encoder(self, msg, location)
def is_obstacle_detected(self, limit)
def __init__(self, robot_id, linear_velocity=0, angular_velocity=0, obstacle_velocity=0.5)
def get_encoder_data(self, key)
def __callback_accelerometer(self, msg)
def get_magnetometer_data(self, key)