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 #include <ros/ros.h>
00033 #include <stdlib.h>
00034 #include <netdb.h>
00035 #include <sensor_msgs/LaserScan.h>
00036
00037 #define BUF_SIZE 1024
00038
00039 namespace sick_lms400
00040 {
00042 typedef struct
00043 {
00044 unsigned char* string;
00045 int length;
00046 } MeasurementQueueElement_t;
00047
00049 typedef struct
00050 {
00051 uint16_t Format;
00052 uint16_t DistanceScaling;
00053 int32_t StartingAngle;
00054 uint16_t AngularStepWidth;
00055 uint16_t NumberMeasuredValues;
00056 uint16_t ScanningFrequency;
00057 uint16_t RemissionScaling;
00058 uint16_t RemissionStartValue;
00059 uint16_t RemissionEndValue;
00060 } MeasurementHeader_t;
00061
00062
00064 class SickLMS400
00065 {
00066 public:
00067 SickLMS400 () { }
00068 SickLMS400 (const char* host, int port, int debug_mode);
00069
00070
00071 int Connect ();
00072 int Disconnect ();
00073
00074
00075 int SetAngularResolution (const char* password, float ang_res, float angle_start, float angle_range);
00076 int SetScanningFrequency (const char* password, float freq, float angle_start, float angle_range);
00077 int SetResolutionAndFrequency (float freq, float ang_res, float angle_start, float angle_range);
00078
00079 int StartMeasurement (bool intensity = true);
00080 sensor_msgs::LaserScan ReadMeasurement ();
00081 int StopMeasurement ();
00082
00083 int SetUserLevel (int8_t userlevel, const char* password);
00084 int GetMACAddress (char** macadress);
00085
00086 int SetIP (char* ip);
00087 int SetGateway (char* gw);
00088 int SetNetmask (char* mask);
00089 int SetPort (uint16_t port);
00090
00091 int ResetDevice ();
00092 int TerminateConfiguration ();
00093
00094 int SendCommand (const char* cmd);
00095 int ReadResult ();
00096
00097 int ReadAnswer ();
00098
00099 int ReadConfirmationAndAnswer ();
00100
00101 int EnableRIS (int onoff);
00102 int SetMeanFilterParameters (int num_scans);
00103 int SetRangeFilterParameters (float range_min, float range_max);
00104 int EnableFilters (int filter_mask);
00105
00106
00107 unsigned char* ParseIP (char* ip);
00108
00109 private:
00110
00111 int AssembleCommand (unsigned char* command, int len);
00112
00113 const char* hostname_;
00114 int sockfd_, portno_, n_;
00115 struct sockaddr_in serv_addr_;
00116 #if HAVE_GETADDRINFO
00117 struct addrinfo *addr_ptr_;
00118 #else
00119 struct hostent *server_;
00120 #endif
00121
00122
00123 int verbose_;
00124 int ExtendedRIS_;
00125 int MeanFilterNumScans_;
00126 float RangeFilterTopLimit_;
00127 float RangeFilterBottomLimit_;
00128 int FilterMask_;
00129
00130 long int scanning_frequency_, resolution_;
00131
00132
00133 unsigned char buffer_[4096];
00134 unsigned int bufferlength_;
00135
00136
00137 unsigned char command_[BUF_SIZE];
00138 int commandlength_;
00139 std::vector<MeasurementQueueElement_t>* MeasurementQueue_;
00140 };
00141 }