实物部署【Switching Sampling Space of Model Predictive Path-Integral Controller to Balance Efficiency and Safety in 4WIDS Vehicle Navigation】


部署环境
- Ubuntu 20.04
- ROS Noetic
- gcc 9.4.0
- numpy 1.20.3
- numexpr 2.7.3
- cmake 3.12.4(3.5 及以上,不能用 cmake 4 系列)
- 松灵 ranger mini 3.0
- 禾赛 32线雷达
- xsense IMU
整体运行指令流程
nullspace_mpc_README.md
# 打开禾赛雷达
cd /home/yehuo/Lidar/Hesai
source devel/setup.bash
roslaunch hesai_lidar cloud_nodelet.launch lidar_type:="PandarXT-32" frame_id:="PandarXT-32"
# 时间同步命令
# sudo apt install linuxptp
ifconfig -a
sudo ptp4l -m -4 -i enp11s0 -S
# 打开imu
cd /home/yehuo/IMU/xsense/Xsens_MTi_ROS_Driver_and_Ntrip_Client/src/xsens_ros_mti_driver/build
sudo chmod 777 /dev/ttyUSB0
source devel/setup.bash
roslaunch xsens_mti_driver xsens_mti_node.launch # display.launch
# 打开点云地图
cd /home/yehuo/location/location_ws
source devel/setup.bash
roslaunch pointcloudmap_load pointcloudmap_load.launch
# 启动定位程序
cd /home/yehuo/location/location_ws
source devel/setup.bash
roslaunch neu_localization neu_localization.launch
# 启动四轮四转向车(遥控器使能)
cd /home/yehuo/agilexrobotics/agilexrobotics_ws
source devel/setup.bash
rosrun ranger_bringup bringup_can2usb.bash
roslaunch ranger_bringup ranger_mini_v2.launch
# 启动 nullspace_mpc 项目
cd /home/yehuo/nullspace_mpc_test
make navigation_nullspace_mpc


与原项目的区别
基于禾赛3d雷达进行定位,使用的是自己的定位程序
- 为了与原项目的程序相容,基于 pointcloud_to_laserscan 功能包将三维的点云数据改为二维的激光数据
- 此外,将实际场景的三维地图转变为二维地图
实物上需要启动 xsense IMU 的驱动
实物上需要启动底盘的驱动
实物上需要进行时间的同步
rqt_graph 比对
仿真

实物

rqt_tf_tree 比对
仿真

实物

<node pkg="tf" type="static_transform_publisher" name="map2odom" args="0.0 0.0 0.0 0 0 0 1 map odom 100" />
<!--发布 map 坐标系 → odom 坐标系 的静态变换 -->
<node pkg="tf" type="static_transform_publisher" name="base_link2laser_link" args="0.0 0.0 0.0 0 0 0 1 base_link laser_link 100" />
<!-- body_imu 改为 base_link ;base_link 改为 laser_link -->
具体改动代码
三维点云.pcd地图转换为二维栅格.pgm地图
cd /home/yehuo/pcd2pgm/pcd2pgm_ws
source devel/setup.bash
rosrun pcd_to_pgm pcd_to_pgm_node map/custom/drone_map_01.pcd map/custom/drone_map_01 0.05 0.1 2.0
/home/yehuo/nullspace_mpc_test/launch/navigation.launch
<launch>
<!-- ##### SETTINGS { ##### -->
<!-- often changed arguments -->
<arg name="enable_gazebo" default="false"/>
<arg name="gazebo_world_name" default="maze" /> <!-- empty, empty_garden, cylinder_garden, maze -->
<arg name="joy_operation" default="true" />
<arg name="local_planner" default="nullspace_mpc" /> <!-- mppi_3d_a, mppi_3d_b, mppi_4d, mppi_h, nullspace_mpc -->
<!-- arguments -->
<arg name="workspace" default="$(env HOME)/nullspace_mpc" />
<arg name="rvizconfig" default="$(arg workspace)/data/rviz/navigation.rviz" />
<arg name="open_rviz" default="true"/>
<arg name="scan_topic" default="/scan"/> <!-- "/laser_link/scan" -->
<arg name="cmd_vel_topic" default="/cmd_vel"/>
<arg name="odom_topic" default="/odometry"/> <!-- "/groundtruth_odom" -->
<arg name="set_base_frame" default="base_link"/>
<arg name="set_odom_frame" default="odom"/>
<arg name="set_map_frame" default="map"/>
<arg name="initial_pose_x" default="0.0"/>
<arg name="initial_pose_y" default="0.0"/>
<arg name="initial_pose_yaw" default="0.0"/>
<arg name="do_evaluation" default="true" />
<arg name="scenario_config_path" default="file_not_specified"/>
<arg name="eval_result_dir" default="file_not_specified"/>
<arg name="controller_mode" default="default" doc="Mode for nullspace_mpc: choose 'default' or 'lite' to adjust performance"/>
<arg name="show_gazebo_gui" default="false"/> <!-- true -->
<arg name="gazebo_headless" default="false"/>
<rosparam param="/use_sim_time">false</rosparam> <!-- set use_sim_time true to syncronize time with gazebo --> <!-- true -->
<!-- ##### } SETTINGS ##### -->
<!-- ##### COMMON NODES { ##### -->
<!-- launch gazebo world -->
<group if="$(arg enable_gazebo)">
<include file="$(arg workspace)/launch/gazebo_world.launch">
<arg name="gazebo_world_name" value="$(arg gazebo_world_name)" />
<arg name="use_joystick" value="$(arg joy_operation)" />
<arg name="use_vel_driver" value="false" />
<arg name="open_rviz" value="false" />
<arg name="show_gazebo_gui" value="$(arg show_gazebo_gui)" />
<arg name="gazebo_headless" value="$(arg gazebo_headless)" />
</include>
</group>
<!-- map server -->
<!-- <node pkg="map_server" type="map_server" name="map_server" args="$(arg workspace)/data/map/$(arg gazebo_world_name)/map.yaml" /> -->
<node pkg="map_server" type="map_server" name="map_server" args="/home/yehuo/pcd2pgm/pcd2pgm_ws/map/custom/drone_map_01.yaml" />
<!-- 3d map visualizer -->
<!-- <group if="$(arg enable_gazebo)">
<include file="$(find map_visualizer)/launch/map_visualizer.launch">
<arg name="map_name" value="$(arg gazebo_world_name)" />
</include>
</group> -->
<!-- amcl -->
<!-- <node pkg="amcl" type="amcl" name="amcl">
<param name="initial_pose_x" value="$(arg initial_pose_x)"/>
<param name="initial_pose_y" value="$(arg initial_pose_y)"/>
<param name="initial_pose_a" value="$(arg initial_pose_yaw)"/>
<remap from="scan" to="$(arg scan_topic)"/>
<rosparam file="$(arg workspace)/config/amcl.yaml" command="load" />
</node> -->
<!-- rviz -->
<group if="$(arg open_rviz)">
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true" />
</group>
<!-- run pointcloud_to_laserscan node -->
<node pkg="pointcloud_to_laserscan" type="pointcloud_to_laserscan_node" name="pointcloud_to_laserscan">
<remap from="cloud_in" to="/cloud_registered_body"/>
</node>
<!-- ##### } COMMON NODES ##### -->
<!-- ##### LAUNCH SELECTED LOCAL PLANNER { ##### -->
<!-- Nullspace MPC -->
<group if="$(eval local_planner=='nullspace_mpc')">
<!-- nullspace_mpc with controller_mode to adjust performance -->
<include file="$(find nullspace_mpc)/launch/nullspace_mpc.launch">
<arg name="controller_mode" value="$(arg controller_mode)"/>
</include>
<!-- reference_costmap_generator -->
<include file="$(find reference_costmap_generator)/launch/reference_costmap_generator.launch" />
<!-- launch global planner -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<param name="base_local_planner" value="base_local_planner/TrajectoryPlannerROS" />
<rosparam file="$(arg workspace)/config/base_local_planner.yaml" command="load" />
<rosparam file="$(arg workspace)/config/costmap_common_global.yaml" command="load" ns="global_costmap" />
<rosparam file="$(arg workspace)/config/costmap_common_local_nullspace_mpc.yaml" command="load" ns="local_costmap" />
<rosparam file="$(arg workspace)/config/costmap_local.yaml" command="load" />
<rosparam file="$(arg workspace)/config/costmap_global.yaml" command="load" />
<rosparam file="$(arg workspace)/config/move_base.yaml" command="load" />
<remap from="cmd_vel" to="/no_use/cmd_vel"/>
<remap from="odom" to="$(arg odom_topic)"/>
<remap from="scan" to="$(arg scan_topic)"/>
</node>
<!-- launch vel_driver to operate 4WIDS vehicle with /cmd_vel-->
<include file="$(find vel_driver)/launch/vel_driver.launch" />
</group>
<!-- MPPI-3D (a) (exploring 3 dimensional space: vx, vy, omega) -->
<group if="$(eval local_planner=='mppi_3d_a')">
<include file="$(find mppi_3d)/launch/mppi_3d_a.launch" />
<!-- reference_costmap_generator -->
<include file="$(find reference_costmap_generator)/launch/reference_costmap_generator.launch" />
<!-- launch global planner -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<param name="base_local_planner" value="base_local_planner/TrajectoryPlannerROS" />
<rosparam file="$(arg workspace)/config/base_local_planner.yaml" command="load" />
<rosparam file="$(arg workspace)/config/costmap_common_global.yaml" command="load" ns="global_costmap" />
<rosparam file="$(arg workspace)/config/costmap_common_local.yaml" command="load" ns="local_costmap" />
<rosparam file="$(arg workspace)/config/costmap_local.yaml" command="load" />
<rosparam file="$(arg workspace)/config/costmap_global.yaml" command="load" />
<rosparam file="$(arg workspace)/config/move_base.yaml" command="load" />
<remap from="cmd_vel" to="/no_use/cmd_vel"/>
<remap from="odom" to="$(arg odom_topic)"/>
<remap from="scan" to="$(arg scan_topic)"/>
</node>
<!-- launch vel_driver to operate 4WIDS vehicle with /cmd_vel-->
<include file="$(find vel_driver)/launch/vel_driver.launch" />
</group>
<!-- MPPI-3D (b) (exploring 3 dimensional space: vx, vy, omega) -->
<group if="$(eval local_planner=='mppi_3d_b')">
<include file="$(find mppi_3d)/launch/mppi_3d_b.launch" />
<!-- reference_costmap_generator -->
<include file="$(find reference_costmap_generator)/launch/reference_costmap_generator.launch" />
<!-- launch global planner -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<param name="base_local_planner" value="base_local_planner/TrajectoryPlannerROS" />
<rosparam file="$(arg workspace)/config/base_local_planner.yaml" command="load" />
<rosparam file="$(arg workspace)/config/costmap_common_global.yaml" command="load" ns="global_costmap" />
<rosparam file="$(arg workspace)/config/costmap_common_local.yaml" command="load" ns="local_costmap" />
<rosparam file="$(arg workspace)/config/costmap_local.yaml" command="load" />
<rosparam file="$(arg workspace)/config/costmap_global.yaml" command="load" />
<rosparam file="$(arg workspace)/config/move_base.yaml" command="load" />
<remap from="cmd_vel" to="/no_use/cmd_vel"/>
<remap from="odom" to="$(arg odom_topic)"/>
<remap from="scan" to="$(arg scan_topic)"/>
</node>
<!-- launch vel_driver to operate 4WIDS vehicle with /cmd_vel-->
<include file="$(find vel_driver)/launch/vel_driver.launch" />
</group>
<!-- MPPI-4D (exploring 4 dimensional space) -->
<group if="$(eval local_planner=='mppi_4d')">
<include file="$(find mppi_4d)/launch/mppi_4d.launch" />
<!-- reference_costmap_generator -->
<include file="$(find reference_costmap_generator)/launch/reference_costmap_generator.launch" />
<!-- launch global planner -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<param name="base_local_planner" value="base_local_planner/TrajectoryPlannerROS" />
<rosparam file="$(arg workspace)/config/base_local_planner.yaml" command="load" />
<rosparam file="$(arg workspace)/config/costmap_common_global.yaml" command="load" ns="global_costmap" />
<rosparam file="$(arg workspace)/config/costmap_common_local.yaml" command="load" ns="local_costmap" />
<rosparam file="$(arg workspace)/config/costmap_local.yaml" command="load" />
<rosparam file="$(arg workspace)/config/costmap_global.yaml" command="load" />
<rosparam file="$(arg workspace)/config/move_base.yaml" command="load" />
<remap from="cmd_vel" to="/no_use/cmd_vel"/>
<remap from="odom" to="$(arg odom_topic)"/>
<remap from="scan" to="$(arg scan_topic)"/>
</node>
<!-- launch vel_driver to operate 4WIDS vehicle with /cmd_vel-->
<include file="$(find vel_driver)/launch/vel_driver.launch" />
</group>
<!-- MPPI-H (switching MPPI-3D and MPPI-4D in real-time) -->
<group if="$(eval local_planner=='mppi_h')">
<include file="$(find mppi_h)/launch/mppi_h.launch" />
<!-- reference_costmap_generator -->
<include file="$(find reference_costmap_generator)/launch/reference_costmap_generator.launch" />
<!-- launch global planner -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<param name="base_local_planner" value="base_local_planner/TrajectoryPlannerROS" />
<rosparam file="$(arg workspace)/config/base_local_planner.yaml" command="load" />
<rosparam file="$(arg workspace)/config/costmap_common_global.yaml" command="load" ns="global_costmap" />
<rosparam file="$(arg workspace)/config/costmap_common_local.yaml" command="load" ns="local_costmap" />
<rosparam file="$(arg workspace)/config/costmap_local.yaml" command="load" />
<rosparam file="$(arg workspace)/config/costmap_global.yaml" command="load" />
<rosparam file="$(arg workspace)/config/move_base.yaml" command="load" />
<remap from="cmd_vel" to="/no_use/cmd_vel"/>
<remap from="odom" to="$(arg odom_topic)"/>
<remap from="scan" to="$(arg scan_topic)"/>
</node>
<!-- launch vel_driver to operate 4WIDS vehicle with /cmd_vel-->
<include file="$(find vel_driver)/launch/vel_driver.launch" />
</group>
<!-- (not supported) move_base [base local planner] -->
<group if="$(eval local_planner=='base')">
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<param name="base_local_planner" value="base_local_planner/TrajectoryPlannerROS" />
<rosparam file="$(arg workspace)/config/base_local_planner.yaml" command="load" />
<rosparam file="$(arg workspace)/config/costmap_common_global.yaml" command="load" ns="global_costmap" />
<rosparam file="$(arg workspace)/config/costmap_common_local.yaml" command="load" ns="local_costmap" />
<rosparam file="$(arg workspace)/config/costmap_local.yaml" command="load" />
<rosparam file="$(arg workspace)/config/costmap_global.yaml" command="load" />
<rosparam file="$(arg workspace)/config/move_base.yaml" command="load" />
<remap from="cmd_vel" to="$(arg cmd_vel_topic)"/>
<remap from="odom" to="$(arg odom_topic)"/>
<remap from="scan" to="$(arg scan_topic)"/>
</node>
<!-- launch vel_driver to operate 4WIDS vehicle with /cmd_vel-->
<include file="$(find vel_driver)/launch/vel_driver.launch" />
</group>
<!-- (not supported) move_base [teb local planner] -->
<group if="$(eval local_planner=='teb')">
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<param name="base_local_planner" value="teb_local_planner/TebLocalPlannerROS" />
<rosparam file="$(arg workspace)/config/teb_local_planner.yaml" command="load" />
<rosparam file="$(arg workspace)/config/costmap_common_global.yaml" command="load" ns="global_costmap" />
<rosparam file="$(arg workspace)/config/costmap_common_local.yaml" command="load" ns="local_costmap" />
<rosparam file="$(arg workspace)/config/costmap_local.yaml" command="load" />
<rosparam file="$(arg workspace)/config/costmap_global.yaml" command="load" />
<rosparam file="$(arg workspace)/config/move_base_teb.yaml" command="load" />
<remap from="cmd_vel" to="$(arg cmd_vel_topic)"/>
<remap from="odom" to="$(arg odom_topic)"/>
<remap from="scan" to="$(arg scan_topic)"/>
</node>
<!-- launch vel_driver to operate 4WIDS vehicle with /cmd_vel-->
<include file="$(find vel_driver)/launch/vel_driver.launch" />
</group>
<!-- ##### } LAUNCH SELECTED LOCAL PLANNER ##### -->
<!-- ##### { OPTIONAL NODES ##### -->
<!-- evaluator -->
<group if="$(arg do_evaluation)">
<include file="$(find mpc_nav_evaluator)/launch/mpc_nav_evaluator.launch">
<arg name="scenario_config_path" value="$(arg scenario_config_path)" />
<arg name="eval_result_dir" value="$(arg eval_result_dir)" />
</include>
</group>
<!-- ##### } OPTIONAL NODES ##### -->
</launch>
/home/yehuo/nullspace_mpc_test/src/control/nullspace_mpc/config/nullspace_mpc.yaml
# topic names
## subscribing topics
odom_topic: /odometry ## 仿真使用 /groundtruth_odom 实物使用 /odometry
ref_path_topic: /move_base/NavfnROS/plan
collision_costmap_topic: /move_base/local_costmap/costmap
distance_error_map_topic: /distance_error_map
ref_yaw_map_topic: /ref_yaw_map
## publishing topics
control_cmd_vel_topic: /cmd_vel
mppi_absvel_topic: /mpc/cmd/absvel
mppi_vx_topic: /mpc/cmd/vx
mppi_vy_topic: /mpc/cmd/vy
mppi_omega_topic: /mpc/cmd/omega
calc_time_topic: /mpc/calc_time
mppi_overlay_text_topic: /mpc/overlay_text
mppi_optimal_traj_topic: /mpc/optimal_traj
mppi_sampled_traj_topic: /mpc/sampled_traj
mppi_via_state_seq_topic: /mpc/via_state_seq
mpc_eval_msg_topic: /mpc/eval_info
# navigation params
navigation:
xy_goal_tolerance: 0.5 # [m]
yaw_goal_tolerance: 0.15 # [rad] set 6.28 to ignore angular error
goal_snap_distance_for_via_pos: 0.3 # [m]
goal_snap_distance_for_via_angle: 1.5 # [rad]
# target_system params
target_system:
l_f: 0.5 # [m]
l_r: 0.5 # [m]
d_l: 0.5 # [m]
d_r: 0.5 # [m]
tire_radius: 0.2 # [m]
# controller params
controller:
name: "nullspace_mpc"
control_interval: 0.05 # [s]
num_samples: 200 # number of samples
prediction_horizon: 15 # [steps]
step_len_sec: 0.125 # [s]
param_exploration: 0.01
param_lambda: 250.0
param_alpha: 0.975
idx_via_states: [4, 9, 15] # index of via states in the prediction horizon (indices must be less than prediction_horizon)
sigma: [
0.2, 0.25, 0.393, # noise for via state at step 4
0.2, 0.25, 0.393, # noise for via state at step 9
0.2, 0.01, 0.393, # noise for via state at step 15
]
reduce_computation: true # if true, noise sampling is done only once and the same noise is used for all processes.
weight_cmd_change: [0.0, 0.0, 0.0] # penalty weight for variation of [vx, vy, omega]
weight_vehicle_cmd_change: [1.4, 1.4, 1.4, 1.4, 0.1, 0.1, 0.1, 0.1] # penalty weight for variation of [fl_steer, fr_steer, rl_steer, rr_steer, fl_vel, fr_vel, rl_vel, rr_vel]
ref_velocity: 2.0 # [m/s]
weight_velocity_error: 10.0
weight_angular_error: 30.0
weight_collision_penalty: 50.0
weight_distance_error_penalty: 40.0
weight_terminal_state_penalty: 0.0
use_sg_filter: true # set true to use Savitzky-Golay filter for smoothing the control input
sg_filter_half_window_size: 8 # value in the range of 1 ~ (prediction_horizon - 1) is allowed.
sg_filter_poly_order: 2
# Note:
## - to change the velocity limit of the controller, check ../include/nullspace_mpc/common_type.hpp
## - to edit the prediction model or the cost function, check ../include/nullspace_mpc/nullspace_mpc_setting.hpp
实物部署【Switching Sampling Space of Model Predictive Path-Integral Controller to Balance Efficiency and Safety in 4WIDS Vehicle Navigation】的更多相关文章
- MVC(Model(模型) View(视图) Controller(控制器))
复习 1. 商品表 增删改查 index.php add.php view.php edit.php action.php 2. MVC(Model(模型) Vie ...
- ASP.NET MVC轻教程 Step By Step 4——Model、View和Controller
ASP.NET MVC中的Model(数据模型)主要包括定义数据结构.数据库读写.数据验证等等和对象处理相关的工作. 在解决方案资源管理器中找到Model文件夹,点击右键,添加一个新类,名为“Mess ...
- Asp.Net Core 入门(四)—— Model、View、Controller
和我们学习Asp.Net MVC一样,Asp.Net Core MVC的Model.View.Controller也和我们熟悉的Asp.Net MVC中的相似.不同的是我们在使用Asp.Net Cor ...
- MATLAB模型预测控制(MPC,Model Predictive Control)
模型预测控制是一种基于模型的闭环优化控制策略. 预测控制算法的三要素:内部(预测)模型.参考轨迹.控制算法.现在一般则更清楚地表述为内部(预测)模型.滚动优化.反馈控制. 大量的预测控制权威性文献都无 ...
- 【控制】模型预测控制 MPC 【合集】Model Predictive Control
1.模型预测控制--运动学模型 2.模型预测控制--模型线性化 3.模型预测控制--模型离散化 4.模型预测控制--预测 5.模型预测控制--控制律优化二次型优化 6.模型预测控制--反馈控制 7.模 ...
- 2013/11/22工作随笔-缓存是放在Model层还是放在Controller层
web网站的典型代码框架就是MVC架构,Model层负责数据获取,Controller层负责逻辑控制,View层则负责展示. 一般数据获取是去mysql中获取数据 但是这里有个问题,我们不会每次请求都 ...
- 1、ASP.NET Core2.0之Model、View、Controller
一.新建空项目 打开VS2017,新建→项目,选择如下: 点击,确定,弹出的界面选择如下: 选择空项目,因为选择其他的话会自动生成很多用不到的类,显得项目不够“清爽”,ASP.NET Core选择2. ...
- 浅谈ThinkPHP3.2的子域名部署和路由优化(一)
前言:建立一个网站系统,往往包含多个子网站,例如PC官网,移动端官网,后台管理,数据源自一个相同的数据库,整个架构上,从ThinkPHP来看,可以大体理解为Model(M)是一样的,Controlle ...
- Azure ARM (10) ARM模式下的虚拟机和Classic Model虚拟机的区别
<Windows Azure Platform 系列文章目录> 本文内容比较多,请大家仔细阅读,谢谢! 请读者注意,在Azure ARM平台,有两种虚拟机模式:经典虚拟机和ARM虚拟机 A ...
- 关于.net MVC5+EF6 网站部署的问题
创建mvc web application,采用code first 的方式,MVC5,EF6.0 整了一个网站.开发完之后.直接publish.就这样部署到服务器上了. 在使用过程中发现,网站打开的 ...
随机推荐
- 【iOS】从实际出发理解多线程(二)--NSThread高级操作
上篇文章讲了一下NSThread的基本操作,本篇讲一下NSThread的一些高级用法. 线程间资源共享&线程加锁 在程序运行过程中,如果存在多线程,呢么各个线程读写资源就会存在先后.同时读写资 ...
- uniapp开发的h5引入uni.webview.js注意事项
webview加载的h5页面明明按照uniapp官方文档引入了uni-webview.js,但仍无法使用uni.navigateTo等方法? 若是普通html那可能是引入方式不对,若webview中加 ...
- 【STM32系列】"Flash Timeout Reset the Target and try it again."问题解决方式之一
前言 博主使用DAP下载器烧录程序到STM32G4的时候,遇到了Flash Timeout的问题,原本以为是锁芯片了,正发愁呢,没想到随便改一下就好了. 问题 解决方法 魔术棒 -> Debug ...
- Typora小教程
公式与代码 数学公式
- 操作系统层面反删除恢复文件损坏太多处理—-oracle碎片恢复
联系:手机/微信(+86 13429648788) QQ(107644445) 标题:操作系统层面反删除恢复文件损坏太多处理--碎片恢复 作者:惜分飞版权所有[未经本人同意,不得以任何形式转载,否则有 ...
- MySQL专题面试题-二叉树、红黑树、B 树、B+树
演示网址:https://www.cs.usfca.edu/~galles/visualization/Algorithms.html 所谓的索引,就是帮助MySQL高效获取数据的排好序的数据结构,基 ...
- 分布式Redis解决方案之Redisson
1.前言 Redisson是Redis官方推荐的Java版的Redis客户端.底层使用netty框架,并提供了与java对象相对应的分布式对象.分布式集合.分布式锁和同步器.分布式服务等一系列的Red ...
- MySQL中OPTIMIZE TABLE和慢查询分析
先来看看手册中关于 OPTIMIZE 的描述: OPTIMIZE [LOCAL | NO_WRITE_TO_BINLOG] TABLE tbl_name [, tbl_name] ...如果您已经删除 ...
- 图片压缩优化结合Base64存储的系统改进方案
需要帮助用户解决图片压缩优化结合Base64存储的问题.用户之前已经提到他们目前将图片以Base64格式存储在数据库中,导致接口传输数据过大,加载时间长达3秒.他们现在想通过图片压缩来优化系统,但不采 ...
- 基于JavaWeb理财系统-项目实战
文档地址: 链接:https://pan.baidu.com/s/1rTKBpgDe2hW6EW9Cjwf9gg?pwd=6lsy 提取码:6lsy 0.课程介绍 我们非常高兴地为大家推出一门全新的 ...