4#ifndef AUBO_SDK_ROBOT_INTERFACE_H
5#define AUBO_SDK_ROBOT_INTERFACE_H
16#include <aubo/global_config.h>
virtual ~RobotInterface()
RobotStatePtr getRobotState()
RobotState (机器人状态查询) Get robot state interface
RobotConfigPtr getRobotConfig()
RobotConfig (机器人配置管理) Get RobotConfig interface
IoControlPtr getIoControl()
IoControl (IO输入输出控制) Get IO control interface
TracePtr getTrace()
Trace (日志与弹窗) Get alarm information interface
ForceControlPtr getForceControl()
ForceControl(力控模块) Get force control interface
MotionControlPtr getMotionControl()
MotionControl (运动规划与控制) Get motion planning interface
RobotManagePtr getRobotManage()
RobotManage (机器人生命周期管理) Get robot management interface (power on, start, stop, etc....
RobotAlgorithmPtr getRobotAlgorithm()
RobotAlgorithm (机器人算法工具) Get robot utility algorithm interface
SyncMovePtr getSyncMove()
SyncMove (同步运动控制和轴组管理) Get synchronized motion interface
Motion control interface.
std::shared_ptr< RobotManage > RobotManagePtr
std::shared_ptr< RobotInterface > RobotInterfacePtr
std::shared_ptr< Trace > TracePtr
std::shared_ptr< MotionControl > MotionControlPtr
std::shared_ptr< ForceControl > ForceControlPtr
std::shared_ptr< IoControl > IoControlPtr
std::shared_ptr< SyncMove > SyncMovePtr
std::shared_ptr< RobotConfig > RobotConfigPtr
std::shared_ptr< RobotAlgorithm > RobotAlgorithmPtr
std::shared_ptr< RobotState > RobotStatePtr
获取机器人配置接口,如获取DH参数、碰撞等级、安装位姿等等
获取机器人状态接口,如关节速度、关节角度、固件/硬件版本
Interface for injecting logs into the controller's logging system.