迷你无人车 Navigation 导航(3)

news2024/11/19 19:18:10

迷你无人车 Navigation 导航(3)

自己实现了对于迷你无人车关节的控制,由于原本的关节布置仅支持阿克曼转向,因此先进行阿克曼转向的控制

修改 URDF 文件

添加 transmission 标签,定义关节的驱动

<transmission name="right_rear_joint_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="right_rear_joint">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="right_rear_joint_motor">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
<transmission name="front_steer_right_joint_trans">
  <type>transmission_interface/SimpleTransmission</type>
  <joint name="front_steer_right_joint">
    <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
  </joint>
  <actuator name="front_steer_right_joint_motor">
    <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    <mechanicalReduction>1</mechanicalReduction>
  </actuator>
</transmission>

注意位置控制关节中 limit 的设置,一开始均设置为 0,无法进行位置控制

<joint name="front_steer_right_joint" type="revolute">
    <origin rpy="0 0 0"  xyz="0.17 -0.21 0.102" />
    <parent link="base_link" />
    <child link="front_steer_right_link" />
    <axis xyz="0 0 1" />     <!-- charge steer direction default is 0 0 1-->
    <limit lower="-0.69" upper="0.69" effort="2.0" velocity="1.0" />
 </joint>

配置 ros_control 插件

<gazebo>
    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
      <!-- <robotSimType>steer_bot_hardware_gazebo/SteerBotHardwareGazebo</robotSimType>
      <legacyModeNS>false</legacyModeNS> -->
      <robotNamespace>/steer_neor_mini</robotNamespace>
      <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
      <legacyModeNS>true</legacyModeNS>
    </plugin>
  </gazebo>

注意命名空间的设置

配置 yaml 文件

在该文件中添加各关节控制器类型(速度控制/位置控制),以及控制器的 PID 系数

steer_neor_mini:
  joint_state_controller:
    type: joint_state_controller/JointStateController
    publish_rate: 50

 # Velocity Controllers ----速度控制器---------------------
  left_rear_wheel_velocity_controller:
    type: effort_controllers/JointVelocityController
    joint: left_rear_joint
    pid: {p: 1.0, i: 0.0, d: 0.0, i_clamp: 0.0}
  right_rear_wheel_velocity_controller:
    type: effort_controllers/JointVelocityController
    joint: right_rear_joint
    pid: {p: 1.0, i: 0.0, d: 0.0, i_clamp: 0.0}
  left_front_wheel_velocity_controller:
    type: effort_controllers/JointVelocityController
    joint: front_left_wheel_joint
    pid: {p: 1.0, i: 0.0, d: 0.0, i_clamp: 0.0}
  right_front_wheel_velocity_controller:
    type: effort_controllers/JointVelocityController
    joint: front_right_wheel_joint
    pid: {p: 1.0, i: 0.0, d: 0.0, i_clamp: 0.0}

  # Position Controllers ---位置控制器-----------------------
  left_steering_hinge_position_controller:
    joint: front_steer_left_joint
    type: effort_controllers/JointPositionController
    pid: {p: 0.5, i: 0.0, d: 0.0}
  right_steering_hinge_position_controller:
    joint: front_steer_right_joint
    type: effort_controllers/JointPositionController
    pid: {p: 0.5, i: 0.0, d: 0.0}

配置 launch 文件

<?xml version="1.0"?>
<launch>

    <arg name="x" default="0.0"/>
    <arg name="y" default="0.0"/>
    <arg name="z" default="0.0" />
    <arg name="roll" default="0.0"/>
    <arg name="pitch" default="0.0"/>
    <arg name="yaw" default="0.0"/>
    <arg name="controllers" default="joint_state_controller
                                    left_rear_wheel_velocity_controller right_rear_wheel_velocity_controller
                                    left_front_wheel_velocity_controller right_front_wheel_velocity_controller
                                    left_steering_hinge_position_controller right_steering_hinge_position_controller"/>

    <!-- Gazebo  -->
    <!--Load the surrounding environment into Gazebo-->
    <include file="$(find gazebo_ros)/launch/empty_world.launch" >
        <arg name="world_name" value="$(find neor_mini)/worlds/cooneo_office.world"/>
    </include>

    <!-- Load the robot description -->
    <param name="robot_description" command="cat $(find neor_mini)/urdf/neor_mini_gazebo_sensors.urdf"/>

    <!-- Load ros_controllers configuration parameters -->
    <!-- <rosparam file="$(find steer_mini_gazebo)/mini_control/config/ctrl_ackermann_steering_controller.yaml" command="load"   /> -->
    <!-- <rosparam file="$(find steer_mini_gazebo)/mini_control/config/ctrl_gains.yaml" command="load"   /> -->
    <rosparam file="$(find steer_mini_gazebo)/mini_control/config/ctrl_joint_state_publisher.yaml" command="load"   />
    <!-- <rosparam file="$(find steer_mini_gazebo)/mini_control/config/ctrl_steer_bot_hardware_gazebo.yaml" command="load"   /> -->
    <rosparam file="$(find steer_mini_gazebo)/mini_control/config/my_controller.yaml" command="load"/>

    <!-- Spawn the controllers -->
    <!-- <node pkg="controller_manager" type="spawner" name="controller_spawner"  args="joint_state_publisher ackermann_steering_controller" output="screen" respawn="false" /> -->
    <node pkg="controller_manager" type="spawner" name="controller_spawner" output="screen" respawn="false" 
        ns="/steer_neor_mini" args="$(arg controllers)"/>

    <!-- Launch  the robot state publisher -->
    <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher">
        <param name="publish_frequency" value="50.0"/>
        <remap from="/joint_states" to="/steer_neor_mini/joint_states"/>
    </node>

    <!-- Launch a rqt steering GUI for publishing to /steer_bot/steer_drive_controller/cmd_vel -->
    <!-- <node pkg="rqt_robot_steering" type="rqt_robot_steering" name="rqt_robot_steering" > -->
        <!-- <param name="default_topic" value="ackermann_steering_controller/cmd_vel"/>                         default velocity control topic name -->
        <!-- <param name="default_vx_max" value="1.0"/>                        linear velocity max value    m/s -->
        <!-- <param name="default_vx_min" value="-1.0"/>                       linear velocity min value    m/s -->
        <!-- <param name="default_vw_max" value="0.69"/>                    angular velocity max value  rad/s (adaptor for urdf joint limit) -->
        <!-- <param name="default_vw_min" value="-0.69"/>                   angular velocity min value  rad/s (adaptor for urdf joint limit) -->
    <!-- </node> -->

    <!-- Start the Gazebo node and configure the location and posture of the accident when the model is loaded -->
    <node name="spawn_vehicle" pkg="gazebo_ros" type="spawn_model" args="-urdf -param robot_description -model neor_mini -gazebo_namespace /gazebo 
              -x $(arg x) -y $(arg y) -z $(arg z)
              -R $(arg roll) -P $(arg pitch) -Y $(arg yaw)"
          respawn="false" output="screen" />
    <!-- ******************************************************************************************************************************************* -->

   <node name="laser_to_base_link" pkg="tf" type="static_transform_publisher" args="0.0 0.0 0.135 0 0 0 base_link laser_link 40 " />
   <node name="imu_to_base_link" pkg="tf" type="static_transform_publisher" args="-0.10 0.0 0.02 0 0 0 base_link imu_link 40 " />
   <node name="camera_to_base_link" pkg="tf" type="static_transform_publisher" args="0.12 0.0 0.12 0 0 0 base_link camera_link 40 " />

</launch>

💡 注意各文件中命名空间的一致性

车轮速度解算

沿用四轮车的解算代码,更新车长、车宽以及车轮直径参数,目前只进行阿克曼转向的解算控制

#include <cmd_to_neor/wheelparams.h>
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include <std_msgs/Float64.h>
#include <Eigen/Core>
#include <Eigen/Dense>
#include <cmath>
#include <iostream>
#include <mutex>
#include "myTools.hpp"
using namespace std;
using namespace Eigen;

ros::Publisher pub_vel_left_rear_wheel;
ros::Publisher pub_vel_right_rear_wheel;
ros::Publisher pub_vel_left_front_wheel;
ros::Publisher pub_vel_right_front_wheel;
ros::Publisher pub_pos_left_steering_hinge;
ros::Publisher pub_pos_right_steering_hinge;
cmd_to_neor::wheelparams w_params;
AidTool::Ptr aidtool;

Matrix<double, 8, 3> coff_mat; // 机器人模型参数矩阵
Matrix<double, 3, 1> xyw;      // 机器人Vx, Vy, W向量
Matrix<double, 8, 1> p_xyw;

// 机器人长的一半
const double half_len = 0.3492 / 2;
// 机器人宽的一半
const double half_wid = 0.36 / 2;
const double WHELL_DIA = 0.0625;
const double REDUCER_RATIO = 1.0;

mutex mut;

void computeWheelVel_pivotSteer();
void computeWheelVel_ackermannSteer(double linear_vel, double front, double rear);
double computeAckermannRatio(double vel);

std_msgs::Float64 vel_left_rear_wheel;
std_msgs::Float64 vel_right_rear_wheel;
std_msgs::Float64 vel_left_front_wheel;
std_msgs::Float64 vel_right_front_wheel;
std_msgs::Float64 pos_left_steering_hinge;
std_msgs::Float64 pos_right_steering_hinge;

double toRealVel(const double vel){
    return vel / (M_PI * WHELL_DIA) * REDUCER_RATIO;
}

double toReaPos(const double pos){
    return pos * 180 / M_PI * REDUCER_RATIO;
}

void robot_callback(const geometry_msgs::Twist::ConstPtr &msg)
{
    memset(&w_params, 0, sizeof(w_params));

    doublelinear_vel = msg->linear.x;
    double front_angle = msg->angular.z;
    computeWheelVel_ackermannSteer(linear_vel, front_angle, 0);

    vel_left_rear_wheel.data = toRealVel(w_params.lb_v);
    vel_right_rear_wheel.data = toRealVel(w_params.rb_v);
    vel_left_front_wheel.data = toRealVel(w_params.lf_v);
    vel_right_front_wheel.data = toRealVel(w_params.rf_v);
    pos_left_steering_hinge.data = w_params.lf_p;
    pos_right_steering_hinge.data = w_params.rf_p;
    cout << "lr_v:" << vel_left_rear_wheel.data << ";rr_v:" << vel_right_rear_wheel.data << \
        ";lf_v:" << vel_left_front_wheel.data << ";rf_v:" << vel_right_front_wheel.data << endl;
    cout << "lf_p:" << pos_left_steering_hinge.data << ";rf_p:" << pos_right_steering_hinge.data << endl;
    cout << "--------------" << endl; 

    lock_guard<mutex> lock(mut);
    pub_vel_left_rear_wheel.publish(vel_left_rear_wheel);
    pub_vel_right_rear_wheel.publish(vel_right_rear_wheel);
    pub_vel_left_front_wheel.publish(vel_left_front_wheel);
    pub_vel_right_front_wheel.publish(vel_right_front_wheel);
    pub_pos_left_steering_hinge.publish(pos_left_steering_hinge);
    pub_pos_right_steering_hinge.publish(pos_right_steering_hinge);
    mut.unlock();
}

int main(int argc, char **argv)
{
    coff_mat << 1, 0, -half_wid,
        0, 1, half_len,
        1, 0, -half_wid,
        0, 1, -half_len,
        1, 0, half_wid,
        0, 1, -half_len,
        1, 0, half_wid,
        0, 1, half_len;

    const string vel_left_rear_wheel_topic = "/steer_neor_mini/left_rear_wheel_velocity_controller/command";
    const string vel_right_rear_wheel_topic = "/steer_neor_mini/right_rear_wheel_velocity_controller/command";
    const string vel_left_front_wheel_topic = "/steer_neor_mini/left_front_wheel_velocity_controller/command";
    const string vel_right_front_wheel_topic = "/steer_neor_mini/right_front_wheel_velocity_controller/command";
    const string pos_left_steering_hinge_topic = "/steer_neor_mini/left_steering_hinge_position_controller/command";
    const string pos_right_steering_hinge_topic = "/steer_neor_mini/right_steering_hinge_position_controller/command";

    aidtool = make_shared<AidTool>();
    ros::init(argc, argv, "cmd_to_neor");
    ros::NodeHandle nh;

    pub_vel_left_rear_wheel = nh.advertise<std_msgs::Float64>(vel_left_rear_wheel_topic, 1);
    pub_vel_right_rear_wheel = nh.advertise<std_msgs::Float64>(vel_right_rear_wheel_topic, 1);
    pub_vel_left_front_wheel = nh.advertise<std_msgs::Float64>(vel_left_front_wheel_topic, 1);
    pub_vel_right_front_wheel = nh.advertise<std_msgs::Float64>(vel_right_front_wheel_topic, 1);
    pub_pos_left_steering_hinge = nh.advertise<std_msgs::Float64>(pos_left_steering_hinge_topic, 1);
    pub_pos_right_steering_hinge = nh.advertise<std_msgs::Float64>(pos_right_steering_hinge_topic, 1);
    ros::Subscriber sub = nh.subscribe("/cmd_vel", 1, robot_callback);
    ros::spin();

    return 0;
}

void computeWheelVel_pivotSteer()
{
    lock_guard<mutex> lock(mut);
    // 左前
    if (p_xyw(0, 0) == 0)
    {
        if (p_xyw(1, 0) > 0)
        {
            w_params.lf_p = M_PI_2;
        }
        else if (p_xyw(1, 0) < 0)
        {
            w_params.lf_p = -M_PI_2;
        }
        else
        {
            w_params.lf_p = 0;
        }
    }
    else
    {
        w_params.lf_p = atan(p_xyw(1, 0) / p_xyw(0, 0));
    }

    if (p_xyw(0, 0) == 0.0 && p_xyw(1, 0) == 0.0)
    {
        w_params.lf_v = 0.0;
    }
    else if (p_xyw(0, 0) == 0)
    {
        w_params.lf_v = p_xyw(1, 0) / sin(w_params.lf_p);
    }
    else
    {
        w_params.lf_v = p_xyw(0, 0) / cos(w_params.lf_p);
    }

    // 左后
    if (p_xyw(2, 0) == 0)
    {
        if (p_xyw(3, 0) > 0)
        {
            w_params.lb_p = M_PI_2;
        }
        else if (p_xyw(3, 0) < 0)
        {
            w_params.lb_p = -M_PI_2;
        }
        else
        {
            w_params.lb_p = 0;
        }
    }
    else
    {
        w_params.lb_p = atan(p_xyw(3, 0) / p_xyw(2, 0));
    }

    if (p_xyw(2, 0) == 0.0 && p_xyw(3, 0) == 0.0)
    {
        w_params.lb_v = 0.0;
    }
    else if (p_xyw(2, 0) == 0)
    {
        w_params.lb_v = p_xyw(3, 0) / sin(w_params.lb_p);
    }
    else
    {
        w_params.lb_v = p_xyw(2, 0) / cos(w_params.lb_p);
    }

    // 右后
    if (p_xyw(4, 0) == 0)
    {
        if (p_xyw(5, 0) > 0)
        {
            w_params.rb_p = M_PI_2;
        }
        else if (p_xyw(5, 0) < 0)
        {
            w_params.rb_p = -M_PI_2;
        }
        else
        {
            w_params.rb_p = 0;
        }
    }
    else
    {
        w_params.rb_p = atan(p_xyw(5, 0) / p_xyw(4, 0));
    }

    if (p_xyw(4, 0) == 0.0 && p_xyw(5, 0) == 0.0)
    {
        w_params.rb_v = 0.0;
    }
    else if (p_xyw(4, 0) == 0)
    {
        w_params.rb_v = p_xyw(5, 0) / sin(w_params.rb_p);
    }
    else
    {
        w_params.rb_v = p_xyw(4, 0) / cos(w_params.rb_p);
    }

    // 右前
    if (p_xyw(6, 0) == 0)
    {
        if (p_xyw(7, 0) > 0)
        {
            w_params.rf_p = M_PI_2;
        }
        else if (p_xyw(7, 0) < 0)
        {
            w_params.rf_p = -M_PI_2;
        }
        else
        {
            w_params.rf_p = 0;
        }
    }
    else
    {
        w_params.rf_p = atan(p_xyw(7, 0) / p_xyw(6, 0));
    }

    if (p_xyw(6, 0) == 0.0 && p_xyw(7, 0) == 0.0)
    {
        w_params.rf_v = 0.0;
    }
    else if (p_xyw(6, 0) == 0)
    {
        w_params.rf_v = p_xyw(7, 0) / sin(w_params.rf_p);
    }
    else
    {
        w_params.rf_v = p_xyw(6, 0) / cos(w_params.rf_p);
    }
    mut.unlock();
}

void computeWheelVel_ackermannSteer(double linear_vel, double front, double rear)
{
    lock_guard<mutex> lock(mut);
    // cout << "front_angle: " << aidtool->rad2deg(front) << "\t rear_angle: " << aidtool->rad2deg(rear) << endl;
    double d_vertical = 0.0, l_up = half_len;
    if (front != 0)
    {
        d_vertical = 2 * half_len * cos(front) * cos(rear) / sin(front - rear);
        l_up = 2 * half_len * sin(front) * cos(rear) / sin(front - rear);
        // cout << "d_vertical: " << d_vertical << "\tl_up: " << l_up << endl;
        w_params.lf_p = atan(2 * half_len * sin(front) * cos(rear) / (2 * half_len * cos(front) * cos(rear) - half_wid * sin(front - rear)));
        w_params.rf_p = atan(2 * half_len * sin(front) * cos(rear) / (2 * half_len * cos(front) * cos(rear) + half_wid * sin(front - rear)));
        w_params.lb_p = atan(2 * half_len * cos(front) * sin(rear) / (2 * half_len * cos(front) * cos(rear) - half_wid * sin(front - rear)));
        w_params.rb_p = atan(2 * half_len * cos(front) * sin(rear) / (2 * half_len * cos(front) * cos(rear) + half_wid * sin(front - rear)));
    }

    double Rc = sqrt(pow(half_len - l_up, 2) + pow(d_vertical, 2));
    if (Rc == 0)
    {
        w_params.lf_v = linear_vel;
        w_params.rf_v = linear_vel;
        w_params.lb_v = linear_vel;
        w_params.rb_v = linear_vel;
    }
    else
    {
        double Rlf = sqrt(pow(l_up, 2) + pow(d_vertical - half_wid, 2));
        double Rrf = sqrt(pow(l_up, 2) + pow(d_vertical + half_wid, 2));
        double Rlr = sqrt(pow(2 * half_len - l_up, 2) + pow(d_vertical - half_wid, 2));
        double Rrr = sqrt(pow(2 * half_len - l_up, 2) + pow(d_vertical + half_wid, 2));
        double angular_vel = linear_vel / Rc;
        w_params.lf_v = angular_vel * Rlf;
        w_params.rf_v = angular_vel * Rrf;
        w_params.lb_v = angular_vel * Rlr;
        w_params.rb_v = angular_vel * Rrr;
    }
    mut.unlock();
}

double computeAckermannRatio(double vel)
{
    double corner_stiffness = -100000.0;
    double mass = 250;
    lock_guard<mutex> lock(mut);
    double ratio = 1 - 4 * half_len * corner_stiffness / (2 * half_len * corner_stiffness - mass * pow(vel, 2));
    mut.unlock();
    return ratio;
}

话题组织

完整的话题组织如下,可以通过 Logitech 手柄控制 Gazebo 中的迷你无人车以阿克曼转向方式运动

在这里插入图片描述

实际效果如下

在这里插入图片描述

下一步计划修改 URDF 模型进行四轮转向和原地转向控制

参考

阿克曼结构移动机器人的gazebo仿真(五)

阿克曼结构移动机器人的gazebo仿真(六)

https://wiki.ros.org/urdf/XML/Transmission

https://wiki.ros.org/urdf/XML/joint

探究–gazebo里 关节是如何动起来的____实现默认插件joint控制

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

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

相关文章

MySQL Oracle区别

由于SQL Server不常用&#xff0c;所以这里只针对MySQL数据库和Oracle数据库的区别 (1) 对事务的提交 MySQL默认是自动提交&#xff0c;而Oracle默认不自动提交&#xff0c;需要用户手动提交&#xff0c;需要在写commit;指令或者点击commit按钮 (2) 分页查询 MySQL是直接在SQL语…

使用鳄鱼指标和ADX开立空头的条件,3秒讲清楚

使用鳄鱼指标和ADX开立空头的条件其实很简单&#xff0c;anzo capital昂首资本3秒钟讲清楚。 首先&#xff0c;市场行情需呈水平状态。再者&#xff0c;均线体系开始向上发散&#xff0c;给出明确的信号。最后&#xff0c;ADX确认该信号&#xff0c;要求指数上涨20%以上&#…

Weblogic(CVE-2017-10271)与 Struts2(s2-045) 反序列化漏洞复现

文章目录 Java 反序列化漏洞复现weblogic环境搭建漏洞复现 Struts2(s2-045)环境搭建漏洞复现**漏洞利用** Java 反序列化漏洞复现 weblogic Weblogic < 10.3.6 ‘wls-wsat’ XMLDecoder 反序列化漏洞&#xff08;CVE-2017-10271&#xff09; ​ Weblogic的WLS Security组…

深度学习模型复杂度分析大杂烩

深度学习模型复杂度分析大杂烩 时间复杂度和空间复杂度是衡量一个算法的两个重要指标,用于表示算法的最差状态所需的时间增长量和所需辅助空间. 在深度学习神经网络模型中我们也通过&#xff1a; 计算量/FLOPS&#xff08;时间复杂度&#xff09;即模型的运算次数 访存量/By…

C++设计模式_04_Strategy 策略模式

接上篇&#xff0c;本篇将会介绍C设计模式中的Strategy 策略模式&#xff0c;和上篇模板方法Template Method一样&#xff0c;仍属于“组件协作”模式&#xff0c;它与Template Method有着异曲同工之妙。 文章目录 1. 动机&#xff08; Motivation&#xff09;2. 代码演示Stra…

2023-9-11 拆分-Nim游戏

题目链接&#xff1a;拆分-Nim游戏 #include <iostream> #include <cstring> #include <algorithm> #include <unordered_set>using namespace std;const int N 110;int f[N];int sg(int x) {if(f[x] ! -1) return f[x];unordered_set<int> S;f…

pip和conda的环境管理,二者到底应该如何使用

关于pip与conda是否能混用的问题&#xff0c;Anaconda官方早就给出了回答 先说结论&#xff0c;如果conda和pip在相同环境下掺杂使用&#xff0c;尤其是频繁使用这两个工具进行包的安装&#xff0c;可能会导致环境状态混乱 就像其他包管理器一样&#xff0c;大部分这些问题均…

Python开发手册 — 有勇气的牛排

前言 一、编程规约 二、异常日志 三、单元测试 四、安全规约 4.1 【强制】用户页面/功能进行权限校验 隶属于用户个人的页面或者功能必须进行权限控制校验。 说明&#xff1a;防止没有做水平校验就可随意访问、修改、删除别人的数据&#xff0c;比如查看那他人的私信内容…

浅析Open vSwitch数据结构:哈希表hmap/smap/shash

文章目录 概述hmaphmap数据结构初始化hmap插入节点扩展hmap空间resize函数 删除节点遍历所有节点辅助函数hmap_first辅助函数hmap_next smapsmap数据结构插入节点删除节点查找节点遍历所有节点 shashshash数据结构插入节点删除节点查找节点遍历所有节点 概述 在OVS软件中&…

卡尔曼滤波公式推导(总结)

假设 小车在t时刻的初始状态可以用Pt&#xff08;当前位置&#xff09;&#xff0c;Vt&#xff08;当前速度&#xff09;&#xff0c;Ut表示加速度&#xff1a; 预测&#xff1a; 利用上一个时刻的旧状态和系统的动量模型&#xff08;如加速度&#xff0c;速度等&#xff09;…

Android逆向——脱壳解析

“壳”是一种对程序进行加密的程序&#xff0c;“壳”形象地表现了这个功能。我们可以把被加壳的程序当成食物&#xff0c;而加壳程序就是在外面加上一层坚硬的外壳&#xff0c;防止别人去窃取其中的程序。加壳后的程序依然可以被直接运行。在程序运行时壳的代码先运行&#xf…

修改hosts文件无权限解决办法

文章目录 一、问题描述二、解决办法 一、问题描述 当我们在hosts文件中添加内容后----->点击文件右上角X按钮---->点击保存 系统会弹出我们没有权限的问题 二、解决办法 在搜索栏中搜索cmd---->右键命令提示符---->点击以管理员身份运行 输入cd C:\Windows\Sy…

文件上传漏洞(CVE-2022-30887)

简介 多语言药房管理系统&#xff08;MPMS&#xff09;是用PHP和MySQL开发的&#xff0c;该软件的主要目的是在药房和客户之间提供一套接口&#xff0c;客户是该软件的主要用户。该软件有助于为药房业务创建一个综合数据库&#xff0c;并根据到期、产品等各种参数提供各种报告…

OpenMMLab MMYOLO目标检测环境搭建(一)

1、环境搭建 conda create -n mmyolo python3.7 -y #创建环境 conda activate mmyolo #激活环境 conda install pytorch torchvision torchaudio cudatoolkit10.2 -c pytorch #安装 PyTorch and torchvision (官方)#如果网不好&#xff0c;可以这样安装 pi…

KNN算法回归问题介绍和实现

上篇博客中&#xff0c;介绍了使用KNN算法实现分类问题&#xff0c;本篇文章介绍使用KNN算法实现回归问题。介绍思路是先使用sklearn包提供的方法实现一个KNN算法的回归问题。再自定义实现一个KNN算法的回归问题工具类。 一、sklearn包使用KNN算法 1. 准备数据 使用sklearn包…

【C++基础】观察者模式(“发布-订阅”模式)

本文参考&#xff1a;观察者模式 - 摩根斯 | 爱编程的大丙 观察者模式允许我们定义一种订阅机制&#xff0c;可在对象事件发生时通知所有的观察者对象&#xff0c;使它们能够自动更新。观察者模式还有另外一个名字叫做“发布-订阅”模式。 发布者&#xff1a; 添加订阅者&…

【数据关联(1)】Tracking-by-detection 多目标跟踪范式与“数据关联”的关系说明

这个领域有一些专有名词需要大家清楚&#xff01; 文章目录 1 Tracking-by-detection multi-object tracking(MOT) 范式跟踪器是什么&#xff1f;1.1 关系图&#xff08;个人理解&#xff0c;如有错误请指正&#xff09;1.2 跟踪器有哪些&#xff1f; 2、核心部分“数据关联”…

Python格式化字符串(格式化输出)

print() 函数的用法&#xff0c;这只是最简单最初级的形式&#xff0c;print() 还有很多高级的玩法&#xff0c;比如格式化输出&#xff0c;这就是本节要讲解的内容。 熟悉C语言 printf() 函数的读者能够轻而易举学会 Python print() 函数&#xff0c;它们是非常类似的。 pri…

SegNetr: 重新思考 U 形网络中的局部-全局交互和跳过连接

SegNetr 会议分析摘要贡献方法整体框架1. SegNetr Block2.Information Retention Skip Connection 实验1.对比实验2.消融实验2.1 Effect of local-global interactions.2.2 Effect of patch size2.3 Effect of IRSC 可借鉴参考 会议分析 论文出处&#xff1a; arXiv预印版 除了…

C++在C语言基础上的优化

目录 一、命名空间 1、命名空间的定义 2、命名空间的使用 二、输入&输出 三、缺省参数 1、缺省参数的概念 2、缺省参数的分类 四、函数重载 五、引用 1.引用的概念 2.引用的特性 3、引用和指针的区别 六、内联函数 七、基于范围的for循环 一、命名空间 命名空…