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

装甲模块组合特征 更多...

#include <rmvl/combo/armor.h>

类 rm::Armor 继承关系图:
rm::Armor 的协作图:

Public 类型

using ptr = std::shared_ptr<Armor>
 
using const_ptr = std::shared_ptr<const Armor>
 
- Public 类型 继承自 rm::combo
using ptr = std::shared_ptr<combo>
 
using const_ptr = std::shared_ptr<const combo>
 

Public 成员函数

combo::ptr clone (double tick) override
 从另一个组合体进行构造
 
float getComboRatio ()
 获取组合特征宽高比
 
float getWidthRatio ()
 获取左右灯条宽度的比值
 
float getLengthRatio ()
 获取左右灯条长度的比值
 
float getCornerAngle ()
 获取左右灯条错位角
 
float getError ()
 获取匹配误差
 
ArmorSizeType getArmorType ()
 获取装甲板大小类型
 
void setType (RobotType stat)
 设置机器人类型 RobotType
 
void setExtrinsic (const CameraExtrinsics &extrinsic)
 设置相机外参
 
const cv::Vec2f & getPose () const
 获取装甲板姿态法向量
 
- Public 成员函数 继承自 rm::combo
float height () const
 获取组合体高度
 
float width () const
 获取组合体宽度
 
float angle () const
 获取组合体角度
 
cv::Point2f center () const
 获取组合体中心点
 
const std::vector< cv::Point2f > & corners () const
 获取组合体角点
 
cv::Point2f corner (int idx) const
 获取指定角点
 
const CameraExtrinsicsextrinsic () const
 获取组合体相机外参
 
RMStatus type () const
 获取组合体类型
 
double tick () const
 获取捕获该组合体的时间点
 
cv::Point2f getRelativeAngle () const
 获取组合体的相对目标转角
 
const ImuDataimu () const
 获取组合体当前的 IMU 数据
 
feature::ptr at (std::size_t idx)
 获取指定特征
 
const feature::const_ptr at (std::size_t idx) const
 获取指定特征
 
const auto & data () const
 获取特征列表数据
 
std::size_t size () const
 获取特征列表大小
 
bool empty () const
 判断特征列表是否为空
 

静态 Public 成员函数

static ptr make_combo (LightBlob::ptr p_left, LightBlob::ptr p_right, const ImuData &imu_data, double tick, ArmorSizeType armor_size_type=ArmorSizeType::UNKNOWN)
 Armor 构造接口
 
static void loadSVM (const std::string &path)
 加载 SVM 装甲板大小分类的 *.xml 文件
 
static void imuConvertToCamera (const cv::Matx33f &gyro_rmat, const cv::Vec3f &gyro_tvec, const ImuData &imu_data, cv::Matx33f &cam_rmat, cv::Vec3f &cam_tvec)
 装甲板相机外参从 IMU 坐标系转化为相机坐标系
 
static void cameraConvertToImu (const cv::Matx33f &cam_rmat, const cv::Vec3f &cam_tvec, const ImuData &imu_data, cv::Matx33f &gyro_rmat, cv::Vec3f &gyro_tvec)
 装甲板相机外参从相机坐标系转化为 IMU 坐标系
 
static bool isContainBlob (LightBlob::ptr blob, Armor::ptr armor)
 判断单个装甲板所在区域内是否包含指定的灯条
 
static cv::Mat getNumberROI (cv::Mat src, const_ptr p_armor)
 根据图像中指定装甲板的信息,截取仅包含数字的 ROI
 

额外继承的成员函数

- Protected 属性 继承自 rm::combo
std::vector< feature::ptr_features
 特征列表
 
float _height {}
 高度
 
float _width {}
 宽度
 
float _angle {}
 角度
 
RMStatus _type {}
 类型
 
cv::Point2f _center
 中心点
 
cv::Point2f _relative_angle
 相对目标转角
 
ImuData _imu_data
 当前 IMU 数据
 
std::vector< cv::Point2f > _corners
 角点
 
CameraExtrinsics _extrinsic
 相机外参
 
double _tick {}
 捕获该组合体时的时间点
 

详细描述

装甲模块组合特征

注解
  • 特征包括 [0]: 左灯条,[1]: 右灯条
  • 角点为 [0]: 左灯条下顶点,[1]: 左灯条上顶点,[2]: 右灯条上顶点,[3]: 右灯条下顶点

成员类型定义说明

◆ const_ptr

using rm::Armor::const_ptr = std::shared_ptr<const Armor>

◆ ptr

using rm::Armor::ptr = std::shared_ptr<Armor>

成员函数说明

◆ cameraConvertToImu()

static void rm::Armor::cameraConvertToImu ( const cv::Matx33f & cam_rmat,
const cv::Vec3f & cam_tvec,
const ImuData & imu_data,
cv::Matx33f & gyro_rmat,
cv::Vec3f & gyro_tvec )
static

装甲板相机外参从相机坐标系转化为 IMU 坐标系

参数
[in]cam_rmat相机坐标系下的装甲板旋转矩阵
[in]cam_tvec相机坐标系下的装甲板平移向量
[in]imu_dataIMU 数据信息
[out]gyro_rmatIMU 坐标系下的装甲板旋转矩阵
[out]gyro_tvecIMU 坐标系下的装甲板平移向量

◆ clone()

combo::ptr rm::Armor::clone ( double tick)
overridevirtual

从另一个组合体进行构造

参数
[in]tick当前时间点,可用 rm::Timer::now() 获取
返回
指向新组合体的共享指针

实现了 rm::combo.

◆ getArmorType()

ArmorSizeType rm::Armor::getArmorType ( )
inline

获取装甲板大小类型

◆ getComboRatio()

float rm::Armor::getComboRatio ( )
inline

获取组合特征宽高比

◆ getCornerAngle()

float rm::Armor::getCornerAngle ( )
inline

获取左右灯条错位角

◆ getError()

float rm::Armor::getError ( )
inline

获取匹配误差

◆ getLengthRatio()

float rm::Armor::getLengthRatio ( )
inline

获取左右灯条长度的比值

◆ getNumberROI()

static cv::Mat rm::Armor::getNumberROI ( cv::Mat src,
const_ptr p_armor )
static

根据图像中指定装甲板的信息,截取仅包含数字的 ROI

参数
[in]src输入图像
[in]p_armor指定的参考装甲板
返回
ROI
示例
samples/detector/hik/sample_hik_armor_collection.cpp , 以及 samples/detector/mv/sample_mv_armor_collection.cpp.

◆ getPose()

const cv::Vec2f & rm::Armor::getPose ( ) const
inline

获取装甲板姿态法向量

◆ getWidthRatio()

float rm::Armor::getWidthRatio ( )
inline

获取左右灯条宽度的比值

◆ imuConvertToCamera()

static void rm::Armor::imuConvertToCamera ( const cv::Matx33f & gyro_rmat,
const cv::Vec3f & gyro_tvec,
const ImuData & imu_data,
cv::Matx33f & cam_rmat,
cv::Vec3f & cam_tvec )
static

装甲板相机外参从 IMU 坐标系转化为相机坐标系

参数
[in]gyro_rmatIMU 坐标系下的装甲板旋转矩阵
[in]gyro_tvecIMU 坐标系下的装甲板平移向量
[in]imu_dataIMU 数据信息
[out]cam_rmat相机坐标系下的装甲板旋转矩阵
[out]cam_tvec相机坐标系下的装甲板平移向量

◆ isContainBlob()

static bool rm::Armor::isContainBlob ( LightBlob::ptr blob,
Armor::ptr armor )
static

判断单个装甲板所在区域内是否包含指定的灯条

参数
[in]blob指定的灯条
[in]armor单一装甲板
返回
是否包含灯条中心

◆ loadSVM()

static void rm::Armor::loadSVM ( const std::string & path)
inlinestatic

加载 SVM 装甲板大小分类的 *.xml 文件

参数
[in]path*.xml 文件路径

◆ make_combo()

static ptr rm::Armor::make_combo ( LightBlob::ptr p_left,
LightBlob::ptr p_right,
const ImuData & imu_data,
double tick,
ArmorSizeType armor_size_type = ArmorSizeType::UNKNOWN )
static

Armor 构造接口

注解
若提供具体的 armor_size_type 参数,则不进行可行性验证,直接强制构造
参数
[in]p_left左灯条共享指针
[in]p_right右灯条共享指针
[in]imu_data当前时刻组合特征对应的 IMU 数据
[in]tick捕获组合特征的时间点
[in]armor_size_type需要指定的大小装甲板类型,默认为 ArmorSizeType::UNKNOWN
返回
若成功,返回 Armor 的共享指针,否则返回空

◆ setExtrinsic()

void rm::Armor::setExtrinsic ( const CameraExtrinsics & extrinsic)
inline

设置相机外参

函数调用图:

◆ setType()

void rm::Armor::setType ( RobotType stat)
inline

设置机器人类型 RobotType


该类的文档由以下文件生成: