1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253 |
- #ifndef C2_ETH_DRIVER_H_
- #define C2_ETH_DRIVER_H_
- #include <free_lidar/lidar_struct.h>
- #include <free_lidar/lidar_driver.h>
- #include <string>
- #include <deque>
- #include <stdint.h>
- #define C2_ETH_ROS_VER "2.00.00.008"
- namespace free_optics{
- class C2EthDriver : public LidarDriver
- {
- public:
- C2EthDriver();
- ~C2EthDriver();
- bool connect(const std::string hostname, int port=2111);
- void disconnect();
- bool getDeviceState(uint8_t &state);
- bool getDeviceName(std::string &name);
- bool getFirmwareVersion(uint32_t &version);
- bool getSerialNumber(uint32_t &sn);
- bool login(uint8_t &state);
- bool getScanAngle(int32_t &start_angle, int32_t &stop_angle);
- bool setScanAngle(int32_t start_angle, int32_t stop_angle);
- bool setScanConfig(uint16_t frequency, uint16_t resolution);
- bool getMeasureRange(float &range_min, float &range_max);
- bool getScanData(uint8_t state);
- bool scanDataReceiver();
- private:
- int socket_fd_;
- };
- }
- #endif
|