12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364 |
- #ifndef __ROBOT_H__
- #define __ROBOT_H__
- #include <map>
- #include <string>
- #include <vector>
- #include <ros/ros.h>
- #include <sensor_msgs/PointCloud.h>
- #include "map/path.h"
- #include "common/def.h"
- namespace robot {
- void init(ros::NodeHandle nh);
- RobotInfo GetRobotInfo();
- void SetName(std::string name);
- void SetID(std::string id);
- void SetState(std::string state);
- void SetLocation(LocationInfo loc);
- void SetMaps(std::map<std::string, MapInfo> maps);
- void SetHardwareEmcy(bool emcy);
- void SetSoftwareEmcy(bool emcy);
- void SetTrafficEmcy(bool emcy);
- void SetBattery(BatteryInfo battery);
- void SetGpio(std::map<std::string, bool> gpio);
- void SetResource(ResourceInfo resource);
- LocationInfo GetLocationInfo();
- std::map<std::string, MapInfo> GetMapLists();
- EmcyInfo GetEmcyInfo();
- BatteryInfo GetBatteryInfo();
- std::map<std::string, bool> GetGpioInfo();
- void SetNavigationConfig(NavigationConfigInfo info);
- NavigationConfigInfo GetNavigationConfig();
- void SetLaserConfig(LaserConfigInfo info);
- std::map<std::string, LaserConfigInfo> GetLaserConfig();
- }
- #endif
|