Go to the documentation of this file.00001
00027 #include <ros/ros.h>
00028 #include <boost/shared_ptr.hpp>
00029 #include <boost/make_shared.hpp>
00030 #include <boost/asio.hpp>
00031
00032 #include "omron_os32c_driver/os32c.h"
00033 #include "odva_ethernetip/serialization/serializable_buffer.h"
00034 #include "odva_ethernetip/cpf_packet.h"
00035 #include "odva_ethernetip/cpf_item.h"
00036 #include "odva_ethernetip/sequenced_address_item.h"
00037 #include "odva_ethernetip/sequenced_data_item.h"
00038
00039 using std::cout;
00040 using std::endl;
00041 using boost::shared_ptr;
00042 using boost::make_shared;
00043 using boost::asio::buffer;
00044 using eip::Session;
00045 using eip::serialization::SerializableBuffer;
00046 using eip::RRDataResponse;
00047 using eip::CPFItem;
00048 using eip::CPFPacket;
00049 using eip::SequencedAddressItem;
00050 using eip::SequencedDataItem;
00051 using omron_os32c_driver::RangeAndReflectanceMeasurement;
00052
00053 namespace omron_os32c_driver {
00054
00055 const double OS32C::ANGLE_MIN = DEG2RAD(-135.2);
00056 const double OS32C::ANGLE_MAX = DEG2RAD( 135.2);
00057 const double OS32C::ANGLE_INC = DEG2RAD(0.4);
00058 const double OS32C::DISTANCE_MIN = 0.002;
00059 const double OS32C::DISTANCE_MAX = 50;
00060
00061 EIP_UINT OS32C::getRangeFormat()
00062 {
00063 mrc_.range_report_format = getSingleAttribute(0x73, 1, 4, (EIP_UINT)0);
00064 return mrc_.range_report_format;
00065 }
00066
00067 void OS32C::setRangeFormat(EIP_UINT format)
00068 {
00069 setSingleAttribute(0x73, 1, 4, format);
00070 mrc_.range_report_format = format;
00071 }
00072
00073 EIP_UINT OS32C::getReflectivityFormat()
00074 {
00075 mrc_.reflectivity_report_format = getSingleAttribute(0x73, 1, 5, (EIP_UINT)0);
00076 return mrc_.reflectivity_report_format;
00077 }
00078
00079 void OS32C::setReflectivityFormat(EIP_UINT format)
00080 {
00081 setSingleAttribute(0x73, 1, 5, format);
00082 mrc_.reflectivity_report_format = format;
00083 }
00084
00085 void OS32C::calcBeamMask(double start_angle, double end_angle, EIP_BYTE mask[])
00086 {
00087 if (start_angle > (ANGLE_MAX + ANGLE_INC / 2))
00088 {
00089 throw std::invalid_argument("Start angle is greater than max");
00090 }
00091 if (end_angle < (ANGLE_MIN - ANGLE_INC / 2))
00092 {
00093 throw std::invalid_argument("End angle is greater than max");
00094 }
00095 if (start_angle - end_angle <= ANGLE_INC)
00096 {
00097 throw std::invalid_argument("Starting angle is less than ending angle");
00098 }
00099
00100 int start_beam = calcBeamNumber(start_angle);
00101 int end_beam = calcBeamNumber(end_angle);
00102 start_angle_ = calcBeamCentre(start_beam);
00103 end_angle_ = calcBeamCentre(end_beam);
00104
00105
00106 int start_byte = start_beam / 8;
00107 int start_bit = start_beam - start_byte * 8;
00108 int end_byte = end_beam / 8;
00109 int end_bit = end_beam - end_byte * 8;
00110
00111
00112 if (start_byte > 0)
00113 {
00114 memset(mask, 0, start_byte);
00115 }
00116
00117
00118 if (start_bit)
00119 {
00120
00121 mask[start_byte] = ~((1 << start_bit) - 1);
00122 }
00123 else
00124 {
00125 --start_byte;
00126 }
00127
00128
00129 memset(mask + start_byte + 1, 0xFF, end_byte - start_byte - 1);
00130
00131
00132 mask[end_byte] = (1 << (end_bit + 1)) - 1;
00133
00134
00135 memset(mask + end_byte + 1, 0, 87 - end_byte);
00136 }
00137
00138 void OS32C::selectBeams(double start_angle, double end_angle)
00139 {
00140 calcBeamMask(start_angle, end_angle, mrc_.beam_selection_mask);
00141 shared_ptr<SerializableBuffer> sb = make_shared<SerializableBuffer>(
00142 buffer(mrc_.beam_selection_mask));
00143 setSingleAttributeSerializable(0x73, 1, 12, sb);
00144 }
00145
00146 RangeAndReflectanceMeasurement OS32C::getSingleRRScan()
00147 {
00148 RangeAndReflectanceMeasurement rr;
00149 getSingleAttributeSerializable(0x75, 1, 3, rr);
00150 return rr;
00151 }
00152
00153 void OS32C::fillLaserScanStaticConfig(sensor_msgs::LaserScan* ls)
00154 {
00155 ls->angle_max = start_angle_;
00156 ls->angle_min = end_angle_;
00157 ls->angle_increment = ANGLE_INC;
00158 ls->range_min = DISTANCE_MIN;
00159 ls->range_max = DISTANCE_MAX;
00160 }
00161
00162 void OS32C::convertToLaserScan(const RangeAndReflectanceMeasurement& rr, sensor_msgs::LaserScan* ls)
00163 {
00164 if (rr.range_data.size() != rr.header.num_beams ||
00165 rr.reflectance_data.size() != rr.header.num_beams)
00166 {
00167 throw std::invalid_argument("Number of beams does not match vector size");
00168 }
00169
00170
00171 ls->time_increment = rr.header.scan_beam_period / 1000000000.0;
00172
00173 ls->scan_time = rr.header.scan_rate / 1000000.0;
00174
00175
00176
00177 ls->ranges.resize(rr.header.num_beams);
00178 ls->intensities.resize(rr.header.num_beams);
00179 for (int i = 0; i < rr.header.num_beams; ++i)
00180 {
00181 if (rr.range_data[i] == 0x0001)
00182 {
00183
00184 ls->ranges[i] = 0;
00185 }
00186 else if (rr.range_data[i] == 0xFFFF)
00187 {
00188
00189 ls->ranges[i] = DISTANCE_MAX;
00190 }
00191 else
00192 {
00193 ls->ranges[i] = rr.range_data[i] / 1000.0;
00194 }
00195 ls->intensities[i] = rr.reflectance_data[i];
00196 }
00197 }
00198
00199 void OS32C::convertToLaserScan(const MeasurementReport& mr, sensor_msgs::LaserScan* ls)
00200 {
00201 if (mr.measurement_data.size() != mr.header.num_beams)
00202 {
00203 throw std::invalid_argument("Number of beams does not match vector size");
00204 }
00205
00206
00207 ls->time_increment = mr.header.scan_beam_period / 1000000000.0;
00208
00209 ls->scan_time = mr.header.scan_rate / 1000000.0;
00210
00211
00212
00213 ls->ranges.resize(mr.header.num_beams);
00214 for (int i = 0; i < mr.header.num_beams; ++i)
00215 {
00216 if (mr.measurement_data[i] == 0x0001)
00217 {
00218
00219 ls->ranges[i] = 0;
00220 }
00221 else if (mr.measurement_data[i] == 0xFFFF)
00222 {
00223
00224 ls->ranges[i] = DISTANCE_MAX;
00225 }
00226 else
00227 {
00228 ls->ranges[i] = mr.measurement_data[i] / 1000.0;
00229 }
00230 }
00231 }
00232
00233 void OS32C::sendMeasurmentReportConfigUDP()
00234 {
00235
00236 CPFPacket pkt;
00237 shared_ptr<SequencedAddressItem> address =
00238 make_shared<SequencedAddressItem>(
00239 getConnection(connection_num_).o_to_t_connection_id, mrc_sequence_num_++);
00240 shared_ptr<MeasurementReportConfig> data = make_shared<MeasurementReportConfig>();
00241 *data = mrc_;
00242 pkt.getItems().push_back(CPFItem(0x8002, address));
00243 pkt.getItems().push_back(CPFItem(0x00B1, data));
00244 sendIOPacket(pkt);
00245 }
00246
00247 MeasurementReport OS32C::receiveMeasurementReportUDP()
00248 {
00249 CPFPacket pkt = receiveIOPacket();
00250 if (pkt.getItemCount() != 2)
00251 {
00252 throw std::logic_error("IO Packet received with wrong number of items");
00253 }
00254 if (pkt.getItems()[1].getItemType() != 0x00B1)
00255 {
00256 throw std::logic_error("IO Packet received with wrong data type");
00257 }
00258
00259 SequencedDataItem<MeasurementReport> data;
00260 pkt.getItems()[1].getDataAs(data);
00261 return data;
00262 }
00263
00264 void OS32C::startUDPIO()
00265 {
00266 EIP_CONNECTION_INFO_T o_to_t, t_to_o;
00267 o_to_t.assembly_id = 0x71;
00268 o_to_t.buffer_size = 0x006E;
00269 o_to_t.rpi = 0x00177FA0;
00270 t_to_o.assembly_id = 0x66;
00271 t_to_o.buffer_size = 0x0584;
00272 t_to_o.rpi = 0x00013070;
00273
00274 connection_num_ = createConnection(o_to_t, t_to_o);
00275 }
00276
00277 }