51 uint16_t DistanceScaling;
52 int32_t StartingAngle;
53 uint16_t AngularStepWidth;
54 uint16_t NumberMeasuredValues;
55 uint16_t ScanningFrequency;
56 uint16_t RemissionScaling;
57 uint16_t RemissionStartValue;
58 uint16_t RemissionEndValue;
66 lms400_cola (
const char* host,
int port,
int debug_mode);
73 int SetAngularResolution (
const char* password,
float ang_res,
float angle_start,
float angle_range);
74 int SetScanningFrequency (
const char* password,
float freq,
float angle_start,
float angle_range);
75 int SetResolutionAndFrequency (
float freq,
float ang_res,
float angle_start,
float angle_range);
77 int StartMeasurement (
bool intensity =
true);
78 player_laser_data ReadMeasurement ();
79 int StopMeasurement ();
81 int SetUserLevel (int8_t userlevel,
const char* password);
82 int GetMACAddress (
char** macadress);
85 int SetGateway (
char* gw);
86 int SetNetmask (
char* mask);
87 int SetPort (uint16_t port);
90 int TerminateConfiguration ();
92 int SendCommand (
const char* cmd);
97 int ReadConfirmationAndAnswer ();
99 int EnableRIS (
int onoff);
100 player_laser_config GetConfiguration ();
101 int SetMeanFilterParameters (
int num_scans);
102 int SetRangeFilterParameters (
float *ranges);
103 int EnableFilters (
int filter_mask);
106 unsigned char* ParseIP (
char* ip);
110 int assemblecommand (
unsigned char* command,
int len);
112 const char* hostname;
113 int sockfd, portno, n;
114 struct sockaddr_in serv_addr;
116 struct addrinfo *addr_ptr;
118 struct hostent *server;
124 int MeanFilterNumScans;
125 float RangeFilterTopLimit;
126 float RangeFilterBottomLimit;
128 player_laser_config Configuration;
131 unsigned char buffer[4096];
132 unsigned int bufferlength;
135 unsigned char command[BUF_SIZE];
137 std::vector<MeasurementQueueElement_t>* MeasurementQueue;