42 cmd_vel_pub_ = nh->create_publisher<geometry_msgs::msg::Twist>(
"/cmd_vel", rclcpp::QoS(1));
47 geometry_msgs::msg::Twist cmd_vel;
50 geometry_msgs::msg::Pose currentPose = pose->toPoseMsg();
52 rclcpp::Rate loop_rate(10);
53 double countAngle = 0;
54 auto prevyaw = tf2::getYaw(currentPose.orientation);
58 currentPose = pose->toPoseMsg();
59 tf2::fromMsg(currentPose.orientation, q);
60 auto currentYaw = tf2::getYaw(currentPose.orientation);
61 auto deltaAngle = angles::shortest_angular_distance(prevyaw, currentYaw);
62 countAngle += deltaAngle;
67 auto omega = angular_error *
k_betta_;
74 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] delta angle: " << deltaAngle);
75 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] cummulated angle: " << countAngle);
82 getLogger(),
"[" <<
getName() <<
"] command angular speed: " << cmd_vel.angular.z);
86 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] GOAL REACHED. Sending stop command.");
89 cmd_vel.angular.z = 0;