Go to the documentation of this file.00001
00025 #include "cyberglove/serial_glove.hpp"
00026
00027 #include <iostream>
00028
00029 namespace cyberglove_freq
00030 {
00031 const std::string CybergloveFreq::fastest = "t 1152 0\r";
00032 const std::string CybergloveFreq::hundred_hz = "t 1152 1\r";
00033 const std::string CybergloveFreq::fourtyfive_hz = "t 2560 1\r";
00034 const std::string CybergloveFreq::ten_hz = "t 11520 1\r";
00035 const std::string CybergloveFreq::one_hz = "t 57600 2\r";
00036 }
00037
00038 namespace cyberglove
00039 {
00040 const unsigned short CybergloveSerial::glove_size = 22;
00041
00042 CybergloveSerial::CybergloveSerial(std::string serial_port, boost::function<void(std::vector<float>, bool)> callback) :
00043 nb_msgs_received(0), glove_pos_index(0), current_value(0), light_on(true), button_on(true), no_errors(true)
00044 {
00045
00046 for (int i = 0; i < glove_size; ++i)
00047 {
00048 glove_positions.push_back(0);
00049 }
00050
00051
00052 cereal_port = boost::shared_ptr<cereal::CerealPort>(new cereal::CerealPort());
00053 cereal_port->open(serial_port.c_str());
00054
00055
00056 callback_function = callback;
00057 }
00058
00059 CybergloveSerial::~CybergloveSerial()
00060 {
00061 cereal_port->stopStream();
00062
00063 cereal_port->write("^c", 2);
00064 }
00065
00066 int CybergloveSerial::set_filtering(bool value)
00067 {
00068 if( value )
00069 {
00070 cereal_port->write("f 1\r", 4);
00071 std::cout << " - Data filtered" << std::endl;
00072 }
00073 else
00074 {
00075 cereal_port->write("f 0\r", 4);
00076 std::cout << " - Data not filtered" << std::endl;
00077 }
00078 cereal_port->flush();
00079
00080
00081 sleep(1);
00082
00083 return 0;
00084 }
00085
00086 int CybergloveSerial::set_transmit_info(bool value)
00087 {
00088 if( value )
00089 {
00090 cereal_port->write("u 1\r", 4);
00091 std::cout << " - Additional info transmitted" << std::endl;
00092 }
00093 else
00094 {
00095 cereal_port->write("u 0\r", 4);
00096 std::cout << " - Additional info not transmitted" << std::endl;
00097 }
00098 cereal_port->flush();
00099
00100
00101 sleep(1);
00102
00103 return 0;
00104 }
00105
00106 int CybergloveSerial::set_frequency(std::string frequency)
00107 {
00108 cereal_port->write(frequency.c_str(), frequency.size());
00109 cereal_port->flush();
00110
00111
00112 sleep(1);
00113 return 0;
00114 }
00115
00116 int CybergloveSerial::start_stream()
00117 {
00118 std::cout << "starting stream"<<std::endl;
00119
00120 cereal_port->startReadStream(boost::bind(&CybergloveSerial::stream_callback, this, _1, _2));
00121
00122
00123 cereal_port->write("S", 1);
00124 cereal_port->flush();
00125
00126 return 0;
00127 }
00128
00129 void CybergloveSerial::stream_callback(char* world, int length)
00130 {
00131
00132 for (int i = 0; i < length; ++i)
00133 {
00134 current_value = (int)(unsigned char)world[i];
00135 switch( current_value )
00136 {
00137 case 'S':
00138
00139 ++nb_msgs_received;
00140
00141 glove_pos_index = 0;
00142
00143 no_errors = true;
00144 break;
00145
00146 default:
00147
00148 switch( glove_pos_index )
00149 {
00150 case glove_size:
00151
00152
00153
00154 if(current_value & 2)
00155 button_on = true;
00156 else
00157 button_on = false;
00158
00159 if(current_value & 4)
00160 light_on = true;
00161 else
00162 light_on = false;
00163
00164 break;
00165
00166 case glove_size + 1:
00167
00168
00169
00170 if( current_value == 0 && no_errors)
00171 callback_function(glove_positions, light_on);
00172 break;
00173
00174 default:
00175
00176
00177 if( current_value == 0)
00178 no_errors = false;
00179
00180
00181 glove_positions[glove_pos_index] = (((float)current_value) - 1.0f) / 254.0f;
00182 break;
00183 }
00184
00185 ++glove_pos_index;
00186 break;
00187 }
00188 }
00189 }
00190
00191 int CybergloveSerial::get_nb_msgs_received()
00192 {
00193 return nb_msgs_received;
00194 }
00195 }
00196
00197
00198
00199
00200
00201