4#ifndef AUBO_SDK_ROBOT_INTERFACE_H
5#define AUBO_SDK_ROBOT_INTERFACE_H
16#include <aubo/global_config.h>
virtual ~RobotInterface()
RobotStatePtr getRobotState()
Robot State Query Get robot state interface
RobotConfigPtr getRobotConfig()
Robot Configuration Management Get RobotConfig interface
IoControlPtr getIoControl()
IO Input/Output Control Get IO control interface
TracePtr getTrace()
Log and Pop-up Get alarm information interface
ForceControlPtr getForceControl()
Force Control Module Get force control interface
MotionControlPtr getMotionControl()
Motion Planning and Control Get motion planning interface
RobotManagePtr getRobotManage()
Robot Lifecycle Management Get robot management interface (power on, start, stop,...
RobotAlgorithmPtr getRobotAlgorithm()
Robot Algorithm Tool Get robot utility algorithm interface
SyncMovePtr getSyncMove()
Synchronized Movement Control and Axis Group Management 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.