ARS_408毫米波雷达数据解析学习记录-利用RVIZ实现解析结果的可视化

2023-05-16

前面已经基本完成了ARS_408毫米波雷达数据的获取与解析工作。虽然已经将从CAN口获取的数据解析处理成指定的消息类型并进行了发布,但是需要注意的是,它们只是处于文本数据形态,我们仍然无法得到直观的显示结果,如点的分布和目标相对传感器的位置分布等等。因此,这部分将会利用ROS中的 Rviz 三维可视化平台来对解析后的clusters / object数据进行三维可视化显示。

此外,考虑到之前部分是通过运行其它节点来启动的,因此为了操作方便,考虑利用launch文件一次性启动多个节点。

一、RVIZ 部分

  • 定义 ContinentalRadarRViz 类
#ifndef ARS_40X_ARS_40X_RVIZ_HPP
#define ARS_40X_ARS_40X_RVIZ_HPP

#include <ros/ros.h>

namespace ars_40X {
enum {
  POINT,
  CAR,
  TRUCK,
  PEDESTRIAN,
  MOTORCYCLE,
  BICYCLE,
  WIDE,
  RESERVED
};	//定义object模式中class_type取值的枚举变量
enum {
  INVALID,
  PERCENT_25,
  PERCENT_50,
  PERCENT_75,
  PERCENT_90,
  PERCENT_99,
  PERCENT_99_9,
  PERCENT_100
};	//定义clusters/object中prob_of_exist取值的枚举变量
class ContinentalRadarRViz {
 public:
  ContinentalRadarRViz();
  ~ContinentalRadarRViz();
 private:
  void clusters_callback(ars_40X::ClusterList cluster_list);	//接收clusters数据的回调函数
  void objects_callback(ars_40X::ObjectList object_list);	//接收object数据的回调函数
  ros::Publisher clusters_pub_;		//创建可视化clusters数据的发布者
  ros::Publisher objects_pub_;		//创建可视化object数据的发布者
  ros::Publisher velocity_pub_;		//创建velocity数据的发布者
  ros::Subscriber clusters_sub_;	//创建clusters解析数据的订阅者
  ros::Subscriber objects_sub_;		//创建object解析数据的订阅者
};
}
#endif //ARS_40X_ARS_40X_RVIZ_HPP
  • ContinentalRadarRViz类的实现
#include <ros/ros.h>
#include <visualization_msgs/MarkerArray.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>

#include "ars_40X/ClusterList.h"
#include "ars_40X/ObjectList.h"
#include "ars_40X/ros/ars_40X_rviz.hpp"

namespace ars_40X {
ContinentalRadarRViz::ContinentalRadarRViz() {
  ros::NodeHandle nh;
  clusters_pub_ = nh.advertise<visualization_msgs::MarkerArray>("visualize_clusters", 50);	//发布名为visualize_clusters的topic,消息类型为visualization_msgs::MarkerArray,发布序列的大小为50。
  objects_pub_ = nh.advertise<visualization_msgs::MarkerArray>("visualize_objects", 50);	//发布名为visualize_objects的topic,消息类型为visualization_msgs::MarkerArray,发布序列的大小为50。
  velocity_pub_ = nh.advertise<visualization_msgs::MarkerArray>("visualize_velocity", 50);	//发布名为visualize_velocity的topic,消息类型为visualization_msgs::MarkerArray,发布序列的大小为50。
  clusters_sub_ =
      nh.subscribe("ars_40X/clusters", 50, &ContinentalRadarRViz::clusters_callback, this);	//订阅ars_40X/clusters话题,并将获取的数据交由回调函数clusters_callback处理,消息队列上限为50。
  objects_sub_ =
      nh.subscribe("ars_40X/objects", 50, &ContinentalRadarRViz::objects_callback, this);	//订阅ars_40X/objects话题,并将获取的数据交由回调函数objects_callback处理,消息队列上限为50。
}
ContinentalRadarRViz::~ContinentalRadarRViz() {
}
void ContinentalRadarRViz::clusters_callback(ars_40X::ClusterList cluster_list) {
  visualization_msgs::MarkerArray marker_array;			//创建要发布的消息队列对象
  for (auto cluster : cluster_list.clusters) {		//遍历从话题中获取的cluster数据
    visualization_msgs::Marker marker;	//创建单个的Marker对象
    marker.type = visualization_msgs::Marker::POINTS;	//指定Marker的类型为POINTS类型
    marker.header.frame_id = cluster_list.header.frame_id;	
    marker.action = visualization_msgs::Marker::ADD;	//action域指定marker的行为,包括ADD(增加)和DELETE(删除)操作
    marker.header.stamp = cluster_list.header.stamp;
    marker.id = cluster.id;		//为这个marker设置一个唯一的ID,一个marker接收到相同ns和id就会用新的信息代替旧的
    marker.points.push_back(cluster.position.pose.position);	//将点坐标加入到marker内的点队列内
    switch (cluster.prob_of_exist) {
      case INVALID: {
        marker.color.r = 0.0f;
        marker.color.g = 0.0f;
        marker.color.b = 0.0f;	//黑色
        marker.ns = "Invalid";	//命名空间(ns)和id是用来给这个marker创建一个唯一的名字的
        break;
      }
      case PERCENT_25: {
        marker.color.r = 0.0f;
        marker.color.g = 0.0f;
        marker.color.b = 1.0f;	//蓝色
        marker.ns = "25%";
        break;
      }
      case PERCENT_50: {
        marker.color.r = 0.0f;
        marker.color.g = 1.0f;
        marker.color.b = 0.0f;	//绿色
        marker.ns = "50%";
        break;
      }
      case PERCENT_75: {
        marker.color.r = 0.0f;
        marker.color.g = 1.0f;
        marker.color.b = 1.0f;	//青色
        marker.ns = "75%";
        break;
      }
      case PERCENT_90: {
        marker.color.r = 1.0f;
        marker.color.g = 0.0f;
        marker.color.b = 0.0f;	//红色
        marker.ns = "90%";
        break;
      }
      case PERCENT_99: {
        marker.color.r = 1.0f;
        marker.color.g = 0.0f;
        marker.color.b = 1.0f;	//亮紫色(洋红色)
        marker.ns = "99%";
        break;
      }
      case PERCENT_99_9: {
        marker.color.r = 1.0f;
        marker.color.g = 1.0f;
        marker.color.b = 0.0f;	//黄色
        marker.ns = "99.9%";
        break;
      }
      case PERCENT_100: {
        marker.color.r = 1.0f;
        marker.color.g = 1.0f;
        marker.color.b = 1.0f;	//白色
        marker.ns = "100%";
        break;
      }
    }
    marker.scale.x = 0.1;
    marker.scale.y = 0.1;	//指定了Marker的规模,对于基本形状,1表示在这边长度是1米。
    marker.color.a = 1.0;	//alpha值为0意味着完全透明, 1意味着完全不透明
    marker.lifetime.fromSec(0.1);	//lifetime域指定marker在被自动删除之前会持续多久
    marker_array.markers.push_back(marker);
  }
  clusters_pub_.publish(marker_array);
}
void ContinentalRadarRViz::objects_callback(ars_40X::ObjectList object_list) {
  visualization_msgs::MarkerArray marker_array, velocity_array;	//创建要发布的消息队列对象
  for (auto object : object_list.objects) {
    visualization_msgs::Marker marker;	//创建单个的Marker对象
    marker.type = visualization_msgs::Marker::LINE_STRIP;	//指定Marker的类型是线。LINE_STRIP类型将每个点用作一组连接的线中的顶点,其中点0连接到点1, 点1连接到点2,点2连接到点3等
    marker.header.frame_id = object_list.header.frame_id;
    marker.action = visualization_msgs::Marker::ADD;	//指定我们要对marker做什么的, 有ADD和DELETE两个选项, ADD是创建或者修改
    marker.header.stamp = object_list.header.stamp;
    marker.id = object.id;	//为这个marker设置一个唯一的ID,一个marker接收到相同ns和id就会用新的信息代替旧的
    geometry_msgs::Point pos1, pos2, pos3, pos4;	//创建Point对象
    tf2::Quaternion q;	//创建tf2类型的四元数
    q.setValue(
        object.position.pose.orientation.x,
        object.position.pose.orientation.y,
        object.position.pose.orientation.z,
        object.position.pose.orientation.w);	//设置四元数的值
    tf2::Matrix3x3 m(q);	//四元数转换为旋转矩阵
    double roll, pitch, yaw;	//定义欧拉角
    m.getRPY(roll, pitch, yaw);		//从旋转矩阵中获取欧拉角的值
    if (isnan(yaw)) {	//如果给定的值能被转换为数字,则返回false;如果不能转换为数字,则返回true
      continue;
    }
    marker.pose = object.position.pose;		//给marker的位姿赋值,(在线中的点通过位姿变换)
    pos1.x = object.length / 2;
    pos1.y = object.width / 2;
    pos2.x = object.length / 2;
    pos2.y = -object.width / 2;
    pos3.x = -object.length / 2;
    pos3.y = -object.width / 2;
    pos4.x = -object.length / 2;
    pos4.y = object.width / 2;		//获取矩形四个角点坐标
    marker.points.push_back(pos1);
    marker.points.push_back(pos2);
    marker.points.push_back(pos3);
    marker.points.push_back(pos4);
    marker.points.push_back(pos1);	//将角点坐标存入到marker中
    marker.scale.x = 0.1;	//设置线段宽度

    switch (object.class_type) {
      case POINT: {				//点
        marker.color.r = 0.0f;
        marker.color.g = 0.0f;
        marker.color.b = 0.0f;	//黑色
        break;
      }
      case CAR: {				//车
        marker.color.r = 0.0f;
        marker.color.g = 0.0f;
        marker.color.b = 1.0f;	//蓝色
        break;
      }
      case TRUCK: {				//卡车
        marker.color.r = 0.0f;
        marker.color.g = 1.0f;
        marker.color.b = 0.0f;	//绿色
        break;
      }
      case PEDESTRIAN: {		//行人
        marker.color.r = 0.0f;
        marker.color.g = 1.0f;
        marker.color.b = 1.0f;	//青色
        break;
      }
      case MOTORCYCLE: {		//摩托车
        marker.color.r = 1.0f;
        marker.color.g = 0.0f;
        marker.color.b = 0.0f;	//红色
        break;
      }
      case BICYCLE: {			//自行车
        marker.color.r = 1.0f;
        marker.color.g = 0.0f;
        marker.color.b = 1.0f;	//亮紫色(洋红色)
        break;
      }
      case WIDE: {				//其它类型
        marker.color.r = 1.0f;
        marker.color.g = 1.0f;
        marker.color.b = 0.0f;	//黄色
        break;
      }
      case RESERVED: {			//保留
        marker.color.r = 1.0f;
        marker.color.g = 1.0f;
        marker.color.b = 1.0f;	//白色
        break;
      }
    }
    switch (object.prob_of_exist) {
      case INVALID: {
        marker.ns = "Invalid";	//根据目标的prob_of_exist为maker指定命名空间(ns)
        break;
      }
      case PERCENT_25: {
        marker.ns = "25%";
        break;
      }
      case PERCENT_50: {
        marker.ns = "50%";
        break;
      }
      case PERCENT_75: {
        marker.ns = "75%";
        break;
      }
      case PERCENT_90: {
        marker.ns = "90%";
        break;
      }
      case PERCENT_99: {
        marker.ns = "99%";
        break;
      }
      case PERCENT_99_9: {
        marker.ns = "99.9%";
        break;
      }
      case PERCENT_100: {
        marker.ns = "100%";
        break;
      }
    }
    marker.color.a = 1.0;	//设置marker为完全不透明
    marker.lifetime.fromSec(0.1);	//lifetime域指定marker在被自动删除之前会坚持多久
    marker_array.markers.push_back(marker);		//将初始话后的marker加入到marker_array中

    visualization_msgs::Marker velocity;	//创建用来存放velocity的Marker对象
    velocity.type = visualization_msgs::Marker::TEXT_VIEW_FACING;	//设置Marker类型为有方向的3D的文字
    velocity.header.frame_id = object_list.header.frame_id;
    velocity.action = visualization_msgs::Marker::ADD;
    velocity.header.stamp = object_list.header.stamp;
    velocity.id = object.id;
    velocity.text = std::to_string(hypot(object.relative_velocity.twist.linear.x,
                                         object.relative_velocity.twist.linear.y));	//hypot() 返回欧几里德范数 sqrt(x*x + y*y), 这里是计算目标速度并将其赋值给velocity的text部分
    velocity.pose = object.position.pose;	//将object位姿赋值给velocity,即指定文字的位置和方向
    velocity.scale.z = 1;	//TEXT_VIEW_FACING类型仅使用scale.z用于指定文本字体的高度
    velocity.color.a = 1;	//内容设置为完全不透明

    velocity_array.markers.push_back(velocity);
  }
  objects_pub_.publish(marker_array);	
  velocity_pub_.publish(velocity_array);	//发布object位置及其速度信息
}
}

int main(int argc, char **argv) {
  ros::init(argc, argv, "ars_40X_rviz");	//ros初始化,节点名称为ars_40X_rviz
  ars_40X::ContinentalRadarRViz ars_40X_rviz;	//创建ContinentalRadarRViz类对象
  ros::spin();
}
  • 修改 package.xml 和 CMakeLists.txt 文件

    ①package.xml文件(增加部分)

<build_depend>message_generation</build_depend> <build_export_depend>message_runtime</build_export_depend>
...

<depend>geometry_msgs</depend>
<depend>visualization_msgs</depend>
...
<exec_depend>message_runtime</exec_depend>

​ ②CMakeLists.txt文件(增加部分)

find_package(geometry_msgs REQUIRED)
find_package(visualization_msgs REQUIRED)

add_executable(ars_40X_rviz
    src/ros/ars_40X_rviz.cpp
    )
add_dependencies(ars_40X_rviz ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp)
target_link_libraries(ars_40X_rviz ${catkin_LIBRARIES})

install(
    TARGETS
	...
    ars_40X_rviz
	...
    ARCHIVE DESTINATION lib/${PROJECT_NAME}
    LIBRARY DESTINATION lib/${PROJECT_NAME}
    RUNTIME DESTINATION lib/${PROJECT_NAME}
)

二、添加 launch 文件

  • 考虑到直接无参数启动rviz时使用的是默认配置文件~/.rviz/default.rviz,为方便节点启动时直接使用已经设置好的rviz配置,可以将之前正常运行时的rviz配置保存为配置文件,并在rviz启动时作为参数传入。

  • 必备的节点属性:

    • pkg: 表示该节点的package,相当于 rosrun 命令后面的第一个参数;
    • type: 可执行文件的名字,rosrun 命令的第二个参数;是否可以理解为要执行的节点
    • name: 该节点的名字,相当于代码中 ros::init() 中设置的信息,有了它代码中的名称会被覆盖(因此一般会与代码中的命名保持一致)。
  • 其它属性

    • output: 将标准输出显示在屏幕上而不是记录在日志中;

    • 包含其他文件include file=“path to launch file”: 在启动文件中包含其他启动文件的内容(包括所有的节点和参数),可使用如下命令使路径更为简单include file="($find package-name)/launch-file-name"

    • 启动参数(launch arguments): 为了使启动文件便于配置,roslaunch 还支持启动参数,有时也简称为参数甚至 args,其功能有点像可执行程序中的局部变量。 声明参数:<arg name="arg-name" default="arg-value"/>

      获取参数:一旦参数值被声明并且被赋值,可以用下面的 arg 替换(arg substitution)语法来使用该参数值了:$(arg arg-name) 每个该替换出现的地方,roslaunch 都将它替换成参数值。

<launch>
  <arg name="visualize" default="true"/>
  <arg name="obstacle_array" default="false"/>		<!--定义参数的初始化 -->

  <node pkg="ars_40X" type="ars_40X_ros" name="ars_40X_ros" output="screen">
  </node>			<!-- 启动ars_40X包内的ars_40X_ros节点,节点的名字为“ars_40X_ros,将其中的标准输出显示在屏幕上”-->

  <group if="$(arg visualize)">		<!--根据参数 $(arg visualize)的值判断是否需要启动rviz节点-->
    <node pkg="ars_40X" type="ars_40X_rviz" name="ars_40X_rviz"/>
    <node pkg="rviz" type="rviz" name="rviz" args="-d $(find ars_40X)/rviz_cfg/ars_40X.rviz"/>	<!--args中的"-d"表示配置文件路径,"$(find ars_40X)/rviz_cfg/ars_40X.rviz"表示查找ars_40X包目录下的rviz配置文件 -->
  </group>

  <group if="$(arg obstacle_array)">	<!--根据参数 $(arg obstacle_array)的值判断是否需要启动obstacle_array节点-->
    <node pkg="ars_40X" type="ars_40X_obstacle_array" name="ars_40X_obstacle_array">
    </node>
  </group>
</launch>
  • 使用方法
roslaunch package-name launch-file-name arg-name:=arg-value 
本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

ARS_408毫米波雷达数据解析学习记录-利用RVIZ实现解析结果的可视化 的相关文章

  • Elasticsearch Linux安装详细步骤

    1 ElasticSearch 安装 1 1 ElasticSearch安装 1 上传ElasticSearch安装包 alt 43 p span class token comment 打开sftp窗口 span span class t
  • Ubuntu常用命令

    whoami 查看当前登录用户 su lt 用户名 gt 切换用户 useradd lt 用户名 gt 创建用户 passwd lt 用户名 gt 修改用户密码 history 查看历史命令 xff01 行数 直接执行曾经使用过命令 pwd
  • 用自己的摄像头运行SVO(效果不好)

    SVO Fast Semi Direct Monocular Visual Odometry 一 摘要 semi direct 半直接减小了特征提取的量匹配的运动估计更鲁棒直接从pixel intensities xff08 像素强度 xf
  • vnc远程登录工具 vnc远程登录工具如何选择与使用呢

    对于vnc远程登录工具 xff0c 如何选择与使用呢 xff1f 我目前所使用的就是这一款 xff1a IIS7服务器管理工具 作为IIS7服务器管理工具 xff0c 它可以对vnc站点进行批量管理 xff0c 十分便捷 除此之外 xff0
  • 局域网vnc远程控制软件,那些超级好用的局域网vnc远程控制软件

    其实在我们程序员的日常工作中 xff0c 难免会用到vnc远程控制 xff0c 那在小伙伴们的日常工作中 xff0c 有哪些好用的局域网vnc远程控制软件呢 xff1f 大家都有哪些了解呢 xff1f 那今天就让我们大家一起来交流一下有哪些
  • vnc使用教程,快速上手的vnc批量管理使用教程

    在日常工作过程中 肯定有很多程序员小伙伴们会有vnc批量管理使用教程的需求吧 小编也一样 那大家是如何实现vnc批量管理的呢 接下来 我将会对快速上手的vnc批量管理使用教程作一个简单介绍 首先 xff0c 我使用的是IIS7服务器管理工具
  • vnc使用教程,超实用的vnc使用教程

    在工作中 xff0c 难免会使用到vnc 小编也一样 很多小伙伴也问过我这个问题 xff0c 什么样的vnc使用教程能做到简单快捷 那大家知道vnc使用过程中 xff0c 是如何实现简单快捷的呢 接下来 我将会对vnc使用教程作一个简单介绍
  • 百度数据可视化Sugar BI — 数据监控与预警(附保姆级教程)

    最近答主一直在用百度智能云的Sugar BI xff0c 于是把他家官网里几个非常实用的数据可视化最佳实践资料 xff0c 分享至知乎 xff0c 希望可以帮到各位朋友 数据监控是有效且及时的反馈出数据异常的一种手段 通过对数据的监控去观察
  • windows如何使用vnc,只需5步轻松掌握windows下使用vnc

    出门在外忘了带档案怎么办 xff1f FTP server 上头忘了开帐号怎么办 xff1f 这些麻烦的问题其实都可以靠 VNC 解决 IIS7服务器管理工具是一款免费的远程控制软件 xff0c 能让你轻松控制远程的计算机 xff0c 它可
  • vnc viewer安卓版,5步掌握vnc viewer安卓版的使用方法

    vnc viewer是针对安卓系统而开发的一款手机远程桌面连接电脑软件 xff0c 该软件需要配合pc端的vnc服务端使用 xff0c 当用户在电脑上开启了vnc服务端 xff0c 再通过vnc viewer就可以在手机上随意操作电脑 xf
  • vncviewer使用教程,6步掌握vncviewer的使用教程

    vnc viewer是一款远程控制的软件 xff0c 一般用于远程解决电脑故障或软件调试 xff0c 下文小编就为大家带来vnc viewer远程控制电脑的教程 xff0c 相信看了你就会使用它了 IIS7服务器管理工具能让你轻松控制远程的
  • 常见的ftp工具有哪些,分享8款常见的ftp工具

    市面上有很多ftp服务器软件 xff0c 但是功能参差不齐 xff0c 安全性太多没有保障 xff0c 小编也进了很多坑 xff0c 为了让您少走弯路 xff0c 今天给大家分享8款常见的ftp工具 每款都很有特色 xff0c 感兴趣的小伙
  • tftp命令怎么传输文件,5步掌握tftp命令的使用方法

    FTP让用户得以下载存放于远端主机的文件 xff0c 也能将文件上传到远端主机放置 tftp是简单的文字模式ftp程序 xff0c 它所使用的指令和FTP类似 IIS7服务器管理工具可以批量管理 定时上传下载 同步操作 数据备份 到期提醒
  • filezilla ftp设置,7步完成filezilla ftp设置

    FTP服务器 File Transfer Protocol Server 是在互联网上提供文件存储和访问服务的计算机 xff0c 它们依照FTP协议提供服务 FTP是文件传输协议 xff0c 就是专门用来传输文件的协议 这篇文章主要介绍fi
  • 8uftp无法取得目录列表,解决8uftp无法取得目录列表的问题只需4步

    最近发现自己买的香港空间出现一个很严重的问题 xff0c ftp连接时无法取得目录列表 xff0c 因为之前一直固定在一家买空间 xff0c 所以善良的我很自然的打电话给这位老朋友让他赶紧起床看一看 xff0c 当时是凌晨两点半 几分钟后
  • 大数据ftp软件,2步完成大数据ftp软件的连接与命令操作

    ftp软件是什么软件 xff0c 可能有人会回答说不知道 xff0c 因为一般只有从事网站管理的工作者会使用的多一点 但不是每个人生来就会的 xff0c 所以刚开始肯定都会学习怎么使用ftp软件 这篇文章就来告诉大家大数据ftp软件大数据f
  • PID算法控制平衡小车直立

    1 平衡小车直立控制 xff1a 如果我们要控制一根木棍在手上直立 xff0c 需要两个步骤 gt 托着木棒的手可以移动 gt 眼睛能看到木棒的倾斜角度和倾斜趋势 xff08 角速度 xff09 类比到平衡小车中 xff0c 同理想让小车保
  • 数据结构 - 链式队列

    1 链式队列 链式队列 xff1a 用链表形式实现的队列 链表结点为队列数据存储区 xff0c 链表结点包括两部分数据存储 区和指针存储区 数据存储区 xff1a 存放真实有效数据的区域 指针存储区 xff1a 存放下一个链表结点的地址 2
  • Sugar BI:如何在下钻中改变地图范围

    下钻是指在点击本图表的某一部分时 xff0c 可以打开一个新的图表或超链接 xff0c 进而查看与图表此部分相关的详细信息 Sugar BI支持无限层级的下钻 xff0c 只要下钻的弹出展示的图表也是支持下钻的 xff0c 就可以继续配置进
  • darknet_ros部署及测试

    一 darknet ros部署 1 创建ROS工作空间 span class token function mkdir span p catkin ws src span class token builtin class name cd

随机推荐

  • ensp 查看命令(display)

    ensp 查看命令 xff08 display xff09 span class token number 1 span display this span class token comment 查看当前配置过的命令 span span
  • 关于HTTP 和 HTTPS

    什么是http 超文本传输协议 Http xff0c HyperText Transfer Protocol 是互联网上应用最为广泛的一种网络协议 xff0c 设计Htto最初的目的是提供一种发布和接收HTML页面的方法 xff0c 他可以
  • 关于事件流的简单理解

    JS事件 1 首先 xff0c 什么是事件 xff1f JavaScript和Html发生交互是通过事件来实现的 xff0c 事件 xff0c 就是文档或浏览器窗口发生一些特定的交互的瞬间 2 什么是事件流 xff1f 事件流就是 xff0
  • Vue中引入自定义公共组件方法以及步骤

    什么是公共组件 xff0c 公共组件的使用场景 项目中如果多个页面都显示有相同的区域内容 xff0c 则该公共区域内容可以封装成公共组件进行使用 步骤 xff1a 1 创建自定义公共组件 xff0c 在src下的components目录中自
  • vue中的data为什么是一个函数

    首先 xff1a 组件是一个可复用的Vue实例 xff0c 一个组件被创建好之后 xff0c 就可能被用在各个地方 xff0c 而组件不管被复用多少次 xff0c 组件中data数据都应该是相互隔离 xff0c 互不影响的 xff0c 基于
  • Vue中key值的作用

    Vue中key值的作用 首先v for 在列表渲染时 xff0c 我们可以用v for基于一个数组来渲染一个列表 v for指令需要使用item in arr形式的特殊语法来进行渲染列表 xff0c arr是源数据 xff0c span c
  • 电商后台管理项目d01

    电商后台管理项目d01 1 项目技术栈 2 项目初始化 3 Element UI 的按需引入 4 路由配置 5 Axios 的封装 6 实现登录功能 7 完成首页部分 8 用户管理 用户列表 9 权限管理 1 角色
  • react之jsx语法规则

    希望在之后的日子里 xff0c 能够时常更新 xff01 定义虚拟DOM时 xff0c 不要写引号 标签中混入JSX表达式时 xff0c 要用 样式的类名不要用class属性 xff0c 要是用clsaaName属性 lt h1 class
  • 电子凭证文件上传

    最近 xff0c 一直在做一些关于文件上传 xff0c 以及凭证导出打印的工作 xff0c 做一些记录 xff0c 方便日后的查阅 对了 xff0c 我在这里用的是antDesign这个第三方组件 文件上传 vue模板中 lt p gt l
  • 可视化图表API格式要求有哪些?Sugar BI详细代码示例(2)

    Sugar BI中的每个图表可以对应一个数据 API xff0c 用户浏览报表时 xff0c 选定一定的过滤条件 xff0c 点击 查询 按钮将会通过 API 拉取相应的数据 xff1b 前面说过 xff0c 为了确保用户数据的安全性 xf
  • "Warning: GetWindowMenuPopup failed! "

    对mdi程序中一个弹出菜单警告原因的分析 作者 laomai 网址 http blog csdn net laomai xff08 转载时请注明出处 xff09 一 引子 最近在编译一个别人的mdi程序代码 xff0c 在调试程序时 vc6
  • div仿input的使用

    需求描述 xff0c 输入框支持文本输入 xff0c 以及支持标签在对应节点的插入 1 首先封装组件 xff0c 通过父子组件传参的方式进行数据的处理 用富文本插件体积略大通过div标签的contenteditable属性来处理成仿inpu
  • 关于优雅去重的一些感想

    也就不赘述有的没的 xff0c 看代码 1 通过reduce 方法进行去重 this pageDataList 61 this pageDataList reduce tempArr item 61 gt if tempArr findIn
  • java形参的改变会影响实参吗?

    java形参的改变会影响实参吗 xff1f 昨天做题的时候遇到了这个问题 xff08 如图所示 xff09 xff0c 传入的参数是int 数组 xff0c 实参跟着形参一起改变了 但是之前传入int型参数时形参的改变是不会影响实参的 所以
  • 快速教你数据清洗的步骤及方法,不可错过

    说起数据清洗 xff0c 可能会有些小伙伴会觉得这一步可以忽略掉 xff0c 但是 xff01 作为混迹在数据分析这一块多年的老油条 xff0c 小编在此严肃地声明 xff01 资料清理是资料处理中最不能被忽略的部分 xff0c 它是资料分
  • 阿里八年大佬,分享三款值得推荐的开源接口测试工具

    三款值得推荐的开源接口测试工具 接口测试可以测试APIs Application Programming Interface 是否符合功能 xff0c 可靠性 xff0c 性能和安全要求 接口测试对于成功的CI DevOps来说至关重要 J
  • Gazebo的安装&与ROS的连接

    一 安装 1 添加源 span class token function sudo span span class token function sh span c span class token string 39 echo 34 de
  • 3d仿真文献综述

    文献综述 Vincent文论创新点Digital Twin based synchronised control and simulation of the industrial robotic cell using Virtual Rea
  • MATLAB多个子图 用一个 colorbar

    多个子图使用同一个colorbar left bottom width height ps42 61 zeros 8 4 ps42 3 61 0 44 ps42 4 61 0 20 ps42 7 8 2 61 0 08 ps42 5 6 2
  • ARS_408毫米波雷达数据解析学习记录-利用RVIZ实现解析结果的可视化

    前面已经基本完成了ARS 408毫米波雷达数据的获取与解析工作 虽然已经将从CAN口获取的数据解析处理成指定的消息类型并进行了发布 xff0c 但是需要注意的是 xff0c 它们只是处于文本数据形态 xff0c 我们仍然无法得到直观的显示结