ROS——Gazebo仿真——全向轮小车——运动学模型分析

冷不防 2022-04-04 06:14 671阅读 0赞

文章目录

  • 运动学模型
  • 小车坐标系下运动模型分析
  • 小车坐标系与世界坐标系转换
    • 小车坐标系转换到世界坐标系
    • 世界坐标系转换到小车坐标系
  • 小车运动与电机转动对应关系
  • 完整代码

运动学模型

  三轮全向轮小车结构示意图如图所示:

watermark_type_ZmFuZ3poZW5naGVpdGk_shadow_10_text_aHR0cHM6Ly9ibG9nLmNzZG4ubmV0L3FxXzE2Nzc1Mjkz_size_16_color_FFFFFF_t_70

图中V1,V2和V3也分别称为V_left,V_back和V_right,对应三个轮子的转速,转动的正方向如图所示。

小车坐标系下运动模型分析

  • V x m = 2 V 2 − V 1 − V 3 3 {V}_x^m=\frac{2V_2-V_1-V3}{3} Vxm​=32V2​−V1​−V3​
  • V y m = 3 V 3 − 3 V 1 3 {V}_y^m=\frac{\sqrt{3}V_3-\sqrt{3}V_1}{3} Vym​=33​V3​−3​V1​​
  • ω p = V 1 + V 2 + V 3 3 L {\omega}_p=\frac{V_1+V_2+V_3}{3L} ωp​=3LV1​+V2​+V3​​

对应C语言代码如下:

  1. bool forwardMobile(smart_car::KinematicsForward::Request &request, smart_car::KinematicsForward::Response &response) {
  2. response.output.x = ((2.0L * request.input.v_back) - request.input.v_left - request.input.v_right) / 3.0L;
  3. response.output.y = ((sqrt3 * request.input.v_right) - (sqrt3 * request.input.v_left)) / 3.0L;
  4. response.output.theta = (request.input.v_left + request.input.v_back + request.input.v_right) / L3;
  5. return true;
  6. }

小车坐标系与世界坐标系转换

小车坐标系转换到世界坐标系

小车坐标系转换到世界坐标系的公式如下:

  • V x w = cos ⁡ ( θ ) V x m − sin ⁡ ( θ ) V y m {V}_x^w=\cos(\theta)V_x^m-\sin(\theta)V_y^m Vxw​=cos(θ)Vxm​−sin(θ)Vym​
  • V y w = sin ⁡ ( θ ) V x m + cos ⁡ ( θ ) V y m {V}_y^w=\sin(\theta)V_x^m+\cos(\theta)V_y^m Vyw​=sin(θ)Vxm​+cos(θ)Vym​

  其中 V x w {V}_x^w Vxw​与 V y w {V}_y^w Vyw​分别代表世界坐标系下 x x x与 y y y轴的方向, V x m {V}_x^m Vxm​与 V y m {V}_y^m Vym​分别代表小车坐标系下 x x x与 y y y轴的方向。

对应c语言代码如下:

  1. void mobileToWorldCore(double Vxm, double Vym, double& Vxw, double& Vyw) {
  2. Vxw = (std::cos(theta) * Vxm) - (std::sin(theta) * Vym);
  3. Vyw = (std::sin(theta) * Vxm) + (std::cos(theta) * Vym);
  4. }

世界坐标系转换到小车坐标系

同理,小车坐标系转换到小车坐标系的公式如下:

  • V x m = cos ⁡ ( θ ) V x w + sin ⁡ ( θ ) V y w {V}_x^m=\cos(\theta)V_x^w+\sin(\theta)V_y^w Vxm​=cos(θ)Vxw​+sin(θ)Vyw​
  • V y m = − sin ⁡ ( θ ) V x w + cos ⁡ ( θ ) V y w {V}_y^m=-\sin(\theta)V_x^w+\cos(\theta)V_y^w Vym​=−sin(θ)Vxw​+cos(θ)Vyw​

对应c语言代码如下:

  1. void worldToMobileCore(double Vxw, double Vyw, double& Vxm, double& Vym) {
  2. Vxm = (std::cos(theta) * Vxw) + (std::sin(theta) * Vyw);
  3. Vym = - (std::sin(theta) * Vxw) + (std::cos(theta) * Vyw);
  4. }

小车运动与电机转动对应关系

  • V 1 = − V x m 2 − 3 V y m 2 + L ω p {V}_1=-\frac{V_x^m}{2}-\frac{\sqrt{3}V_y^m}{2}+L\omega_p V1​=−2Vxm​​−23​Vym​​+Lωp​
  • V 2 = V x m + L ω p {V}_2=V_x^m+L\omega_p V2​=Vxm​+Lωp​
  • V 3 = − V x m 2 + 3 V y m 2 + L ω p {V}_3=-\frac{V_x^m}{2}+\frac{\sqrt{3}V_y^m}{2}+L\omega_p V3​=−2Vxm​​+23​Vym​​+Lωp​

对应C语言代码为:

  1. bool inverseMobile(smart_car::KinematicsInverse::Request &request, smart_car::KinematicsInverse::Response &response) {
  2. long double V__m_x2 = - request.input.x / 2.0L;
  3. long double sqrt3V__m_y2 = (sqrt3 * request.input.y) / 2.0L;
  4. long double Lomega_p = L * request.input.theta;
  5. response.output.v_left = V__m_x2 - sqrt3V__m_y2 + Lomega_p;
  6. response.output.v_back = request.input.x + Lomega_p;
  7. response.output.v_right = V__m_x2 + sqrt3V__m_y2 + Lomega_p;
  8. return true;

完整代码


  1. #include <cmath>
  2. #include <string>
  3. #include <ros/ros.h>
  4. #include <geometry_msgs/Pose2D.h>
  5. #include <sensor_msgs/JointState.h>
  6. #include <smart_car/FrameToFrame.h>
  7. #include <smart_car/KinematicsForward.h>
  8. #include <smart_car/KinematicsInverse.h>
  9. #include <kdl/frames.hpp>
  10. #include <kdl_parser/kdl_parser.hpp>
  11. long double L;
  12. long double L3;
  13. long double sqrt3;
  14. long double theta = 0;
  15. void mobileToWorldCore(double Vxm, double Vym, double& Vxw, double& Vyw) {
  16. Vxw = (std::cos(theta) * Vxm) - (std::sin(theta) * Vym);
  17. Vyw = (std::sin(theta) * Vxm) + (std::cos(theta) * Vym);
  18. }
  19. bool mobileToWorld(smart_car::FrameToFrame::Request &request, smart_car::FrameToFrame::Response &response) {
  20. mobileToWorldCore(request.input.x, request.input.y, response.output.x, response.output.y);
  21. }
  22. void worldToMobileCore(double Vxw, double Vyw, double& Vxm, double& Vym) {
  23. Vxm = (std::cos(theta) * Vxw) + (std::sin(theta) * Vyw);
  24. Vym = - (std::sin(theta) * Vxw) + (std::cos(theta) * Vyw);
  25. }
  26. bool worldToMobile(smart_car::FrameToFrame::Request &request, smart_car::FrameToFrame::Response &response) {
  27. worldToMobileCore(request.input.x, request.input.y, response.output.x, response.output.y);
  28. }
  29. bool forwardMobile(smart_car::KinematicsForward::Request &request, smart_car::KinematicsForward::Response &response) {
  30. response.output.x = ((2.0L * request.input.v_back) - request.input.v_left - request.input.v_right) / 3.0L;
  31. response.output.y = ((sqrt3 * request.input.v_right) - (sqrt3 * request.input.v_left)) / 3.0L;
  32. response.output.theta = (request.input.v_left + request.input.v_back + request.input.v_right) / L3;
  33. return true;
  34. }
  35. bool forwardWorld(smart_car::KinematicsForward::Request &request, smart_car::KinematicsForward::Response &response) {
  36. forwardMobile(request, response);
  37. mobileToWorldCore(response.output.x, response.output.y, response.output.x, response.output.y);
  38. return true;
  39. }
  40. bool inverseMobile(smart_car::KinematicsInverse::Request &request, smart_car::KinematicsInverse::Response &response) {
  41. long double V__m_x2 = - request.input.x / 2.0L;
  42. long double sqrt3V__m_y2 = (sqrt3 * request.input.y) / 2.0L;
  43. long double Lomega_p = L * request.input.theta;
  44. response.output.v_left = V__m_x2 - sqrt3V__m_y2 + Lomega_p;
  45. response.output.v_back = request.input.x + Lomega_p;
  46. response.output.v_right = V__m_x2 + sqrt3V__m_y2 + Lomega_p;
  47. return true;
  48. }
  49. bool inverseWorld(smart_car::KinematicsInverse::Request &request, smart_car::KinematicsInverse::Response &response) {
  50. worldToMobileCore(request.input.x, request.input.y, request.input.x, request.input.y);
  51. inverseMobile(request, response);
  52. return true;
  53. }
  54. void onPoseWorldMessage(const geometry_msgs::Pose2D::ConstPtr& input){
  55. theta = input->theta;
  56. }
  57. int main(int argc, char **argv){
  58. ros::init(argc, argv, "kinematics");
  59. ros::NodeHandle node;
  60. {
  61. std::string description;
  62. if(!node.getParam("robot_description",description)) {
  63. ROS_ERROR("Could not find '/robot_description'.");
  64. return -1;
  65. }
  66. KDL::Tree tree;
  67. if (!kdl_parser::treeFromString(description, tree)) {
  68. ROS_ERROR("Failed to construct KDL tree.");
  69. return -1;
  70. }
  71. KDL::Chain chain;
  72. if (!tree.getChain("base_link", "rim_back_link", chain)) {
  73. ROS_ERROR("Failed to get chain from KDL tree.");
  74. return -1;
  75. }
  76. KDL::Frame frame = chain.getSegment(0).pose(0);
  77. L = std::sqrt(std::pow(frame.p.x() - 0.0L, 2.0L) + std::pow(frame.p.y() - 0.0L, 2.0L));
  78. node.setParam("parameter/wheel/distance", (double) L);
  79. L3 = 3.0L * L;
  80. sqrt3 = std::sqrt(3.0L);
  81. double parameter;
  82. if (!node.getParam("parameter/initial/theta", parameter)) {
  83. parameter = 0;
  84. }
  85. theta = parameter;
  86. }
  87. ros::ServiceServer forwardMobileService = node.advertiseService("kinematics_forward_mobile", forwardMobile);
  88. ros::ServiceServer forwardWorldService = node.advertiseService("kinematics_forward_world" , forwardWorld );
  89. ros::ServiceServer inverseMobileService = node.advertiseService("kinematics_inverse_mobile", inverseMobile);
  90. ros::ServiceServer inverseWorldService = node.advertiseService("kinematics_inverse_world" , inverseWorld );
  91. ros::ServiceServer mobileToWorldService = node.advertiseService("kinematics_mobile_to_world" , mobileToWorld);
  92. ros::ServiceServer worldToMobileService = node.advertiseService("kinematics_world_to_mobile" , worldToMobile);
  93. ros::Subscriber subscriber = node.subscribe("pose/world", 1, onPoseWorldMessage);
  94. ros::spin();
  95. return 0;
  96. }

发表评论

表情:
评论列表 (有 0 条评论,671人围观)

还没有评论,来说两句吧...

相关阅读