00001 #include "ros/ros.h"
00002 #include "std_msgs/Float32.h"
00003 #include "std_msgs/Int16.h"
00004 #include "geometry_msgs/Twist.h"
00005 #include "nav_msgs/Odometry.h"
00006 #include "pheeno_robot.h"
00007 #include <vector>
00008 #include <complex>
00009 #include <cstdlib>
00010 #include <iostream>
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020 PheenoRobot::PheenoRobot(std::string pheeno_name)
00021 {
00022 ROS_INFO("Creating Pheeno Robot.");
00023 pheeno_namespace_id = pheeno_name;
00024
00025
00026 for (int i = 0; i < 6; i++)
00027 {
00028 ir_sensor_values.push_back(0);
00029 }
00030
00031
00032 for (int i = 0; i < 3; i++)
00033 {
00034 odom_pose_position.push_back(0);
00035 odom_twist_linear.push_back(0);
00036 odom_twist_angular.push_back(0);
00037
00038 magnetometer_values.push_back(0);
00039 gyroscope_values.push_back(0);
00040 accelerometer_values.push_back(0);
00041 }
00042
00043
00044 for (int i = 0; i < 4; i++)
00045 {
00046 odom_pose_orient.push_back(0);
00047 encoder_values.push_back(0);
00048 }
00049
00050
00051 sub_ir_center_ = nh_.subscribe(pheeno_name + "/scan_center", 10,
00052 &PheenoRobot::irSensorCenterCallback, this);
00053 sub_ir_right_ = nh_.subscribe(pheeno_name + "/scan_right", 10,
00054 &PheenoRobot::irSensorRightCallback, this);
00055 sub_ir_left_ = nh_.subscribe(pheeno_name + "/scan_left", 10,
00056 &PheenoRobot::irSensorLeftCallback, this);
00057 sub_ir_cr_ = nh_.subscribe(pheeno_name + "/scan_cr", 10,
00058 &PheenoRobot::irSensorCRightCallback, this);
00059 sub_ir_cl_ = nh_.subscribe(pheeno_name + "/scan_cl", 10,
00060 &PheenoRobot::irSensorCLeftCallback, this);
00061 sub_ir_back_ = nh_.subscribe(pheeno_name + "/scan_back", 10,
00062 &PheenoRobot::irSensorBackCallback, this);
00063 sub_ir_bottom_ = nh_.subscribe(pheeno_name + "/scan_bottom", 10,
00064 &PheenoRobot::irSensorBottomCallback, this);
00065
00066
00067 sub_odom_ = nh_.subscribe(pheeno_name + "/odom", 1,
00068 &PheenoRobot::odomCallback, this);
00069
00070
00071 sub_encoder_LL_ = nh_.subscribe(pheeno_name + "/encoder_LL", 10,
00072 &PheenoRobot::encoderLLCallback, this);
00073 sub_encoder_LR_ = nh_.subscribe(pheeno_name + "/encoder_LR", 10,
00074 &PheenoRobot::encoderLRCallback, this);
00075 sub_encoder_RL_ = nh_.subscribe(pheeno_name + "/encoder_RL", 10,
00076 &PheenoRobot::encoderRLCallback, this);
00077 sub_encoder_RR_ = nh_.subscribe(pheeno_name + "/encoder_RR", 10,
00078 &PheenoRobot::encoderRRCallback, this);
00079
00080
00081 sub_magnetometer_ = nh_.subscribe(pheeno_name + "/magnetometer", 10,
00082 &PheenoRobot::magnetometerCallback, this);
00083 sub_gyroscope_ = nh_.subscribe(pheeno_name + "/gyroscope", 10,
00084 &PheenoRobot::gyroscopeCallback, this);
00085 sub_accelerometer_ = nh_.subscribe(pheeno_name + "/accelerometer", 10,
00086 &PheenoRobot::accelerometerCallback, this);
00087
00088
00089 pub_cmd_vel_ = nh_.advertise<geometry_msgs::Twist>(pheeno_name + "/cmd_vel", 100);
00090
00091 }
00092
00093
00094
00095
00096
00097
00098
00099 void PheenoRobot::publish(geometry_msgs::Twist velocity)
00100 {
00101 pub_cmd_vel_.publish(velocity);
00102 }
00103
00104
00105
00106
00107 void PheenoRobot::irSensorCenterCallback(const std_msgs::Float32::ConstPtr& msg)
00108 {
00109 ir_sensor_center.data = msg->data;
00110 ir_sensor_values[0] = static_cast<double>(msg->data);
00111 }
00112
00113
00114
00115
00116 void PheenoRobot::irSensorBackCallback(const std_msgs::Float32::ConstPtr& msg)
00117 {
00118 ir_sensor_back.data = msg->data;
00119 ir_sensor_values[1] = static_cast<double>(msg->data);
00120 }
00121
00122
00123
00124
00125 void PheenoRobot::irSensorRightCallback(const std_msgs::Float32::ConstPtr& msg)
00126 {
00127 ir_sensor_right.data = msg->data;
00128 ir_sensor_values[2] = static_cast<double>(msg->data);
00129 }
00130
00131
00132
00133
00134 void PheenoRobot::irSensorLeftCallback(const std_msgs::Float32::ConstPtr& msg)
00135 {
00136 ir_sensor_left.data = msg->data;
00137 ir_sensor_values[3] = static_cast<double>(msg->data);
00138 }
00139
00140
00141
00142
00143 void PheenoRobot::irSensorCRightCallback(const std_msgs::Float32::ConstPtr& msg)
00144 {
00145 ir_sensor_c_right.data = msg->data;
00146 ir_sensor_values[4] = static_cast<double>(msg->data);
00147 }
00148
00149
00150
00151
00152 void PheenoRobot::irSensorCLeftCallback(const std_msgs::Float32::ConstPtr& msg)
00153 {
00154 ir_sensor_c_left.data = msg->data;
00155 ir_sensor_values[5] = static_cast<double>(msg->data);
00156 }
00157
00158
00159
00160
00161
00162 bool PheenoRobot::irSensorTriggered(float sensor_limit)
00163 {
00164 int count = 0;
00165 for (int i = 0; i < 7; i++)
00166 {
00167 if (ir_sensor_values[i] < sensor_limit)
00168 {
00169 count += 1;
00170 }
00171 }
00172
00173
00174 return (count > 1) ? true : false;
00175 }
00176
00177
00178
00179
00180
00181
00182
00183
00184
00185
00186
00187 void PheenoRobot::irSensorBottomCallback(const std_msgs::Int16::ConstPtr& msg)
00188 {
00189 if (msg->data < 1600)
00190 {
00191 ir_sensor_bottom.data = 0;
00192 }
00193 else
00194 {
00195 ir_sensor_bottom.data = 1;
00196 }
00197 }
00198
00199
00200
00201
00202
00203
00204
00205
00206
00207 void PheenoRobot::odomCallback(const nav_msgs::Odometry::ConstPtr& msg)
00208 {
00209
00210 odom_pose_position[0] = static_cast<double>(msg->pose.pose.position.x);
00211 odom_pose_position[1] = static_cast<double>(msg->pose.pose.position.y);
00212 odom_pose_position[2] = static_cast<double>(msg->pose.pose.position.z);
00213 odom_pose_orient[0] = static_cast<double>(msg->pose.pose.orientation.x);
00214 odom_pose_orient[1] = static_cast<double>(msg->pose.pose.orientation.y);
00215 odom_pose_orient[2] = static_cast<double>(msg->pose.pose.orientation.z);
00216 odom_pose_orient[3] = static_cast<double>(msg->pose.pose.orientation.w);
00217
00218
00219 odom_twist_linear[0] = static_cast<double>(msg->twist.twist.linear.x);
00220 odom_twist_linear[1] = static_cast<double>(msg->twist.twist.linear.y);
00221 odom_twist_linear[2] = static_cast<double>(msg->twist.twist.linear.z);
00222 odom_twist_angular[0] = static_cast<double>(msg->twist.twist.angular.x);
00223 odom_twist_angular[1] = static_cast<double>(msg->twist.twist.angular.y);
00224 odom_twist_angular[2] = static_cast<double>(msg->twist.twist.angular.z);
00225 }
00226
00227
00228
00229
00230 void PheenoRobot::encoderLLCallback(const std_msgs::Int16::ConstPtr& msg)
00231 {
00232 encoder_values[0] = static_cast<int>(msg->data);
00233 }
00234
00235
00236
00237
00238 void PheenoRobot::encoderLRCallback(const std_msgs::Int16::ConstPtr& msg)
00239 {
00240 encoder_values[1] = static_cast<int>(msg->data);
00241 }
00242
00243
00244
00245
00246 void PheenoRobot::encoderRLCallback(const std_msgs::Int16::ConstPtr& msg)
00247 {
00248 encoder_values[2] = static_cast<int>(msg->data);
00249 }
00250
00251
00252
00253
00254 void PheenoRobot::encoderRRCallback(const std_msgs::Int16::ConstPtr& msg)
00255 {
00256 encoder_values[3] = static_cast<int>(msg->data);
00257 }
00258
00259
00260
00261
00262 void PheenoRobot::magnetometerCallback(const geometry_msgs::Vector3::ConstPtr& msg)
00263 {
00264 magnetometer_values[0] = static_cast<double>(msg->x);
00265 magnetometer_values[1] = static_cast<double>(msg->y);
00266 magnetometer_values[2] = static_cast<double>(msg->z);
00267 }
00268
00269
00270
00271
00272 void PheenoRobot::gyroscopeCallback(const geometry_msgs::Vector3::ConstPtr& msg)
00273 {
00274 gyroscope_values[0] = static_cast<double>(msg->x);
00275 gyroscope_values[1] = static_cast<double>(msg->y);
00276 gyroscope_values[2] = static_cast<double>(msg->z);
00277 }
00278
00279
00280
00281
00282 void PheenoRobot::accelerometerCallback(const geometry_msgs::Vector3::ConstPtr& msg)
00283 {
00284 accelerometer_values[0] = static_cast<double>(msg->x);
00285 accelerometer_values[1] = static_cast<double>(msg->y);
00286 accelerometer_values[2] = static_cast<double>(msg->z);
00287 }
00288
00289
00290
00291
00292
00293
00294
00295
00296 void PheenoRobot::piCamCallback()
00297 {
00298 ROS_INFO("Not in use yet.");
00299 }
00300
00301
00302
00303
00304 double PheenoRobot::randomTurn(float angular)
00305 {
00306 return rand() % 10 + 1 <= 5 ? (-1 * angular) : angular;
00307 }
00308
00309
00310
00311
00312
00313
00314
00315
00316
00317 void PheenoRobot::avoidObstaclesLinear(double& linear, double& angular, float angular_velocity, float linear_velocity, double range_to_avoid)
00318 {
00319 if (ir_sensor_values[0] < range_to_avoid)
00320 {
00321 if (std::abs((ir_sensor_values[2] - ir_sensor_values[3])) < 5.0 ||
00322 (ir_sensor_values[2] > range_to_avoid && ir_sensor_values[3] > range_to_avoid))
00323 {
00324 linear = 0.0;
00325 angular = randomTurn();
00326 }
00327
00328 if (ir_sensor_values[2] < ir_sensor_values[3])
00329 {
00330 linear = 0.0;
00331 angular = -1 * angular_velocity;
00332 }
00333 else
00334 {
00335 linear = 0.0;
00336 angular = angular_velocity;
00337 }
00338 }
00339 else if (ir_sensor_values[4] < range_to_avoid && ir_sensor_values[5] < range_to_avoid)
00340 {
00341 linear = 0.0;
00342 angular = randomTurn();
00343 }
00344 else if (ir_sensor_values[4] < range_to_avoid)
00345 {
00346 linear = 0.0;
00347 angular = -1 * angular_velocity;
00348 }
00349 else if (ir_sensor_values[5] < range_to_avoid)
00350 {
00351 linear = 0.0;
00352 angular = angular_velocity;
00353 }
00354 else if (ir_sensor_values[2] < range_to_avoid)
00355 {
00356 linear = 0.0;
00357 angular = -1 * angular_velocity;
00358 }
00359 else if (ir_sensor_values[3] < range_to_avoid)
00360 {
00361 linear = 0.0;
00362 angular = angular_velocity;
00363 }
00364 else
00365 {
00366 linear = linear_velocity;
00367 angular = 0.0;
00368 }
00369 }
00370
00371
00372
00373
00374
00375
00376
00377
00378
00379
00380 void PheenoRobot::avoidObstaclesAngular(double& angular, double& random_turn_value, float angular_velocity, double range_to_avoid)
00381 {
00382 if (ir_sensor_values[0] < range_to_avoid)
00383 {
00384 if (std::abs((ir_sensor_values[2] - ir_sensor_values[3])) < 5.0 ||
00385 (ir_sensor_values[2] > range_to_avoid && ir_sensor_values[3] > range_to_avoid))
00386 {
00387 angular = randomTurn();
00388 }
00389
00390 if (ir_sensor_values[2] < ir_sensor_values[3])
00391 {
00392 angular = -1 * angular_velocity;
00393 }
00394 else
00395 {
00396 angular = angular_velocity;
00397 }
00398 }
00399 else if (ir_sensor_values[4] < range_to_avoid && ir_sensor_values[5] < range_to_avoid)
00400 {
00401 angular = randomTurn();
00402 }
00403 else if (ir_sensor_values[4] < range_to_avoid)
00404 {
00405 angular = -1 * angular_velocity;
00406 }
00407 else if (ir_sensor_values[5] < range_to_avoid)
00408 {
00409 angular = angular_velocity;
00410 }
00411 else if (ir_sensor_values[2] < range_to_avoid)
00412 {
00413 angular = -1 * angular_velocity;
00414 }
00415 else if (ir_sensor_values[3] < range_to_avoid)
00416 {
00417 angular = angular_velocity;
00418 }
00419 else
00420 {
00421 angular = random_turn_value;
00422 }
00423
00424 if (angular != random_turn_value)
00425 {
00426 random_turn_value = angular;
00427 }
00428 }