robot.h 1.8 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364
  1. #ifndef __ROBOT_H__
  2. #define __ROBOT_H__
  3. #include <map>
  4. #include <string>
  5. #include <vector>
  6. #include <ros/ros.h>
  7. #include <sensor_msgs/PointCloud.h>
  8. // #include "server/locate.h"
  9. #include "map/path.h"
  10. #include "common/def.h"
  11. namespace robot {
  12. void init(ros::NodeHandle nh);
  13. RobotInfo GetRobotInfo(); //获取机器人信息
  14. void SetName(std::string name); //更新名字
  15. void SetID(std::string id); //更新ID
  16. void SetState(std::string state); //更新状态
  17. void SetLocation(LocationInfo loc); //更新定位信息
  18. void SetMaps(std::map<std::string, MapInfo> maps); //更新地图列表
  19. void SetHardwareEmcy(bool emcy); //设置硬件急停
  20. void SetSoftwareEmcy(bool emcy); //设置软件急停
  21. void SetTrafficEmcy(bool emcy); //设置交通管制急停
  22. void SetBattery(BatteryInfo battery); //更新电池信息
  23. void SetGpio(std::map<std::string, bool> gpio); //更新IO信息
  24. void SetResource(ResourceInfo resource); //更新AGV占用资源信息
  25. LocationInfo GetLocationInfo(); //获取定位信息
  26. std::map<std::string, MapInfo> GetMapLists(); //获取地图列表信息
  27. EmcyInfo GetEmcyInfo(); //获取急停信息
  28. BatteryInfo GetBatteryInfo(); //获取电池信息
  29. std::map<std::string, bool> GetGpioInfo(); //获取IO信息
  30. void SetNavigationConfig(NavigationConfigInfo info); //设置导航配置信息
  31. NavigationConfigInfo GetNavigationConfig(); //获取导航配置信息
  32. void SetLaserConfig(LaserConfigInfo info); //设置雷达参数
  33. std::map<std::string, LaserConfigInfo> GetLaserConfig(); //获取雷达参数
  34. }//robot
  35. #endif