Program Listing for File LMS1xx.h
↰ Return to documentation for file (include/LMS1xx/LMS1xx.h
)
/*
* LMS1xx.h
*
* Created on: 09-08-2010
* Author: Konrad Banachowicz
***************************************************************************
* This library is free software; you can redistribute it and/or *
* modify it under the terms of the GNU Lesser General Public *
* License as published by the Free Software Foundation; either *
* version 2.1 of the License, or (at your option) any later version. *
* *
* This library is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU *
* Lesser General Public License for more details. *
* *
* You should have received a copy of the GNU Lesser General Public *
* License along with this library; if not, write to the Free Software *
* Foundation, Inc., 59 Temple Place, *
* Suite 330, Boston, MA 02111-1307 USA *
* *
***************************************************************************/
#ifndef LMS1XX_H_
#define LMS1XX_H_
#include "LMS1xx/lms_buffer.h"
#include "LMS1xx/lms_structs.h"
#include <string>
#include <stdint.h>
#include "rclcpp/logging.hpp"
typedef enum
{
undefined = 0,
initialisation = 1,
configuration = 2,
idle = 3,
rotated = 4,
in_preparation = 5,
ready = 6,
ready_for_measurement = 7
} status_t;
class LMS1xx
{
public:
LMS1xx();
virtual ~LMS1xx();
void connect(std::string host, int port = 2111);
void disconnect();
bool isConnected();
void startMeas();
void stopMeas();
status_t queryStatus();
void login();
scanCfg getScanCfg() const;
void setScanCfg(const scanCfg &cfg);
void setScanDataCfg(const scanDataCfg &cfg);
scanOutputRange getScanOutputRange() const;
void scanContinous(int start);
bool getScanData(scanData* scan_data);
void saveConfig();
void startDevice();
protected:
static void parseScanData(char* buf, scanData* data);
bool connected_;
rclcpp::Logger logger_;
LMSBuffer buffer_;
int socket_fd_;
};
#endif /* LMS1XX_H_ */