三轮全向移动机器人线速度和角速度标定

 为什么需要标定?

首先我们来明确标定的定义,标定是在测量时,对测试设备的精度进行复核,并及时对误差进行消除的动态过程。根据该定义我们就能了解,其实任何的设备在刚制造出来后,无论你的制造过程有多精密,误差总是存在的。只不过有时候误差可能在我们的接受范围内,所以有些设备就不必标定了。拿我们的三轮全向移动小车来说的话,这个标定过程是不可少的。因为小车是一个具有机械安装结构和电机驱动的设备,机械结构安装会存在误差,电机的性能也会各不相同。这样即使我们的控制程序是一样的,那在具有安装误差和电机性能不同的小车上运行起来移动效果肯定也是不一样的。所以,我们需要每制作好一台轮式移动小车后,都需要对其移动的线速度和转动的角速度进行标定。只有在标定后,小车的移动距离理论值才会跟实际测量值一样。这样我们小车在进行自动导航时,往目标点移动时才能更好的进行定位。

1 准备工作

1)将下面链接中的校准文件下载到自己的工作空间下,机器人校准程序代码下载链接:carebot_calibration.zip官方版下载丨最新版下载丨绿色版下载丨APP下载-123云盘

 2)卷尺一个或者长的直尺也可以。

2 校准阶段

2.1 编译校准文件

将上述的准备下载到工作空间下后,使用如下指令对下载的标定包进行编译

catkin_make -DCATKIN_WHITELIST_PACKAGES="carebot_calibration"
2.2 标定实现

参考此链接进行标定即可:1.三轮全向移动小车的线速度标定 - ROS小课堂

其中的标定结果会在终端中自动计算出来,其计算公式为:

linear_scale = 实际的行走距离 / 预设定的距离

例如:预设定的距离:1.5米, 实际的行走距离2.33米,那么 linear_scale 的值为:

linear_scale = 2.33 / 1.5 = 1.553

注:角度的标定计算方式也是如此,angular_scale = 实际的旋转角度 / 预设定的角度

3 写入标定结果

标定完成后,会得到一个 linear_scale 的结果,该结果是在标定后所得到的,我们需要将此结果写入到 my_arduino_params.yaml 文件中的 linear_scale_correction 处,该文件的路径在

/home/car/omniWheelCareRobot/rosCode/src/ros_arduino_bridge/ros_arduino_python/config

保存此文件后,到此线速度的标定到此便完成。其中角速度一般也需要标定,但是在测试过程中,小车的角度比较精准,便使用了默认值 angular_scale_correction:1.00 。

4 测试验证标定结果

使用此程序代码测试机器人直行1米,接着旋转180°,再返回到起始点。此程序可以测试机器人的旋转角度与直线行走距离是否达到精准的效果。

1)创建 robot_ws 的工作空间

mkdir -p robot_ws/src
cd robot_ws/src
catkin_init_workspace
cd ..
catkin_make

2)使用 vscode 打开进入到 robot_src/src 文件夹下,创建名为 test_pack 的包文件,其依赖有 std_msgs roscpp rospy geometry_msgs 。

3)创建名为 go2back.cpp 的测试的程序,代码如下:

#include <ros/ros.h>
#include <signal.h>
#include <geometry_msgs/Twist.h>
#include <string.h>
 
ros::Publisher cmdVelPub;
 
void shutdown(int sig)
{
  cmdVelPub.publish(geometry_msgs::Twist());
  ROS_INFO("timed_out_and_back.cpp ended!");
  ros::shutdown();
}
 
int main(int argc, char** argv)
{
 
  ros::init(argc, argv, "go_and_back");
  std::string topic = "/cmd_vel";
  ros::NodeHandle node;
  //Publisher to control the robot's speed
  cmdVelPub = node.advertise<geometry_msgs::Twist>(topic, 1);
 
  //How fast will we update the robot's movement?
  double rate = 50;
  //Set the equivalent ROS rate variable
  ros::Rate loopRate(rate);
 
  //execute a shutdown function when exiting
  signal(SIGINT, shutdown);
  ROS_INFO("timed_out_and_back.cpp start...");
 
  //Set the forward linear speed to 0.2 meters per second
  float linear_speed = 0.2;
 
  //Set the travel distance to 1.0 meters
  float goal_distance = 1.0;
 
  //How long should it take us to get there?
  float linear_duration = goal_distance / linear_speed;
 
  //Set the rotation speed to 1.0 radians per second
  float angular_speed = 1.0;
 
  //Set the rotation angle to Pi radians (180 degrees)
  float goal_angle = M_PI;
 
  //How long should it take to rotate?
  float angular_duration = goal_angle / angular_speed;
 
  int count = 0;//Loop through the two legs of the trip
  int ticks;
  geometry_msgs::Twist speed; // 控制信号载体 Twist message
  while (ros::ok())
  {
 
    speed.linear.x = linear_speed; // 设置线速度,正为前进,负为后退
    // Move forward for a time to go 1 meter
    ticks = int(linear_duration * rate);
    for(int i = 0; i < ticks; i++)
    {
      cmdVelPub.publish(speed); // 将刚才设置的指令发送给机器人
      loopRate.sleep();
    }
    //Stop the robot before the rotation
    cmdVelPub.publish(geometry_msgs::Twist());
    //loopRate.sleep();
    ROS_INFO("rotation...!");
 
    //Now rotate left roughly 180 degrees
    speed.linear.x = 0;
    //Set the angular speed
    speed.angular.z = angular_speed; // 设置角速度,正为左转,负为右转
    //Rotate for a time to go 180 degrees
    ticks = int(angular_duration * rate);
    for(int i = 0; i < ticks; i++)
    {
       cmdVelPub.publish(speed); // 将刚才设置的指令发送给机器人
       loopRate.sleep();
    }
    speed.angular.z = 0;
    //Stop the robot before the next leg
    cmdVelPub.publish(geometry_msgs::Twist());
 
    count++;
    if(count == 2)
    {
      count = 0;
      cmdVelPub.publish(geometry_msgs::Twist());
      ROS_INFO("timed_out_and_back.cpp ended!");
      ros::shutdown();
    }
    else
    {
      ROS_INFO("go back...!");
    }
  }
 
  return 0;
}

并在 CMakeLists.txt 文件中添加 go2back.cpp 的文件,方便其能找到该C++文件。

4)然后在终端中使用 catkin_make 对所创建的 C++ 文件进行编译。

5)使用如下指令进行测试

# 启动机器人底盘
source ./devel/setup.bash
roslaunch carebot_bringup carebot_bringup

# 启动测试程序
source ./devel/setup.bash
rosrun test_pack go2back 

启动程序后,便可看到机器人直行1米之后,旋转180°再返回起始点。此程序便可以检验所标定线速度和旋转角度是否可以达到想要效果,如果可以便可以放心使用,不可以便继续校准即可。


参考博客

4.ROS机器人线速度校正_哔哩哔哩_bilibili

​​​​​​1.三轮全向移动小车的线速度标定 - ROS小课堂

ros机器人直行1米再旋转180度,最终回到起点_ros控制机器人转动特定角度-CSDN博客 

  • 10
    点赞
  • 13
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值