当前位置:   article > 正文

ROS与STM32F407实现消息通信(含源码)_std_msgs 转sensor_msgs/imu

std_msgs 转sensor_msgs/imu

关注微信公众号“混沌无形”,后台回复:13462EE。免费获取完整工程源码!

本文参考STM32F1与ROS的通信工程:https://blog.csdn.net/qq_36349536/article/details/82773064,针对STM32F4的相关寄存器进行修改,实现STM32F407与ROS kinetic实现串口通信 ,message格式遵循ROS消息标准。

并实现4WD机器人驱动控制及轨迹跟踪,其代码包含:GY901陀螺仪数据读取、通过CAN总线控制4个大疆电机M1、电机的PID控制以及4WD机器人的正逆运动学模型。

文件目录为

  1. C:.
  2. ├─BSP
  3. ├─CORE
  4. ├─DRIVER
  5. │ ├─CAN1
  6. │ ├─gy85
  7. │ ├─Kinematics
  8. │ ├─LED
  9. │ ├─MOTORCONTROLL
  10. │ ├─PID
  11. │ └─WT901C
  12. ├─FWLIB
  13. │ ├─inc
  14. │ └─src
  15. ├─HARDWARE
  16. │ ├─BEEP
  17. │ ├─KEY
  18. │ └─LED
  19. ├─OBJ
  20. ├─ROSLIB
  21. │ ├─actionlib
  22. │ ├─actionlib_msgs
  23. │ ├─actionlib_tutorials
  24. │ ├─bond
  25. │ ├─control_msgs
  26. │ ├─diagnostic_msgs
  27. │ ├─driver_base
  28. │ ├─dynamic_reconfigure
  29. │ ├─examples
  30. │ │ ├─ADC
  31. │ │ ├─Blink
  32. │ │ ├─BlinkM
  33. │ │ ├─button_example
  34. │ │ ├─Clapper
  35. │ │ ├─HelloWorld
  36. │ │ ├─IrRanger
  37. │ │ ├─Logging
  38. │ │ ├─Odom
  39. │ │ ├─pubsub
  40. │ │ ├─ServiceClient
  41. │ │ ├─ServiceServer
  42. │ │ ├─ServoControl
  43. │ │ ├─Temperature
  44. │ │ ├─TimeTF
  45. │ │ └─Ultrasound
  46. │ ├─gazebo_msgs
  47. │ ├─geometry_msgs
  48. │ ├─hector_mapping
  49. │ ├─hector_nav_msgs
  50. │ ├─laser_assembler
  51. │ ├─nav_msgs
  52. │ ├─nodelet
  53. │ ├─pcl_msgs
  54. │ ├─polled_camera
  55. │ ├─riki_msgs
  56. │ ├─ros
  57. │ ├─roscpp
  58. │ ├─roscpp_tutorials
  59. │ ├─rosgraph_msgs
  60. │ ├─rospy_tutorials
  61. │ ├─rosserial_arduino
  62. │ ├─rosserial_msgs
  63. │ ├─ros_arduino_msgs
  64. │ ├─sensor_msgs
  65. │ ├─shape_msgs
  66. │ ├─smach_msgs
  67. │ ├─std_msgs
  68. │ ├─std_srvs
  69. │ ├─stereo_msgs
  70. │ ├─tests
  71. │ │ ├─array_test
  72. │ │ ├─float64_test
  73. │ │ └─time_test
  74. │ ├─tf
  75. │ ├─tf2_msgs
  76. │ ├─theora_image_transport
  77. │ ├─topic_tools
  78. │ ├─trajectory_msgs
  79. │ ├─turtlesim
  80. │ ├─turtle_actionlib
  81. │ └─visualization_msgs
  82. ├─SYSTEM
  83. │ ├─delay
  84. │ ├─sys
  85. │ └─usart
  86. └─USER
  87. ├─Listings
  88. └─Objects

main函数部分如下

  1. #include <stdio.h>
  2. #include "hardwareserial.h"
  3. #include "millisecondtimer.h"
  4. #include <ros.h>
  5. #include "std_msgs/String.h"
  6. #include "std_msgs/Float64.h"
  7. #include "sstream"
  8. #include <geometry_msgs/Vector3.h>
  9. #include <geometry_msgs/Quaternion.h>
  10. #include <ros/time.h>
  11. #include <geometry_msgs/Twist.h>
  12. #include <sensor_msgs/Imu.h>
  13. #include "led.h"
  14. #include "Kinematics.h"
  15. #include "wt901.h"
  16. #include "can1.h"
  17. #include "motorcontroll.h"
  18. #include "PID.h"
  19. Led led0(LED0);
  20. Led led1(LED1);
  21. Kinematics car(MAX_RPM, WHEEL_DIAMETER, BASE_WIDTH,X_COEFFICIENT_CAR, MOTORGEARRATIO);
  22. PID motor1SpdPID(-16384, 16384, K_P, K_I, K_D);
  23. PID motor2SpdPID(-16384, 16384, K_P, K_I, K_D);
  24. PID motor3SpdPID(-16384, 16384, K_P, K_I, K_D);
  25. PID motor4SpdPID(-16384, 16384, K_P, K_I, K_D);
  26. //更新IMU信息
  27. sensor_msgs::Imu updateIMUMsg()
  28. {
  29. sensor_msgs::Imu wt901Msg;
  30. wt901Msg.angular_velocity.x = getAngularVelocity().angvel0;
  31. wt901Msg.angular_velocity.y = getAngularVelocity().angvel1;
  32. wt901Msg.angular_velocity.z = getAngularVelocity().angvel2;
  33. wt901Msg.linear_acceleration.x = getLinearAccleration().linacc0;
  34. wt901Msg.linear_acceleration.y = getLinearAccleration().linacc1;
  35. wt901Msg.linear_acceleration.z = getLinearAccleration().linacc2;
  36. wt901Msg.orientation.w = getOrientation().orien0;
  37. wt901Msg.orientation.x = getOrientation().orien1;
  38. wt901Msg.orientation.y = getOrientation().orien2;
  39. wt901Msg.orientation.z = getOrientation().orien3;
  40. return wt901Msg;
  41. }
  42. ros::NodeHandle nh;
  43. //陀螺仪信息
  44. sensor_msgs::Imu IMUMsg;
  45. //发布IMU信息
  46. ros::Publisher imu_msg_pub("imu", &IMUMsg);
  47. //定义几何中心速度信息
  48. float vx = 0;
  49. float wz = 0;
  50. uint32_t previous_command_time = 0;
  51. //**********
  52. geometry_msgs::Twist viewVel;
  53. void vel_callback( const geometry_msgs::Twist& cmd_msg)
  54. {
  55. wz = cmd_msg.angular.z;
  56. vx = cmd_msg.linear.x;
  57. viewVel = cmd_msg;
  58. }
  59. ros::Subscriber<geometry_msgs::Twist> vel_cmd_sub("cmd_vel", &vel_callback);
  60. //*************查看电机速度-临时使用
  61. geometry_msgs::Quaternion mspd;
  62. ros::Publisher mspd_msg_pub("mspd", &mspd);
  63. ros::Publisher vel_msg_pub("viewVelCmd", &viewVel);
  64. int main(void)
  65. {
  66. NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2); //很有必要性
  67. uint32_t previous_control_time = 0;
  68. uint32_t previous_led_time = 0;
  69. uint32_t previous_imu_time = 0;
  70. uint32_t previous_motor_time = 0;
  71. bool OnOff = true;
  72. SystemInit(); //系统时钟初始化
  73. initialise(); //延时函数初始化*/
  74. CAN1_Configuration();
  75. led0.init();
  76. led1.init();
  77. wt901Init(9600);
  78. nh.initNode(); //初始化
  79. while (!nh.connected()) //等待连接
  80. {
  81. nh.spinOnce();
  82. }
  83. nh.loginfo("robot_Star Connected!"); //打印连接成功
  84. delay(10);
  85. nh.advertise(imu_msg_pub);
  86. nh.advertise(mspd_msg_pub);
  87. nh.advertise(vel_msg_pub);
  88. nh.subscribe(vel_cmd_sub);
  89. delay(10);
  90. while(1)
  91. {
  92. //速度控制
  93. if( (millis() - previous_control_time) >= (1000/PID_RATE) )
  94. {
  95. Kinematics::motorSpd spd = car.VelToMotorSpd(vx, 0 ,wz);
  96. int M1Spd = int(motor1SpdPID.compute(spd.m_left_front, readMotorSpd(1)));
  97. int M2Spd = int(motor1SpdPID.compute(spd.m_right_front, readMotorSpd(2)));
  98. int M3Spd = int(motor1SpdPID.compute(spd.m_left_back, readMotorSpd(3)));
  99. int M4Spd = int(motor1SpdPID.compute(spd.m_right_back, readMotorSpd(4)));
  100. Set_CM_Current(M1Spd, M2Spd, M3Spd, M4Spd);
  101. //待改
  102. // mspd.w = M1Spd;
  103. // mspd.x = M2Spd;
  104. // mspd.y = M3Spd;
  105. // mspd.z = M4Spd;
  106. mspd.w = spd.m_left_front;
  107. mspd.x = spd.m_right_front;
  108. mspd.y = spd.m_left_back;
  109. mspd.z = spd.m_right_back;
  110. previous_control_time = millis();
  111. }
  112. //停止电机
  113. // if ((millis() - previous_command_time) >= 2000)
  114. // {
  115. // vx = 0;
  116. // wz = 0;
  117. // Set_CM_Current(0, 0, 0, 0);
  118. // }
  119. //发布陀螺仪信息
  120. if ((millis() - previous_imu_time) >= (1000 / IMU_PUBLISH_RATE))
  121. {
  122. IMUMsg = updateIMUMsg();
  123. imu_msg_pub.publish(&IMUMsg);
  124. previous_imu_time = millis();
  125. }
  126. //发布电机信息---需要改
  127. if ((millis() - previous_motor_time) >= (1000 / VEL_PUBLISH_RATE))
  128. {
  129. mspd_msg_pub.publish(&mspd);
  130. vel_msg_pub.publish(&viewVel);
  131. previous_motor_time = millis();
  132. }
  133. //led闪烁
  134. if ((millis() - previous_led_time) >= (1000 / LED_RATE))
  135. {
  136. led0.on_off(OnOff);
  137. OnOff = !OnOff;
  138. previous_led_time = millis();
  139. }
  140. nh.spinOnce();
  141. }
  142. return 0;
  143. }

喜欢的话,请关注微信公众号,可阅读更多好文!

声明:本文内容由网友自发贡献,不代表【wpsshop博客】立场,版权归原作者所有,本站不承担相应法律责任。如您发现有侵权的内容,请联系我们。转载请注明出处:https://www.wpsshop.cn/w/笔触狂放9/article/detail/479328
推荐阅读
相关标签
  

闽ICP备14008679号