Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include "roomba_500_series/GoDock.h"
00038
00039 GoDockAction::GoDockAction(std::string name) : as_(nh_, name, boost::bind(&GoDockAction::goalCallback, this, _1)) , action_name_(name)
00040 {
00041 ir_sub_ = nh_.subscribe("/ir_character", 1, &GoDockAction::irCallback, this);
00042 bat_sub_ = nh_.subscribe("/battery", 1, &GoDockAction::batteryCallback, this);
00043
00044 cmd_vel_pub_ = nh_.advertise<geometry_msgs::Twist>("/cmd_vel", 1);
00045 }
00046
00047 GoDockAction::~GoDockAction()
00048 {
00049
00050 }
00051
00052 void GoDockAction::goalCallback(const roomba_500_series::GoDockGoalConstPtr & goal)
00053 {
00054 ros::Rate r(10);
00055 ROS_INFO("GoDock -- Initiating docking proceadure...");
00056
00057 int no_signal = 0;
00058 ros::Time start_time = ros::Time::now();
00059 while(true)
00060 {
00061
00062 if(!as_.isActive()) return;
00063
00064 if(ir_character_.omni == 0 && ir_character_.left == 0 && ir_character_.right == 0) no_signal++;
00065 else no_signal = 0;
00066 if(no_signal == 10)
00067 {
00068 as_.setAborted();
00069 ROS_INFO("GoDock - Aborting...");
00070 sendCmdVel(0.0, 0.0);
00071 return;
00072 }
00073
00074 if(dock_)
00075 {
00076 as_.setSucceeded();
00077 ROS_INFO("GoDock -- Charging!");
00078 sendCmdVel(0.0, 0.0);
00079 return;
00080 }
00081
00082
00083 if((ir_character_.left == RED_BUOY_GREEN_BUOY && ir_character_.right == RED_BUOY_GREEN_BUOY) || (ir_character_.left == RED_BUOY_GREEN_BUOY_FORCE_FIELD && ir_character_.right == RED_BUOY_GREEN_BUOY_FORCE_FIELD))
00084 {
00085 sendCmdVel(0.05, 0.0);
00086 }
00087 else if(ir_character_.left == RED_BUOY || ir_character_.left == RED_BUOY_FORCE_FIELD)
00088 {
00089 sendCmdVel(0.05, 0.1);
00090 }
00091 else if(ir_character_.right == GREEN_BUOY || ir_character_.right == GREEN_BUOY_FORCE_FIELD)
00092 {
00093 sendCmdVel(0.05, -0.1);
00094 }
00095
00096 r.sleep();
00097 }
00098 }
00099
00100 void GoDockAction::irCallback(const roomba_500_series::IRCharacterConstPtr & ir)
00101 {
00102 ir_character_.omni = ir->omni;
00103 ir_character_.left = ir->left;
00104 ir_character_.right = ir->right;
00105 }
00106
00107 void GoDockAction::batteryCallback(const roomba_500_series::BatteryConstPtr & bat)
00108 {
00109 dock_ = bat->dock;
00110 }
00111
00112 void GoDockAction::sendCmdVel(float linear, float angular)
00113 {
00114 geometry_msgs::Twist cmd_vel;
00115 cmd_vel.linear.x = linear;
00116 cmd_vel.angular.z = angular;
00117 cmd_vel_pub_.publish(cmd_vel);
00118 }
00119
00120