pheeno_robot.cpp
Go to the documentation of this file.
1 #include "ros/ros.h"
2 #include "std_msgs/Float32.h"
3 #include "std_msgs/Int16.h"
4 #include "geometry_msgs/Twist.h"
5 #include "nav_msgs/Odometry.h"
7 #include <vector>
8 #include <complex>
9 #include <cstdlib>
10 #include <iostream>
11 
12 /*
13  * Contructor for the PheenoRobot Class.
14  *
15  * The class constructor fills all std::vector variables with zeros
16  * for use by the setters. Publishers and Subscribers are formally
17  * defined as well.
18  *
19  */
20 PheenoRobot::PheenoRobot(std::string pheeno_name)
21 {
22  ROS_INFO("Creating Pheeno Robot.");
23  pheeno_namespace_id_ = pheeno_name;
24 
25  // Create IR sensor vector upon construction. (6 placements)
26  for (int i = 0; i < 6; i++)
27  {
28  ir_sensor_vals_.push_back(0);
29  }
30 
31  // Create sensor vector upon construction. (3 placements)
32  for (int i = 0; i < 3; i++)
33  {
34  odom_pose_position_.push_back(0);
35  odom_twist_linear_.push_back(0);
36  odom_twist_angular_.push_back(0);
37 
38  magnetometer_vals_.push_back(0);
39  gyroscope_vals_.push_back(0);
40  accelerometer_vals_.push_back(0);
41  }
42 
43  // Create sensor vector upon construction. (4 placements)
44  for (int i = 0; i < 4; i++)
45  {
46  odom_pose_orient_.push_back(0);
47  encoder_vals_.push_back(0);
48  }
49 
50  // IR Sensor Subscribers
51  sub_ir_center_ = nh_.subscribe(pheeno_name + "/scan_center", 10,
53  sub_ir_right_ = nh_.subscribe(pheeno_name + "/scan_right", 10,
55  sub_ir_left_ = nh_.subscribe(pheeno_name + "/scan_left", 10,
57  sub_ir_cr_ = nh_.subscribe(pheeno_name + "/scan_cr", 10,
59  sub_ir_cl_ = nh_.subscribe(pheeno_name + "/scan_cl", 10,
61  sub_ir_back_ = nh_.subscribe(pheeno_name + "/scan_back", 10,
63  sub_ir_bottom_ = nh_.subscribe(pheeno_name + "/scan_bottom", 10,
65 
66  // Odom Subscriber
67  sub_odom_ = nh_.subscribe(pheeno_name + "/odom", 1,
69 
70  // Encoder Subscribers
71  sub_encoder_LL_ = nh_.subscribe(pheeno_name + "/encoder_LL", 10,
73  sub_encoder_LR_ = nh_.subscribe(pheeno_name + "/encoder_LR", 10,
75  sub_encoder_RL_ = nh_.subscribe(pheeno_name + "/encoder_RL", 10,
77  sub_encoder_RR_ = nh_.subscribe(pheeno_name + "/encoder_RR", 10,
79 
80  // Magnetometer, Gyroscope, Accelerometer Subscriber
81  sub_magnetometer_ = nh_.subscribe(pheeno_name + "/magnetometer", 10,
83  sub_gyroscope_ = nh_.subscribe(pheeno_name + "/gyroscope", 10,
85  sub_accelerometer_ = nh_.subscribe(pheeno_name + "/accelerometer", 10,
87 
88  // cmd_vel Publisher
89  pub_cmd_vel_ = nh_.advertise<geometry_msgs::Twist>(pheeno_name + "/cmd_vel", 100);
90 
91 }
92 
93 /*
94  * Publishes command velocity (cmd_vel) messages.
95  *
96  * The specific Topic name that the message is published to is defined
97  * in the Constructor for the PheenoRobot class.
98  */
99 void PheenoRobot::publish(geometry_msgs::Twist velocity)
100 {
101  pub_cmd_vel_.publish(velocity);
102 }
103 
104 /*
105  * Callback function for the IR Sensor (center) ROS subscriber.
106  */
107 void PheenoRobot::irSensorCenterCallback(const std_msgs::Float32::ConstPtr& msg)
108 {
109  ir_sensor_vals_[Pheeno::IR::CENTER] = static_cast<double>(msg->data);
110 }
111 
112 /*
113  * Callback function for the IR Sensor (back) ROS subscriber.
114  */
115 void PheenoRobot::irSensorBackCallback(const std_msgs::Float32::ConstPtr& msg)
116 {
117  ir_sensor_vals_[Pheeno::IR::BACK] = static_cast<double>(msg->data);
118 }
119 
120 /*
121  * Callback function for the IR Sensor (right) ROS subscriber.
122  */
123 void PheenoRobot::irSensorRightCallback(const std_msgs::Float32::ConstPtr& msg)
124 {
125  ir_sensor_vals_[Pheeno::IR::RIGHT] = static_cast<double>(msg->data);
126 }
127 
128 /*
129  * Callback function for the IR Sensor (left) ROS subscriber.
130  */
131 void PheenoRobot::irSensorLeftCallback(const std_msgs::Float32::ConstPtr& msg)
132 {
133  ir_sensor_vals_[Pheeno::IR::LEFT] = static_cast<double>(msg->data);
134 }
135 
136 /*
137  * Callback function for the IR Sensor (center-right) ROS subscriber.
138  */
139 void PheenoRobot::irSensorCRightCallback(const std_msgs::Float32::ConstPtr& msg)
140 {
141  ir_sensor_vals_[Pheeno::IR::CRIGHT] = static_cast<double>(msg->data);
142 }
143 
144 /*
145  * Callback function for the IR Sensor (center-left) ROS subscriber.
146  */
147 void PheenoRobot::irSensorCLeftCallback(const std_msgs::Float32::ConstPtr& msg)
148 {
149  ir_sensor_vals_[Pheeno::IR::CLEFT] = static_cast<double>(msg->data);
150 }
151 
152 /*
153  * Given a specific sensor limit, this member function returns a bool if
154  * any of the sensors within ir_sensor_values is triggered.
155  */
156 bool PheenoRobot::irSensorTriggered(float sensor_limit)
157 {
158  int count = 0;
159  for (int i = 0; i < 7; i++)
160  {
161  if (ir_sensor_vals_[i] < sensor_limit)
162  {
163  count += 1;
164  }
165  }
166 
167  // Greater than 1 instead of 0, because we aren't using the back IR sensor.
168  return (count > 1) ? true : false;
169 }
170 
171 /*
172  * Callback function for the IR Sensor (bottom) ROS subscriber.
173  *
174  * Sets the data to either 0 or 1 if the message recieved is less than
175  * 1600 or greater than 1600, respectively. The 1600 number is dependent
176  * on the IR sensor used, therefore its value can be changed for use with
177  * different applications.
178  *
179  * NOTE: ONLY FOR THE PHEENO MARKOV CHAIN EXPERIMENT.
180  */
181 void PheenoRobot::irSensorBottomCallback(const std_msgs::Int16::ConstPtr& msg)
182 {
183  if (msg->data < 1600)
184  {
185  ir_sensor_bottom_.data = 0; // Black on the bottom
186  }
187  else
188  {
189  ir_sensor_bottom_.data = 1; // White on the bottom
190  }
191 }
192 
193 /*
194  * Callback function for the odom ROS subscriber.
195  *
196  * This will set message data to odom pose (position and orientation) and twist
197  * (linear and angular) variables.
198  *
199  * NOTE: ONLY USED IF `libgazebo_ros_p3d.so` PLUGIN IS IN THE XACRO FILE.
200  */
201 void PheenoRobot::odomCallback(const nav_msgs::Odometry::ConstPtr& msg)
202 {
203  // Assign values to appropriate pose information.
204  odom_pose_position_[0] = static_cast<double>(msg->pose.pose.position.x);
205  odom_pose_position_[1] = static_cast<double>(msg->pose.pose.position.y);
206  odom_pose_position_[2] = static_cast<double>(msg->pose.pose.position.z);
207  odom_pose_orient_[0] = static_cast<double>(msg->pose.pose.orientation.x);
208  odom_pose_orient_[1] = static_cast<double>(msg->pose.pose.orientation.y);
209  odom_pose_orient_[2] = static_cast<double>(msg->pose.pose.orientation.z);
210  odom_pose_orient_[3] = static_cast<double>(msg->pose.pose.orientation.w);
211 
212  // Assign values to appropriate twist information.
213  odom_twist_linear_[0] = static_cast<double>(msg->twist.twist.linear.x);
214  odom_twist_linear_[1] = static_cast<double>(msg->twist.twist.linear.y);
215  odom_twist_linear_[2] = static_cast<double>(msg->twist.twist.linear.z);
216  odom_twist_angular_[0] = static_cast<double>(msg->twist.twist.angular.x);
217  odom_twist_angular_[1] = static_cast<double>(msg->twist.twist.angular.y);
218  odom_twist_angular_[2] = static_cast<double>(msg->twist.twist.angular.z);
219 }
220 
221 /*
222  * Callback function for the Encoder LL ROS subscriber.
223  */
224 void PheenoRobot::encoderLLCallback(const std_msgs::Int16::ConstPtr& msg)
225 {
226  encoder_vals_[Pheeno::ENCODER::LL] = static_cast<int>(msg->data);
227 }
228 
229 /*
230  * Callback function for the Encoder LR ROS subscriber.
231  */
232 void PheenoRobot::encoderLRCallback(const std_msgs::Int16::ConstPtr& msg)
233 {
234  encoder_vals_[Pheeno::ENCODER::LR] = static_cast<int>(msg->data);
235 }
236 
237 /*
238  * Callback function for the Encoder RL ROS subscriber.
239  */
240 void PheenoRobot::encoderRLCallback(const std_msgs::Int16::ConstPtr& msg)
241 {
242  encoder_vals_[Pheeno::ENCODER::RL] = static_cast<int>(msg->data);
243 }
244 
245 /*
246  * Callback function for the Encoder RR ROS subscriber.
247  */
248 void PheenoRobot::encoderRRCallback(const std_msgs::Int16::ConstPtr& msg)
249 {
250  encoder_vals_[Pheeno::ENCODER::RR] = static_cast<int>(msg->data);
251 }
252 
253 /*
254  * Callback function for the Magnetometer sensor ROS subscriber.
255  */
256 void PheenoRobot::magnetometerCallback(const geometry_msgs::Vector3::ConstPtr& msg)
257 {
258  magnetometer_vals_[0] = static_cast<double>(msg->x);
259  magnetometer_vals_[1] = static_cast<double>(msg->y);
260  magnetometer_vals_[2] = static_cast<double>(msg->z);
261 }
262 
263 /*
264  * Callback function for the Gyroscope sensor ROS subscriber.
265  */
266 void PheenoRobot::gyroscopeCallback(const geometry_msgs::Vector3::ConstPtr& msg)
267 {
268  gyroscope_vals_[0] = static_cast<double>(msg->x);
269  gyroscope_vals_[1] = static_cast<double>(msg->y);
270  gyroscope_vals_[2] = static_cast<double>(msg->z);
271 }
272 
273 /*
274  * Callback function for the Accelerometer sensor ROS subscriber.
275  */
276 void PheenoRobot::accelerometerCallback(const geometry_msgs::Vector3::ConstPtr& msg)
277 {
278  accelerometer_vals_[0] = static_cast<double>(msg->x);
279  accelerometer_vals_[1] = static_cast<double>(msg->y);
280  accelerometer_vals_[2] = static_cast<double>(msg->z);
281 }
282 
283 /*
284  * Callback function for the Pi Cam ROS subscriber.
285  *
286  * Will recieve sensor_msgs.Image() messages and save only the current frame. If
287  * the user needs to do image manipulation, use the CV_BRIDGE ros package to
288  * convert the sensor_msgs.Image() data type to one useable by OpenCV.
289  */
291 {
292  ROS_INFO("Not in use yet.");
293 }
294 
295 /*
296  * Generates a random turn direction (a sign change) based on a user provided value.
297  */
298 double PheenoRobot::randomTurn(float angular)
299 {
300  return rand() % 10 + 1 <= 5 ? (-1 * angular) : angular;
301 }
302 
303 /*
304  * Obstacle avoidance logic for a robot moving in a linear motion.
305  *
306  * Using class specific IR values, this simple if-else logic progresses by
307  * comparing them to a certain range to avoid (default value). If triggered,
308  * the references to linear and angular are set to specific values to make the
309  * robot avoid the obstacle.
310  */
311 void PheenoRobot::avoidObstaclesLinear(double& linear, double& angular, float angular_velocity, float linear_velocity, double range_to_avoid)
312 {
313  if (ir_sensor_vals_[Pheeno::IR::CENTER] < range_to_avoid)
314  {
316  (ir_sensor_vals_[Pheeno::IR::RIGHT] > range_to_avoid && ir_sensor_vals_[Pheeno::IR::LEFT] > range_to_avoid))
317  {
318  linear = 0.0;
319  angular = randomTurn();
320  }
321 
322  if (ir_sensor_vals_[Pheeno::IR::RIGHT] < ir_sensor_vals_[Pheeno::IR::LEFT])
323  {
324  linear = 0.0;
325  angular = -1 * angular_velocity; // Turn Left
326  }
327  else
328  {
329  linear = 0.0;
330  angular = angular_velocity; // Turn Right
331  }
332  }
333  else if (ir_sensor_vals_[Pheeno::IR::CRIGHT] < range_to_avoid && ir_sensor_vals_[Pheeno::IR::CLEFT] < range_to_avoid)
334  {
335  linear = 0.0;
336  angular = randomTurn();
337  }
338  else if (ir_sensor_vals_[Pheeno::IR::CRIGHT] < range_to_avoid)
339  {
340  linear = 0.0;
341  angular = -1 * angular_velocity; // Turn Left
342  }
343  else if (ir_sensor_vals_[Pheeno::IR::CLEFT] < range_to_avoid)
344  {
345  linear = 0.0;
346  angular = angular_velocity; // Turn Right
347  }
348  else if (ir_sensor_vals_[Pheeno::IR::RIGHT] < range_to_avoid)
349  {
350  linear = 0.0;
351  angular = -1 * angular_velocity; // Turn Left
352  }
353  else if (ir_sensor_vals_[Pheeno::IR::LEFT] < range_to_avoid)
354  {
355  linear = 0.0;
356  angular = angular_velocity; // Turn Right
357  }
358  else
359  {
360  linear = linear_velocity; // Move Straight
361  angular = 0.0;
362  }
363 }
364 
365 /*
366  * Obstacle avoidance logic for a robot moving in an angular (turning) motion.
367  *
368  * Using class specific IR values, this simple if-else logic progresses by
369  * comparing them to a certain range to avoid (default value). If triggered,
370  * the references to angular are set to specific values to make the robot avoid
371  * the obstacle. Compared to the linear version of this callback member
372  * function, this function only modifies the angular reference.
373  */
374 void PheenoRobot::avoidObstaclesAngular(double& angular, double& random_turn_value, float angular_velocity, double range_to_avoid)
375 {
376  if (ir_sensor_vals_[Pheeno::IR::CENTER] < range_to_avoid)
377  {
379  (ir_sensor_vals_[Pheeno::IR::RIGHT] > range_to_avoid && ir_sensor_vals_[Pheeno::IR::LEFT] > range_to_avoid))
380  {
381  angular = randomTurn();
382  }
383 
384  if (ir_sensor_vals_[Pheeno::IR::RIGHT] < ir_sensor_vals_[Pheeno::IR::LEFT])
385  {
386  angular = -1 * angular_velocity; // Turn Left
387  }
388  else
389  {
390  angular = angular_velocity; // Turn Right
391  }
392  }
393  else if (ir_sensor_vals_[Pheeno::IR::CRIGHT] < range_to_avoid && ir_sensor_vals_[Pheeno::IR::CLEFT] < range_to_avoid)
394  {
395  angular = randomTurn();
396  }
397  else if (ir_sensor_vals_[Pheeno::IR::CRIGHT] < range_to_avoid)
398  {
399  angular = -1 * angular_velocity; // Turn Left
400  }
401  else if (ir_sensor_vals_[Pheeno::IR::CLEFT] < range_to_avoid)
402  {
403  angular = angular_velocity; // Turn Right
404  }
405  else if (ir_sensor_vals_[Pheeno::IR::RIGHT] < range_to_avoid)
406  {
407  angular = -1 * angular_velocity; // Turn Left
408  }
409  else if (ir_sensor_vals_[Pheeno::IR::LEFT] < range_to_avoid)
410  {
411  angular = angular_velocity; // Turn Right
412  }
413  else
414  {
415  angular = random_turn_value;
416  }
417 
418  if (angular != random_turn_value)
419  {
420  random_turn_value = angular;
421  }
422 }
bool irSensorTriggered(float sensor_limits)
void irSensorCLeftCallback(const std_msgs::Float32::ConstPtr &msg)
ros::NodeHandle nh_
Definition: pheeno_robot.h:88
void accelerometerCallback(const geometry_msgs::Vector3::ConstPtr &msg)
void publish(geometry_msgs::Twist velocity)
void irSensorBottomCallback(const std_msgs::Int16::ConstPtr &msg)
std::vector< double > gyroscope_vals_
Definition: pheeno_robot.h:56
void gyroscopeCallback(const geometry_msgs::Vector3::ConstPtr &msg)
void publish(const boost::shared_ptr< M > &message) const
PheenoRobot(std::string pheeno_name)
ros::Subscriber sub_ir_cr_
Definition: pheeno_robot.h:94
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber sub_odom_
Definition: pheeno_robot.h:99
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
void encoderRLCallback(const std_msgs::Int16::ConstPtr &msg)
void irSensorCenterCallback(const std_msgs::Float32::ConstPtr &msg)
ros::Subscriber sub_gyroscope_
Definition: pheeno_robot.h:105
std::vector< double > odom_pose_position_
Definition: pheeno_robot.h:61
ros::Subscriber sub_encoder_RL_
Definition: pheeno_robot.h:102
ros::Subscriber sub_magnetometer_
Definition: pheeno_robot.h:104
void irSensorBackCallback(const std_msgs::Float32::ConstPtr &msg)
ros::Subscriber sub_ir_left_
Definition: pheeno_robot.h:93
ros::Subscriber sub_encoder_LR_
Definition: pheeno_robot.h:101
std_msgs::Int16 ir_sensor_bottom_
Definition: pheeno_robot.h:52
std::vector< double > odom_twist_angular_
Definition: pheeno_robot.h:64
void magnetometerCallback(const geometry_msgs::Vector3::ConstPtr &msg)
ros::Subscriber sub_ir_bottom_
Definition: pheeno_robot.h:97
std::vector< double > accelerometer_vals_
Definition: pheeno_robot.h:57
std::vector< double > odom_pose_orient_
Definition: pheeno_robot.h:62
#define ROS_INFO(...)
std::vector< int > encoder_vals_
Definition: pheeno_robot.h:54
ros::Subscriber sub_encoder_RR_
Definition: pheeno_robot.h:103
ros::Subscriber sub_ir_center_
Definition: pheeno_robot.h:91
ros::Subscriber sub_ir_right_
Definition: pheeno_robot.h:92
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::vector< double > odom_twist_linear_
Definition: pheeno_robot.h:63
ros::Subscriber sub_accelerometer_
Definition: pheeno_robot.h:106
void piCamCallback()
void encoderLRCallback(const std_msgs::Int16::ConstPtr &msg)
ros::Subscriber sub_encoder_LL_
Definition: pheeno_robot.h:100
std::vector< double > magnetometer_vals_
Definition: pheeno_robot.h:55
ros::Publisher pub_cmd_vel_
Definition: pheeno_robot.h:109
void avoidObstaclesAngular(double &angular, double &random_turn_value, float angular_velocity=1.2, double range_to_avoid=20.0)
ros::Subscriber sub_ir_back_
Definition: pheeno_robot.h:96
ros::Subscriber sub_ir_cl_
Definition: pheeno_robot.h:95
void encoderLLCallback(const std_msgs::Int16::ConstPtr &msg)
void encoderRRCallback(const std_msgs::Int16::ConstPtr &msg)
void irSensorLeftCallback(const std_msgs::Float32::ConstPtr &msg)
double randomTurn(float angular=0.06)
void irSensorCRightCallback(const std_msgs::Float32::ConstPtr &msg)
std::vector< double > ir_sensor_vals_
Definition: pheeno_robot.h:53
std::string pheeno_namespace_id_
Definition: pheeno_robot.h:43
void irSensorRightCallback(const std_msgs::Float32::ConstPtr &msg)
void avoidObstaclesLinear(double &linear, double &angular, float angular_velocity=1.2, float linear_velocity=0.08, double range_to_avoid=20.0)


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