Ultrasonic.h
Go to the documentation of this file.
00001 //
00002 // Created by tom on 15/05/16.
00003 //
00004 
00005 #ifndef ROBOTICAN_HARDWARE_INTERFACE_ULTRASONIC_H
00006 #define ROBOTICAN_HARDWARE_INTERFACE_ULTRASONIC_H
00007 
00008 #include <sensor_msgs/Range.h>
00009 #include <robotican_hardware_interface/Device.h>
00010 #include <robotican_hardware_interface/ros_utils.h>
00011 #include <robotican_hardware_interface/RiCBoardManager.h>
00012 
00013 #define URF_HRLV_MaxSonar_an2m 5.0/ 1000.0 
00014 #define MIN_RANGE_URF_HRLV_MaxSonar 0.3f // min 0.16f
00015 #define MAX_RANGE_URF_HRLV_MaxSonar 5.0f //max 6.45f
00016 #define FIELD_OF_VIEW_URF_HRLV_MaxSonar 0.7f //0.7f
00017 
00018 #define URF_LV_MaxSonar_an2m 13004.8/65535.0/1000.0
00019 #define MIN_RANGE_URF_LV_MaxSonar 0.16f
00020 #define MAX_RANGE_URF_LV_MaxSonar 6.45f
00021 #define FIELD_OF_VIEW_URF_LV_MaxSonar 0.7f
00022 
00023 
00024 namespace robotican_hardware {
00025     class Ultrasonic : public Device {
00026     private:
00027         byte _pin;
00028         std::string _topicName;
00029         std::string _frameId;
00030         double _analog2Range;
00031         ros::Publisher _ultrasonicRead;
00032 
00033     protected:
00034         virtual void buildDevice();
00035 
00036     public:
00037         Ultrasonic(byte id, TransportLayer *transportLayer, byte pin, std::string topicName,
00038                    std::string frameId, std::string sonarName);
00039 
00040         virtual void update(const DeviceMessage *deviceMessage);
00041 
00042         virtual void write();
00043 
00044         virtual void deviceAck(const DeviceAck *ack);
00045     };
00046 }
00047 
00048 #endif //ROBOTICAN_HARDWARE_INTERFACE_ULTRASONIC_H


robotican_hardware_interface
Author(s):
autogenerated on Fri Oct 27 2017 03:02:48