41 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);
55 double kp_linear = 0.5;
56 double ki_linear = 0.0;
57 double kd_linear = 0.1;
59 double kp_angular = 0.5;
60 double ki_angular = 0.0;
61 double kd_angular = 0.1;
65 RCLCPP_INFO_STREAM_THROTTLE(
67 "CbPositionControlFreeSpace, current pose: " << currentPose.position.x <<
", "
68 << currentPose.position.y <<
", "
69 << tf2::getYaw(currentPose.orientation));
71 RCLCPP_INFO_STREAM_THROTTLE(
73 "CbPositionControlFreeSpace, target pose: " <<
target_pose_.position.x <<
", "
78 currentPose = pose->toPoseMsg();
84 double error_x =
target_pose_.position.x - currentPose.position.x;
85 double error_y =
target_pose_.position.y - currentPose.position.y;
88 double distance_to_target = std::sqrt(error_x * error_x + error_y * error_y);
91 getLogger(),
"[" <<
getName() <<
"] distance to target: " << distance_to_target
97 RCLCPP_INFO(
getLogger(),
"Goal reached!");
99 geometry_msgs::msg::Twist cmd_vel_msg;
100 cmd_vel_msg.linear.x = 0.0;
101 cmd_vel_msg.angular.z = 0.0;
108 double desired_yaw = std::atan2(error_y, error_x);
112 double yaw_error = desired_yaw - (tf2::getYaw(currentPose.orientation) + M_PI);
115 while (yaw_error > M_PI) yaw_error -= 2 * M_PI;
116 while (yaw_error < -M_PI) yaw_error += 2 * M_PI;
119 double cmd_linear_x = kp_linear * distance_to_target + ki_linear *
integral_linear_ +
135 geometry_msgs::msg::Twist cmd_vel_msg;
137 cmd_vel_msg.linear.x = cmd_linear_x;
138 cmd_vel_msg.angular.z = cmd_angular_z;
191 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] Finished behavior execution");