ROS进阶——运动规划分析

19 篇文章 74 订阅
7 篇文章 5 订阅

一、运动规划算法简述

实现流程

通过给定的轨迹点,根据设定的最大速度和加速度计算每个点的速度,加速度和时间帧。

  • 轨迹点:可通过插补获得,数据类型为moveit_msgs::RobotTrajectory
  • 设定的最大速度和加速度:为URDF文件中设定参数

规划器

当前ROS提供三种规划器:

  • Time-optimal Trajectory Parameterization
  • Iterative Spline Parameterization
  • Iterative Parabolic Time Parameterization

分析

在规划固定轨迹时(直线,圆弧),规划获得速度和加速度一般会有抖动,特别是在精确的规划下,因此在对轨迹要求不高的情况下,使用样条曲线(Spline Curves)拟合轨迹可以获得较好的运动规划结果,若需要精确的固定轨迹规划,建议降低速度。

应用

  • 通过planning_adapters调用

ompl_planning_pipeline.launch中修改default_planner_request_adapters/AddTimeParameterization,若使用其他规划器,修改对应planning_pipeline.launch。(可将不支持算法制作成plugin再调用,详细参考ROS进阶——MoveIt Planning Request Adapters

规划算法调用
Time-optimal Trajectory ParameterizationAddTimeOptimalParameterization(>=Melodic)
Iterative Spline ParameterizationAddIterativeSplineParameterization
Iterative Parabolic Time ParameterizationAddTimeParameterization
  • 手动调用

当使用自定义规划算法(按照默认算法编写接口)或者新的算法(旧ros版本不支持)时,可以直接通过类调用,但注意在moveit通过plan规划时,会调用planning_adapters设置的规划算法,因此手动调用需要在plan之后。

参考:Add better functionality for adding Time Parametrization to a Cartesian Trajectory

// First to create a RobotTrajectory object
robot_trajectory::RobotTrajectory rt(group->getCurrentState()->getRobotModel(), "hand");

// Second get a RobotTrajectory from trajectory
rt.setRobotTrajectoryMsg(*group->getCurrentState(), trajectory_msg);

// Thrid create a iterative time
trajectory_processing::IterativeParabolicTimeParameterization iptp;// 五次样条曲线插补

trajectory_processing::IterativeSplineParameterization isp;// 三次样条曲线

trajectory_processing::TimeOptimalTrajectoryGeneration totg;//时间优化
      
// Fourth compute computeTimeStamps
// bool ItSuccess = iptp.computeTimeStamps(rt);
// bool ItSuccess = isp.computeTimeStamps(rt);
bool ItSuccess = totg.computeTimeStamps(rt);
OS_INFO("Computed time stamp %s", ItSuccess ? "SUCCEDED" : "FAILED");

// Get RobotTrajectory_msg from RobotTrajectory
rt.getRobotTrajectoryMsg(trajectory_msg);

computeTimeStamps函数定义(三个规划器一样)

bool trajectory_processing::IterativeParabolicTimeParameterization::computeTimeStamps(
robot_trajectory::RobotTrajectory & trajectory, //轨迹数据
const double max_velocity_scaling_factor = 1.0, //速度比例
const double max_acceleration_scaling_factor = 1.0 //加速度比例
)

速度比例和加速度比例是对关节最大速度和加速度的约束,值范围为0-1,最大值的设置值在joint_limits.yaml文件中定义。

二、Time-optimal Trajectory Parameterization

Add time-optimal trajectory parameterization

算法原理:Time-Optimal Path Following (July 2012)

注意:该规划算法在melodic版本以上才整合到moveit中

分析

  1. 该规划器输出轨迹为等时间间距(其余为等距)
  2. 该规划器在小间距下规划的速度和加速度较其余两种优化算法更加合理与平滑,在较大间距下三种规划算法效果差距不大,良好的规划间距会因机械臂参数的不同而有所不同。
  3. 在过小间距下(0.001s)插补,会出现运动规划不恒定,规划速度不平滑的现象,经测试在0.005s(不同机械臂不一致,同时需要根据控制器输出频率等确定)的规划间距下可以有较为稳定和理想的规划效果。

参数设置

TimeOptimalTrajectoryGeneration(const double path_tolerance = 0.1, 
                                const double resample_dt = 0.1);
  • path_tolerance,轨迹宽容度,允许轨迹相对实际轨迹的误差量,单位m。
  • resample_dt,输出轨迹时间间距,单位s。

减少轨迹宽容度和时间间隔会导致速度和加速度出现抖动,应根据实际情况调整。

低版本(kinetic)使用

下载time_optimal_trajectory_generation.htime_optimal_trajectory_generation.cpp放到workspcae中手动调用或制作为插件调用,程序采用c++14标准编写,使用低标准需要进行修改。

修改

std::make_unique<LinearPathSegment>(start_config, end_config)//c++14

std::unique_ptr<LinearPathSegment>(new LinearPathSegment(start_config, end_config))//c++11

若编译器支持c++14无需修改

实现效果
在这里插入图片描述

  1. 直线插补-时间间距0.001s,精度1mm

注意:该间距下规划所得结果不恒定

  • 操作空间
    在这里插入图片描述
  • 关节空间
    在这里插入图片描述
    在这里插入图片描述
  1. 直线插补-时间间距0.01s,精度10mm
  • 操作空间
    在这里插入图片描述
  • 关节空间
    在这里插入图片描述
    在这里插入图片描述
  1. 直线插补-时间间距0.1s,精度100mm
  • 操作空间
    在这里插入图片描述
  • 关节空间
    在这里插入图片描述
    在这里插入图片描述

三、Iterative Spline Parameterization

Improved IPTP by fitting a cubic spline

实现效果
在这里插入图片描述

  1. 直线插补-1mm
  • 操作空间
    在这里插入图片描述
  • 关节空间
    在这里插入图片描述
    在这里插入图片描述
  1. 直线插补-10mm
  • 操作空间
    在这里插入图片描述
  • 关节空间
    在这里插入图片描述
    在这里插入图片描述
  1. 直线插补-100mm
  • 操作空间
    在这里插入图片描述
  • 关节空间
    在这里插入图片描述
    在这里插入图片描述

四、Iterative Parabolic Time Parameterization

分析

  1. 该运动规划器为moveit默认使用规划器,可以实现速度和加速度平滑,但无法避免加速度的抖动,详细参考Improve time parameterization
  2. 该规划器等间距插补,平滑速度和加速度,适合用在低速精确轨迹控制下。

实现效果
在这里插入图片描述

  1. 直线插补-1mm
  • 操作空间
    在这里插入图片描述
  • 关节空间
    在这里插入图片描述
    在这里插入图片描述
  1. 直线插补-10mm
  • 操作空间
    在这里插入图片描述
  • 关节空间
    在这里插入图片描述
    在这里插入图片描述
  1. 直线插补-100mm
  • 操作空间
    在这里插入图片描述
  • 关节空间
    在这里插入图片描述
    在这里插入图片描述

参考

https://github.com/ros-planning/moveit/tree/melodic-devel/moveit_core/trajectory_processing/include/moveit/trajectory_processing

libmoveit_default_planning_request_adapter_plugins

串口通信在ROS中是非常常见和重要的功能。下面是一些关于ROS串口通信的进阶知识: 1. 安装serial包:首先,你需要安装ROS的serial包。在终端中运行以下命令来安装:`sudo apt-get install ros-<your_ros_version>-serial` 2. 创建ROS节点:使用ROS中的串口通信,你需要创建一个ROS节点来处理串口数据。你可以使用C++或者Python编写节点。 3. 打开串口:在ROS节点中,你需要打开串口并进行配置。你可以使用serial包提供的函数来打开和配置串口。例如,在C++中,你可以使用`serial::Serial::open()`函数来打开串口,并使用`serial::Serial::setBaudrate()`函数来设置波特率。 4. 发送和接收数据:一旦打开了串口,你就可以通过串口发送和接收数据了。你可以使用serial包提供的函数来发送和接收字节流。例如,在C++中,你可以使用`serial::Serial::write()`函数来发送数据,并使用`serial::Serial::read()`函数来接收数据。 5. ROS消息和串口数据转换:通常,你可能还需要将串口数据转换为ROS消息,以便在ROS系统中进行处理。你可以根据你的需求创建自定义的ROS消息类型,并编写转换代码将串口数据转换为ROS消息。例如,在Python中,你可以使用`rospy.Publisher`来发布ROS消息。 6. ROS参数配置:为了方便地配置串口参数,你可以使用ROS参数服务器。你可以使用`rosparam`命令或者在launch文件中设置参数。这样,你就可以在运行节点时动态地配置串口参数。 这些是ROS中串口通信的一些进阶知识。希望对你有帮助!如果你还有其他问题,请随时提问。
评论 17
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值