Go to the documentation of this file.00001 #include "ros/ros.h"
00002 #include "std_msgs/Float32.h"
00003 #include "geometry_msgs/Twist.h"
00004 #include "command_line_parser.h"
00005 #include "pheeno_robot.h"
00006
00007 int main(int argc, char **argv) {
00008
00009 std::string pheeno_name;
00010
00011
00012 CommandLineParser cml_parser(argc, argv);
00013
00014
00015 if (cml_parser["-n"])
00016 {
00017 std::string pheeno_number = cml_parser("-n");
00018 pheeno_name = "/pheeno_" + pheeno_number;
00019 }
00020 else
00021 {
00022 ROS_ERROR("Need to provide Pheeno number!");
00023 }
00024
00025
00026
00027 ros::init(argc, argv, "obstacle_avoidance_node");
00028
00029
00030 PheenoRobot pheeno = PheenoRobot(pheeno_name);
00031
00032
00033 ros::Rate loop_rate(10);
00034
00035
00036 double saved_time = ros::Time::now().toSec();
00037 double current_duration;
00038 double turn_direction = pheeno.randomTurn(0.07);
00039 double linear = 0.0;
00040 double angular = 0.0;
00041 geometry_msgs::Twist cmd_vel_msg;
00042
00043 while (ros::ok())
00044 {
00045
00046 current_duration = ros::Time::now().toSec() - saved_time;
00047
00048 if (current_duration <= 2.0) {
00049 pheeno.avoidObstaclesLinear(linear, angular, turn_direction);
00050 cmd_vel_msg.linear.x = linear;
00051 cmd_vel_msg.angular.z = angular;
00052
00053 } else if (current_duration < 5.0) {
00054 pheeno.avoidObstaclesAngular(angular, turn_direction);
00055 cmd_vel_msg.linear.x = linear;
00056 cmd_vel_msg.angular.z = angular;
00057
00058 } else {
00059
00060 saved_time = ros::Time::now().toSec();
00061 turn_direction = pheeno.randomTurn(0.07);
00062 }
00063
00064
00065 pheeno.publish(cmd_vel_msg);
00066 ros::spinOnce();
00067 loop_rate.sleep();
00068 }
00069 }