ros_node.cpp 19 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599
  1. /**
  2. * navigation.
  3. *
  4. * Copyright (C) 2019 成都河狸智能科技有限责任公司.
  5. * All rights reserved.
  6. *
  7. * Author: lumin
  8. */
  9. #include <ros/ros.h>
  10. #include <tf/tf.h>
  11. #include <tf/transform_listener.h>
  12. #include <geometry_msgs/PoseStamped.h>
  13. #include <nav_msgs/Odometry.h>
  14. #include <nav_msgs/Path.h>
  15. #include <actionlib/server/simple_action_server.h>
  16. #include <actionlib/client/simple_action_client.h>
  17. #include <std_msgs/Float64.h>
  18. #include <base_msgs/navigation_cmdAction.h>
  19. #include <base_msgs/navigation_cmdFeedback.h>
  20. #include <base_msgs/navigation_cmdResult.h>
  21. #include "Eigen/Core"
  22. #include "obstacle/obstacle.h"
  23. #include "face/diff/diff.h"
  24. #include "face/forklift/forklift.h"
  25. #include "face/mecanum/mecanum.h"
  26. #include "common/common.h"
  27. #include "space_lib/space_lib.h"
  28. #include "core/core.h"
  29. // #include "space_key/space_key.h"
  30. namespace nav {
  31. typedef actionlib::SimpleActionServer<base_msgs::navigation_cmdAction> NavigationBaseActionServer;
  32. ros::Publisher local_path_pub_, global_path_pub_, cmd_pub_;
  33. ros::NodeHandle* nh_;
  34. NavigationBaseActionServer* as_;
  35. std::string motion_model_ = "diff";
  36. std::string cmd_vel_topic_ = "/cmd_vel";
  37. std::unique_ptr<planner::Core> nb_ = nullptr;
  38. std::unique_ptr<obs::ObstacleIdentify> obstacle_function_;
  39. int rate_;
  40. float minimal_vel_ = 0;
  41. float minimal_rot_ = 0;
  42. float location_cost_ = 0;
  43. float smooth_coeff_ = 0.4;
  44. float slow_threshold_ = 0.3;
  45. float stop_threshold_ = 0.15;
  46. float stop_dist_ = 0.8;
  47. float slow_dist_ = 2.0;
  48. bool debug_ = false;
  49. common::NavState nav_state_;
  50. bool __executeCycle(const base_msgs::navigation_cmdGoal& cmd_goal);
  51. bool __getRobotPose(geometry_msgs::PoseStamped& current_pose);
  52. void __sendFeedback(const uint64_t& time_stamp, const std::string& info, int32_t status, int32_t progress, std::string addition_info = "");
  53. void __executeCb(const base_msgs::navigation_cmdGoalConstPtr& goal);
  54. void __mapPoseCallback(const geometry_msgs::Pose2DConstPtr& msg);
  55. void __buildTask(const base_msgs::navigation_cmdGoal& goal);
  56. void __switchNb(const base_msgs::navigation_cmdGoal& goal);
  57. void __publishZeroVelocity();
  58. float __smoothCoeff();
  59. geometry_msgs::Twist __commonTwist2Twist(common::Twist& twist);
  60. geometry_msgs::PoseStamped robot_current_position_;
  61. std::mutex map_pose_mutex_;
  62. #define LOCK_MAP_POSE() std::lock_guard<std::mutex> lock(map_pose_mutex_);
  63. std::mutex odom_mutex_;
  64. #define LOCK_ODOM() std::lock_guard<std::mutex> lock(odom_mutex_);
  65. static geometry_msgs::PoseStamped setRPY(double z)
  66. {
  67. geometry_msgs::PoseStamped pose_stamp;
  68. tf::Quaternion q;
  69. q.setRPY(0, 0, z);
  70. pose_stamp.pose.orientation.w = q.getW();
  71. pose_stamp.pose.orientation.x = q.getX();
  72. pose_stamp.pose.orientation.y = q.getY();
  73. pose_stamp.pose.orientation.z = q.getZ();
  74. pose_stamp.pose.position.x = 0;
  75. pose_stamp.pose.position.y = 0;
  76. pose_stamp.pose.position.z = 0;
  77. return pose_stamp;
  78. }
  79. static geometry_msgs::PoseStamped __transformCommonPoint2PoseStamped(const common::Point& p)
  80. {
  81. geometry_msgs::PoseStamped pose_stamp;
  82. tf::Transform transform;
  83. tf::Quaternion q;
  84. q.setRPY(0, 0, p.theta);
  85. pose_stamp.pose.position.x = p.x;
  86. pose_stamp.pose.position.y = p.y;
  87. pose_stamp.pose.orientation.w = q.getW();
  88. pose_stamp.pose.orientation.x = q.getX();
  89. pose_stamp.pose.orientation.y = q.getY();
  90. pose_stamp.pose.orientation.z = q.getZ();
  91. return pose_stamp;
  92. }
  93. static common::Point __transformPoseStamped2CommonPoint(const geometry_msgs::PoseStamped& pose)
  94. {
  95. common::Point p;
  96. p.x = pose.pose.position.x;
  97. p.y = pose.pose.position.y;
  98. p.theta = tf::getYaw(pose.pose.orientation);
  99. return p;
  100. }
  101. static common::Path __transformRosPath2CommonPath(const std::vector<geometry_msgs::Pose2D>& ros_path)
  102. {
  103. common::Path path;
  104. for (const geometry_msgs::Pose2D& pose : ros_path) {
  105. common::Point p;
  106. p.x = pose.x;
  107. p.y = pose.y;
  108. p.theta = pose.theta;
  109. path.push_back(p);
  110. }
  111. return path;
  112. }
  113. static geometry_msgs::PoseStamped __transformCommonPoint2PoseStamped(common::Point& p)
  114. {
  115. geometry_msgs::PoseStamped pst = setRPY(p.theta);
  116. pst.pose.position.x = p.x;
  117. pst.pose.position.y = p.y;
  118. return pst;
  119. }
  120. static nav_msgs::Path __transformCommonPath2RosPath(const common::Path& path)
  121. {
  122. nav_msgs::Path ros_path;
  123. for (const common::Point& pose : path) {
  124. ros_path.poses.push_back(__transformCommonPoint2PoseStamped(pose));
  125. }
  126. ros_path.header.stamp = ros::Time::now();
  127. ros_path.header.frame_id = "/map";
  128. return ros_path;
  129. }
  130. /**
  131. *将point转到base坐标系, point和base需要在同一个坐标系
  132. */
  133. static common::Point __bT(common::Point& point, common::Point& base)
  134. {
  135. Eigen::Matrix<float, 2, 1> t2(base.x, base.y);
  136. Eigen::Rotation2D<float> r2(base.theta);
  137. Eigen::Matrix<float, 2, 1> t1(point.x, point.y);
  138. Eigen::Rotation2D<float> r1(point.theta);
  139. Eigen::Matrix<float, 2, 1> t = r2.inverse() * t1 - r2.inverse() * t2;
  140. Eigen::Rotation2D<float> r = r2.inverse() * r1;
  141. common::Point bt;
  142. bt.x = t(0);
  143. bt.y = t(1);
  144. bt.theta = common::norm(r.angle());
  145. return bt;
  146. }
  147. Json::Value __config()
  148. {
  149. std::string path = space::home() + "configure/nav_config.json";
  150. Json::Value c = space::readConfig(path);
  151. Json::Value cy = c;
  152. space::jsonValueTo(c["motion_model"], motion_model_) ?
  153. false : (c["motion_model"] = motion_model_ = "diff");
  154. space::jsonValueTo(c["minimal_vel"], minimal_vel_) ?
  155. false : (c["minimal_vel"] = minimal_vel_ = 0);
  156. space::jsonValueTo(c["minimal_rot"], minimal_rot_) ?
  157. false : (c["minimal_rot"] = minimal_rot_ = 0);
  158. space::jsonValueTo(c["rate"], rate_)?
  159. false : (c["rate"] = rate_ = 50);
  160. space::jsonValueTo(c["cmd_vel_topic"], cmd_vel_topic_) ?
  161. false : (c["cmd_vel_topic"] = cmd_vel_topic_ = "cmd_vel");
  162. space::jsonValueTo(c["debug"], debug_) ?
  163. false : (c["debug"] = debug_ = false);
  164. space::jsonValueTo(c["slow_dist"], slow_dist_) ?
  165. false : (c["slow_dist"] = slow_dist_ = 2.0);
  166. space::jsonValueTo(c["stop_dist"], stop_dist_) ?
  167. false : (c["stop_dist"] = stop_dist_ = 0.8);
  168. if(cy != c) {
  169. space::writeConfig(path, c);
  170. }
  171. return c;
  172. }
  173. void run(tf::TransformListener& tf)
  174. {
  175. nh_ = new ros::NodeHandle();
  176. as_ = new NavigationBaseActionServer(ros::NodeHandle(), "nav_base",
  177. boost::bind(&__executeCb, _1), false);
  178. static ros::Subscriber map_pose_sb = nh_->subscribe<geometry_msgs::Pose2D>(
  179. "map_pose", 1, &__mapPoseCallback);
  180. obstacle_function_ = std::unique_ptr<obs::ObstacleIdentify>(new obs::ObstacleIdentify());
  181. as_->start();
  182. __config();
  183. LOG(INFO)<<"cmd topic ["<<cmd_vel_topic_<<"]";
  184. LOG(INFO)<<"rate ["<<rate_<<"]";
  185. LOG(INFO)<<"motion model ["<<motion_model_<<"]";
  186. LOG(INFO)<<"!@#:navigation start done";
  187. ros::spin();
  188. }
  189. void __executeCb(const base_msgs::navigation_cmdGoalConstPtr& goal)
  190. {
  191. ros::NodeHandle n;
  192. ros::Rate rate = ros::Rate(rate_);
  193. base_msgs::navigation_cmdGoal copy_goal = *goal;
  194. cmd_pub_ = nh_->advertise<geometry_msgs::Twist>(cmd_vel_topic_, 1);
  195. __buildTask(copy_goal);
  196. base_msgs::navigation_cmdGoal cmd_goal = *goal;
  197. while (n.ok() && ros::ok()) {
  198. if(as_->isPreemptRequested()) {
  199. if(as_->isNewGoalAvailable()) {
  200. cmd_goal = *as_->acceptNewGoal();
  201. __buildTask(cmd_goal);
  202. }
  203. else {
  204. as_->setPreempted();
  205. break;
  206. }
  207. }
  208. rate.sleep();
  209. ros::spinOnce();
  210. if (__executeCycle(cmd_goal)) {
  211. base_msgs::navigation_cmdResult result;
  212. result.result = 1;
  213. result.type = "done";
  214. as_->setSucceeded(result, "Goal reached.");
  215. break;
  216. }
  217. if (debug_) {
  218. common::Path local_path = nb_->getLocalPath();
  219. common::Path global_path = nb_->getGlobalPath();
  220. local_path_pub_.publish(__transformCommonPath2RosPath(local_path));
  221. global_path_pub_.publish(__transformCommonPath2RosPath(global_path));
  222. }
  223. }
  224. LOG(INFO)<<"done !!";
  225. cmd_pub_.shutdown();
  226. nb_->destroy();
  227. obstacle_function_->stop();
  228. return;
  229. }
  230. void __buildTask(const base_msgs::navigation_cmdGoal& goal)
  231. {
  232. __config();
  233. __switchNb(goal);
  234. obstacle_function_->start();
  235. common::Config config = nb_->getConfig();
  236. config.max_linear = goal.max_linear;
  237. config.max_transla = goal.max_linear_y;
  238. config.max_angular = goal.max_angular;
  239. // config.toler_x = goal.x_tolerate;
  240. // config.toler_y = goal.y_tolerate;
  241. // config.toler_theta = goal.yaw_tolerate;
  242. nb_->setConfig(config);
  243. common::Path path;
  244. path = __transformRosPath2CommonPath(goal.goal);
  245. if (goal.towards.size() == path.size()) {
  246. for (int i = 0;i < goal.towards.size();i++) {
  247. path[i].head = goal.towards[i];
  248. }
  249. }
  250. if (goal.limit_linear_x.size() == path.size()) {
  251. for (int i = 0;i < goal.limit_linear_x.size();i++) {
  252. path[i].max_linear = goal.limit_linear_x[i];
  253. }
  254. }
  255. nb_->setPath(path);
  256. if (debug_) {
  257. local_path_pub_ = nh_->advertise<nav_msgs::Path>("local_path", 1);
  258. global_path_pub_ = nh_->advertise<nav_msgs::Path>("global_path", 1);
  259. }
  260. }
  261. common::NavState __obstacle(common::Point& sta_pose, common::Twist& cmd)
  262. {
  263. float distance = 0.0;
  264. if (obstacle_function_->isClose(sta_pose)) {
  265. return common::NavState::ING;
  266. }
  267. // 已经撞上?
  268. if (obstacle_function_->isObstacleInArea(0.0, 0.0, 0.0, distance)) {
  269. return common::NavState::HIT_OBSTACLE;
  270. }
  271. if (fabs(cmd.x) < 1e-3) { // 0.001 m/s, 旋转避障判断
  272. float ff = cmd.angular > 0 ? 0.17 : -0.17;
  273. if (obstacle_function_->isObstacleInArea(0.0, 0.0, ff, distance)) {
  274. return common::NavState::HIT_OBSTACLE;
  275. }
  276. else {
  277. return common::NavState::ING;
  278. }
  279. }
  280. common::Path pah = nb_->getLocalPath();
  281. for (int i = 0;i < (int)pah.size() - 1;i++) {
  282. pah[i].theta = atan2(pah[i + 1].y - pah[i].y, pah[i + 1].x - pah[i].x);
  283. common::Point bt = __bT(pah[i], sta_pose);
  284. if (obstacle_function_->isObstacleInArea(bt.x, bt.y, bt.theta, distance)) {
  285. if (distance < slow_dist_) {
  286. float k = distance / (slow_dist_ * 2.0);
  287. cmd.x *= k;
  288. cmd.y *= k;
  289. cmd.angular *= k;
  290. }
  291. if (distance < stop_dist_) {
  292. cmd = common::Twist();
  293. return common::NavState::STOP;
  294. }
  295. return common::NavState::PATH_BLOCK;
  296. }
  297. }
  298. common::Path pah2 = nb_->interPath(2);
  299. for (int i = 0;i < (int)pah2.size() - 1;i++) {
  300. pah2[i].theta = atan2(pah2[i + 1].y - pah2[i].y, pah2[i + 1].x - pah2[i].x);
  301. common::Point bt = __bT(pah2[i], sta_pose);
  302. if (obstacle_function_->isObstacleInArea(bt.x, bt.y, bt.theta, distance)) {
  303. if (distance < slow_dist_) {
  304. float k = distance / (slow_dist_ * 2.0);
  305. cmd.x *= k;
  306. cmd.y *= k;
  307. cmd.angular *= k;
  308. }
  309. if (distance < stop_dist_) {
  310. cmd = common::Twist();
  311. return common::NavState::STOP;
  312. }
  313. return common::NavState::PATH_BLOCK;
  314. }
  315. }
  316. return common::NavState::ING;
  317. }
  318. bool __executeCycle(const base_msgs::navigation_cmdGoal& cmd_goal)
  319. {
  320. geometry_msgs::PoseStamped current_pose = setRPY(0);
  321. if (!__getRobotPose(current_pose)) {
  322. __sendFeedback(cmd_goal.time_stamp, "location error", 0, 0);
  323. return false;
  324. }
  325. common::Twist twist;
  326. common::Point po = __transformPoseStamped2CommonPoint(current_pose);
  327. nav_state_ =
  328. nb_->computeVelocityCommands(po, twist);
  329. common::NavState obsS = __obstacle(po, twist);
  330. if (obsS != common::NavState::ING) {
  331. nav_state_ = obsS;
  332. }
  333. geometry_msgs::Twist cmd_vel = __commonTwist2Twist(twist);
  334. if (std::isnan(cmd_vel.linear.x) ||
  335. std::isnan(cmd_vel.angular.z) ||
  336. std::isnan(cmd_vel.linear.y) ||
  337. std::isinf(cmd_vel.linear.x) ||
  338. std::isinf(cmd_vel.angular.z) ||
  339. std::isinf(cmd_vel.linear.y))
  340. {
  341. __sendFeedback(cmd_goal.time_stamp, "speed error", 2001, 0);
  342. __publishZeroVelocity();
  343. return false;
  344. }
  345. if (nav_state_ == common::NavState::ING) {
  346. __sendFeedback(cmd_goal.time_stamp, "ing", 0, 0);
  347. cmd_pub_.publish(cmd_vel);
  348. }
  349. else if (nav_state_ == common::NavState::ROTATE) {
  350. __sendFeedback(cmd_goal.time_stamp, "rotate", 0, 0);
  351. cmd_pub_.publish(cmd_vel);
  352. }
  353. else if (nav_state_ == common::NavState::HEAD_WARN) {
  354. __sendFeedback(cmd_goal.time_stamp, "head wran", 0, 0);
  355. cmd_pub_.publish(cmd_vel);
  356. }
  357. else if (nav_state_ == common::NavState::PATH_BLOCK) {
  358. __sendFeedback(cmd_goal.time_stamp, "path block", 2002, 0);
  359. cmd_pub_.publish(cmd_vel);
  360. }
  361. else if (nav_state_ == common::NavState::STOP) {
  362. __sendFeedback(cmd_goal.time_stamp, "path block and stop", 2006, 0);
  363. cmd_pub_.publish(cmd_vel);
  364. }
  365. else if (nav_state_ == common::NavState::HIT_OBSTACLE) {
  366. __sendFeedback(cmd_goal.time_stamp, "hit obstacle", 2001, 0);
  367. __publishZeroVelocity();
  368. }
  369. else if (nav_state_ == common::NavState::PATH_EMPTY) {
  370. __sendFeedback(cmd_goal.time_stamp, "path is empty", 2004, 0);
  371. __publishZeroVelocity();
  372. }
  373. else if (nav_state_ == common::NavState::OFF_COURSE) {
  374. __sendFeedback(cmd_goal.time_stamp, "start too far", 2003, 0);
  375. __publishZeroVelocity();
  376. }
  377. else if (nav_state_ == common::NavState::DONE) {
  378. float d = hypot(current_pose.pose.position.x - cmd_goal.goal.back().x,
  379. current_pose.pose.position.y - cmd_goal.goal.back().y);
  380. if (d > cmd_goal.x_tolerate || d > cmd_goal.y_tolerate) {
  381. __sendFeedback(cmd_goal.time_stamp, "low precision", 2005, 0);
  382. }
  383. __publishZeroVelocity();
  384. return true;
  385. }
  386. return false;
  387. }
  388. bool __getRobotPose(geometry_msgs::PoseStamped& current_pose)
  389. {
  390. LOCK_MAP_POSE()
  391. if ((ros::Time::now() - robot_current_position_.header.stamp).toSec() > 1.0) {
  392. return false;
  393. }
  394. current_pose = robot_current_position_;
  395. return true;
  396. }
  397. geometry_msgs::Twist __commonTwist2Twist(common::Twist& twist)
  398. {
  399. geometry_msgs::Twist cmd_vel;
  400. cmd_vel.linear.x = twist.x;
  401. cmd_vel.linear.y = twist.y;
  402. cmd_vel.angular.z = twist.angular;
  403. bool xb = fabs(twist.x) < minimal_vel_;
  404. bool yb = fabs(twist.y) < minimal_vel_;
  405. bool rb = fabs(twist.angular) < minimal_rot_;
  406. if (xb && yb && rb) {
  407. float k = 1;
  408. if (fabs(twist.x) > 1e-3) {
  409. k = minimal_vel_ / twist.x;
  410. }else if (fabs(twist.angular) > 1e-3) {
  411. k = minimal_rot_ / twist.angular;
  412. }else if (fabs(twist.y) > 1e-3) {
  413. k = minimal_vel_ / twist.y;
  414. }
  415. k = fabs(k);
  416. cmd_vel.linear.x *= k;
  417. cmd_vel.linear.y *= k;
  418. cmd_vel.angular.z *= k;
  419. }
  420. return cmd_vel;
  421. }
  422. void __mapPoseCallback(const geometry_msgs::Pose2DConstPtr& msg)
  423. {
  424. geometry_msgs::PoseStamped current_pose;
  425. current_pose = setRPY(msg->theta);
  426. current_pose.header.stamp = ros::Time::now();
  427. current_pose.header.frame_id = "map";
  428. current_pose.pose.position.x = msg->x;
  429. current_pose.pose.position.y = msg->y;
  430. LOCK_MAP_POSE()
  431. robot_current_position_ = std::move(current_pose);
  432. }
  433. void __sendFeedback(const uint64_t& time_stamp, const std::string& info, int32_t status, int32_t progress, std::string addition_info)
  434. {
  435. base_msgs::navigation_cmdFeedback feedback;
  436. feedback.time_stamp = time_stamp;
  437. feedback.info = info;
  438. feedback.status = status;
  439. feedback.progress = progress;
  440. feedback.addition_info = addition_info;
  441. as_->publishFeedback(feedback);
  442. }
  443. void __publishZeroVelocity()
  444. {
  445. geometry_msgs::Twist cmd_vel;
  446. cmd_vel.linear.x = 0.0;
  447. cmd_vel.linear.y = 0.0;
  448. cmd_vel.angular.z = 0.0;
  449. cmd_pub_.publish(cmd_vel);
  450. }
  451. void __switchNb(const base_msgs::navigation_cmdGoal& goal)
  452. {
  453. if (nb_ != nullptr) {
  454. nb_->reset();
  455. }
  456. if (motion_model_ == "diff") {
  457. nb_ = std::unique_ptr<diff::Diff>(new diff::Diff());
  458. }
  459. else if (motion_model_ == "mecanum") {
  460. nb_ = std::unique_ptr<mecanum::Mecanum>(new mecanum::Mecanum());
  461. }
  462. else if (motion_model_ == "forklift") {
  463. nb_ = std::unique_ptr<forklift::FL>(new forklift::FL());
  464. }
  465. }
  466. }
  467. int main(int argc, char** argv){
  468. ros::init(argc, argv, "space_nav");
  469. // if(space::key::chk()) {
  470. // LOG(WARNING) << "推荐使用正版软件";
  471. // space::key::rt(86400);
  472. // return 0;
  473. // }
  474. tf::TransformListener tf(ros::Duration(10));
  475. nav::run(tf);
  476. ros::spin();
  477. return(0);
  478. }