RMVL  2.5.0-dev
Robotic Manipulation and Vision Library
载入中...
搜索中...
未找到

机器人控制模块 更多...

#include <rmvl/lpss/robot.hpp>

rm::lpss::RobotController 的协作图:

Public 成员函数

 RobotController (const std::vector< std::string > &joint_names, ctl::ControlLawBase::ptr ctl_law=ctl::UnitTF::create())
 构造机器人控制器
bool submit (const msg::JointTrajectory &traj)
 提交待执行关节轨迹
void reset () noexcept
 重置控制器状态,清空轨迹缓存,用于设置新轨迹前的状态清理
msg::JointState sample (const msg::JointState &feedback={}) noexcept
 采样并得到控制系统的输入值

详细描述

机器人控制模块

构造及析构函数说明

◆ RobotController()

rm::lpss::RobotController::RobotController ( const std::vector< std::string > & joint_names,
ctl::ControlLawBase::ptr ctl_law = ctl::UnitTF::create() )

构造机器人控制器

参数
[in]joint_names机器人关节名称列表,必须是 RobotPlanner 管理的关节集合的非空子集
[in]ctl_law控制律对象指针,默认为单位传递函数配合位置映射
函数调用图:

成员函数说明

◆ reset()

void rm::lpss::RobotController::reset ( )
noexcept

重置控制器状态,清空轨迹缓存,用于设置新轨迹前的状态清理

◆ sample()

msg::JointState rm::lpss::RobotController::sample ( const msg::JointState & feedback = {})
noexcept

采样并得到控制系统的输入值

参数
[in]feedback当前反馈状态,具体是否需要传入由控制律实现决定
返回
msg::JointState
函数调用图:

◆ submit()

bool rm::lpss::RobotController::submit ( const msg::JointTrajectory & traj)

提交待执行关节轨迹

将自动完成轨迹校验,包括:

  • 关节名校验: \(S_{C}\subseteq S_{P}\),其中 \(S_{C}\) 是控制器管理的关节集合, \(S_{P}\) 是轨迹中出现的关节集合
  • 时间轴校验:points[i].time_from_start 必须严格递增
  • 维度校验:每个轨迹点的位置/速度/加速度向量长度与关节数量一致(字段为空则按策略补全)
参数
[in]traj输入关节轨迹
返回
是否成功提交,失败时一般是由于轨迹校验未通过