【PX4二次开发】PX4添加无人机模型和一些问题的总结
从SolidWorks中导出STL模型文件
SolidWorks建模
在Solidworks中开展建模工作,搭建无人机的模型。模型主要由机体,电机,螺旋桨等零件组成。
SolidWorks零件添加质量属性
为了尽量与实物的质量分布相同,我在对每个零件建模的时候都提前对实物的质量和尺寸进行测量,最后自定义材料属性并赋值给零件。这样可以尽可能地保证模型和实物的相似度,最终装配体的质量属性如下:
新建参考坐标系并导出STL文件
此处,我选取了无人机模型的重心作为坐标系的原点,并将坐标轴的X轴对齐无人机的机头方向。
另存为STL,选项中选择输出坐标系为刚才新建的坐标系。
PX4固件中的设置
方便起见,本次直接在PX4的默认启动模型iris基础上进行更改如下(也可以参考PX4官方文档教程新定义机型,本次不涉及):
SDF文件修改
在PX4-Autopilot/Tools/sitl_gazebo/models/iris文件夹中,新建一个sdf文件。仿照iris.sdf文件修改添加无人机质量,惯性矩,电机位置,机体和螺旋桨可视化文件,电机插件(电机常数、扭力系数,最大转速等参数可以通过动力系统实验测得数据),示例如下:
microfly.sdf
<!-- DO NOT EDIT: Generated from iris.sdf.jinja -->
<sdf version='1.6'>
<model name='microfly'>
<link name='base_link'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.279</mass>
<inertia>
<ixx>0.000509927</ixx>
<ixy>-0.0000</ixy>
<ixz>-0.0000</ixz>
<iyy>0.000543117</iyy>
<izy>-0.0000</izy>
<izz>0.000833593</izz>
</inertia>
</inertial>
<collision name='base_link_inertia_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<box>
<size>0.136 0.096 0.069</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='base_link_inertia_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://iris/meshes/microfly.STL</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/DarkGrey</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
</link>
<link name='/imu_link'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.001</mass>
<inertia>
<ixx>1e-06</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1e-06</iyy>
<iyz>0</iyz>
<izz>1e-06</izz>
</inertia>
</inertial>
</link>
<joint name='/imu_joint' type='revolute'>
<child>/imu_link</child>
<parent>base_link</parent>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>0</lower>
<upper>0</upper>
<effort>0</effort>
<velocity>0</velocity>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name='rotor_0'>
<pose>0.0535 -0.0535 -0.0224 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.0037</mass>
<inertia>
<ixx>9.50e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>9.50e-07</iyy>
<iyz>0</iyz>
<izz>1.816e-06</izz>
</inertia>
</inertial>
<collision name='rotor_0_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.045</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_0_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://iris/meshes/microfly_3.5_prpo_ccw.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/RedTransparent</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
</link>
<joint name='rotor_0_joint' type='revolute'>
<child>rotor_0</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name='rotor_1'>
<pose>-0.0535 0.0535 -0.0224 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.0037</mass>
<inertia>
<ixx>9.50e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>9.50e-07</iyy>
<iyz>0</iyz>
<izz>1.816e-06</izz>
</inertia>
</inertial>
<collision name='rotor_1_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.045</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_1_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://iris/meshes/microfly_3.5_prpo_ccw.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/BlueTransparent</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
</link>
<joint name='rotor_1_joint' type='revolute'>
<child>rotor_1</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name='rotor_2'>
<pose>0.0535 0.0535 -0.0224 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.0037</mass>
<inertia>
<ixx>9.50e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>9.50e-07</iyy>
<iyz>0</iyz>
<izz>1.816e-06</izz>
</inertia>
</inertial>
<collision name='rotor_2_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.045</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_2_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://iris/meshes/microfly_3.5_prpo_cw.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/RedTransparent</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
</link>
<joint name='rotor_2_joint' type='revolute'>
<child>rotor_2</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name='rotor_3'>
<pose>-0.0535 -0.0535 -0.0224 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.0037</mass>
<inertia>
<ixx>9.50e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>9.50e-07</iyy>
<iyz>0</iyz>
<izz>1.816e-06</izz>
</inertia>
</inertial>
<collision name='rotor_3_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.045</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_3_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://iris/meshes/microfly_3.5_prpo_cw.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/BlueTransparent</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
</link>
<joint name='rotor_3_joint' type='revolute'>
<child>rotor_3</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<plugin name='rosbag' filename='libgazebo_multirotor_base_plugin.so'>
<robotNamespace/>
<linkName>base_link</linkName>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='front_right_motor_model' filename='libgazebo_motor_model.so'>
<robotNamespace/>
<jointName>rotor_0_joint</jointName>
<linkName>rotor_0</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1200</maxRotVelocity>
<motorConstant>8.015e-07</motorConstant>
<momentConstant>0.0135</momentConstant>
<commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
<rotorDragCoefficient>0.000175</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>/motor_speed/0</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='back_left_motor_model' filename='libgazebo_motor_model.so'>
<robotNamespace/>
<jointName>rotor_1_joint</jointName>
<linkName>rotor_1</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1200</maxRotVelocity>
<motorConstant>8.015e-07</motorConstant>
<momentConstant>0.0135</momentConstant>
<commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
<motorNumber>1</motorNumber>
<rotorDragCoefficient>0.000175</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>/motor_speed/1</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='front_left_motor_model' filename='libgazebo_motor_model.so'>
<robotNamespace/>
<jointName>rotor_2_joint</jointName>
<linkName>rotor_2</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1200</maxRotVelocity>
<motorConstant>8.015e-07</motorConstant>
<momentConstant>0.0135</momentConstant>
<commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
<motorNumber>2</motorNumber>
<rotorDragCoefficient>0.000175</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>/motor_speed/2</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='back_right_motor_model' filename='libgazebo_motor_model.so'>
<robotNamespace/>
<jointName>rotor_3_joint</jointName>
<linkName>rotor_3</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1200</maxRotVelocity>
<motorConstant>8.015e-07</motorConstant>
<momentConstant>0.0135</momentConstant>
<commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
<motorNumber>3</motorNumber>
<rotorDragCoefficient>0.000175</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>/motor_speed/3</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<include>
<uri>model://gps</uri>
<pose>0 0 0 0 0 0</pose>
<name>gps0</name>
</include>
<joint name='gps0_joint' type='fixed'>
<child>gps0::link</child>
<parent>base_link</parent>
</joint>
<plugin name='groundtruth_plugin' filename='libgazebo_groundtruth_plugin.so'>
<robotNamespace/>
</plugin>
<plugin name='magnetometer_plugin' filename='libgazebo_magnetometer_plugin.so'>
<robotNamespace/>
<pubRate>100</pubRate>
<noiseDensity>0.0004</noiseDensity>
<randomWalk>6.4e-06</randomWalk>
<biasCorrelationTime>600</biasCorrelationTime>
<magTopic>/mag</magTopic>
</plugin>
<plugin name='barometer_plugin' filename='libgazebo_barometer_plugin.so'>
<robotNamespace/>
<pubRate>50</pubRate>
<baroTopic>/baro</baroTopic>
<baroDriftPaPerSec>0</baroDriftPaPerSec>
</plugin>
<plugin name='mavlink_interface' filename='libgazebo_mavlink_interface.so'>
<robotNamespace/>
<imuSubTopic>/imu</imuSubTopic>
<magSubTopic>/mag</magSubTopic>
<baroSubTopic>/baro</baroSubTopic>
<mavlink_addr>INADDR_ANY</mavlink_addr>
<mavlink_tcp_port>4560</mavlink_tcp_port>
<mavlink_udp_port>14560</mavlink_udp_port>
<serialEnabled>0</serialEnabled>
<serialDevice>/dev/ttyACM0</serialDevice>
<baudRate>921600</baudRate>
<qgc_addr>INADDR_ANY</qgc_addr>
<qgc_udp_port>14550</qgc_udp_port>
<sdk_addr>INADDR_ANY</sdk_addr>
<sdk_udp_port>14540</sdk_udp_port>
<hil_mode>0</hil_mode>
<hil_state_level>0</hil_state_level>
<send_vision_estimation>0</send_vision_estimation>
<send_odometry>1</send_odometry>
<enable_lockstep>1</enable_lockstep>
<use_tcp>1</use_tcp>
<motorSpeedCommandPubTopic>/gazebo/command/motor_speed</motorSpeedCommandPubTopic>
<control_channels>
<channel name='rotor1'>
<input_index>0</input_index>
<input_offset>0</input_offset>
<input_scaling>2000</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>100</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
</channel>
<channel name='rotor2'>
<input_index>1</input_index>
<input_offset>0</input_offset>
<input_scaling>2000</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>100</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
</channel>
<channel name='rotor3'>
<input_index>2</input_index>
<input_offset>0</input_offset>
<input_scaling>2000</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>100</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
</channel>
<channel name='rotor4'>
<input_index>3</input_index>
<input_offset>0</input_offset>
<input_scaling>2000</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>100</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
</channel>
<channel name='rotor5'>
<input_index>4</input_index>
<input_offset>1</input_offset>
<input_scaling>324.6</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
<joint_control_pid>
<p>0.1</p>
<i>0</i>
<d>0</d>
<iMax>0.0</iMax>
<iMin>0.0</iMin>
<cmdMax>2</cmdMax>
<cmdMin>-2</cmdMin>
</joint_control_pid>
<joint_name>zephyr_delta_wing::propeller_joint</joint_name>
</channel>
<channel name='rotor6'>
<input_index>5</input_index>
<input_offset>0</input_offset>
<input_scaling>0.524</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>position</joint_control_type>
<joint_name>zephyr_delta_wing::flap_left_joint</joint_name>
<joint_control_pid>
<p>10.0</p>
<i>0</i>
<d>0</d>
<iMax>0</iMax>
<iMin>0</iMin>
<cmdMax>20</cmdMax>
<cmdMin>-20</cmdMin>
</joint_control_pid>
</channel>
<channel name='rotor7'>
<input_index>6</input_index>
<input_offset>0</input_offset>
<input_scaling>0.524</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>position</joint_control_type>
<joint_name>zephyr_delta_wing::flap_right_joint</joint_name>
<joint_control_pid>
<p>10.0</p>
<i>0</i>
<d>0</d>
<iMax>0</iMax>
<iMin>0</iMin>
<cmdMax>20</cmdMax>
<cmdMin>-20</cmdMin>
</joint_control_pid>
</channel>
<channel name='rotor8'>
<input_index>7</input_index>
<input_offset>0</input_offset>
<input_scaling>0.524</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>position</joint_control_type>
</channel>
</control_channels>
</plugin>
<static>0</static>
<plugin name='rotors_gazebo_imu_plugin' filename='libgazebo_imu_plugin.so'>
<robotNamespace/>
<linkName>/imu_link</linkName>
<imuTopic>/imu</imuTopic>
<gyroscopeNoiseDensity>0.00018665</gyroscopeNoiseDensity>
<gyroscopeRandomWalk>3.8785e-05</gyroscopeRandomWalk>
<gyroscopeBiasCorrelationTime>1000.0</gyroscopeBiasCorrelationTime>
<gyroscopeTurnOnBiasSigma>0.0087</gyroscopeTurnOnBiasSigma>
<accelerometerNoiseDensity>0.00186</accelerometerNoiseDensity>
<accelerometerRandomWalk>0.006</accelerometerRandomWalk>
<accelerometerBiasCorrelationTime>300.0</accelerometerBiasCorrelationTime>
<accelerometerTurnOnBiasSigma>0.196</accelerometerTurnOnBiasSigma>
</plugin>
</model>
</sdf>
mesh文件添加
在同目录下的mesh文件夹中添加上述sdf文件所需的STL文件。
环境依赖添加
将 ~/PX4-Autopilot/ 和 ~/PX4-Autopilot/Tools/sitl_gazebo目录添加到 ROS_PACKAGE_PATH 中。如果 sitl_gazebo 目录包含与仿真相关的 ROS 包或依赖项,添加这个目录后,ROS 可以识别这些包。
我直接将这些命令写入到了.bashrc文件中。
source ~/PX4-Autopilot/Tools/setup_gazebo.bash ~/PX4-Autopilot ~/PX4-Autopilot/build/px4_sitl_default
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:~/PX4-Autopilot
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:~/PX4-Autopilot/Tools/sitl_gazebo
launch文件修改
本次只简单地将PX4-Autopilot/launch 文件夹中的 posix_sitl.launch 的sdf文件修改为前边定义的sdf文件,也可以新建一个launch文件,这里就偷懒了。
<arg name="vehicle" default="iris"/>
<arg name="world" default="$(find mavlink_sitl_gazebo)/worlds/empty.world"/>
<arg name="sdf" default="$(find mavlink_sitl_gazebo)/models/$(arg vehicle)/microfly.sdf"/>
启动仿真
cd PX4-Autopilot/
roslaunch px4 posix_sitl.launch
gazebo中无人机悄悄移动
描述
启动px4 gazebo仿真后,在没有进行解锁和其他操作的情况下,无人机会缓慢移动,且伴随着抖动。查看base_link的pose信息发现模型有一个较大的pitch角,这导致了模型一直朝着一个方向移动。
分析
主要是由于SDF模型定义中惯性矩与碰撞几何体质量分布对应不上导致的!碰撞几何体的定义应与模型的实际形状和质量分布一致。如果碰撞几何体的形状或位置与实际物体不一致,也可能导致模型在仿真中出现额外的力矩。
解决方法:
首先对物理模型的参数进行简化,将非对角的系数置为零,找到一个与简化后物理模型质量、转动惯量参数相同的长方体作为简化的几何体,计算方法如下:
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.279</mass>
<inertia>
<ixx>0.000509927</ixx>
<ixy>-0.0000</ixy>
<ixz>-0.0000</ixz>
<iyy>0.000543117</iyy>
<izy>-0.0000</izy>
<izz>0.000833593</izz>
</inertia>
</inertial>
这是我的物理模型质量和惯性矩参数,根据惯性矩计算公式:
I
x
x
=
m
(
b
2
+
c
2
)
/
12
I
y
y
=
m
(
a
2
+
c
2
)
/
12
I
z
z
=
m
(
a
2
+
b
2
)
/
12
I_{xx}=m(b^2+c^2)/12\\ I_{yy}=m(a^2+c^2)/12\\ I_{zz}=m(a^2+b^2)/12
Ixx=m(b2+c2)/12Iyy=m(a2+c2)/12Izz=m(a2+b2)/12
求解得到:
a
≈
0.136
,
b
≈
0.096
,
c
≈
0.069
a \approx 0.136, b \approx 0.096 , c \approx 0.069
a≈0.136,b≈0.096,c≈0.069
因此,长方体的近似尺寸为 0.136 m×0.096 m×0.069 m。
修改碰撞几何体的尺寸定义如下:
<collision name='base_link_inertia_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<box>
<size>0.136 0.096 0.069</size>
</box>
</geometry>
再次打开px4 gazebo仿真之后,模型不再偷偷移动!
写在最后
这是我自己学习的笔记和思考,请大家批评指正!