[ROS 系列学习教程] 建模与仿真 - 使用 ros_control 控制差速轮式机器人

news2024/10/7 18:28:47

在这里插入图片描述

ROS 系列学习教程(总目录)

本文目录

  • 一、差速轮式机器人
  • 二、差速驱动机器人运动学模型
  • 三、对外接口
    • 3.1 输入接口
    • 3.2 输出接口
  • 四、控制器参数
  • 五、配置控制器参数
  • 六、编写硬件抽象接口
  • 七、控制机器人移动
  • 八、源码

ros_control 提供了多种控制器,其中 diff_drive_controller 用于控制差速驱动轮式机器人。

一、差速轮式机器人

差速轮式机器人是一种移动机器人,其运动基于机器人身体两侧的两个独立驱动轮。因此,它可以通过改变轮子的相对旋转速度来改变方向,不需要额外的转向运动。具有这种驱动器的机器人通常有一个或多个脚轮,以防止车辆倾斜。

如果两个轮子以相同的方向和速度驱动,机器人将沿直线行驶。如果两个轮子以相同的速度朝相反的方向转动,如所示图所示,机器人将绕轴的中心点旋转。否则,根据旋转速度和方向,旋转中心可能落在由两个轮胎接触点定义的线上的任何位置。当机器人沿直线行驶时,旋转中心距离机器人无限远。由于机器人的方向取决于两个驱动轮的旋转速度和方向,因此应精确感测和控制这些量。

image-20240623192426694

差速转向机器人与汽车中使用的差速 齿轮类似,两个车轮可以有不同的转速,但与差速齿轮系统不同,差速转向系统将为两个车轮提供动力。差速轮式机器人在机器人技术中得到广泛应用,因为它们的运动易于编程并且可以很好地控制。当今市场上几乎所有的消费机器人都使用差速转向,主要是因为它成本低且简单。

二、差速驱动机器人运动学模型

如下图为轮式机器人的差速驱动运动学模型示意图:

image-20240623192426694

其中,
V − 机器人线速度 ω − 机器人角速度 X O Y − 世界坐标系 X B Y B − 机器人坐标系 φ − 机器人在世界坐标系的角度 r − 车轮半径 b − 轮距 I C R − 瞬时旋转中心 R − 瞬心到机器人中心的距离 v L , v R − 左右轮接地点切向线速度 ω L , ω R − 左右轮角速度 V - 机器人线速度\\ \omega - 机器人角速度\\ XOY - 世界坐标系\\ X_BY_B - 机器人坐标系\\ \varphi - 机器人在世界坐标系的角度\\ r - 车轮半径\\ b - 轮距\\ ICR - 瞬时旋转中心\\ R - 瞬心到机器人中心的距离\\ v_L,v_R - 左右轮接地点切向线速度\\ \omega_L,\omega_R - 左右轮角速度 V机器人线速度ω机器人角速度XOY世界坐标系XBYB机器人坐标系φ机器人在世界坐标系的角度r车轮半径b轮距ICR瞬时旋转中心R瞬心到机器人中心的距离vL,vR左右轮接地点切向线速度ωL,ωR左右轮角速度

有如下关系:
ω ⋅ ( R + b / 2 ) = v R ω ⋅ ( R − b / 2 ) = v L \omega \cdot (R + b/2) = v_R\\ \omega \cdot (R - b/2) = v_L ω(R+b/2)=vRω(Rb/2)=vL
解这两个方程可得 ω \omega ω R R R
ω = ( v R − v L ) / b R = b / 2 ⋅ ( v R + v L ) / ( v R − v L ) \omega = (v_R-v_L)/b\\ R = b/2 \cdot(v_R+v_L)/(v_R-v_L) ω=(vRvL)/bR=b/2(vR+vL)/(vRvL)
利用角速度方程可得机器人瞬时速度 V V V
V = ω ⋅ R = ( v R + v L ) / 2 V = \omega \cdot R = (v_R+v_L)/2 V=ωR=(vR+vL)/2
车轮切向速度也可以写成:
v R = r ⋅ ω R v L = r ⋅ ω L v_R = r \cdot \omega_R\\ v_L = r \cdot \omega_L vR=rωRvL=rωL
则机器人在本体坐标系中的运动学模型为:
[ x ˙ B y ˙ B φ ˙ ] = [ v ⋅ x B v ⋅ y B ω ] = ⏞ v = r ω [ r 2 r 2 0 0 − r b r b ] [ ω L ω R ] \begin{bmatrix} \dot{x}_B \\ \dot{y}_B \\ \dot{\varphi} \end{bmatrix} = \begin{bmatrix} v \cdot x_B \\ v \cdot y_B \\ \omega \end{bmatrix} \overbrace{=}^{v=r\omega} \begin{bmatrix} \frac r2 & \frac r2 \\ 0 & 0 \\ -\frac rb & \frac rb \end{bmatrix} \begin{bmatrix} \omega_L \\ \omega_R \end{bmatrix} x˙By˙Bφ˙ = vxBvyBω = v=rω 2r0br2r0br [ωLωR]
再通过坐标变换,最终可以得到机器人在世界坐标中的运动学模型:
[ x ˙ y ˙ φ ˙ ] = [ cos ⁡ φ 0 sin ⁡ φ 0 0 1 ] [ V ω ] \begin{bmatrix} \dot{x} \\ \dot{y} \\ \dot{\varphi} \end{bmatrix} = \begin{bmatrix} \cos\varphi & 0 \\ \sin\varphi & 0 \\ 0 & 1 \end{bmatrix} \begin{bmatrix} V \\ \omega \end{bmatrix} x˙y˙φ˙ = cosφsinφ0001 [Vω]
其中, V V V ω \omega ω 为控制变量。

通常我们需要通过机器人的速度和结构参数逆解出左右轮的转速,用于控制电机。在这种情况下,可以很容易地重新表述前面提到的方程。使用如下方程:
R = V / ω ω R = v R / r ω L = v L / r R = V/\omega\\ \omega_R = v_R/r\\ \omega_L = v_L/r R=V/ωωR=vR/rωL=vL/r
可得左右轮角速度方程:
ω R = V + ω ⋅ b / 2 r ω L = V − ω ⋅ b / 2 r \omega_R = \frac{V+\omega \cdot b/2}{r} \\ \omega_L = \frac{V-\omega \cdot b/2}{r} ωR=rV+ωb/2ωL=rVωb/2

三、对外接口

diff_drive_controller 主要通过订阅速度命令作为模块的输入,然后解析运动学模型控制电机,达到控制机器人的目的。

3.1 输入接口

  • cmd_vel(geometry_msgs/Twist)

    位于控制器的命名空间下,给机器人发布速度

3.2 输出接口

  • odom(nav_msgs/Odometry)

    位于控制器的命名空间下,根据硬件反馈计算的里程计信息

  • /tf(tf/tfMessage)

    从 odom 转换为 base_link

  • cmd_vel_out(geometry_msgs/TwistStamped)

    publish_cmd 参数设置为 True 时可用。在控制器的输入上应用限制器后的 Twist。

四、控制器参数

diff_drive_controller 提供了一些参数,用于配置机器人控制。

参数数据类型说明
left_wheelstring /string[…]左轮关节名称或关节名称列表
right_wheelstring /string[…]右轮关节名称或关节名称列表
pose_covariance_diagonaldouble[6]用于里程计位姿发布的协方差矩阵的对角线
twist_covariance_diagonaldouble[6]用于里程计 twist 发布的协方差矩阵的对角线
publish_ratedouble发布里程计的频率,用于 tf 和 odom(单位:Hz,默认值: 50.0)
wheel_separationdouble轮距,左轮和右轮之间的距离。如果未指定此参数,diff_drive_controller 将尝试从 URDF 读取值
wheel_separation_multiplierdouble轮距参数的系数。用于解释机器人模型和真实机器人之间的差异。(默认值:1.0)
wheel_radiusdouble车轮半径。默认两侧车轮都具有相同的尺寸。如果未指定此参数,diff_drive_controller 将尝试从 URDF 读取值。
wheel_radius_multiplierdouble车轮半径参数的系数。用于解释机器人模型和真实机器人之间的差异。(默认值:1.0)
cmd_vel_timeoutdouble两个连续速度命令之间允许的时间间隔。此延迟后,将向车轮发送零速命令。(单位:s,默认值:0.5)
base_frame_idstring用于填充Odometry消息和TF的child_frame_id(默认值:“base_link”)
linearobject线性速度配置参数
+ xobjectx轴,两轮差速机器人线速度只有x轴
++ has_velocity_limitsbool控制器是否限制线速度。(默认值: false)
++ max_velocitydouble最大线速度(单位:m/s)
++ min_velocitydouble最小线速度(单位:m/s)。未指定时,使用max_velocity
++ has_acceleration_limitsbool控制器是否限制线加速度。(默认值: false)
++ max_accelerationdouble最大线加速度(单位:m/s^2)
++ min_accelerationdouble最小线加速度(单位:m/s^2)。未指定时,使用max_acceleration
++ has_jerk_limitsbool控制器是否限制线加速度的变化快慢(默认值: false)
++ max_jerkdouble最大 jerk(单位:m/s^3)
angularobject角速度配置参数
+ zobjectz轴,两轮差速机器人角速度只有z轴
++ has_velocity_limitsbool控制器是否应该限制角速度(默认值: false)
++ max_velocitydouble最大角速度(单位:rad/s)
++ min_velocitydouble最小角速度(单位:rad/s)。将其设置为 0.0 将禁用逆时针旋转。未指定时,将使用max_velocity
++ has_acceleration_limitsbool控制器是否应该限制角加速度(默认值: false)
++ max_accelerationdouble最大角加速度(单位:rad/s^2)
++ min_accelerationdouble最小角加速度(单位为 rad/s^2)。未指定时,使用max_acceleration。
++ has_jerk_limitsbool控制器是否限制角加速度的变化快慢(默认值: false)
++ max_jerkdouble最大 jerk(单位:rad/s^3)
enable_odom_tfbool是否直接发布到 TF(默认值: true )
odom_frame_idstring里程计的frame_id(默认值:“/odom”)
publish_cmdbool发布要执行的速度命令。用于监控限制器对控制器输入的影响。(默认值: False)
allow_multiple_cmd_vel_publishersbool将其设置为 true 将允许输入接口 ~/cmd_vel 有多个发布者。如果将其设置为 false,则如果 ~/cmd_vel 有多个发布者,则会导致控制器停止运行。(默认值: False)
velocity_rolling_window_sizeint用于计算里程计 twist.linear.x 和 twist.angular.z 速度的平均速度样本数量(默认值: 10)

五、配置控制器参数

最小配置示例(即必要配置项):

diff_drive_controller:
    type: "diff_drive_controller/DiffDriveController"
    left_wheel: "left_wheel_joint"
    right_wheel: "right_wheel_joint"
    pose_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03]
    twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03]

该差速轮式机器人完整配置:

# 用于控制器硬件接口配置
hardware_interface:
  joints:
    - left_wheel_joint
    - right_wheel_joint
    - front_caster_joint
    - back_caster_joint

# joint_state_controller 控制器,用于发布各关节状态
joint_state_controller:
  type: "joint_state_controller/JointStateController"
  publish_rate: 50

# diff_drive_controller 控制器
diff_drive_controller:
  type: "diff_drive_controller/DiffDriveController"
  left_wheel: "left_wheel_joint"
  right_wheel: "right_wheel_joint"
  publish_rate: 50
  pose_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03]
  twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03]
  cmd_vel_timeout: 100
  velocity_rolling_window_size: 1

  publish_cmd: true
  base_frame_id: base_link
  enable_odom_tf: true
  odom_frame_id: odom

  # 轮间距和轮半径
  wheel_separation: 0.38
  wheel_radius: 0.06
  wheel_separation_multiplier: 1.0
  wheel_radius_multiplier: 1.0

  # 速度和加速度限制
  linear:
    x:
      has_velocity_limits: true
      max_velocity: 1.0 # m/s
      has_acceleration_limits: true
      max_acceleration: 3.0 # m/s^2
  angular:
    z:
      has_velocity_limits: true
      max_velocity: 2.0 # rad/s
      has_acceleration_limits: true
      max_acceleration: 6.0 # rad/s^2

六、编写硬件抽象接口

下面写一个两轮差速硬件接口,使用速度控制接口 VelocityJointInterface 控制 joint 的速度,使用 JointStateInterface 获取 joint 的位置、速度、力等信息。

硬件抽象接口头文件:diff_drive_hardware_interface.h

#ifndef DIFF_DRIVE_HARDWARE_INTERFACE_H
#define DIFF_DRIVE_HARDWARE_INTERFACE_H

#include <ros/ros.h>
#include <hardware_interface/joint_command_interface.h>
#include <hardware_interface/joint_state_interface.h>
#include <hardware_interface/robot_hw.h>
#include <controller_manager/controller_manager.h>

class DiffDriveHWInterface : public hardware_interface::RobotHW
{
public:
    struct JointInfo
    {
        std::string name;
        double cmd;
        double pos;
        double vel;
        double eff;

        JointInfo() : name(""), cmd(0.0), pos(0.0), vel(0.0), eff(0.0)
        {}

        JointInfo(std::string name_) 
            : name(name_), cmd(0.0), pos(0.0), vel(0.0), eff(0.0)
        {}

        JointInfo(std::string name_, double cmd_, double pos_, double vel_, double dff_) 
            : name(name_), cmd(cmd_), pos(pos_), vel(vel_), eff(dff_)
        {}

    };
    
public:
    DiffDriveHWInterface(ros::NodeHandle &nh);
    void init();
    void read(const ros::Duration &period);
    void write(const ros::Duration &period);

private:
    ros::NodeHandle m_nh;
    hardware_interface::JointStateInterface m_jnt_state_interface;
    hardware_interface::VelocityJointInterface m_jnt_vel_interface;
    std::vector<JointInfo> m_joints;
};

#endif // DIFF_DRIVE_HARDWARE_INTERFACE_H

源文件:diff_drive_hardware_interface.cpp

#include "diff_drive_control/diff_drive_hardware_interface.h"

DiffDriveHWInterface::DiffDriveHWInterface(ros::NodeHandle &nh) : m_nh(nh)
{
}

/**
 * @brief 初始化关节信息
 *        注册抽象硬件接口
 * 
 */
void DiffDriveHWInterface::init()
{
    std::vector<std::string> joint_names;
    m_nh.getParam("/hardware_interface/joints", joint_names);
    for (std::string name : joint_names)
    {
        m_joints.push_back(JointInfo(name));
    }

    for (auto &joint : m_joints)
    {
        ROS_INFO("get joint: %s", joint.name.c_str());

        // Initialize hardware interface
        hardware_interface::JointStateHandle state_handle(joint.name, &joint.pos, &joint.vel, &joint.eff);
        m_jnt_state_interface.registerHandle(state_handle);

        hardware_interface::JointHandle vel_handle(m_jnt_state_interface.getHandle(joint.name), &joint.cmd);
        m_jnt_vel_interface.registerHandle(vel_handle);
    }

    registerInterface(&m_jnt_state_interface);
    registerInterface(&m_jnt_vel_interface);
}

void DiffDriveHWInterface::read(const ros::Duration &period)
{
    // Read the state of the hardware (e.g., from sensors)
}

void DiffDriveHWInterface::write(const ros::Duration &period)
{
    // Send the command to the hardware (e.g., to actuators)
    for (auto &joint : m_joints)
    {
        joint.pos += joint.vel * period.toSec();
        // if (joint.vel != joint.cmd)
        // {
        //     ROS_INFO("write, joint: %s, cmd: %lf", joint.name.c_str(), joint.cmd);
        // }
        joint.vel = joint.cmd;
    }
}

控制节点:diff_drive_control_node.cpp

#include <ros/ros.h>
#include <controller_manager/controller_manager.h>
#include "diff_drive_control/diff_drive_hardware_interface.h"

int main(int argc, char **argv)
{
    ros::init(argc, argv, "diff_drive_control_node");
    ros::NodeHandle nh;

    DiffDriveHWInterface diff_drive(nh);
    diff_drive.init();

    controller_manager::ControllerManager cm(&diff_drive, nh);

    ros::Rate rate(50.0);
    ros::AsyncSpinner spinner(1);
    spinner.start();

    while (ros::ok())
    {
        ros::Duration period = rate.expectedCycleTime();
        diff_drive.write(period);
        cm.update(ros::Time::now(), period);
        rate.sleep();
    }

    return 0;
}

七、控制机器人移动

机器人模型与硬件接口都准备好了,接下来开始编写业务代码控制机器人。

我们仅给机器人发送速度指令,模拟机器人移动任务,如下:

#include <ros/ros.h>
#include <geometry_msgs/Twist.h>

geometry_msgs::Twist moveRobot(const double& linear, const double& angular)
{
    geometry_msgs::Twist msg;
    msg.linear.x = linear; // 线速度
    msg.linear.y = 0.0;
    msg.linear.z = 0.0;
    msg.angular.x = 0.0;
    msg.angular.y = 0.0;
    msg.angular.z = angular; // 角速度
    ROS_INFO("moveRobot, linear: %.3lf, angular: %.1lf", linear, angular*180/M_PI);

    return msg;
}

int main(int argc, char** argv)
{
    ros::init(argc, argv, "diff_drive_business");
    ros::NodeHandle nh;
    ros::Publisher velPub = nh.advertise<geometry_msgs::Twist>("/diff_drive_controller/cmd_vel", 10);

    ros::Rate rate(10);

    while (ros::ok())
    {
        velPub.publish(moveRobot(0.5, 0));
        ros::Duration(3.0).sleep();
        velPub.publish(moveRobot(0, 1.57));
        ros::Duration(1.0).sleep();

        rate.sleep();
    }

    return 0;
}

编译执行该节点,在rviz中的可视化结果如下:

在这里插入图片描述

八、源码

项目源码

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.coloradmin.cn/o/1886876.html

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈,一经查实,立即删除!

相关文章

Datawhale - 角色要素提取竞赛

文章目录 赛题要求一、赛事背景二、赛事任务三、评审规则1.平台说明2.数据说明3.评估指标4.评测及排行 四、作品提交要求五、 运行BaselineStep1&#xff1a;下载相关库Step2&#xff1a;配置导入Step3&#xff1a;模型测试Step4&#xff1a;数据读取Step5&#xff1a;Prompt设…

工业 web4.0UI 风格品质卓越

工业 web4.0UI 风格品质卓越

【力扣 - 每日一题】3115. 质数的最大距离(一次遍历、头尾遍历、空间换时间、埃式筛、欧拉筛、打表)Golang实现

原题链接 题目描述 给你一个整数数组 nums。 返回两个&#xff08;不一定不同的&#xff09;质数在 nums 中 下标 的 最大距离。 示例 1&#xff1a; 输入&#xff1a; nums [4,2,9,5,3] 输出&#xff1a; 3 解释&#xff1a; nums[1]、nums[3] 和 nums[4] 是质数。因此答…

WPF自定义模板--Button

属性&#xff1a; TemplateBinding&#xff1a;用于在ControlTemplate中绑定到控件的属性&#xff0c;例如Background、BorderBrush等。TargetType&#xff1a;指定该模板应用于哪种控件类型。在这个例子中&#xff0c;是Button。 标准的控件模板代码&#xff1a; <Style…

线性代数大题细节。

4.4 方程组解的结构&#xff08;二&#xff09;_哔哩哔哩_bilibili

eNSP中WLAN的配置和使用

一、基础配置 1.拓扑图 2.VLAN和IP配置 a.R1 <Huawei>system-view [Huawei]sysname R1 GigabitEthernet 0/0/0 [R1-GigabitEthernet0/0/0]ip address 200.200.200.200 24 b.S1 <Huawei>system-view [Huawei]sysname S1 [S1]vlan 100 [S1-vlan100]vlan 1…

vue3 window.location 获取正在访问的地址,也可以通过useRoute来获取相关信息。

1、一般我们在开发的vue3项目的时候&#xff0c;地址是这样&#xff1a;http://192.168.1.101:3100/#/login 然后我们在布署完成以后一般是这样https://xxx.yyyyy.com/uusys/#/login 其实xxx可以是www&#xff0c;也可以是一个二级域名 yyyyy.com是域名&#xff0c;uusys一般…

家政小程序的开发:打造现代式便捷家庭服务

随着现代生活节奏的加快&#xff0c;人们越来越注重生活品质与便利性。在这样的背景下&#xff0c;家政服务市场迅速崛起&#xff0c;成为许多家庭日常生活中不可或缺的一部分。然而&#xff0c;传统的家政服务往往存在信息不对称、服务效率低下等问题。为了解决这些问题&#…

Windows编程上

Windows编程[上] 一、Windows API1.控制台大小设置1.1 GetStdHandle1.2 SetConsoleWindowInfo1.3 SetConsoleScreenBufferSize1.4 SetConsoleTitle1.5 封装为Innks 2.控制台字体设置以及光标调整2.1 GetConsoleCursorInfo2.2 SetConsoleCursorPosition2.3 GetCurrentConsoleFon…

elementPlus自定义el-select下拉样式

如何在f12元素选择器上找到下拉div呢&#xff1f; 给el-select添加 :popper-append-to-body"false" 即可&#xff0c;这样就可以将下拉框添加到body元素中去&#xff0c;否则当我们失去焦点&#xff0c;下拉就消失了&#xff0c;在元素中找不到el-select。剩下就可以…

华硕魔霸5原装Windows10原厂系统 工厂模式 带ASUS Recovery恢复功能

华硕工厂文件恢复系统 &#xff0c;安装结束后带隐藏分区&#xff0c;一键恢复&#xff0c;以及机器所有驱动软件。 系统版本&#xff1a;Windows10 原厂系统下载网址&#xff1a;http://www.bioxt.cn 需准备一个20G以上u盘进行恢复 请注意&#xff1a;仅支持以上型号专用…

系统架构设计师 - 计算机网络(2)

计算机网络 计算机网络IPv6 ★概念IPv6 的优势IPv6 数据格式IPv6 地址应用IPv6 自动 IP 地址配置&#xff08;了解&#xff09;IPv4/IPv6过渡技术 网络接入&#xff08;了解&#xff09;综合布线系统 ★物联网&#xff08;了解&#xff09;概念分层 云计算&#xff08;了解&…

顺序串算法库构建

学习贺利坚老师顺序串算法库 数据结构之自建算法库——顺序串_创建顺序串s1,创建顺序串s2-CSDN博客 本人详细解析博客 串的概念及操作_串的基本操作-CSDN博客 版本更新日志 V1.0: 在贺利坚老师算法库指导下, 结合本人详细解析博客思路基础上,进行测试, 加入异常弹出信息 v1.0补…

将一个程序设置为开机启动【win11】

Windows 在 Windows 系统中&#xff0c;可以通过在 “启动” 文件夹中放置程序的快捷方式来实现开机启动。 按照以下步骤操作&#xff1a; 按 Win R 打开 “运行” 对话框&#xff0c;输入 shell:startup&#xff0c;然后按回车。这将打开 “启动” 文件夹。 找到你想设置为…

动态规划——打家劫舍(C++)

好像&#xff0c;自己读的书确实有点少了。 ——2024年7月2日 198. 打家劫舍 - 力扣&#xff08;LeetCode&#xff09; 题目描述 你是一个专业的小偷&#xff0c;计划偷窃沿街的房屋。每间房内都藏有一定的现金&#xff0c;影响你偷窃的唯一制约因素就是相邻的房屋装有相互连…

Python特征工程 — 1.2 特征分箱

目录 1 什么是特征分箱 2 分箱的重要性及其优势 3 有监督分箱 3.1卡方分箱原理 3.2 决策树分箱 4 无监督分箱 4.1 等距分箱 4.2 等频分箱 4.3 分位数分箱 实验数据&#xff1a;链接&#xff1a;https://pan.baidu.com/s/1yT1ct_ZM5uFLgcYsaBxnHg?pwdczum 提取码&…

JAVA期末速成库(11)第十二章

一、习题介绍 第十二章 Check Point&#xff1a;P454 12.1&#xff0c;12.9&#xff0c;12.10&#xff0c;12,12 二、习题及答案 12.1 What is the advantage of using exception handling? 12.1使用异常处理的优势是什么? 答:使用异常处理有以下优势&#xff1a; 1. 提高…

浙江建筑安全员A证2024年最新考试题库练习

46.总承包单位依法将建设工程分包给其他单位的&#xff0c;分包合同中应当明确各自的安全生产方面的权利、义务。总承包单位对分包工程的安全生产承担&#xff08;&#xff09;责任。 A.全部 B.主要 C.部分 D.连带 答案&#xff1a;D 47.实施总承报的建设工程发生事故&…

一首歌的时间 写成永远

大家好&#xff0c;我是秋意零。 就在&#xff0c;2024年6月20日。我本科毕业了&#xff0c;之前专科毕业挺有感触&#xff0c;也写了一篇文章进行记录。如今又毕业了&#xff0c;还是写一篇文章记录吧&#xff01;&#xff01; 专科毕业总结&#xff1a;大学三年总结&#xf…

编译原理1

NFA&DFA 在正规式的等价证明可以借助正规集&#xff0c;也可以通过有限自动机DFA来证明等价&#xff0c;以下例题是针对DFA证明正规式的等价&#xff0c;主要步骤是①NFA&#xff1b;②状态转换表&#xff1b; ③状态转换矩阵&#xff1b; ④化简DFA&#xff1b; 文法和语…