two_vehicle_test.cpp 2.8 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576
  1. #include <ros/ros.h>
  2. #include "../mpc_two_vehicle/trajectory_tool.h"
  3. #include <tf/transform_listener.h>
  4. #include <tf/transform_broadcaster.h>
  5. #include <tf/transform_datatypes.h>
  6. #include <nav_msgs/Path.h>
  7. #include <turtlesim/Pose.h>
  8. void position_callback(const turtlesim::Pose::ConstPtr& msg)
  9. {
  10. // 发布tf模板
  11. tf::TransformBroadcaster tf_broadcaster_;
  12. tf::Transform transform;
  13. transform.setOrigin(tf::Vector3(msg->x, msg->y, 0.0));
  14. transform.setRotation(tf::Quaternion(0, 0, cos(msg->theta/2.0), sin(msg->theta/2.0)));
  15. tf::StampedTransform transform_msg(transform, ros::Time::now(), "map", "base_link");
  16. tf_broadcaster_.sendTransform(transform_msg);
  17. }
  18. int main(int argc, char **argv)
  19. {
  20. ros::init(argc, argv, "mpc_two_vehicle_test_node");
  21. ros::NodeHandle nh;
  22. ros::Subscriber position_subscriber = nh.subscribe("/turtule1/pose", 10, position_callback);
  23. // ros::Subscriber target_sub_ = nh.subscribe<geometry_msgs::PoseStamped>("/move_base_simple/goal", 1, targetHandler);
  24. ros::Publisher global_trajectory_publisher = nh.advertise<nav_msgs::Path>("global_path", 2);
  25. ros::Publisher local_trajectory_publisher = nh.advertise<nav_msgs::Path>("local_path", 2);
  26. nav_msgs::Path path;
  27. int path_count = 0;
  28. // 路径测试,从(1,1)到(3,1.5),theta=pi/4.0
  29. Trajectory_tool traj_tool;
  30. Eigen::Isometry2d base;
  31. Eigen::Isometry2d target;
  32. Eigen::Matrix2d rotation;
  33. trajectory_type trajectory;
  34. rotation << cos(M_PI_4), -sin(M_PI_4), sin(M_PI_4), cos(M_PI_4);
  35. base.setIdentity();
  36. base.pretranslate(Eigen::Vector2d(1, 1));
  37. target.setIdentity();
  38. target.rotate(rotation);
  39. target.pretranslate(Eigen::Vector2d(9, -1));
  40. bool create_trajectory_result = traj_tool.create_trajectory(base, target, trajectory);
  41. ros::Rate loop_rate(20);
  42. while (ros::ok())
  43. {
  44. // 发布全局路径
  45. if (create_trajectory_result)
  46. {
  47. path.header.frame_id = "map";
  48. path.header.seq = ++path_count;
  49. path.header.stamp = ros::Time::now();
  50. path.poses.clear();
  51. for (size_t i = 0; i < trajectory.size(); i++)
  52. {
  53. geometry_msgs::PoseStamped t_pose;
  54. t_pose.header = path.header;
  55. t_pose.pose.position.x = trajectory[i].translation().x();
  56. t_pose.pose.position.y = trajectory[i].translation().y();
  57. double theta = atan2(trajectory[i].rotation()(1, 0), trajectory[i].rotation()(0, 0));
  58. t_pose.pose.orientation.w = cos(theta / 2.0);
  59. t_pose.pose.orientation.z = sin(theta / 2.0);
  60. path.poses.push_back(t_pose);
  61. }
  62. global_trajectory_publisher.publish(path);
  63. }
  64. ros::spinOnce();
  65. loop_rate.sleep();
  66. }
  67. return 0;
  68. }