12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364 |
- #ifndef __ROBOT_H__
- #define __ROBOT_H__
- #include <map>
- #include <string>
- #include <vector>
- #include <ros/ros.h>
- #include <sensor_msgs/PointCloud.h>
- // #include "server/locate.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); //更新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); //更新IO信息
- void SetResource(ResourceInfo resource); //更新AGV占用资源信息
- LocationInfo GetLocationInfo(); //获取定位信息
- std::map<std::string, MapInfo> GetMapLists(); //获取地图列表信息
- EmcyInfo GetEmcyInfo(); //获取急停信息
- BatteryInfo GetBatteryInfo(); //获取电池信息
- std::map<std::string, bool> GetGpioInfo(); //获取IO信息
- void SetNavigationConfig(NavigationConfigInfo info); //设置导航配置信息
- NavigationConfigInfo GetNavigationConfig(); //获取导航配置信息
- void SetLaserConfig(LaserConfigInfo info); //设置雷达参数
- std::map<std::string, LaserConfigInfo> GetLaserConfig(); //获取雷达参数
- }//robot
- #endif
|