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 #include <sick_tim3xx/sick_tim3xx_common_tcp.h>
00036 #include <boost/asio.hpp>
00037 #include <boost/lambda/lambda.hpp>
00038 #include <algorithm>
00039 #include <iterator>
00040 #include <boost/lexical_cast.hpp>
00041
00042 namespace sick_tim3xx
00043 {
00044
00045 SickTim3xxCommonTcp::SickTim3xxCommonTcp(const std::string & hostname, AbstractParser* parser)
00046 :
00047 SickTim3xxCommon(parser),
00048 socket_(io_service_),
00049 deadline_(io_service_),
00050 hostname_(hostname)
00051 {
00052
00053
00054
00055 deadline_.expires_at(boost::posix_time::pos_infin);
00056 checkDeadline();
00057 }
00058
00059 SickTim3xxCommonTcp::~SickTim3xxCommonTcp()
00060 {
00061 stop_scanner();
00062 close_device();
00063 }
00064
00065 using boost::asio::ip::tcp;
00066 using boost::lambda::var;
00067 using boost::lambda::_1;
00068
00069 int SickTim3xxCommonTcp::init_device()
00070 {
00071
00072 tcp::resolver::iterator iterator;
00073 try
00074 {
00075 tcp::resolver resolver(io_service_);
00076 tcp::resolver::query query(hostname_, "2112");
00077 iterator = resolver.resolve(query);
00078 }
00079 catch (boost::system::system_error &e)
00080 {
00081 ROS_FATAL("Could not resolve host: ... (%d)(%s)", e.code().value(), e.code().message().c_str());
00082 diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "Could not resolve host.");
00083 return EXIT_FAILURE;
00084 }
00085
00086
00087 boost::system::error_code ec;
00088 bool success = false;
00089 for ( ; iterator != tcp::resolver::iterator(); ++iterator)
00090 {
00091 std::string repr = boost::lexical_cast<std::string>(iterator->endpoint());
00092 socket_.close();
00093
00094
00095 deadline_.expires_from_now(boost::posix_time::seconds(5));
00096
00097 ec = boost::asio::error::would_block;
00098 ROS_DEBUG("Attempting to connect to %s", repr.c_str());
00099 socket_.async_connect(iterator->endpoint(), boost::lambda::var(ec) = _1);
00100
00101
00102 do io_service_.run_one(); while (ec == boost::asio::error::would_block);
00103
00104 if (!ec && socket_.is_open())
00105 {
00106 success = true;
00107 ROS_INFO("Succesfully connected to %s", repr.c_str());
00108 break;
00109 }
00110 ROS_ERROR("Failed to connect to %s", repr.c_str());
00111 }
00112
00113
00114 if (!success)
00115 {
00116 ROS_FATAL("Could not connect to host %s", hostname_.c_str());
00117 diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "Could not connect to host.");
00118 return EXIT_FAILURE;
00119 }
00120
00121 input_buffer_.consume(input_buffer_.size());
00122
00123 return EXIT_SUCCESS;
00124 }
00125
00126 int SickTim3xxCommonTcp::close_device()
00127 {
00128 if (socket_.is_open())
00129 {
00130 try
00131 {
00132 socket_.close();
00133 }
00134 catch (boost::system::system_error &e)
00135 {
00136 ROS_ERROR("An error occured during closing of the connection: %d:%s", e.code().value(), e.code().message().c_str());
00137 }
00138 }
00139 return 0;
00140 }
00141
00142 void SickTim3xxCommonTcp::checkDeadline()
00143 {
00144 if (deadline_.expires_at() <= boost::asio::deadline_timer::traits_type::now())
00145 {
00146
00147
00148 socket_.close();
00149 deadline_.expires_at(boost::posix_time::pos_infin);
00150 }
00151
00152
00153 deadline_.async_wait(boost::bind(&SickTim3xxCommonTcp::checkDeadline, this));
00154 }
00155
00156 int SickTim3xxCommonTcp::readWithTimeout(size_t timeout_ms, char *buffer, int buffer_size, int *bytes_read, bool *exception_occured)
00157 {
00158
00159 deadline_.expires_from_now(boost::posix_time::milliseconds(timeout_ms));
00160 const char end_delim = static_cast<char>(0x03);
00161 ec_ = boost::asio::error::would_block;
00162 bytes_transfered_ = 0;
00163
00164
00165 boost::asio::async_read_until(
00166 socket_,
00167 input_buffer_,
00168 end_delim,
00169 boost::bind(
00170 &SickTim3xxCommonTcp::handleRead,
00171 this,
00172 boost::asio::placeholders::error,
00173 boost::asio::placeholders::bytes_transferred
00174 )
00175 );
00176 do io_service_.run_one(); while (ec_ == boost::asio::error::would_block);
00177
00178 if (ec_)
00179 {
00180
00181
00182 if (ec_ != boost::asio::error::would_block)
00183 {
00184 ROS_ERROR("sendSOPASCommand: failed attempt to read from socket: %d: %s", ec_.value(), ec_.message().c_str());
00185 diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "sendSOPASCommand: exception during read_until().");
00186 if (exception_occured != 0)
00187 *exception_occured = true;
00188 }
00189
00190
00191 return EXIT_FAILURE;
00192 }
00193
00194
00195 size_t to_read = bytes_transfered_ > buffer_size - 1 ? buffer_size - 1 : bytes_transfered_;
00196 size_t i = 0;
00197 std::istream istr(&input_buffer_);
00198 if (buffer != 0)
00199 {
00200 istr.read(buffer, to_read);
00201 buffer[to_read] = 0;
00202
00203
00204 if (to_read < bytes_transfered_)
00205 {
00206 ROS_WARN("Dropping %zu bytes to avoid buffer overflow", bytes_transfered_ - to_read);
00207 input_buffer_.consume(bytes_transfered_ - to_read);
00208 }
00209 }
00210 else
00211
00212 input_buffer_.consume(bytes_transfered_);
00213
00214
00215 if (bytes_read != 0)
00216 *bytes_read = to_read;
00217
00218 return EXIT_SUCCESS;
00219 }
00220
00224 int SickTim3xxCommonTcp::sendSOPASCommand(const char* request, std::vector<unsigned char> * reply)
00225 {
00226 if (!socket_.is_open()) {
00227 ROS_ERROR("sendSOPASCommand: socket not open");
00228 diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "sendSOPASCommand: socket not open.");
00229 return EXIT_FAILURE;
00230 }
00231
00232
00233
00234
00235 try
00236 {
00237 boost::asio::write(socket_, boost::asio::buffer(request, strlen(request)));
00238 }
00239 catch (boost::system::system_error &e)
00240 {
00241 ROS_ERROR("write error for command: %s", request);
00242 diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "Write error for sendSOPASCommand.");
00243 return EXIT_FAILURE;
00244 }
00245
00246
00247 const int BUF_SIZE = 1000;
00248 char buffer[BUF_SIZE];
00249 int bytes_read;
00250 if (readWithTimeout(1000, buffer, BUF_SIZE, &bytes_read, 0) == EXIT_FAILURE)
00251 {
00252 ROS_ERROR_THROTTLE(1.0, "sendSOPASCommand: no full reply available for read after 1s");
00253 diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "sendSOPASCommand: no full reply available for read after 5 s.");
00254 return EXIT_FAILURE;
00255 }
00256
00257 if (reply)
00258 {
00259 reply->resize(bytes_read);
00260 std::copy(buffer, buffer + bytes_read, &(*reply)[0]);
00261 }
00262
00263 return EXIT_SUCCESS;
00264 }
00265
00266 int SickTim3xxCommonTcp::get_datagram(unsigned char* receiveBuffer, int bufferSize, int* actual_length)
00267 {
00268 if (!socket_.is_open()) {
00269 ROS_ERROR("get_datagram: socket not open");
00270 diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "get_datagram: socket not open.");
00271 return EXIT_FAILURE;
00272 }
00273
00274
00275
00276
00277 std::vector<unsigned char> reply;
00278
00279
00280 size_t timeout = 500;
00281 bool exception_occured = false;
00282
00283 char *buffer = reinterpret_cast<char *>(receiveBuffer);
00284
00285 if (readWithTimeout(timeout, buffer, bufferSize, actual_length, &exception_occured) != EXIT_SUCCESS)
00286 {
00287 ROS_ERROR_THROTTLE(1.0, "get_datagram: no data available for read after %zu ms", timeout);
00288 diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "get_datagram: no data available for read after timeout.");
00289
00290
00291 if (!socket_.is_open())
00292 {
00293 sleep(1);
00294 ROS_INFO("Failure - attempting to reconnect");
00295 int ret = init_device();
00296 if (ret != EXIT_SUCCESS)
00297 return ret;
00298
00299 return init_scanner();
00300 }
00301
00302 return exception_occured ? EXIT_FAILURE : EXIT_SUCCESS;
00303 }
00304
00305 return EXIT_SUCCESS;
00306 }
00307
00308 }