Rovio.C
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
00038 #include "Robots/Rovio/Rovio.H"
00039 #include "Component/OptionManager.H"
00040
00041
00042 Rovio::Rovio(OptionManager& mgr, const std::string& descrName,
00043 const std::string& tagName) :
00044 ModelComponent(mgr, descrName, tagName),
00045 itsHttpClient(new HTTPClient(mgr))
00046
00047 {
00048 addSubComponent(itsHttpClient);
00049 }
00050
00051
00052 Rovio::~Rovio()
00053 {
00054
00055 }
00056
00057
00058 void Rovio::start2()
00059 {
00060
00061 }
00062
00063 void Rovio::stop2()
00064 {
00065 }
00066
00067
00068 bool Rovio::stop()
00069 {
00070 return sendDriveRequest(STOP, 0);
00071 }
00072
00073
00074 bool Rovio::moveForward(float speed)
00075 {
00076 return sendDriveRequest(FORWARD, speed);
00077 }
00078
00079
00080 bool Rovio::moveBackward(float speed)
00081 {
00082 return sendDriveRequest(BACKWARD, speed);
00083 }
00084
00085
00086 bool Rovio::straightLeft(float speed)
00087 {
00088 return sendDriveRequest(STRAIGHT_LEFT, speed);
00089 }
00090
00091
00092 bool Rovio::straightRight(float speed)
00093 {
00094 return sendDriveRequest(STRAIGHT_RIGHT, speed);
00095 }
00096
00097
00098 bool Rovio::rotateLeft(float speed)
00099 {
00100 return sendDriveRequest(ROTATE_LEFT, speed);
00101 }
00102
00103
00104 bool Rovio::rotateRight(float speed)
00105 {
00106 return sendDriveRequest(ROTATE_RIGHT, speed);
00107 }
00108
00109
00110
00111 bool Rovio::sendDriveRequest(DRIVE_PARAMS dValue, float speed)
00112 {
00113
00114 char params[255];
00115 sprintf(params, "%i&speed=%i", dValue, 10 - (int)(speed*10.0F));
00116
00117 std::string request = "/rev.cgi?Cmd=nav&action=18&drive=" ;
00118 request += params;
00119 std::string ret = itsHttpClient->sendGetRequest(request);
00120
00121 if (ret.size() > 0 )
00122 return true;
00123 else
00124 return false;
00125 }
00126
00127
00128
00129 bool Rovio::getStatus()
00130 {
00131 std::string request = "/rev.cgi?Cmd=nav&action=1" ;
00132 std::string ret = itsHttpClient->sendGetRequest(request);
00133
00134 LINFO("Status %s", ret.c_str());
00135
00136 return true;
00137 }
00138
00139
00140 bool Rovio::setCameraPos(int pos)
00141 {
00142
00143 std::string request;
00144
00145 switch (pos)
00146 {
00147 case 0:
00148 request = "/rev.cgi?Cmd=nav&action=18&drive=12&speed=1" ;
00149 break;
00150 case 1:
00151 request = "/rev.cgi?Cmd=nav&action=18&drive=13&speed=1" ;
00152 break;
00153 case 2:
00154 request = "/rev.cgi?Cmd=nav&action=18&drive=11&speed=1" ;
00155 break;
00156 }
00157
00158 std::string ret = itsHttpClient->sendGetRequest(request);
00159
00160 if (ret.size() > 0 )
00161 return true;
00162 else
00163 return false;
00164 }
00165
00166 bool Rovio::playSound()
00167 {
00168
00169
00170 std::ifstream file ("etc/daisy.wav", std::ios::in|std::ios::binary|std::ios::ate);
00171 if (file.is_open())
00172 {
00173 file.seekg(0, std::ios::end);
00174 long size = file.tellg();
00175 file.seekg(0, std::ios::beg);
00176
00177 LINFO("File open reading %lu into mem", size);
00178
00179 char *buffer = new char[size];
00180
00181 file.read(buffer, size);
00182
00183 itsHttpClient->sendPostRequest("/GetAudio.cgi", buffer, size);
00184
00185 file.close();
00186 }
00187
00188
00189 return true;
00190
00191
00192 }
00193
00194
00195
00196
00197
00198
00199
00200
00201
00202
00203
00204
00205