00001 // 00002 // Created by tom on 08/05/16. 00003 // 00004 00005 #ifndef ROBOTICAN_HARDWARE_INTERFACE_RICBOARDMANAGER_H 00006 #define ROBOTICAN_HARDWARE_INTERFACE_RICBOARDMANAGER_H 00007 00008 #include <vector> 00009 #include <ros/ros.h> 00010 #include <ros/package.h> 00011 #include <boost/thread/thread.hpp> 00012 #include <robotican_hardware_interface/Device.h> 00013 #include <robotican_hardware_interface/Battery.h> 00014 #include <robotican_hardware_interface/Servo.h> 00015 #include <robotican_hardware_interface/ros_utils.h> 00016 #include <hardware_interface/joint_command_interface.h> 00017 #include <robotican_hardware_interface/TransportLayer.h> 00018 #include <robotican_hardware_interface/Ultrasonic.h> 00019 #include <robotican_hardware_interface/Gps.h> 00020 #include <robotican_hardware_interface/Imu.h> 00021 #include <robotican_hardware_interface/RiCMotor.h> 00022 #include <robotican_hardware_interface/Switch.h> 00023 #include <robotican_hardware_interface/Relay.h> 00024 00025 #include <map> 00026 #include <dynamic_reconfigure/server.h> 00027 #include <robotican_hardware_interface/RiCBoardManager.h> 00028 #include <robotican_hardware_interface/RiCBoardConfig.h> 00029 #include <robotican_hardware_interface/RiCBoardServoConfig.h> 00030 00031 00032 00033 #define MAX_BUFF_SIZE 255 00034 #define PC_VERSION 100 00035 #define RIC_BOARD_DEBUG 00036 00037 namespace robotican_hardware { 00038 class CloseLoopMotor; 00039 class CloseLoopMotorWithPotentiometer; 00040 00041 class RiCBoardManager { 00042 private: 00043 byte _rcvBuff[MAX_BUFF_SIZE]; 00044 TransportLayer _transportLayer; 00045 ConnectEnum::ConnectEnum _connectState; 00046 ros::NodeHandle _nodeHandle; 00047 ros::Timer _sendKeepAliveTimer; 00048 ros::Timer _timeoutKeepAliveTimer; 00049 ros::AsyncSpinner _spinner; 00050 std::vector<Device*> _devices; 00051 byte _idGen; 00052 00053 unsigned int getBaudrate(); 00054 00055 std::string getPort(); 00056 00057 void resetBuff(); 00058 00059 void setConnectState(ConnectEnum::ConnectEnum connectState); 00060 00061 void debugMsgHandler(DebugMsg *debugMsg); 00062 00063 void clear(); 00064 00065 public: 00066 RiCBoardManager(); 00067 00068 void buildDevices(); 00069 00070 void buildDevices(hardware_interface::JointStateInterface*, hardware_interface::VelocityJointInterface*); 00071 00072 void buildDevices(hardware_interface::JointStateInterface*, hardware_interface::PositionJointInterface*); 00073 // void buildDevices(hardware_interface::JointStateInterface*, hardware_interface::PositionJointInterface*); 00074 00075 void connect(); 00076 00077 void disconnect(); 00078 00079 void handleMessage(); 00080 00081 void connectionHandle(ConnectState *connectState); 00082 00083 void sendKeepAliveEvent(const ros::TimerEvent &timerEvent); 00084 00085 void timeoutKeepAliveEvent(const ros::TimerEvent &timerEvent); 00086 00087 void keepAliveHandle(KeepAliveMsg *keepAliveMsg); 00088 00089 void deviceMessageHandler(DeviceMessage *deviceMsg); 00090 00091 void write(); 00092 00093 ConnectEnum::ConnectEnum getConnectState(); 00094 }; 00095 } 00096 00097 #endif //ROBOTICAN_HARDWARE_INTERFACE_RICBOARDMANAGER_H